Skip to content

Commit 06081c3

Browse files
Adding minimum range to PC2 in collision monitor (backport #5392) (#5396)
* Adding minimum range to PC2 in collision monitor (#5392) Signed-off-by: SteveMacenski <stevenmacenski@gmail.com> (cherry picked from commit 40a0451) # Conflicts: # nav2_collision_monitor/src/pointcloud.cpp * Update pointcloud.cpp Signed-off-by: Steve Macenski <stevenmacenski@gmail.com> * Update pointcloud.cpp Signed-off-by: Steve Macenski <stevenmacenski@gmail.com> * Update sources_test.cpp Signed-off-by: Steve Macenski <stevenmacenski@gmail.com> --------- Signed-off-by: Steve Macenski <stevenmacenski@gmail.com> Co-authored-by: Steve Macenski <stevenmacenski@gmail.com>
1 parent 77db0a6 commit 06081c3

File tree

3 files changed

+122
-4
lines changed

3 files changed

+122
-4
lines changed

nav2_collision_monitor/include/nav2_collision_monitor/pointcloud.hpp

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -95,6 +95,8 @@ class PointCloud : public Source
9595

9696
// Minimum and maximum height of PointCloud projected to 2D space
9797
double min_height_, max_height_;
98+
// Minimum range from sensor origin to filter out close points
99+
double min_range_;
98100

99101
/// @brief Latest data obtained from pointcloud
100102
sensor_msgs::msg::PointCloud2::ConstSharedPtr data_;

nav2_collision_monitor/src/pointcloud.cpp

Lines changed: 10 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -92,6 +92,13 @@ bool PointCloud::getData(
9292
for (; iter_x != iter_x.end(); ++iter_x, ++iter_y, ++iter_z) {
9393
// Transform point coordinates from source frame -> to base frame
9494
tf2::Vector3 p_v3_s(*iter_x, *iter_y, *iter_z);
95+
96+
// Check range from sensor origin before transformation
97+
double range = p_v3_s.length();
98+
if (range < min_range_) {
99+
continue;
100+
}
101+
95102
tf2::Vector3 p_v3_b = tf_transform * p_v3_s;
96103

97104
// Refill data array
@@ -117,6 +124,9 @@ void PointCloud::getParameters(std::string & source_topic)
117124
nav2_util::declare_parameter_if_not_declared(
118125
node, source_name_ + ".max_height", rclcpp::ParameterValue(0.5));
119126
max_height_ = node->get_parameter(source_name_ + ".max_height").as_double();
127+
nav2_util::declare_parameter_if_not_declared(
128+
node, source_name_ + ".min_range", rclcpp::ParameterValue(0.0));
129+
min_range_ = node->get_parameter(source_name_ + ".min_range").as_double();
120130
}
121131

122132
void PointCloud::dataCallback(sensor_msgs::msg::PointCloud2::ConstSharedPtr msg)

nav2_collision_monitor/test/sources_test.cpp

Lines changed: 110 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -140,6 +140,58 @@ class TestNode : public nav2_util::LifecycleNode
140140
pointcloud_pub_->publish(std::move(msg));
141141
}
142142

143+
void publishPointCloudForMinRange(const rclcpp::Time & stamp)
144+
{
145+
pointcloud_pub_ = this->create_publisher<sensor_msgs::msg::PointCloud2>(
146+
POINTCLOUD_TOPIC, rclcpp::QoS(rclcpp::KeepLast(1)).transient_local().reliable());
147+
148+
std::unique_ptr<sensor_msgs::msg::PointCloud2> msg =
149+
std::make_unique<sensor_msgs::msg::PointCloud2>();
150+
sensor_msgs::PointCloud2Modifier modifier(*msg);
151+
152+
msg->header.frame_id = SOURCE_FRAME_ID;
153+
msg->header.stamp = stamp;
154+
155+
modifier.setPointCloud2Fields(
156+
3, "x", 1, sensor_msgs::msg::PointField::FLOAT32,
157+
"y", 1, sensor_msgs::msg::PointField::FLOAT32,
158+
"z", 1, sensor_msgs::msg::PointField::FLOAT32);
159+
modifier.resize(4);
160+
161+
sensor_msgs::PointCloud2Iterator<float> iter_x(*msg, "x");
162+
sensor_msgs::PointCloud2Iterator<float> iter_y(*msg, "y");
163+
sensor_msgs::PointCloud2Iterator<float> iter_z(*msg, "z");
164+
165+
// Point 0: Very close to origin (0.05, 0.0, 0.15) - range ≈ 0.158,
166+
// should be filtered
167+
*iter_x = 0.05;
168+
*iter_y = 0.0;
169+
*iter_z = 0.15;
170+
++iter_x; ++iter_y; ++iter_z;
171+
172+
// Point 1: Close to origin (0.15, 0.0, 0.15) - range ≈ 0.212,
173+
// should pass with min_range=0.16
174+
*iter_x = 0.15;
175+
*iter_y = 0.0;
176+
*iter_z = 0.15;
177+
++iter_x; ++iter_y; ++iter_z;
178+
179+
// Point 2: At min_range threshold (0.2, 0.0, 0.15) - range ≈ 0.25,
180+
// should pass with min_range=0.16
181+
*iter_x = 0.2;
182+
*iter_y = 0.0;
183+
*iter_z = 0.15;
184+
++iter_x; ++iter_y; ++iter_z;
185+
186+
// Point 3: Beyond min_range (0.5, 0.0, 0.15) - range ≈ 0.522,
187+
// should pass
188+
*iter_x = 0.5;
189+
*iter_y = 0.0;
190+
*iter_z = 0.15;
191+
192+
pointcloud_pub_->publish(std::move(msg));
193+
}
194+
143195
void publishRange(const rclcpp::Time & stamp, const double range)
144196
{
145197
range_pub_ = this->create_publisher<sensor_msgs::msg::Range>(
@@ -296,6 +348,8 @@ class Tester : public ::testing::Test
296348
public:
297349
Tester();
298350
~Tester();
351+
std::shared_ptr<tf2_ros::Buffer> tf_buffer_;
352+
std::shared_ptr<tf2_ros::TransformListener> tf_listener_;
299353

300354
protected:
301355
// Data sources creation routine
@@ -319,10 +373,6 @@ class Tester : public ::testing::Test
319373
std::shared_ptr<PointCloudWrapper> pointcloud_;
320374
std::shared_ptr<RangeWrapper> range_;
321375
std::shared_ptr<PolygonWrapper> polygon_;
322-
323-
private:
324-
std::shared_ptr<tf2_ros::Buffer> tf_buffer_;
325-
std::shared_ptr<tf2_ros::TransformListener> tf_listener_;
326376
}; // Tester
327377

328378
Tester::Tester()
@@ -741,6 +791,62 @@ TEST_F(Tester, testIgnoreTimeShift)
741791
checkPolygon(data);
742792
}
743793

794+
TEST_F(Tester, testPointCloudMinRange)
795+
{
796+
rclcpp::Time curr_time = test_node_->now();
797+
798+
// Create PointCloud object with min_range = 0.2
799+
test_node_->declare_parameter(
800+
std::string(POINTCLOUD_NAME) + ".topic", rclcpp::ParameterValue(POINTCLOUD_TOPIC));
801+
test_node_->set_parameter(
802+
rclcpp::Parameter(std::string(POINTCLOUD_NAME) + ".topic", POINTCLOUD_TOPIC));
803+
test_node_->declare_parameter(
804+
std::string(POINTCLOUD_NAME) + ".min_height", rclcpp::ParameterValue(0.1));
805+
test_node_->set_parameter(
806+
rclcpp::Parameter(std::string(POINTCLOUD_NAME) + ".min_height", 0.1));
807+
test_node_->declare_parameter(
808+
std::string(POINTCLOUD_NAME) + ".max_height", rclcpp::ParameterValue(1.0));
809+
test_node_->set_parameter(
810+
rclcpp::Parameter(std::string(POINTCLOUD_NAME) + ".max_height", 1.0));
811+
test_node_->declare_parameter(
812+
std::string(POINTCLOUD_NAME) + ".min_range", rclcpp::ParameterValue(0.16));
813+
test_node_->set_parameter(
814+
rclcpp::Parameter(std::string(POINTCLOUD_NAME) + ".min_range", 0.16));
815+
816+
pointcloud_ = std::make_shared<PointCloudWrapper>(
817+
test_node_, POINTCLOUD_NAME, tf_buffer_,
818+
BASE_FRAME_ID, GLOBAL_FRAME_ID,
819+
TRANSFORM_TOLERANCE, DATA_TIMEOUT, true);
820+
pointcloud_->configure();
821+
822+
sendTransforms(curr_time);
823+
824+
// Publish pointcloud data with points at various ranges
825+
test_node_->publishPointCloudForMinRange(curr_time);
826+
827+
// Wait until pointcloud receives the data
828+
ASSERT_TRUE(waitPointCloud(500ms));
829+
830+
// Check PointCloud data - should only contain points with range >= min_range (0.16)
831+
std::vector<nav2_collision_monitor::Point> data;
832+
pointcloud_->getData(curr_time, data);
833+
834+
// Should have 3 points: first point (range ≈ 0.158) filtered out, remaining 3 pass
835+
ASSERT_EQ(data.size(), 3u);
836+
837+
// Point 1: (0.15 + 0.1, 0.0 + 0.1) = (0.25, 0.1) - range ≈ 0.212, passes
838+
EXPECT_NEAR(data[0].x, 0.25, EPSILON);
839+
EXPECT_NEAR(data[0].y, 0.1, EPSILON);
840+
841+
// Point 2: (0.2 + 0.1, 0.0 + 0.1) = (0.3, 0.1) - range ≈ 0.25, passes
842+
EXPECT_NEAR(data[1].x, 0.3, EPSILON);
843+
EXPECT_NEAR(data[1].y, 0.1, EPSILON);
844+
845+
// Point 3: (0.5 + 0.1, 0.0 + 0.1) = (0.6, 0.1) - range ≈ 0.522, passes
846+
EXPECT_NEAR(data[2].x, 0.6, EPSILON);
847+
EXPECT_NEAR(data[2].y, 0.1, EPSILON);
848+
}
849+
744850
int main(int argc, char ** argv)
745851
{
746852
// Initialize the system

0 commit comments

Comments
 (0)