Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

cherry pick (#377) (#479) #1

Merged
merged 1 commit into from
Nov 8, 2023
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
1 change: 1 addition & 0 deletions slam_toolbox/include/slam_toolbox/slam_toolbox_common.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -113,6 +113,7 @@ class SlamToolbox
std::string odom_frame_, map_frame_, base_frame_, map_name_, scan_topic_;
ros::Duration transform_timeout_, tf_buffer_dur_, minimum_time_interval_;
int throttle_scans_;
std_msgs::Header scan_header_;

double resolution_;
double position_covariance_scale_;
Expand Down
1 change: 1 addition & 0 deletions slam_toolbox/src/experimental/slam_toolbox_lifelong.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -69,6 +69,7 @@ void LifelongSlamToolbox::laserCallback(
const sensor_msgs::LaserScan::ConstPtr& scan)
/*****************************************************************************/
{
scan_header_ = scan->header;
// no odom info
Pose2 pose;
if(!pose_helper_->getOdomPose(pose, scan->header.stamp))
Expand Down
1 change: 1 addition & 0 deletions slam_toolbox/src/slam_toolbox_async.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -35,6 +35,7 @@ void AsynchronousSlamToolbox::laserCallback(
const sensor_msgs::LaserScan::ConstPtr& scan)
/*****************************************************************************/
{
scan_header_ = scan->header;
// no odom info
karto::Pose2 pose;
if(!pose_helper_->getOdomPose(pose, scan->header.stamp))
Expand Down
17 changes: 10 additions & 7 deletions slam_toolbox/src/slam_toolbox_common.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -176,12 +176,15 @@ void SlamToolbox::publishTransformLoop(const double& transform_publish_period)
{
{
boost::mutex::scoped_lock lock(map_to_odom_mutex_);
geometry_msgs::TransformStamped msg;
tf2::convert(map_to_odom_, msg.transform);
msg.child_frame_id = odom_frame_;
msg.header.frame_id = map_frame_;
msg.header.stamp = ros::Time::now() + transform_timeout_;
tfB_->sendTransform(msg);
if(scan_header_.stamp.toSec() > 0.0 && !scan_header_.frame_id.empty()) {
geometry_msgs::TransformStamped msg;
tf2::convert(map_to_odom_, msg.transform);
msg.child_frame_id = odom_frame_;
msg.header.frame_id = map_frame_;
//TODO: why transform_timeout_ is here?
msg.header.stamp = scan_header_.stamp + transform_timeout_;
tfB_->sendTransform(msg);
}
}
r.sleep();
}
Expand Down Expand Up @@ -327,7 +330,7 @@ bool SlamToolbox::updateMap()
vis_utils::toNavMap(occ_grid, map_.map);

// publish map as current
map_.map.header.stamp = ros::Time::now();
map_.map.header.stamp = scan_header_.stamp;
sst_.publish(map_.map);
sstm_.publish(map_.map.info);

Expand Down
1 change: 1 addition & 0 deletions slam_toolbox/src/slam_toolbox_localization.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -104,6 +104,7 @@ void LocalizationSlamToolbox::laserCallback(
const sensor_msgs::LaserScan::ConstPtr& scan)
/*****************************************************************************/
{
scan_header_ = scan->header;
// no odom info
Pose2 pose;
if(!pose_helper_->getOdomPose(pose, scan->header.stamp))
Expand Down
1 change: 1 addition & 0 deletions slam_toolbox/src/slam_toolbox_sync.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -78,6 +78,7 @@ void SynchronousSlamToolbox::laserCallback(
const sensor_msgs::LaserScan::ConstPtr& scan)
/*****************************************************************************/
{
scan_header_ = scan->header;
// no odom info
karto::Pose2 pose;
if(!pose_helper_->getOdomPose(pose, scan->header.stamp))
Expand Down