diff --git a/include/slam_toolbox/slam_toolbox_common.hpp b/include/slam_toolbox/slam_toolbox_common.hpp index 9274ba545..1f98e78f0 100644 --- a/include/slam_toolbox/slam_toolbox_common.hpp +++ b/include/slam_toolbox/slam_toolbox_common.hpp @@ -138,7 +138,7 @@ class SlamToolbox : public rclcpp::Node // Storage for ROS parameters std::string odom_frame_, map_frame_, base_frame_, map_name_, scan_topic_; rclcpp::Duration transform_timeout_, minimum_time_interval_; - rclcpp::Time scan_timestamped; + std_msgs::msg::Header scan_header; int throttle_scans_; double resolution_; diff --git a/src/experimental/slam_toolbox_lifelong.cpp b/src/experimental/slam_toolbox_lifelong.cpp index a56dc59ca..8d74a0f76 100644 --- a/src/experimental/slam_toolbox_lifelong.cpp +++ b/src/experimental/slam_toolbox_lifelong.cpp @@ -83,8 +83,8 @@ void LifelongSlamToolbox::laserCallback( sensor_msgs::msg::LaserScan::ConstSharedPtr scan) /*****************************************************************************/ { - // store scan timestamped - scan_timestamped = scan->header.stamp; + // store scan header + scan_header = scan->header; // no odom info Pose2 pose; if (!pose_helper_->getOdomPose(pose, scan->header.stamp)) { diff --git a/src/slam_toolbox_async.cpp b/src/slam_toolbox_async.cpp index 3ef1fa84a..ea2a2e879 100644 --- a/src/slam_toolbox_async.cpp +++ b/src/slam_toolbox_async.cpp @@ -35,8 +35,8 @@ void AsynchronousSlamToolbox::laserCallback( sensor_msgs::msg::LaserScan::ConstSharedPtr scan) /*****************************************************************************/ { - // store scan timestamped - scan_timestamped = scan->header.stamp; + // store scan header + scan_header = scan->header; // no odom info Pose2 pose; if (!pose_helper_->getOdomPose(pose, scan->header.stamp)) { diff --git a/src/slam_toolbox_common.cpp b/src/slam_toolbox_common.cpp index b50cbedd0..6d6095e07 100644 --- a/src/slam_toolbox_common.cpp +++ b/src/slam_toolbox_common.cpp @@ -227,12 +227,16 @@ void SlamToolbox::publishTransformLoop( while (rclcpp::ok()) { { boost::mutex::scoped_lock lock(map_to_odom_mutex_); - geometry_msgs::msg::TransformStamped msg; - msg.transform = tf2::toMsg(map_to_odom_); - msg.child_frame_id = odom_frame_; - msg.header.frame_id = map_frame_; - msg.header.stamp = scan_timestamped + transform_timeout_; - tfB_->sendTransform(msg); + rclcpp::Time scan_timestamp = scan_header.stamp; + // Avoid publishing tf with initial 0.0 scan timestamp + if (scan_timestamp.seconds() > 0.0 && !scan_header.frame_id.empty()) { + geometry_msgs::msg::TransformStamped msg; + msg.transform = tf2::toMsg(map_to_odom_); + msg.child_frame_id = odom_frame_; + msg.header.frame_id = map_frame_; + msg.header.stamp = scan_timestamp + transform_timeout_; + tfB_->sendTransform(msg); + } } r.sleep(); } @@ -372,7 +376,7 @@ bool SlamToolbox::updateMap() vis_utils::toNavMap(occ_grid, map_.map); // publish map as current - map_.map.header.stamp = scan_timestamped; + map_.map.header.stamp = scan_header.stamp; sst_->publish( std::move(std::make_unique(map_.map))); sstm_->publish( diff --git a/src/slam_toolbox_localization.cpp b/src/slam_toolbox_localization.cpp index e8dfbf6b9..f20baa3bf 100644 --- a/src/slam_toolbox_localization.cpp +++ b/src/slam_toolbox_localization.cpp @@ -118,8 +118,8 @@ void LocalizationSlamToolbox::laserCallback( sensor_msgs::msg::LaserScan::ConstSharedPtr scan) /*****************************************************************************/ { - // store scan timestamped - scan_timestamped = scan->header.stamp; + // store scan header + scan_header = scan->header; // no odom info Pose2 pose; if (!pose_helper_->getOdomPose(pose, scan->header.stamp)) { diff --git a/src/slam_toolbox_sync.cpp b/src/slam_toolbox_sync.cpp index b2fcd135e..47a39ff28 100644 --- a/src/slam_toolbox_sync.cpp +++ b/src/slam_toolbox_sync.cpp @@ -65,8 +65,8 @@ void SynchronousSlamToolbox::laserCallback( sensor_msgs::msg::LaserScan::ConstSharedPtr scan) /*****************************************************************************/ { - // store scan timestamped - scan_timestamped = scan->header.stamp; + // store scan header + scan_header = scan->header; // no odom info Pose2 pose; if (!pose_helper_->getOdomPose(pose, scan->header.stamp)) {