Skip to content

Commit 40a0451

Browse files
Adding minimum range to PC2 in collision monitor (#5392)
Signed-off-by: SteveMacenski <stevenmacenski@gmail.com>
1 parent c59b9cb commit 40a0451

File tree

3 files changed

+125
-4
lines changed

3 files changed

+125
-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
@@ -102,6 +102,8 @@ class PointCloud : public Source
102102

103103
// Minimum and maximum height of PointCloud projected to 2D space
104104
double min_height_, max_height_;
105+
// Minimum range from sensor origin to filter out close points
106+
double min_range_;
105107

106108
/// @brief Latest data obtained from pointcloud
107109
sensor_msgs::msg::PointCloud2::ConstSharedPtr data_;

nav2_collision_monitor/src/pointcloud.cpp

Lines changed: 12 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -96,6 +96,13 @@ bool PointCloud::getData(
9696
for (; iter_x != iter_x.end(); ++iter_x, ++iter_y, ++iter_z) {
9797
// Transform point coordinates from source frame -> to base frame
9898
tf2::Vector3 p_v3_s(*iter_x, *iter_y, *iter_z);
99+
100+
// Check range from sensor origin before transformation
101+
double range = p_v3_s.length();
102+
if (range < min_range_) {
103+
continue;
104+
}
105+
99106
tf2::Vector3 p_v3_b = tf_transform * p_v3_s;
100107

101108
// Refill data array
@@ -121,6 +128,9 @@ void PointCloud::getParameters(std::string & source_topic)
121128
nav2::declare_parameter_if_not_declared(
122129
node, source_name_ + ".max_height", rclcpp::ParameterValue(0.5));
123130
max_height_ = node->get_parameter(source_name_ + ".max_height").as_double();
131+
nav2::declare_parameter_if_not_declared(
132+
node, source_name_ + ".min_range", rclcpp::ParameterValue(0.0));
133+
min_range_ = node->get_parameter(source_name_ + ".min_range").as_double();
124134
}
125135

126136
void PointCloud::dataCallback(sensor_msgs::msg::PointCloud2::ConstSharedPtr msg)
@@ -145,6 +155,8 @@ PointCloud::dynamicParametersCallback(
145155
min_height_ = parameter.as_double();
146156
} else if (param_name == source_name_ + "." + "max_height") {
147157
max_height_ = parameter.as_double();
158+
} else if (param_name == source_name_ + "." + "min_range") {
159+
min_range_ = parameter.as_double();
148160
}
149161
} else if (param_type == rcl_interfaces::msg::ParameterType::PARAMETER_BOOL) {
150162
if (param_name == source_name_ + "." + "enabled") {

nav2_collision_monitor/test/sources_test.cpp

Lines changed: 111 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -142,6 +142,59 @@ class TestNode : public nav2::LifecycleNode
142142
pointcloud_pub_->publish(std::move(msg));
143143
}
144144

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

305360
protected:
306361
// Data sources creation routine
@@ -324,10 +379,6 @@ class Tester : public ::testing::Test
324379
std::shared_ptr<PointCloudWrapper> pointcloud_;
325380
std::shared_ptr<RangeWrapper> range_;
326381
std::shared_ptr<PolygonWrapper> polygon_;
327-
328-
private:
329-
std::shared_ptr<tf2_ros::Buffer> tf_buffer_;
330-
std::shared_ptr<tf2_ros::TransformListener> tf_listener_;
331382
}; // Tester
332383

333384
Tester::Tester()
@@ -746,6 +797,62 @@ TEST_F(Tester, testIgnoreTimeShift)
746797
checkPolygon(data);
747798
}
748799

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

0 commit comments

Comments
 (0)