@@ -444,37 +444,18 @@ TEST_P(TrajectoryControllerTestParameterized, update_dynamic_tolerances)
444444 executor.cancel ();
445445}
446446
447- /* *
448- * @brief check if hold on startup is deactivated
449- */
450- TEST_P (TrajectoryControllerTestParameterized, no_hold_on_startup)
451- {
452- rclcpp::executors::MultiThreadedExecutor executor;
453-
454- rclcpp::Parameter start_with_holding_parameter (" start_with_holding" , false );
455- SetUpAndActivateTrajectoryController (executor, {start_with_holding_parameter});
456-
457- constexpr auto FIRST_POINT_TIME = std::chrono::milliseconds (250 );
458- updateControllerAsync (rclcpp::Duration (FIRST_POINT_TIME));
459- // after startup without start_with_holding being set, we expect no active trajectory
460- ASSERT_FALSE (traj_controller_->has_active_traj ());
461-
462- executor.cancel ();
463- }
464-
465447/* *
466448 * @brief check if hold on startup
467449 */
468450TEST_P (TrajectoryControllerTestParameterized, hold_on_startup)
469451{
470452 rclcpp::executors::MultiThreadedExecutor executor;
471453
472- rclcpp::Parameter start_with_holding_parameter (" start_with_holding" , true );
473- SetUpAndActivateTrajectoryController (executor, {start_with_holding_parameter});
454+ SetUpAndActivateTrajectoryController (executor, {});
474455
475456 constexpr auto FIRST_POINT_TIME = std::chrono::milliseconds (250 );
476457 updateControllerAsync (rclcpp::Duration (FIRST_POINT_TIME));
477- // after startup with start_with_holding being set , we expect an active trajectory:
458+ // after startup, we expect an active trajectory:
478459 ASSERT_TRUE (traj_controller_->has_active_traj ());
479460 // one point, being the position at startup
480461 std::vector<double > initial_positions{INITIAL_POS_JOINT1, INITIAL_POS_JOINT2, INITIAL_POS_JOINT3};
0 commit comments