@@ -1658,6 +1658,9 @@ TEST_F(Tester, testVelocityPolygonStopGlobalHeight)
16581658 setGlobalHeightParams (POINTCLOUD_NAME, 0.5 );
16591659 setVectors ({" VelocityPolygon" }, {POINTCLOUD_NAME});
16601660
1661+ cm_->set_parameter (
1662+ rclcpp::Parameter (" source_timeout" , 2.0 ));
1663+
16611664 rclcpp::Time curr_time = cm_->now ();
16621665 // Start Collision Monitor node
16631666 cm_->start ();
@@ -1685,6 +1688,17 @@ TEST_F(Tester, testVelocityPolygonStopGlobalHeight)
16851688 ASSERT_EQ (action_state_->action_type , STOP);
16861689 ASSERT_EQ (action_state_->polygon_name , " VelocityPolygon" );
16871690
1691+ // 3. Pointcloud without height field, invalid source.
1692+ publishPointCloud (2.5 , curr_time);
1693+ publishCmdVel (3.0 , 3.0 , 3.0 );
1694+ ASSERT_TRUE (waitCmdVel (500ms));
1695+ ASSERT_NEAR (cmd_vel_out_->linear .y , 0.0 , EPSILON);
1696+ ASSERT_NEAR (cmd_vel_out_->linear .y , 0.0 , EPSILON);
1697+ ASSERT_NEAR (cmd_vel_out_->angular .z , 0.0 , EPSILON);
1698+ ASSERT_TRUE (waitActionState (500ms));
1699+ ASSERT_EQ (action_state_->action_type , STOP);
1700+ ASSERT_EQ (action_state_->polygon_name , " invalid source" );
1701+
16881702 // Stop Collision Monitor node
16891703 cm_->stop ();
16901704}
0 commit comments