Skip to content

Commit 2a73560

Browse files
Summary commit of all changes for adding custom pointcloud field height. (#5586)
Doing this to clear out unsigned commits from history. Signed-off-by: Greg Anderson <107634795+greganderson-vermeer@users.noreply.github.com>
1 parent 1779d92 commit 2a73560

File tree

4 files changed

+148
-1
lines changed

4 files changed

+148
-1
lines changed

‎nav2_collision_monitor/include/nav2_collision_monitor/pointcloud.hpp‎

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -113,6 +113,10 @@ class PointCloud : public Source
113113
double min_height_, max_height_;
114114
// Minimum range from sensor origin to filter out close points
115115
double min_range_;
116+
/**Changes height check from "z" field to "height" field for pipelines utilizing
117+
* ground contouring
118+
*/
119+
bool use_global_height_;
116120

117121
/// @brief Latest data obtained from pointcloud
118122
sensor_msgs::msg::PointCloud2::ConstSharedPtr data_;

‎nav2_collision_monitor/params/collision_monitor_params.yaml‎

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -100,4 +100,5 @@ collision_monitor:
100100
transport_type: "raw" # Options: raw, zlib, draco, zstd
101101
min_height: 0.1
102102
max_height: 0.5
103+
use_global_height: False
103104
enabled: True

‎nav2_collision_monitor/src/pointcloud.cpp‎

Lines changed: 29 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -106,11 +106,35 @@ bool PointCloud::getData(
106106
sensor_msgs::PointCloud2ConstIterator<float> iter_y(*data_, "y");
107107
sensor_msgs::PointCloud2ConstIterator<float> iter_z(*data_, "z");
108108

109+
bool height_present = false;
110+
for (const auto & field : data_->fields) {
111+
if (field.name == "height") {
112+
height_present = true;
113+
}
114+
}
115+
116+
// Reference height field
117+
std::string height_field{"z"};
118+
if (use_global_height_ && height_present) {
119+
height_field = "height";
120+
} else if (use_global_height_) {
121+
RCLCPP_ERROR(logger_, "[%s]: 'use_global_height' parameter true but height field not in cloud",
122+
source_name_.c_str());
123+
return false;
124+
}
125+
sensor_msgs::PointCloud2ConstIterator<float> iter_height(*data_, height_field);
126+
109127
// Refill data array with PointCloud points in base frame
110128
for (; iter_x != iter_x.end(); ++iter_x, ++iter_y, ++iter_z) {
111129
// Transform point coordinates from source frame -> to base frame
112130
tf2::Vector3 p_v3_s(*iter_x, *iter_y, *iter_z);
113131

132+
double data_height = *iter_z;
133+
if (use_global_height_) {
134+
data_height = *iter_height;
135+
++iter_height;
136+
}
137+
114138
// Check range from sensor origin before transformation
115139
double range = p_v3_s.length();
116140
if (range < min_range_) {
@@ -120,7 +144,7 @@ bool PointCloud::getData(
120144
tf2::Vector3 p_v3_b = tf_transform * p_v3_s;
121145

122146
// Refill data array
123-
if (p_v3_b.z() >= min_height_ && p_v3_b.z() <= max_height_) {
147+
if (data_height >= min_height_ && data_height <= max_height_) {
124148
data.push_back({p_v3_b.x(), p_v3_b.y()});
125149
}
126150
}
@@ -139,6 +163,8 @@ void PointCloud::getParameters(std::string & source_topic)
139163
min_height_ = node->declare_or_get_parameter(source_name_ + ".min_height", 0.05);
140164
max_height_ = node->declare_or_get_parameter(source_name_ + ".max_height", 0.5);
141165
min_range_ = node->declare_or_get_parameter(source_name_ + ".min_range", 0.0);
166+
use_global_height_ = node->declare_or_get_parameter(
167+
source_name_ + ".use_global_height", false);
142168
transport_type_ = node->declare_or_get_parameter(
143169
source_name_ + ".transport_type", std::string("raw"));
144170
}
@@ -171,6 +197,8 @@ PointCloud::dynamicParametersCallback(
171197
} else if (param_type == rcl_interfaces::msg::ParameterType::PARAMETER_BOOL) {
172198
if (param_name == source_name_ + "." + "enabled") {
173199
enabled_ = parameter.as_bool();
200+
} else if (param_name == source_name_ + "." + "use_global_height") {
201+
use_global_height_ = parameter.as_bool();
174202
}
175203
}
176204
}

‎nav2_collision_monitor/test/collision_monitor_node_test.cpp‎

Lines changed: 114 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -162,6 +162,7 @@ class Tester : public ::testing::Test
162162
void setPolygonVelocityVectors(
163163
const std::string & polygon_name,
164164
const std::vector<std::string> & polygons);
165+
void setGlobalHeightParams(const std::string & source_name, const double min_height);
165166

166167
// Setting TF chains
167168
void sendTransforms(const rclcpp::Time & stamp);
@@ -172,6 +173,9 @@ class Tester : public ::testing::Test
172173
// Main topic/data working routines
173174
void publishScan(const double dist, const rclcpp::Time & stamp);
174175
void publishPointCloud(const double dist, const rclcpp::Time & stamp);
176+
void publishPointCloudWithHeight(
177+
const double dist, const double height,
178+
const rclcpp::Time & stamp);
175179
void publishRange(const double dist, const rclcpp::Time & stamp);
176180
void publishPolygon(const double dist, const rclcpp::Time & stamp);
177181
void publishCmdVel(const double x, const double y, const double tw);
@@ -439,6 +443,8 @@ void Tester::addSource(
439443
source_name + ".min_height", rclcpp::ParameterValue(0.1));
440444
cm_->declare_parameter(
441445
source_name + ".max_height", rclcpp::ParameterValue(1.0));
446+
cm_->declare_parameter(
447+
source_name + ".use_global_height", rclcpp::ParameterValue(false));
442448
} else if (type == RANGE) {
443449
cm_->declare_parameter(
444450
source_name + ".type", rclcpp::ParameterValue("range"));
@@ -477,6 +483,17 @@ void Tester::setPolygonVelocityVectors(
477483
cm_->declare_parameter(polygon_name + ".velocity_polygons", rclcpp::ParameterValue(polygons));
478484
}
479485

486+
void Tester::setGlobalHeightParams(const std::string & source_name, const double min_height)
487+
{
488+
cm_->declare_or_get_parameter(
489+
source_name + ".use_global_height", true);
490+
cm_->set_parameter(rclcpp::Parameter(source_name + ".use_global_height", true));
491+
492+
cm_->declare_or_get_parameter(
493+
source_name + ".min_height", min_height);
494+
cm_->set_parameter(rclcpp::Parameter(source_name + ".min_height", min_height));
495+
}
496+
480497
void Tester::sendTransforms(const rclcpp::Time & stamp)
481498
{
482499
std::shared_ptr<tf2_ros::TransformBroadcaster> tf_broadcaster =
@@ -584,6 +601,45 @@ void Tester::publishPointCloud(const double dist, const rclcpp::Time & stamp)
584601
pointcloud_pub_->publish(std::move(msg));
585602
}
586603

604+
void Tester::publishPointCloudWithHeight(
605+
const double dist, const double height,
606+
const rclcpp::Time & stamp)
607+
{
608+
std::unique_ptr<sensor_msgs::msg::PointCloud2> msg =
609+
std::make_unique<sensor_msgs::msg::PointCloud2>();
610+
sensor_msgs::PointCloud2Modifier modifier(*msg);
611+
612+
msg->header.frame_id = SOURCE_FRAME_ID;
613+
msg->header.stamp = stamp;
614+
615+
modifier.setPointCloud2Fields(
616+
4, "x", 1, sensor_msgs::msg::PointField::FLOAT32,
617+
"y", 1, sensor_msgs::msg::PointField::FLOAT32,
618+
"z", 1, sensor_msgs::msg::PointField::FLOAT32,
619+
"height", 1, sensor_msgs::msg::PointField::FLOAT32);
620+
modifier.resize(2);
621+
622+
sensor_msgs::PointCloud2Iterator<float> iter_x(*msg, "x");
623+
sensor_msgs::PointCloud2Iterator<float> iter_y(*msg, "y");
624+
sensor_msgs::PointCloud2Iterator<float> iter_z(*msg, "z");
625+
sensor_msgs::PointCloud2Iterator<float> iter_height(*msg, "height");
626+
627+
// Point 0: (dist, 0.01, 0.2, height)
628+
*iter_x = dist;
629+
*iter_y = 0.01;
630+
*iter_z = 0.2;
631+
*iter_height = height;
632+
++iter_x; ++iter_y; ++iter_z; ++iter_height;
633+
634+
// Point 1: (dist, -0.01, 0.2, height)
635+
*iter_x = dist;
636+
*iter_y = -0.01;
637+
*iter_z = 0.2;
638+
*iter_height = height;
639+
640+
pointcloud_pub_->publish(std::move(msg));
641+
}
642+
587643
void Tester::publishRange(const double dist, const rclcpp::Time & stamp)
588644
{
589645
std::unique_ptr<sensor_msgs::msg::Range> msg =
@@ -1589,6 +1645,64 @@ TEST_F(Tester, testVelocityPolygonStop)
15891645
cm_->stop();
15901646
}
15911647

1648+
TEST_F(Tester, testVelocityPolygonStopGlobalHeight)
1649+
{
1650+
// Set Collision Monitor parameters.
1651+
// Add velocity polygon with 2 sub polygon:
1652+
// 1. Forward: 0 -> 0.5 m/s
1653+
// 2. Backward: 0 -> -0.5 m/s
1654+
setCommonParameters();
1655+
addPolygon("VelocityPolygon", VELOCITY_POLYGON, 1.0, "stop");
1656+
addPolygonVelocitySubPolygon("VelocityPolygon", "Forward", 0.0, 0.5, 0.0, 1.0, 4.0);
1657+
addPolygonVelocitySubPolygon("VelocityPolygon", "Backward", -0.5, 0.0, 0.0, 1.0, 2.0);
1658+
setPolygonVelocityVectors("VelocityPolygon", {"Forward", "Backward"});
1659+
addSource(POINTCLOUD_NAME, POINTCLOUD);
1660+
setGlobalHeightParams(POINTCLOUD_NAME, 0.5);
1661+
setVectors({"VelocityPolygon"}, {POINTCLOUD_NAME});
1662+
1663+
cm_->set_parameter(
1664+
rclcpp::Parameter("source_timeout", 2.0));
1665+
1666+
rclcpp::Time curr_time = cm_->now();
1667+
// Start Collision Monitor node
1668+
cm_->start();
1669+
// Check that robot stops when source is enabled
1670+
sendTransforms(curr_time);
1671+
1672+
// 1. Obstacle is in Forward velocity polygon and below global height
1673+
publishPointCloudWithHeight(3.0, 0.4, curr_time);
1674+
ASSERT_FALSE(waitData(std::hypot(3.0, 0.01), 500ms, curr_time));
1675+
publishCmdVel(0.4, 0.0, 0.1);
1676+
ASSERT_TRUE(waitCmdVel(500ms));
1677+
ASSERT_NEAR(cmd_vel_out_->linear.x, 0.4, EPSILON);
1678+
ASSERT_NEAR(cmd_vel_out_->linear.y, 0.0, EPSILON);
1679+
ASSERT_NEAR(cmd_vel_out_->angular.z, 0.1, EPSILON);
1680+
1681+
// 2. Obstacle is in Forward velocity polygon and above global height
1682+
publishPointCloudWithHeight(3.0, 0.6, curr_time);
1683+
ASSERT_TRUE(waitData(std::hypot(3.0, 0.01), 500ms, curr_time));
1684+
publishCmdVel(0.4, 0.0, 0.1);
1685+
ASSERT_TRUE(waitCmdVel(500ms));
1686+
ASSERT_NEAR(cmd_vel_out_->linear.x, 0.0, EPSILON);
1687+
ASSERT_NEAR(cmd_vel_out_->linear.y, 0.0, EPSILON);
1688+
ASSERT_NEAR(cmd_vel_out_->angular.z, 0.0, EPSILON);
1689+
ASSERT_TRUE(waitActionState(500ms));
1690+
ASSERT_EQ(action_state_->action_type, STOP);
1691+
ASSERT_EQ(action_state_->polygon_name, "VelocityPolygon");
1692+
1693+
// 3. Pointcloud without height field, invalid source.
1694+
publishPointCloud(2.5, curr_time);
1695+
ASSERT_FALSE(waitData(std::hypot(2.5, 0.01), 100ms, curr_time));
1696+
publishCmdVel(3.0, 3.0, 3.0);
1697+
ASSERT_FALSE(waitCmdVel(500ms));
1698+
ASSERT_TRUE(waitActionState(500ms));
1699+
ASSERT_EQ(action_state_->action_type, STOP);
1700+
ASSERT_EQ(action_state_->polygon_name, "invalid source");
1701+
1702+
// Stop Collision Monitor node
1703+
cm_->stop();
1704+
}
1705+
15921706
TEST_F(Tester, testSourceAssociatedToPolygon)
15931707
{
15941708
// Set Collision Monitor parameters:

0 commit comments

Comments
 (0)