Skip to content

Commit e2f7fd1

Browse files
Fix
Signed-off-by: ElSayed ElSheikh <[email protected]>
1 parent 4704a16 commit e2f7fd1

File tree

2 files changed

+4
-2
lines changed

2 files changed

+4
-2
lines changed

nav2_collision_monitor/include/nav2_collision_monitor/pointcloud.hpp

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -102,11 +102,13 @@ class PointCloud : public Source
102102
#if RCLCPP_VERSION_GTE(30, 0, 0)
103103
std::shared_ptr<point_cloud_transport::PointCloudTransport> pct_;
104104
point_cloud_transport::Subscriber data_sub_;
105-
std::string transport_type_;
106105
#else
107106
nav2::Subscription<sensor_msgs::msg::PointCloud2>::SharedPtr data_sub_;
108107
#endif
109108

109+
// Transport type used for PointCloud messages (e.g., raw or compressed)
110+
std::string transport_type_;
111+
110112
// Minimum and maximum height of PointCloud projected to 2D space
111113
double min_height_, max_height_;
112114
// Minimum range from sensor origin to filter out close points

nav2_costmap_2d/plugins/obstacle_layer.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -304,7 +304,7 @@ void ObstacleLayer::onInitialize()
304304
#if RCLCPP_VERSION_GTE(30, 0, 0)
305305
sub = std::make_shared<point_cloud_transport::SubscriberFilter>(
306306
*node, topic, transport_type, custom_qos_profile, sub_opt);
307-
// For Kilted compatibility in Message Filters API change
307+
// For Kilted compatibility in Message Filters API change
308308
#elif RCLCPP_VERSION_GTE(29, 6, 0)
309309
sub = std::make_shared<message_filters::Subscriber<sensor_msgs::msg::PointCloud2>>(
310310
node, topic, custom_qos_profile, sub_opt);

0 commit comments

Comments
 (0)