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

fixed timestamps input&output not synchronized #377

Merged
merged 6 commits into from
Apr 16, 2021
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 include/slam_toolbox/slam_toolbox_common.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -138,6 +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;
int throttle_scans_;

double resolution_;
Expand Down
2 changes: 2 additions & 0 deletions src/experimental/slam_toolbox_lifelong.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -83,6 +83,8 @@ void LifelongSlamToolbox::laserCallback(
sensor_msgs::msg::LaserScan::ConstSharedPtr scan)
/*****************************************************************************/
{
// store scan timestamped
scan_timestamped = scan->header.stamp;
// no odom info
Pose2 pose;
if (!pose_helper_->getOdomPose(pose, scan->header.stamp)) {
Expand Down
2 changes: 2 additions & 0 deletions src/slam_toolbox_async.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -35,6 +35,8 @@ void AsynchronousSlamToolbox::laserCallback(
sensor_msgs::msg::LaserScan::ConstSharedPtr scan)
/*****************************************************************************/
{
// store scan timestamped
scan_timestamped = scan->header.stamp;
// no odom info
Pose2 pose;
if (!pose_helper_->getOdomPose(pose, scan->header.stamp)) {
Expand Down
10 changes: 5 additions & 5 deletions src/slam_toolbox_common.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -40,7 +40,7 @@ SlamToolbox::SlamToolbox(rclcpp::NodeOptions options)
processor_type_(PROCESS),
first_measurement_(true),
process_near_pose_(nullptr),
transform_timeout_(rclcpp::Duration::from_nanoseconds(0.5 * 1000000000)),
transform_timeout_(rclcpp::Duration::from_seconds(0.5)),
minimum_time_interval_(std::chrono::nanoseconds(0))
/*****************************************************************************/
{
Expand Down Expand Up @@ -151,9 +151,9 @@ void SlamToolbox::setParams()

double tmp_val = 0.5;
tmp_val = this->declare_parameter("transform_timeout", tmp_val);
transform_timeout_ = rclcpp::Duration::from_nanoseconds(tmp_val * 1000000000);
transform_timeout_ = rclcpp::Duration::from_seconds(tmp_val);
tmp_val = this->declare_parameter("minimum_time_interval", tmp_val);
minimum_time_interval_ = rclcpp::Duration::from_nanoseconds(tmp_val * 1000000000);
minimum_time_interval_ = rclcpp::Duration::from_seconds(tmp_val);

bool debug = false;
debug = this->declare_parameter("debug_logging", debug);
Expand Down Expand Up @@ -231,7 +231,7 @@ void SlamToolbox::publishTransformLoop(
msg.transform = tf2::toMsg(map_to_odom_);
msg.child_frame_id = odom_frame_;
msg.header.frame_id = map_frame_;
msg.header.stamp = this->now() + transform_timeout_;
msg.header.stamp = scan_timestamped + transform_timeout_;
tfB_->sendTransform(msg);
}
r.sleep();
Expand Down Expand Up @@ -372,7 +372,7 @@ bool SlamToolbox::updateMap()
vis_utils::toNavMap(occ_grid, map_.map);

// publish map as current
map_.map.header.stamp = this->now();
map_.map.header.stamp = scan_timestamped;
sst_->publish(
std::move(std::make_unique<nav_msgs::msg::OccupancyGrid>(map_.map)));
sstm_->publish(
Expand Down
2 changes: 2 additions & 0 deletions src/slam_toolbox_localization.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -118,6 +118,8 @@ void LocalizationSlamToolbox::laserCallback(
sensor_msgs::msg::LaserScan::ConstSharedPtr scan)
/*****************************************************************************/
{
// store scan timestamped
scan_timestamped = scan->header.stamp;
// no odom info
Pose2 pose;
if (!pose_helper_->getOdomPose(pose, scan->header.stamp)) {
Expand Down
2 changes: 2 additions & 0 deletions src/slam_toolbox_sync.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -65,6 +65,8 @@ void SynchronousSlamToolbox::laserCallback(
sensor_msgs::msg::LaserScan::ConstSharedPtr scan)
/*****************************************************************************/
{
// store scan timestamped
scan_timestamped = scan->header.stamp;
// no odom info
Pose2 pose;
if (!pose_helper_->getOdomPose(pose, scan->header.stamp)) {
Expand Down