Skip to content

Commit 62ce487

Browse files
[JTC] Remove start_with_holding option (ros-controls#839)
1 parent fcc0847 commit 62ce487

File tree

3 files changed

+4
-31
lines changed

3 files changed

+4
-31
lines changed

joint_trajectory_controller/src/joint_trajectory_controller.cpp

Lines changed: 2 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -944,11 +944,8 @@ controller_interface::CallbackReturn JointTrajectoryController::on_activate(
944944
read_state_from_state_interfaces(last_commanded_state_);
945945
}
946946

947-
// Should the controller start by holding position at the beginning of active state?
948-
if (params_.start_with_holding)
949-
{
950-
add_new_trajectory_msg(set_hold_position());
951-
}
947+
// The controller should start by holding position at the beginning of active state
948+
add_new_trajectory_msg(set_hold_position());
952949
rt_is_holding_.writeFromNonRT(true);
953950

954951
// parse timeout parameter

joint_trajectory_controller/src/joint_trajectory_controller_parameters.yaml

Lines changed: 0 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -73,11 +73,6 @@ joint_trajectory_controller:
7373
one_of<>: [["splines", "none"]],
7474
}
7575
}
76-
start_with_holding: {
77-
type: bool,
78-
default_value: true,
79-
description: "If true, start with holding position after activation. Otherwise, no command will be sent until the first trajectory is received.",
80-
}
8176
allow_nonzero_velocity_at_trajectory_end: {
8277
type: bool,
8378
default_value: false,

joint_trajectory_controller/test/test_trajectory_controller.cpp

Lines changed: 2 additions & 21 deletions
Original file line numberDiff line numberDiff line change
@@ -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
*/
468450
TEST_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

Comments
 (0)