@@ -32,14 +32,14 @@ using trajectory_msgs::msg::JointTrajectoryPoint;
3232std::vector<std::string> joint_names_ = {" joint1" , " joint2" , " joint3" };
3333
3434control_msgs::action::FollowJointTrajectory_Goal prepareGoalMsg (
35- const std::vector<JointTrajectoryPoint> & points, double timeout ,
35+ const std::vector<JointTrajectoryPoint> & points, double goal_time_tolerance ,
3636 const std::vector<control_msgs::msg::JointTolerance> path_tolerance =
3737 std::vector<control_msgs::msg::JointTolerance>(),
3838 const std::vector<control_msgs::msg::JointTolerance> goal_tolerance =
3939 std::vector<control_msgs::msg::JointTolerance>())
4040{
4141 control_msgs::action::FollowJointTrajectory_Goal goal_msg;
42- goal_msg.goal_time_tolerance = rclcpp::Duration::from_seconds (timeout );
42+ goal_msg.goal_time_tolerance = rclcpp::Duration::from_seconds (goal_time_tolerance );
4343 goal_msg.goal_tolerance = goal_tolerance;
4444 goal_msg.path_tolerance = path_tolerance;
4545 goal_msg.trajectory .joint_names = joint_names_;
@@ -183,7 +183,7 @@ TEST_F(TestTolerancesFixture, test_deactivate_tolerances)
183183 path_tolerance.push_back (tolerance);
184184 goal_tolerance.push_back (tolerance);
185185
186- auto goal_msg = prepareGoalMsg (points, 0 .0 , path_tolerance, goal_tolerance);
186+ auto goal_msg = prepareGoalMsg (points, - 1 .0 , path_tolerance, goal_tolerance);
187187 auto active_tolerances = joint_trajectory_controller::get_segment_tolerances (
188188 logger, default_tolerances, goal_msg, params.joints );
189189
@@ -215,6 +215,31 @@ TEST_F(TestTolerancesFixture, test_deactivate_tolerances)
215215// send goal with invalid tolerances, are the default ones used?
216216TEST_F (TestTolerancesFixture, test_invalid_tolerances)
217217{
218+ {
219+ SCOPED_TRACE (" negative goal_time_tolerance" );
220+ std::vector<JointTrajectoryPoint> points;
221+ JointTrajectoryPoint point;
222+ point.time_from_start = rclcpp::Duration::from_seconds (0.5 );
223+ point.positions .resize (joint_names_.size ());
224+
225+ point.positions [0 ] = 1.0 ;
226+ point.positions [1 ] = 2.0 ;
227+ point.positions [2 ] = 3.0 ;
228+ points.push_back (point);
229+
230+ std::vector<control_msgs::msg::JointTolerance> path_tolerance;
231+ control_msgs::msg::JointTolerance tolerance;
232+ tolerance.name = " joint1" ;
233+ tolerance.position = 0.0 ;
234+ tolerance.velocity = 0.0 ;
235+ tolerance.acceleration = 0.0 ;
236+ path_tolerance.push_back (tolerance);
237+
238+ auto goal_msg = prepareGoalMsg (points, -123.0 , path_tolerance);
239+ auto active_tolerances = joint_trajectory_controller::get_segment_tolerances (
240+ logger, default_tolerances, goal_msg, params.joints );
241+ expectDefaultTolerances (active_tolerances);
242+ }
218243 {
219244 SCOPED_TRACE (" negative path position tolerance" );
220245 std::vector<JointTrajectoryPoint> points;
@@ -238,7 +263,6 @@ TEST_F(TestTolerancesFixture, test_invalid_tolerances)
238263 auto goal_msg = prepareGoalMsg (points, 3.0 , path_tolerance);
239264 auto active_tolerances = joint_trajectory_controller::get_segment_tolerances (
240265 logger, default_tolerances, goal_msg, params.joints );
241- EXPECT_DOUBLE_EQ (active_tolerances.goal_time_tolerance , default_goal_time);
242266 expectDefaultTolerances (active_tolerances);
243267 }
244268 {
@@ -264,7 +288,6 @@ TEST_F(TestTolerancesFixture, test_invalid_tolerances)
264288 auto goal_msg = prepareGoalMsg (points, 3.0 , path_tolerance);
265289 auto active_tolerances = joint_trajectory_controller::get_segment_tolerances (
266290 logger, default_tolerances, goal_msg, params.joints );
267- EXPECT_DOUBLE_EQ (active_tolerances.goal_time_tolerance , default_goal_time);
268291 expectDefaultTolerances (active_tolerances);
269292 }
270293 {
@@ -290,7 +313,6 @@ TEST_F(TestTolerancesFixture, test_invalid_tolerances)
290313 auto goal_msg = prepareGoalMsg (points, 3.0 , path_tolerance);
291314 auto active_tolerances = joint_trajectory_controller::get_segment_tolerances (
292315 logger, default_tolerances, goal_msg, params.joints );
293- EXPECT_DOUBLE_EQ (active_tolerances.goal_time_tolerance , default_goal_time);
294316 expectDefaultTolerances (active_tolerances);
295317 }
296318 {
@@ -317,7 +339,6 @@ TEST_F(TestTolerancesFixture, test_invalid_tolerances)
317339 prepareGoalMsg (points, 3.0 , std::vector<control_msgs::msg::JointTolerance>(), goal_tolerance);
318340 auto active_tolerances = joint_trajectory_controller::get_segment_tolerances (
319341 logger, default_tolerances, goal_msg, params.joints );
320- EXPECT_DOUBLE_EQ (active_tolerances.goal_time_tolerance , default_goal_time);
321342 expectDefaultTolerances (active_tolerances);
322343 }
323344 {
@@ -344,7 +365,6 @@ TEST_F(TestTolerancesFixture, test_invalid_tolerances)
344365 prepareGoalMsg (points, 3.0 , std::vector<control_msgs::msg::JointTolerance>(), goal_tolerance);
345366 auto active_tolerances = joint_trajectory_controller::get_segment_tolerances (
346367 logger, default_tolerances, goal_msg, params.joints );
347- EXPECT_DOUBLE_EQ (active_tolerances.goal_time_tolerance , default_goal_time);
348368 expectDefaultTolerances (active_tolerances);
349369 }
350370 {
@@ -371,7 +391,6 @@ TEST_F(TestTolerancesFixture, test_invalid_tolerances)
371391 prepareGoalMsg (points, 3.0 , std::vector<control_msgs::msg::JointTolerance>(), goal_tolerance);
372392 auto active_tolerances = joint_trajectory_controller::get_segment_tolerances (
373393 logger, default_tolerances, goal_msg, params.joints );
374- EXPECT_DOUBLE_EQ (active_tolerances.goal_time_tolerance , default_goal_time);
375394 expectDefaultTolerances (active_tolerances);
376395 }
377396}
@@ -395,7 +414,6 @@ TEST_F(TestTolerancesFixture, test_invalid_joints_path_tolerance)
395414 auto goal_msg = prepareGoalMsg (points, 3.0 , path_tolerance);
396415 auto active_tolerances = joint_trajectory_controller::get_segment_tolerances (
397416 logger, default_tolerances, goal_msg, params.joints );
398- EXPECT_DOUBLE_EQ (active_tolerances.goal_time_tolerance , default_goal_time);
399417 expectDefaultTolerances (active_tolerances);
400418}
401419TEST_F (TestTolerancesFixture, test_invalid_joints_goal_tolerance)
@@ -419,6 +437,5 @@ TEST_F(TestTolerancesFixture, test_invalid_joints_goal_tolerance)
419437 prepareGoalMsg (points, 3.0 , std::vector<control_msgs::msg::JointTolerance>(), goal_tolerance);
420438 auto active_tolerances = joint_trajectory_controller::get_segment_tolerances (
421439 logger, default_tolerances, goal_msg, params.joints );
422- EXPECT_DOUBLE_EQ (active_tolerances.goal_time_tolerance , default_goal_time);
423440 expectDefaultTolerances (active_tolerances);
424441}
0 commit comments