Skip to content

Commit

Permalink
[JTC] Remove start_with_holding option (backport #839)
Browse files Browse the repository at this point in the history
  • Loading branch information
christophfroehlich committed Dec 1, 2023
1 parent 2c26efb commit 392b097
Show file tree
Hide file tree
Showing 3 changed files with 4 additions and 31 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -1001,11 +1001,8 @@ controller_interface::CallbackReturn JointTrajectoryController::on_activate(
read_state_from_state_interfaces(last_commanded_state_);
}

// Should the controller start by holding position at the beginning of active state?
if (params_.start_with_holding)
{
add_new_trajectory_msg(set_hold_position());
}
// The controller should start by holding position at the beginning of active state
add_new_trajectory_msg(set_hold_position());
rt_is_holding_.writeFromNonRT(true);

// parse timeout parameter
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -81,11 +81,6 @@ joint_trajectory_controller:
one_of<>: [["splines", "none"]],
}
}
start_with_holding: {
type: bool,
default_value: true,
description: "If true, start with holding position after activation. Otherwise, no command will be sent until the first trajectory is received.",
}
allow_nonzero_velocity_at_trajectory_end: {
type: bool,
default_value: true,
Expand Down
23 changes: 2 additions & 21 deletions joint_trajectory_controller/test/test_trajectory_controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -496,37 +496,18 @@ TEST_P(TrajectoryControllerTestParameterized, update_dynamic_tolerances)
executor.cancel();
}

/**
* @brief check if hold on startup is deactivated
*/
TEST_P(TrajectoryControllerTestParameterized, no_hold_on_startup)
{
rclcpp::executors::MultiThreadedExecutor executor;

rclcpp::Parameter start_with_holding_parameter("start_with_holding", false);
SetUpAndActivateTrajectoryController(executor, {start_with_holding_parameter});

constexpr auto FIRST_POINT_TIME = std::chrono::milliseconds(250);
updateControllerAsync(rclcpp::Duration(FIRST_POINT_TIME));
// after startup without start_with_holding being set, we expect no active trajectory
ASSERT_FALSE(traj_controller_->has_active_traj());

executor.cancel();
}

/**
* @brief check if hold on startup
*/
TEST_P(TrajectoryControllerTestParameterized, hold_on_startup)
{
rclcpp::executors::MultiThreadedExecutor executor;

rclcpp::Parameter start_with_holding_parameter("start_with_holding", true);
SetUpAndActivateTrajectoryController(executor, {start_with_holding_parameter});
SetUpAndActivateTrajectoryController(executor, {});

constexpr auto FIRST_POINT_TIME = std::chrono::milliseconds(250);
updateControllerAsync(rclcpp::Duration(FIRST_POINT_TIME));
// after startup with start_with_holding being set, we expect an active trajectory:
// after startup, we expect an active trajectory:
ASSERT_TRUE(traj_controller_->has_active_traj());
// one point, being the position at startup
std::vector<double> initial_positions{INITIAL_POS_JOINT1, INITIAL_POS_JOINT2, INITIAL_POS_JOINT3};
Expand Down

0 comments on commit 392b097

Please sign in to comment.