Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
2 changes: 1 addition & 1 deletion include/slam_toolbox/slam_toolbox_common.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -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_;
Expand Down
4 changes: 2 additions & 2 deletions src/experimental/slam_toolbox_lifelong.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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)) {
Expand Down
4 changes: 2 additions & 2 deletions src/slam_toolbox_async.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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)) {
Expand Down
18 changes: 11 additions & 7 deletions src/slam_toolbox_common.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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();
}
Expand Down Expand Up @@ -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<nav_msgs::msg::OccupancyGrid>(map_.map)));
sstm_->publish(
Expand Down
4 changes: 2 additions & 2 deletions src/slam_toolbox_localization.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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)) {
Expand Down
4 changes: 2 additions & 2 deletions src/slam_toolbox_sync.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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)) {
Expand Down