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

Replace TF message filter with explicit canTransform checks (ros2) #518

Open
wants to merge 1 commit into
base: ros2
Choose a base branch
from
Open
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
6 changes: 2 additions & 4 deletions include/slam_toolbox/slam_toolbox_common.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -30,11 +30,9 @@
#include <fstream>

#include "rclcpp/rclcpp.hpp"
#include "message_filters/subscriber.h"
#include "tf2_ros/transform_broadcaster.h"
#include "tf2_ros/transform_listener.h"
#include "tf2_ros/create_timer_ros.h"
#include "tf2_ros/message_filter.h"
#include "tf2/LinearMath/Matrix3x3.h"
#include "tf2_geometry_msgs/tf2_geometry_msgs.hpp"
#include "tf2_sensor_msgs/tf2_sensor_msgs.hpp"
Expand Down Expand Up @@ -100,6 +98,7 @@ class SlamToolbox : public rclcpp::Node
karto::Pose2 & karto_pose);
karto::LocalizedRangeScan * addScan(karto::LaserRangeFinder * laser, PosedScan & scanWPose);
bool updateMap();
bool waitForTransform(const std::string& scan_frame, const rclcpp::Time& stamp);
tf2::Stamped<tf2::Transform> setTransformFromPoses(
const karto::Pose2 & pose,
const karto::Pose2 & karto_pose, const rclcpp::Time & t,
Expand Down Expand Up @@ -130,8 +129,7 @@ class SlamToolbox : public rclcpp::Node
std::unique_ptr<tf2_ros::Buffer> tf_;
std::unique_ptr<tf2_ros::TransformListener> tfL_;
std::unique_ptr<tf2_ros::TransformBroadcaster> tfB_;
std::unique_ptr<message_filters::Subscriber<sensor_msgs::msg::LaserScan>> scan_filter_sub_;
std::unique_ptr<tf2_ros::MessageFilter<sensor_msgs::msg::LaserScan>> scan_filter_;
rclcpp::Subscription<sensor_msgs::msg::LaserScan>::SharedPtr scan_sub_;
std::shared_ptr<rclcpp::Publisher<nav_msgs::msg::OccupancyGrid>> sst_;
std::shared_ptr<rclcpp::Publisher<nav_msgs::msg::MapMetaData>> sstm_;
std::shared_ptr<rclcpp::Publisher<geometry_msgs::msg::PoseWithCovarianceStamped>> pose_pub_;
Expand Down
4 changes: 4 additions & 0 deletions src/experimental/slam_toolbox_lifelong.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -83,6 +83,10 @@ void LifelongSlamToolbox::laserCallback(
sensor_msgs::msg::LaserScan::ConstSharedPtr scan)
/*****************************************************************************/
{
if (!waitForTransform(scan->header.frame_id, scan->header.stamp)) {
return;
}

// store scan header
scan_header = scan->header;
// no odom info
Expand Down
4 changes: 4 additions & 0 deletions src/slam_toolbox_async.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -35,6 +35,10 @@ void AsynchronousSlamToolbox::laserCallback(
sensor_msgs::msg::LaserScan::ConstSharedPtr scan)
/*****************************************************************************/
{
if (!waitForTransform(scan->header.frame_id, scan->header.stamp)) {
return;
}

// store scan header
scan_header = scan->header;
// no odom info
Expand Down
35 changes: 26 additions & 9 deletions src/slam_toolbox_common.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -212,15 +212,9 @@ void SlamToolbox::setROSInterfaces()
std::bind(&SlamToolbox::deserializePoseGraphCallback, this,
std::placeholders::_1, std::placeholders::_2, std::placeholders::_3));

scan_filter_sub_ =
std::make_unique<message_filters::Subscriber<sensor_msgs::msg::LaserScan>>(
shared_from_this().get(), scan_topic_, rmw_qos_profile_sensor_data);
scan_filter_ =
std::make_unique<tf2_ros::MessageFilter<sensor_msgs::msg::LaserScan>>(
*scan_filter_sub_, *tf_, odom_frame_, 1, shared_from_this(),
tf2::durationFromSec(transform_timeout_.seconds()));
scan_filter_->registerCallback(
std::bind(&SlamToolbox::laserCallback, this, std::placeholders::_1));
scan_sub_ = create_subscription<sensor_msgs::msg::LaserScan>(
scan_topic_,
rclcpp::SensorDataQoS().keep_last(1), std::bind(&SlamToolbox::laserCallback, this, std::placeholders::_1));
}

/*****************************************************************************/
Expand Down Expand Up @@ -396,6 +390,29 @@ bool SlamToolbox::updateMap()
return true;
}

/*****************************************************************************/
bool SlamToolbox::waitForTransform(const std::string& scan_frame, const rclcpp::Time& stamp)
/*****************************************************************************/
{
if (!tf_->_frameExists(odom_frame_)) {
RCLCPP_WARN_THROTTLE(get_logger(), *get_clock(), 2000, "tf frame [%s] doesn't exist yet.'", odom_frame_.c_str());
return false;
}

if (!tf_->_frameExists(scan_frame)) {
RCLCPP_WARN_THROTTLE(get_logger(), *get_clock(), 2000, "tf frame [%s] doesn't exist yet.'", scan_frame.c_str());
return false;
}

if (!tf_->canTransform(odom_frame_, scan_frame, stamp, transform_timeout_)) {
RCLCPP_WARN(get_logger(), "Failed to get transform %s -> %s.", scan_frame.c_str(), odom_frame_.c_str());
return false;
}

return true;
}


/*****************************************************************************/
tf2::Stamped<tf2::Transform> SlamToolbox::setTransformFromPoses(
const Pose2 & corrected_pose,
Expand Down
4 changes: 4 additions & 0 deletions src/slam_toolbox_localization.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -118,6 +118,10 @@ void LocalizationSlamToolbox::laserCallback(
sensor_msgs::msg::LaserScan::ConstSharedPtr scan)
/*****************************************************************************/
{
if (!waitForTransform(scan->header.frame_id, scan->header.stamp)) {
return;
}

// store scan header
scan_header = scan->header;
// no odom info
Expand Down
4 changes: 4 additions & 0 deletions src/slam_toolbox_sync.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -65,6 +65,10 @@ void SynchronousSlamToolbox::laserCallback(
sensor_msgs::msg::LaserScan::ConstSharedPtr scan)
/*****************************************************************************/
{
if (!waitForTransform(scan->header.frame_id, scan->header.stamp)) {
return;
}

// store scan header
scan_header = scan->header;
// no odom info
Expand Down