@@ -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+
480497void 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+
587643void 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+
15921706TEST_F (Tester, testSourceAssociatedToPolygon)
15931707{
15941708 // Set Collision Monitor parameters:
0 commit comments