Autoware.Auto
localization_node.hpp
Go to the documentation of this file.
1 // Copyright 2019 the Autoware Foundation
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 //    http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License.
14 //
15 // Co-developed by Tier IV, Inc. and Apex.AI, Inc.
16 
17 #ifndef LOCALIZATION_NODES__LOCALIZATION_NODE_HPP_
18 #define LOCALIZATION_NODES__LOCALIZATION_NODE_HPP_
19 
22 #include <rclcpp/rclcpp.hpp>
23 #include <tf2/buffer_core.h>
24 #include <tf2_ros/transform_listener.h>
25 #include <tf2_geometry_msgs/tf2_geometry_msgs.h>
26 #include <sensor_msgs/msg/point_cloud2.hpp>
30 #include <memory>
31 #include <string>
32 #include <utility>
33 
34 namespace autoware
35 {
36 namespace localization
37 {
38 namespace localization_nodes
39 {
42 
44 struct TopicQoS
45 {
46  std::string topic;
47  rclcpp::QoS qos;
48 };
49 
52 {
53  PUBLISH_TF,
55 };
56 
63 template<typename ObservationMsgT, typename MapMsgT, typename LocalizerT,
64  typename PoseInitializerT>
65 class LOCALIZATION_NODES_PUBLIC RelativeLocalizerNode : public rclcpp::Node
66 {
67 public:
68  using LocalizerBase = localization_common::RelativeLocalizerBase<ObservationMsgT, MapMsgT,
69  typename LocalizerT::RegistrationSummary>;
70  using LocalizerBasePtr = std::unique_ptr<LocalizerBase>;
71  using Cloud = sensor_msgs::msg::PointCloud2;
74  using RegistrationSummary = typename LocalizerT::RegistrationSummary;
75 
87  const std::string & node_name, const std::string & name_space,
88  const TopicQoS & observation_sub_config,
89  const TopicQoS & map_sub_config,
90  const TopicQoS & pose_pub_config,
91  const TopicQoS & initial_pose_sub_config,
92  const PoseInitializerT & pose_initializer,
94  : Node(node_name, name_space),
95  m_pose_initializer(pose_initializer),
96  m_tf_listener(m_tf_buffer, std::shared_ptr<rclcpp::Node>(this, [](auto) {}), false),
97  m_observation_sub(create_subscription<ObservationMsgT>(
98  observation_sub_config.topic,
99  observation_sub_config.qos,
100  [this](typename ObservationMsgT::ConstSharedPtr msg) {observation_callback(msg);})),
101  m_map_sub(
102  create_subscription<MapMsgT>(
103  map_sub_config.topic, map_sub_config.qos,
104  [this](typename MapMsgT::ConstSharedPtr msg) {map_callback(msg);})),
105  m_pose_publisher(
106  create_publisher<PoseWithCovarianceStamped>(
107  pose_pub_config.topic,
108  pose_pub_config.qos)),
109  m_initial_pose_sub(
110  create_subscription<PoseWithCovarianceStamped>(
111  initial_pose_sub_config.topic, initial_pose_sub_config.qos,
112  [this](const typename PoseWithCovarianceStamped::ConstSharedPtr msg) {
113  initial_pose_callback(msg);
114  })) {
115  if (publish_tf == LocalizerPublishMode::PUBLISH_TF) {
116  m_tf_publisher = create_publisher<tf2_msgs::msg::TFMessage>("/tf", pose_pub_config.qos);
117  }
118  }
119 
120  // Constructor for ros2 components
121  // TODO(yunus.caliskan): refactor constructors together reduce the repeated code.
123  const std::string & node_name,
124  const rclcpp::NodeOptions & options,
125  const PoseInitializerT & pose_initializer)
126  : Node(node_name, options),
127  m_pose_initializer(pose_initializer),
128  m_tf_listener(m_tf_buffer, std::shared_ptr<rclcpp::Node>(this, [](auto) {}), false),
129  m_observation_sub(create_subscription<ObservationMsgT>(
130  "points_in",
131  rclcpp::QoS{rclcpp::KeepLast{
132  static_cast<size_t>(declare_parameter("observation_sub.history_depth").template
133  get<size_t>())}},
134  [this](typename ObservationMsgT::ConstSharedPtr msg) {observation_callback(msg);})),
135  m_map_sub(
136  create_subscription<MapMsgT>(
137  "ndt_map",
138  rclcpp::QoS{rclcpp::KeepLast{
139  static_cast<size_t>(declare_parameter("map_sub.history_depth").
140  template get<size_t>())}}.transient_local(),
141  [this](typename MapMsgT::ConstSharedPtr msg) {map_callback(msg);})),
142  m_pose_publisher(
143  create_publisher<PoseWithCovarianceStamped>(
144  "ndt_pose",
145  rclcpp::QoS{rclcpp::KeepLast{
146  static_cast<size_t>(declare_parameter(
147  "pose_pub.history_depth").template get<size_t>())}})),
148  m_initial_pose_sub(
149  create_subscription<PoseWithCovarianceStamped>(
150  "initialpose",
151  rclcpp::QoS{rclcpp::KeepLast{10}},
152  [this](const typename PoseWithCovarianceStamped::ConstSharedPtr msg) {
153  initial_pose_callback(msg);
154  }))
155  {
156  init();
157  }
158 
164  const std::string & node_name, const std::string & name_space,
165  const PoseInitializerT & pose_initializer)
166  : Node(node_name, name_space),
167  m_pose_initializer(pose_initializer),
168  m_tf_listener(m_tf_buffer, std::shared_ptr<rclcpp::Node>(this, [](auto) {}), false),
169  m_observation_sub(create_subscription<ObservationMsgT>(
170  "points_in",
171  rclcpp::QoS{rclcpp::KeepLast{
172  static_cast<size_t>(declare_parameter("observation_sub.history_depth").template
173  get<size_t>())}},
174  [this](typename ObservationMsgT::ConstSharedPtr msg) {observation_callback(msg);})),
175  m_map_sub(
176  create_subscription<MapMsgT>(
177  "ndt_map",
178  rclcpp::QoS{rclcpp::KeepLast{
179  static_cast<size_t>(declare_parameter("map_sub.history_depth").
180  template get<size_t>())}}.transient_local(),
181  [this](typename MapMsgT::ConstSharedPtr msg) {map_callback(msg);})),
182  m_pose_publisher(
183  create_publisher<PoseWithCovarianceStamped>(
184  "ndt_pose",
185  rclcpp::QoS{rclcpp::KeepLast{
186  static_cast<size_t>(declare_parameter(
187  "pose_pub.history_depth").template get<size_t>())}})),
188  m_initial_pose_sub(
189  create_subscription<PoseWithCovarianceStamped>(
190  "initialpose",
191  rclcpp::QoS{rclcpp::KeepLast{10}},
192  [this](const typename PoseWithCovarianceStamped::ConstSharedPtr msg) {
193  initial_pose_callback(msg);
194  }))
195  {
196  init();
197  }
198 
200  const typename rclcpp::Publisher<PoseWithCovarianceStamped>::ConstSharedPtr get_publisher()
201  {
202  return m_pose_publisher;
203  }
204 
205 protected:
208  void set_localizer(LocalizerBasePtr && localizer_ptr)
209  {
210  m_localizer_ptr = std::forward<LocalizerBasePtr>(localizer_ptr);
211  }
212 
214  virtual void on_bad_registration(std::exception_ptr eptr) // NOLINT
215  {
216  on_exception(eptr, "on_bad_registration");
217  }
218 
220  virtual void on_bad_map(std::exception_ptr eptr) // NOLINT
221  {
222  on_exception(eptr, "on_bad_map");
223  }
224 
225  void on_exception(std::exception_ptr eptr, const std::string & error_source) // NOLINT
226  {
227  try {
228  if (eptr) {
229  std::rethrow_exception(eptr);
230  } else {
231  RCLCPP_ERROR(get_logger(), error_source + ": error nullptr");
232  }
233  } catch (const std::exception & e) {
234  RCLCPP_ERROR(get_logger(), e.what());
235  }
236  }
237 
239  virtual void on_observation_with_invalid_map(typename ObservationMsgT::ConstSharedPtr)
240  {
241  RCLCPP_WARN(
242  get_logger(), "Received observation without a valid map, "
243  "ignoring the observation.");
244  }
245 
249  {
250  (void) pose;
251  RCLCPP_WARN(
252  get_logger(), "Relative localizer has an invalid pose estimate. "
253  "The result is ignored.");
254  }
255 
256 
263  virtual bool validate_output(
264  const RegistrationSummary & summary,
265  const PoseWithCovarianceStamped & pose, const TransformStamped & guess)
266  {
267  (void) summary;
268  (void) pose;
269  (void) guess;
270  return true;
271  }
272 
273 private:
274  void init()
275  {
276  if (declare_parameter("publish_tf").template get<bool>()) {
277  m_tf_publisher = create_publisher<tf2_msgs::msg::TFMessage>(
278  "/tf",
279  rclcpp::QoS{rclcpp::KeepLast{m_pose_publisher->get_queue_size()}});
280  }
281 
282  if (declare_parameter("init_hack.enabled", false)) {
284  // TODO(yunus.caliskan): Remove in #425
285  // Since this hack is only needed for the demo, it is not provided in the non-ros constructor.
286  geometry_msgs::msg::TransformStamped init_hack_transform;
287  auto & tf = init_hack_transform.transform;
288  tf.rotation.x = declare_parameter("init_hack.quaternion.x").template get<float64_t>();
289  tf.rotation.y = declare_parameter("init_hack.quaternion.y").template get<float64_t>();
290  tf.rotation.z = declare_parameter("init_hack.quaternion.z").template get<float64_t>();
291  tf.rotation.w = declare_parameter("init_hack.quaternion.w").template get<float64_t>();
292  tf.translation.x = declare_parameter("init_hack.translation.x").template get<float64_t>();
293  tf.translation.y = declare_parameter("init_hack.translation.y").template get<float64_t>();
294  tf.translation.z = declare_parameter("init_hack.translation.z").template get<float64_t>();
295  init_hack_transform.header.frame_id = "map";
296  init_hack_transform.child_frame_id = "base_link";
297  m_external_pose = init_hack_transform;
298  m_external_pose_available = true;
299  m_use_hack = true;
300  // we currently need the hack for the AVP demo MS2.
302  }
303  }
304 
306  virtual void handle_registration_summary(const RegistrationSummary &) {}
307 
310  void observation_callback(typename ObservationMsgT::ConstSharedPtr msg_ptr)
311  {
312  check_localizer();
313  if (!m_localizer_ptr->map_valid()) {
314  on_observation_with_invalid_map(msg_ptr);
315  return;
316  }
317 
318  const auto observation_time = ::time_utils::from_message(get_stamp(*msg_ptr));
319  const auto & observation_frame = get_frame_id(*msg_ptr);
320  const auto & map_frame = m_localizer_ptr->map_frame_id();
321 
322  try {
324  if (m_external_pose_available) {
325  // If someone set a transform and then requests a different transform, that's an error
326  if (m_external_pose.header.frame_id != map_frame ||
327  m_external_pose.child_frame_id != observation_frame)
328  {
329  throw std::runtime_error(
330  "The pose initializer's set_external_pose() "
331  "and guess() methods were called with different frames.");
332  }
333  m_external_pose_available = false;
334  initial_guess = m_external_pose;
335  initial_guess.header.stamp = get_stamp(*msg_ptr);
336  } else {
337  initial_guess =
338  m_pose_initializer.guess(m_tf_buffer, observation_time, map_frame, observation_frame);
339  }
340 
341  PoseWithCovarianceStamped pose_out;
342  const auto summary =
343  m_localizer_ptr->register_measurement(*msg_ptr, initial_guess, pose_out);
344  if (validate_output(summary, pose_out, initial_guess)) {
345  m_pose_publisher->publish(pose_out);
346  // This is to be used when no state estimator or alternative source of
347  // localization is available.
348  if (m_tf_publisher) {
349  publish_tf(pose_out);
350  // republish point cloud so visualization has no issues with the timestamp
351  // being too new (no transform yet). Reset the timestamp to zero so visualization
352  // is not bothered if odom->base_link transformation is available
353  // only at different time stamps.
354  auto msg = *msg_ptr;
355  msg.header.stamp = time_utils::to_message(tf2::TimePointZero);
356  m_obs_republisher->publish(msg);
357  }
358 
359  handle_registration_summary(summary);
360  } else {
361  on_invalid_output(pose_out);
362  }
363  } catch (...) {
364  // TODO(mitsudome-r) remove this hack in #458
365  if (m_tf_publisher && m_use_hack) {
366  republish_tf(get_stamp(*msg_ptr));
367  }
368  on_bad_registration(std::current_exception());
369  }
370  }
371 
374  void map_callback(typename MapMsgT::ConstSharedPtr msg_ptr)
375  {
376  check_localizer();
377  try {
378  m_localizer_ptr->set_map(*msg_ptr);
379  } catch (...) {
380  on_bad_map(std::current_exception());
381  }
382  }
383 
385  void publish_tf(const PoseWithCovarianceStamped & pose_msg)
386  {
387  const auto & pose = pose_msg.pose.pose;
388  tf2::Quaternion rotation{pose.orientation.x, pose.orientation.y, pose.orientation.z,
389  pose.orientation.w};
390  tf2::Vector3 translation{pose.position.x, pose.position.y, pose.position.z};
391  const tf2::Transform map_base_link_transform{rotation, translation};
392 
393  // Wait for odom to base_link transform to be available
394  bool odom_to_bl_found = m_tf_buffer.canTransform("odom", "base_link", tf2::TimePointZero);
395 
396  while (!odom_to_bl_found) {
397  RCLCPP_INFO(get_logger(), "Waiting for odom to base_link transform to be available.");
398  std::this_thread::sleep_for(std::chrono::seconds(1));
399  odom_to_bl_found = m_tf_buffer.canTransform("odom", "base_link", tf2::TimePointZero);
400  }
401 
403  try {
404  odom_tf = m_tf_buffer.lookupTransform(
405  "odom", "base_link",
406  time_utils::from_message(pose_msg.header.stamp));
407  } catch (const tf2::ExtrapolationException &) {
408  odom_tf = m_tf_buffer.lookupTransform("odom", "base_link", tf2::TimePointZero);
409  }
410  tf2::Quaternion odom_rotation{odom_tf.transform.rotation.x,
411  odom_tf.transform.rotation.y, odom_tf.transform.rotation.z, odom_tf.transform.rotation.w};
412  tf2::Vector3 odom_translation{odom_tf.transform.translation.x, odom_tf.transform.translation.y,
413  odom_tf.transform.translation.z};
414  const tf2::Transform odom_base_link_transform{odom_rotation, odom_translation};
415 
416  const auto map_odom_tf = map_base_link_transform * odom_base_link_transform.inverse();
417 
418  tf2_msgs::msg::TFMessage tf_message;
420  tf_stamped.header.stamp = pose_msg.header.stamp;
421  tf_stamped.header.frame_id = m_localizer_ptr->map_frame_id();
422  tf_stamped.child_frame_id = "odom";
423  const auto & tf_trans = map_odom_tf.getOrigin();
424  const auto & tf_rot = map_odom_tf.getRotation();
425  tf_stamped.transform.translation.set__x(tf_trans.x()).set__y(tf_trans.y()).
426  set__z(tf_trans.z());
427  tf_stamped.transform.rotation.set__x(tf_rot.x()).set__y(tf_rot.y()).set__z(tf_rot.z()).
428  set__w(tf_rot.w());
429  tf_message.transforms.push_back(tf_stamped);
430  m_tf_publisher->publish(tf_message);
431  }
432 
433  // TODO(mitsudome-r) remove this hack in #458
435  void republish_tf(builtin_interfaces::msg::Time stamp)
436  {
437  auto map_odom_tf = m_tf_buffer.lookupTransform(
438  m_localizer_ptr->map_frame_id(), "odom",
439  tf2::TimePointZero);
440  map_odom_tf.header.stamp = stamp;
441  tf2_msgs::msg::TFMessage tf_message;
442  tf_message.transforms.push_back(map_odom_tf);
443  m_tf_publisher->publish(tf_message);
444  }
445 
447  void check_localizer() const
448  {
449  if (!m_localizer_ptr) {
450  throw std::runtime_error(
451  "Localizer node needs a valid localizer to be set before it "
452  "can register measurements. Call `set_localizer(...)` first.");
453  }
454  }
455 
456  void initial_pose_callback(const typename PoseWithCovarianceStamped::ConstSharedPtr msg_ptr)
457  {
458  // The child frame is implicitly base_link.
459  // Ensure the parent frame is the map frame
460  const std::string & map_frame = m_localizer_ptr->map_frame_id();
461  if (!m_tf_buffer.canTransform(map_frame, msg_ptr->header.frame_id, tf2::TimePointZero)) {
462  RCLCPP_ERROR(
463  get_logger(),
464  "Failed to find transform from %s to %s frame. Failed to give initial pose.",
465  msg_ptr->header.frame_id, map_frame);
466  return;
467  }
468  const auto transform = m_tf_buffer.lookupTransform(
469  map_frame, msg_ptr->header.frame_id,
470  tf2::TimePointZero);
471 
472 
473  geometry_msgs::msg::TransformStamped input_pose_stamped;
474  input_pose_stamped.header = msg_ptr->header;
475  input_pose_stamped.child_frame_id = "base_link";
476  input_pose_stamped.transform.rotation = msg_ptr->pose.pose.orientation;
477  input_pose_stamped.transform.translation.x = msg_ptr->pose.pose.position.x;
478  input_pose_stamped.transform.translation.y = msg_ptr->pose.pose.position.y;
479  input_pose_stamped.transform.translation.z = msg_ptr->pose.pose.position.z;
480  geometry_msgs::msg::TransformStamped transformed_pose_stamped;
481  tf2::doTransform(input_pose_stamped, transformed_pose_stamped, transform);
482 
483  // Note: The frame_id in the result is already the map_frame, no need to set it.
484  transformed_pose_stamped.child_frame_id = "base_link";
485 
486  // For future reference: We can't write this pose to /tf here.
487  // If this message comes from RViz and we're running in simulation, RViz
488  // and data coming from LGSVL (the observations) will sometimes have very
489  // large differences in their timestamps (e.g. RViz being 40s newer).
490  // If this pose was published to /tf, it would be seen as being way in the
491  // future and the localizer couldn't use it as its next initial pose.
492  // We'd need to know the current time before it can be published, and set the
493  // time in the header to a recent time.
494  m_external_pose = transformed_pose_stamped;
495  m_external_pose_available = true;
496  }
497 
498  LocalizerBasePtr m_localizer_ptr;
499  PoseInitializerT m_pose_initializer;
500  tf2::BufferCore m_tf_buffer;
501  tf2_ros::TransformListener m_tf_listener;
502  typename rclcpp::Subscription<ObservationMsgT>::SharedPtr m_observation_sub;
503  typename rclcpp::Subscription<MapMsgT>::SharedPtr m_map_sub;
504  typename rclcpp::Publisher<PoseWithCovarianceStamped>::SharedPtr m_pose_publisher;
505  typename rclcpp::Publisher<tf2_msgs::msg::TFMessage>::SharedPtr m_tf_publisher{nullptr};
506  typename rclcpp::Publisher<ObservationMsgT>::SharedPtr m_obs_republisher{
507  create_publisher<ObservationMsgT>("observation_republish", 10)};
508 
509  // Receive updates from "/initialpose" (e.g. rviz2)
510  typename rclcpp::Subscription<PoseWithCovarianceStamped>::SharedPtr m_initial_pose_sub;
511  // Stores "/initialpose", the timestamp is not used/valid
512  geometry_msgs::msg::TransformStamped m_external_pose;
513  bool m_external_pose_available{false};
514 
515  bool m_use_hack{false};
516 };
517 } // namespace localization_nodes
518 } // namespace localization
519 } // namespace autoware
520 #endif // LOCALIZATION_NODES__LOCALIZATION_NODE_HPP_
autoware::localization::localization_nodes::LocalizerPublishMode
LocalizerPublishMode
Enum to specify if the localizer node must publish to /tf topic or not.
Definition: localization_node.hpp:51
autoware::localization::localization_nodes::RelativeLocalizerNode::validate_output
virtual bool validate_output(const RegistrationSummary &summary, const PoseWithCovarianceStamped &pose, const TransformStamped &guess)
Definition: localization_node.hpp:263
time_utils::to_message
TIME_UTILS_PUBLIC builtin_interfaces::msg::Time to_message(std::chrono::system_clock::time_point t)
Convert from std::chrono::time_point to time message.
Definition: time_utils.cpp:71
motion::motion_testing_nodes::TFMessage
tf2_msgs::msg::TFMessage TFMessage
Definition: motion_testing_publisher.hpp:34
autoware::localization::localization_nodes::TopicQoS::qos
rclcpp::QoS qos
Definition: localization_node.hpp:47
autoware::localization::localization_nodes::TopicQoS::topic
std::string topic
Definition: localization_node.hpp:46
autoware::common::helper_functions::message_field_adapters::get_stamp
const TimeStamp & get_stamp(const T &msg) noexcept
Definition: message_adapters.hpp:101
autoware::localization::localization_nodes::TopicQoS
Helper struct that groups topic name and QoS setting for a publisher or subscription.
Definition: localization_node.hpp:44
localizer_base.hpp
autoware::localization::localization_nodes::LocalizerPublishMode::NO_PUBLISH_TF
@ NO_PUBLISH_TF
autoware::localization::localization_nodes::RelativeLocalizerNode< sensor_msgs::msg::PointCloud2, sensor_msgs::msg::PointCloud2, ndt::P2DNDTLocalizer< Optimizer_ >, PoseInitializer_ >::PoseWithCovarianceStamped
typename LocalizerBase::PoseWithCovarianceStamped PoseWithCovarianceStamped
Definition: localization_node.hpp:72
autoware::localization::localization_nodes::RelativeLocalizerNode::get_publisher
const rclcpp::Publisher< PoseWithCovarianceStamped >::ConstSharedPtr get_publisher()
Get a const pointer of the output publisher. Can be used for matching against subscriptions.
Definition: localization_node.hpp:200
autoware::localization::localization_common::RelativeLocalizerBase::PoseWithCovarianceStamped
geometry_msgs::msg::PoseWithCovarianceStamped PoseWithCovarianceStamped
Definition: localizer_base.hpp:61
autoware::localization::localization_nodes::RelativeLocalizerNode::on_exception
void on_exception(std::exception_ptr eptr, const std::string &error_source)
Definition: localization_node.hpp:225
autoware::localization::localization_nodes::RelativeLocalizerNode::RelativeLocalizerNode
RelativeLocalizerNode(const std::string &node_name, const std::string &name_space, const TopicQoS &observation_sub_config, const TopicQoS &map_sub_config, const TopicQoS &pose_pub_config, const TopicQoS &initial_pose_sub_config, const PoseInitializerT &pose_initializer, LocalizerPublishMode publish_tf=LocalizerPublishMode::NO_PUBLISH_TF)
Definition: localization_node.hpp:86
initialization.hpp
autoware::localization::localization_nodes::RelativeLocalizerNode
Definition: localization_node.hpp:65
message_adapters.hpp
This file includes common helper functions.
autoware::localization::localization_nodes::RelativeLocalizerNode::on_bad_map
virtual void on_bad_map(std::exception_ptr eptr)
Handle the exceptions during map setting.
Definition: localization_node.hpp:220
autoware::localization::localization_nodes::RelativeLocalizerNode::on_observation_with_invalid_map
virtual void on_observation_with_invalid_map(typename ObservationMsgT::ConstSharedPtr)
Default behavior when an observation is received with no valid existing map.
Definition: localization_node.hpp:239
autoware::common::helper_functions::message_field_adapters::get_frame_id
const std::string & get_frame_id(const T &msg) noexcept
Definition: message_adapters.hpp:83
autoware::localization::localization_nodes::RelativeLocalizerNode< sensor_msgs::msg::PointCloud2, sensor_msgs::msg::PointCloud2, ndt::P2DNDTLocalizer< Optimizer_ >, PoseInitializer_ >::RegistrationSummary
typename ndt::P2DNDTLocalizer< Optimizer_ > ::RegistrationSummary RegistrationSummary
Definition: localization_node.hpp:74
autoware
This file defines the lanelet2_map_provider_node class.
Definition: quick_sort.hpp:24
visibility_control.hpp
motion::planning::recordreplay_planner_nodes::Transform
geometry_msgs::msg::TransformStamped Transform
Definition: recordreplay_planner_node.hpp:56
motion::motion_testing_nodes::TransformStamped
geometry_msgs::msg::TransformStamped TransformStamped
Definition: motion_testing_publisher.hpp:37
time_utils::from_message
TIME_UTILS_PUBLIC std::chrono::system_clock::time_point from_message(builtin_interfaces::msg::Time t) noexcept
Convert from std::chrono::time_point from time message.
Definition: time_utils.cpp:84
autoware::localization::localization_nodes::RelativeLocalizerNode< sensor_msgs::msg::PointCloud2, sensor_msgs::msg::PointCloud2, ndt::P2DNDTLocalizer< Optimizer_ >, PoseInitializer_ >::LocalizerBasePtr
std::unique_ptr< LocalizerBase > LocalizerBasePtr
Definition: localization_node.hpp:70
autoware::localization::localization_nodes::RelativeLocalizerNode::on_invalid_output
virtual void on_invalid_output(PoseWithCovarianceStamped &pose)
Definition: localization_node.hpp:248
autoware::localization::localization_nodes::LocalizerPublishMode::PUBLISH_TF
@ PUBLISH_TF
autoware::localization::localization_nodes::RelativeLocalizerNode< sensor_msgs::msg::PointCloud2, sensor_msgs::msg::PointCloud2, ndt::P2DNDTLocalizer< Optimizer_ >, PoseInitializer_ >::TransformStamped
typename LocalizerBase::Transform TransformStamped
Definition: localization_node.hpp:73
time_utils.hpp
autoware::localization::localization_nodes::RelativeLocalizerNode::RelativeLocalizerNode
RelativeLocalizerNode(const std::string &node_name, const std::string &name_space, const PoseInitializerT &pose_initializer)
Definition: localization_node.hpp:163
autoware::localization::localization_nodes::RelativeLocalizerNode::on_bad_registration
virtual void on_bad_registration(std::exception_ptr eptr)
Handle the exceptions during registration.
Definition: localization_node.hpp:214
autoware::localization::localization_common::RelativeLocalizerBase
Definition: localizer_base.hpp:58
autoware::localization::localization_nodes::RelativeLocalizerNode::set_localizer
void set_localizer(LocalizerBasePtr &&localizer_ptr)
Definition: localization_node.hpp:208
tf2::doTransform
void doTransform(const geometry_msgs::msg::Point32 &t_in, geometry_msgs::msg::Point32 &t_out, const geometry_msgs::msg::TransformStamped &transform)
Apply a geometry_msgs TransformStamped to an geometry_msgs Point32 type. This function is a specializ...
Definition: tf2_autoware_auto_msgs.hpp:54
autoware::localization::localization_nodes::RelativeLocalizerNode::RelativeLocalizerNode
RelativeLocalizerNode(const std::string &node_name, const rclcpp::NodeOptions &options, const PoseInitializerT &pose_initializer)
Definition: localization_node.hpp:122
autoware::localization::localization_nodes::RelativeLocalizerNode< sensor_msgs::msg::PointCloud2, sensor_msgs::msg::PointCloud2, ndt::P2DNDTLocalizer< Optimizer_ >, PoseInitializer_ >::Cloud
sensor_msgs::msg::PointCloud2 Cloud
Definition: localization_node.hpp:71