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

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
7 changes: 7 additions & 0 deletions nav2_amcl/include/nav2_amcl/amcl_node.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -29,6 +29,7 @@
#include <vector>

#include "message_filters/subscriber.hpp"
#include "rclcpp/version.h"

#include "geometry_msgs/msg/pose_stamped.hpp"
#include "nav2_util/lifecycle_node.hpp"
Expand Down Expand Up @@ -171,8 +172,14 @@ class AmclNode : public nav2_util::LifecycleNode
* @brief Initialize incoming data message subscribers and filters
*/
void initMessageFilters();

// To Support Kilted and Older from Message Filters API change
#if RCLCPP_VERSION_GTE(29, 6, 0)
std::unique_ptr<message_filters::Subscriber<sensor_msgs::msg::LaserScan>> laser_scan_sub_;
#else
std::unique_ptr<message_filters::Subscriber<sensor_msgs::msg::LaserScan,
rclcpp_lifecycle::LifecycleNode>> laser_scan_sub_;
#endif
std::unique_ptr<tf2_ros::MessageFilter<sensor_msgs::msg::LaserScan>> laser_scan_filter_;
message_filters::Connection laser_scan_connection_;

Expand Down
6 changes: 6 additions & 0 deletions nav2_amcl/src/amcl_node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1523,9 +1523,15 @@ AmclNode::initMessageFilters()
{
auto sub_opt = rclcpp::SubscriptionOptions();
sub_opt.callback_group = callback_group_;

#if RCLCPP_VERSION_GTE(29, 6, 0)
laser_scan_sub_ = std::make_unique<message_filters::Subscriber<sensor_msgs::msg::LaserScan>>(
shared_from_this(), scan_topic_, rclcpp::SensorDataQoS(), sub_opt);
#else
laser_scan_sub_ = std::make_unique<message_filters::Subscriber<sensor_msgs::msg::LaserScan,
rclcpp_lifecycle::LifecycleNode>>(
shared_from_this(), scan_topic_, rmw_qos_profile_sensor_data, sub_opt);
#endif

laser_scan_filter_ = std::make_unique<tf2_ros::MessageFilter<sensor_msgs::msg::LaserScan>>(
*laser_scan_sub_, *tf_buffer_, odom_frame_id_, 10,
Expand Down
6 changes: 6 additions & 0 deletions nav2_costmap_2d/include/nav2_costmap_2d/obstacle_layer.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -43,6 +43,7 @@
#include <vector>

#include "rclcpp/rclcpp.hpp"
#include "rclcpp/version.h"
#include "laser_geometry/laser_geometry.hpp"
#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wreorder"
Expand Down Expand Up @@ -234,8 +235,13 @@ class ObstacleLayer : public CostmapLayer
/// @brief Used to project laser scans into point clouds
laser_geometry::LaserProjection projector_;
/// @brief Used for the observation message filters
#if RCLCPP_VERSION_GTE(29, 6, 0)
std::vector<std::shared_ptr<message_filters::SubscriberBase>>
observation_subscribers_;
#else
std::vector<std::shared_ptr<message_filters::SubscriberBase<rclcpp_lifecycle::LifecycleNode>>>
observation_subscribers_;
#endif
/// @brief Used to make sure that transforms are available for each sensor
std::vector<std::shared_ptr<tf2_ros::MessageFilterBase>> observation_notifiers_;
/// @brief Used to store observations from various sensors
Expand Down
28 changes: 24 additions & 4 deletions nav2_costmap_2d/plugins/obstacle_layer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -231,13 +231,23 @@

// create a callback for the topic
if (data_type == "LaserScan") {
// For Kilted and Older Support from Message Filters API change
#if RCLCPP_VERSION_GTE(29, 6, 0)
std::shared_ptr<message_filters::Subscriber<sensor_msgs::msg::LaserScan>> sub;
#else
std::shared_ptr<message_filters::Subscriber<sensor_msgs::msg::LaserScan,
rclcpp_lifecycle::LifecycleNode>> sub;
#endif

// For Jazzy compatibility
#if RCLCPP_VERSION_GTE(29, 0, 0)
// For Kilted compatibility in Message Filters API change
#if RCLCPP_VERSION_GTE(29, 6, 0)
sub = std::make_shared<message_filters::Subscriber<sensor_msgs::msg::LaserScan>>(
node, topic, custom_qos_profile, sub_opt);
// For Jazzy compatibility in Message Filters API change
#elif RCLCPP_VERSION_GTE(29, 0, 0)
sub = std::make_shared<message_filters::Subscriber<sensor_msgs::msg::LaserScan,
rclcpp_lifecycle::LifecycleNode>>(node, topic, custom_qos_profile, sub_opt);
// For Humble and Older compatibility in Message Filters API change
#else
sub = std::make_shared<message_filters::Subscriber<sensor_msgs::msg::LaserScan,
rclcpp_lifecycle::LifecycleNode>>(
Expand Down Expand Up @@ -271,13 +281,23 @@
observation_notifiers_.back()->setTolerance(rclcpp::Duration::from_seconds(0.05));

} else {
// For Kilted and Older Support from Message Filters API change
#if RCLCPP_VERSION_GTE(29, 6, 0)
std::shared_ptr<message_filters::Subscriber<sensor_msgs::msg::PointCloud2>> sub;

Check warning on line 286 in nav2_costmap_2d/plugins/obstacle_layer.cpp

View check run for this annotation

Codecov / codecov/patch

nav2_costmap_2d/plugins/obstacle_layer.cpp#L286

Added line #L286 was not covered by tests
#else
std::shared_ptr<message_filters::Subscriber<sensor_msgs::msg::PointCloud2,
rclcpp_lifecycle::LifecycleNode>> sub;
#endif

// For Jazzy compatibility
#if RCLCPP_VERSION_GTE(29, 0, 0)
// For Kilted compatibility in Message Filters API change
#if RCLCPP_VERSION_GTE(29, 6, 0)
sub = std::make_shared<message_filters::Subscriber<sensor_msgs::msg::PointCloud2>>(

Check warning on line 294 in nav2_costmap_2d/plugins/obstacle_layer.cpp

View check run for this annotation

Codecov / codecov/patch

nav2_costmap_2d/plugins/obstacle_layer.cpp#L294

Added line #L294 was not covered by tests
node, topic, custom_qos_profile, sub_opt);
// For Jazzy compatibility in Message Filters API change
#elif RCLCPP_VERSION_GTE(29, 0, 0)
sub = std::make_shared<message_filters::Subscriber<sensor_msgs::msg::PointCloud2,
rclcpp_lifecycle::LifecycleNode>>(node, topic, custom_qos_profile, sub_opt);
// For Humble and Older compatibility in Message Filters API change
#else
sub = std::make_shared<message_filters::Subscriber<sensor_msgs::msg::PointCloud2,
rclcpp_lifecycle::LifecycleNode>>(
Expand Down
Loading