17 #ifndef LOCALIZATION_NODES__LOCALIZATION_NODE_HPP_
18 #define LOCALIZATION_NODES__LOCALIZATION_NODE_HPP_
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>
36 namespace localization
38 namespace localization_nodes
63 template<
typename ObservationMsgT,
typename MapMsgT,
typename LocalizerT,
64 typename PoseInitializerT>
69 typename LocalizerT::RegistrationSummary>;
71 using Cloud = sensor_msgs::msg::PointCloud2;
87 const std::string & node_name,
const std::string & name_space,
88 const TopicQoS & observation_sub_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);})),
102 create_subscription<MapMsgT>(
103 map_sub_config.topic, map_sub_config.qos,
104 [
this](
typename MapMsgT::ConstSharedPtr msg) {map_callback(msg);})),
106 create_publisher<PoseWithCovarianceStamped>(
107 pose_pub_config.topic,
108 pose_pub_config.qos)),
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);
116 m_tf_publisher = create_publisher<tf2_msgs::msg::TFMessage>(
"/tf", pose_pub_config.qos);
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>(
131 rclcpp::QoS{rclcpp::KeepLast{
132 static_cast<size_t>(declare_parameter(
"observation_sub.history_depth").template
134 [
this](
typename ObservationMsgT::ConstSharedPtr msg) {observation_callback(msg);})),
136 create_subscription<MapMsgT>(
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);})),
143 create_publisher<PoseWithCovarianceStamped>(
145 rclcpp::QoS{rclcpp::KeepLast{
146 static_cast<size_t>(declare_parameter(
147 "pose_pub.history_depth").template get<size_t>())}})),
149 create_subscription<PoseWithCovarianceStamped>(
151 rclcpp::QoS{rclcpp::KeepLast{10}},
152 [
this](
const typename PoseWithCovarianceStamped::ConstSharedPtr msg) {
153 initial_pose_callback(msg);
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>(
171 rclcpp::QoS{rclcpp::KeepLast{
172 static_cast<size_t>(declare_parameter(
"observation_sub.history_depth").template
174 [
this](
typename ObservationMsgT::ConstSharedPtr msg) {observation_callback(msg);})),
176 create_subscription<MapMsgT>(
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);})),
183 create_publisher<PoseWithCovarianceStamped>(
185 rclcpp::QoS{rclcpp::KeepLast{
186 static_cast<size_t>(declare_parameter(
187 "pose_pub.history_depth").template get<size_t>())}})),
189 create_subscription<PoseWithCovarianceStamped>(
191 rclcpp::QoS{rclcpp::KeepLast{10}},
192 [
this](
const typename PoseWithCovarianceStamped::ConstSharedPtr msg) {
193 initial_pose_callback(msg);
200 const typename rclcpp::Publisher<PoseWithCovarianceStamped>::ConstSharedPtr
get_publisher()
202 return m_pose_publisher;
210 m_localizer_ptr = std::forward<LocalizerBasePtr>(localizer_ptr);
216 on_exception(eptr,
"on_bad_registration");
222 on_exception(eptr,
"on_bad_map");
225 void on_exception(std::exception_ptr eptr,
const std::string & error_source)
229 std::rethrow_exception(eptr);
231 RCLCPP_ERROR(get_logger(), error_source +
": error nullptr");
233 }
catch (
const std::exception & e) {
234 RCLCPP_ERROR(get_logger(), e.what());
242 get_logger(),
"Received observation without a valid map, "
243 "ignoring the observation.");
252 get_logger(),
"Relative localizer has an invalid pose estimate. "
253 "The result is ignored.");
276 if (declare_parameter(
"publish_tf").
template get<bool>()) {
277 m_tf_publisher = create_publisher<tf2_msgs::msg::TFMessage>(
279 rclcpp::QoS{rclcpp::KeepLast{m_pose_publisher->get_queue_size()}});
282 if (declare_parameter(
"init_hack.enabled",
false)) {
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;
306 virtual void handle_registration_summary(
const RegistrationSummary &) {}
310 void observation_callback(
typename ObservationMsgT::ConstSharedPtr msg_ptr)
313 if (!m_localizer_ptr->map_valid()) {
314 on_observation_with_invalid_map(msg_ptr);
319 const auto & observation_frame =
get_frame_id(*msg_ptr);
320 const auto & map_frame = m_localizer_ptr->map_frame_id();
324 if (m_external_pose_available) {
326 if (m_external_pose.header.frame_id != map_frame ||
327 m_external_pose.child_frame_id != observation_frame)
329 throw std::runtime_error(
330 "The pose initializer's set_external_pose() "
331 "and guess() methods were called with different frames.");
333 m_external_pose_available =
false;
334 initial_guess = m_external_pose;
335 initial_guess.header.stamp =
get_stamp(*msg_ptr);
338 m_pose_initializer.guess(m_tf_buffer, observation_time, map_frame, observation_frame);
341 PoseWithCovarianceStamped pose_out;
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);
348 if (m_tf_publisher) {
349 publish_tf(pose_out);
356 m_obs_republisher->publish(msg);
359 handle_registration_summary(summary);
361 on_invalid_output(pose_out);
365 if (m_tf_publisher && m_use_hack) {
368 on_bad_registration(std::current_exception());
374 void map_callback(
typename MapMsgT::ConstSharedPtr msg_ptr)
378 m_localizer_ptr->set_map(*msg_ptr);
380 on_bad_map(std::current_exception());
385 void publish_tf(
const PoseWithCovarianceStamped & pose_msg)
387 const auto & pose = pose_msg.pose.pose;
388 tf2::Quaternion rotation{pose.orientation.x, pose.orientation.y, pose.orientation.z,
390 tf2::Vector3 translation{pose.position.x, pose.position.y, pose.position.z};
391 const tf2::Transform map_base_link_transform{rotation, translation};
394 bool odom_to_bl_found = m_tf_buffer.canTransform(
"odom",
"base_link", tf2::TimePointZero);
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);
404 odom_tf = m_tf_buffer.lookupTransform(
407 }
catch (
const tf2::ExtrapolationException &) {
408 odom_tf = m_tf_buffer.lookupTransform(
"odom",
"base_link", tf2::TimePointZero);
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};
416 const auto map_odom_tf = map_base_link_transform * odom_base_link_transform.inverse();
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()).
429 tf_message.transforms.push_back(tf_stamped);
430 m_tf_publisher->publish(tf_message);
435 void republish_tf(builtin_interfaces::msg::Time stamp)
437 auto map_odom_tf = m_tf_buffer.lookupTransform(
438 m_localizer_ptr->map_frame_id(),
"odom",
440 map_odom_tf.header.stamp = stamp;
442 tf_message.transforms.push_back(map_odom_tf);
443 m_tf_publisher->publish(tf_message);
447 void check_localizer()
const
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.");
456 void initial_pose_callback(
const typename PoseWithCovarianceStamped::ConstSharedPtr msg_ptr)
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)) {
464 "Failed to find transform from %s to %s frame. Failed to give initial pose.",
465 msg_ptr->header.frame_id, map_frame);
468 const auto transform = m_tf_buffer.lookupTransform(
469 map_frame, msg_ptr->header.frame_id,
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;
484 transformed_pose_stamped.child_frame_id =
"base_link";
494 m_external_pose = transformed_pose_stamped;
495 m_external_pose_available =
true;
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)};
510 typename rclcpp::Subscription<PoseWithCovarianceStamped>::SharedPtr m_initial_pose_sub;
513 bool m_external_pose_available{
false};
515 bool m_use_hack{
false};
520 #endif // LOCALIZATION_NODES__LOCALIZATION_NODE_HPP_