@@ -449,6 +449,59 @@ TEST_P(TrajectoryControllerTestParameterized, update_dynamic_parameters)
449449 executor.cancel ();
450450}
451451
452+ /* *
453+ * @brief check if dynamic tolerances are updated
454+ */
455+ TEST_P (TrajectoryControllerTestParameterized, update_dynamic_tolerances)
456+ {
457+ rclcpp::executors::MultiThreadedExecutor executor;
458+
459+ SetUpAndActivateTrajectoryController (executor);
460+
461+ updateController ();
462+
463+ // test default parameters
464+ {
465+ auto tols = traj_controller_->get_tolerances ();
466+ EXPECT_EQ (tols.goal_time_tolerance , 0.0 );
467+ for (size_t i = 0 ; i < joint_names_.size (); ++i)
468+ {
469+ EXPECT_EQ (tols.state_tolerance .at (i).position , 0.0 );
470+ EXPECT_EQ (tols.goal_state_tolerance .at (i).position , 0.0 );
471+ EXPECT_EQ (tols.goal_state_tolerance .at (i).velocity , 0.01 );
472+ }
473+ }
474+
475+ // change parameters, update and see what happens
476+ std::vector<rclcpp::Parameter> new_tolerances{
477+ rclcpp::Parameter (" constraints.goal_time" , 1.0 ),
478+ rclcpp::Parameter (" constraints.stopped_velocity_tolerance" , 0.02 ),
479+ rclcpp::Parameter (" constraints.joint1.trajectory" , 1.0 ),
480+ rclcpp::Parameter (" constraints.joint2.trajectory" , 2.0 ),
481+ rclcpp::Parameter (" constraints.joint3.trajectory" , 3.0 ),
482+ rclcpp::Parameter (" constraints.joint1.goal" , 10.0 ),
483+ rclcpp::Parameter (" constraints.joint2.goal" , 20.0 ),
484+ rclcpp::Parameter (" constraints.joint3.goal" , 30.0 )};
485+ for (const auto & param : new_tolerances)
486+ {
487+ traj_controller_->get_node ()->set_parameter (param);
488+ }
489+ updateController ();
490+
491+ {
492+ auto tols = traj_controller_->get_tolerances ();
493+ EXPECT_EQ (tols.goal_time_tolerance , 1.0 );
494+ for (size_t i = 0 ; i < joint_names_.size (); ++i)
495+ {
496+ EXPECT_EQ (tols.state_tolerance .at (i).position , static_cast <double >(i) + 1.0 );
497+ EXPECT_EQ (tols.goal_state_tolerance .at (i).position , 10.0 * (static_cast <double >(i) + 1.0 ));
498+ EXPECT_EQ (tols.goal_state_tolerance .at (i).velocity , 0.02 );
499+ }
500+ }
501+
502+ executor.cancel ();
503+ }
504+
452505/* *
453506 * @brief check if hold on startup is deactivated
454507 */
0 commit comments