Skip to content

Commit e3c21e5

Browse files
[JTC] Add Parameter to Toggle State Setting on Activation (#1231) (#1319)
* [JTC] Add param to setting last command interface value as state on activation * [JTC] add a note about set_last_command_interface_value_as_state_on_activation to release_notes. Updated the parameters.yaml description to match the same wording. --------- Co-authored-by: Bence Magyar <[email protected]> Co-authored-by: Christoph Fröhlich <[email protected]> (cherry picked from commit f96d2fc) Co-authored-by: Kenta Kato <[email protected]>
1 parent b78380c commit e3c21e5

File tree

3 files changed

+10
-1
lines changed

3 files changed

+10
-1
lines changed

doc/release_notes.rst

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -45,6 +45,8 @@ joint_trajectory_controller
4545
* -1 - The tolerance is "erased". If there was a default, the joint will be
4646
allowed to move without restriction.
4747
48+
* Add the boolean parameter ``set_last_command_interface_value_as_state_on_activation``. When set to ``true``, the last command interface value is used as both the current state and the last commanded state upon activation. When set to ``false``, the current state is used for both (`#1231 <https://github.com/ros-controls/ros2_controllers/pull/1231>`_).
49+
4850
pid_controller
4951
************************
5052
* 🚀 The PID controller was added 🎉 (`#434 <https://github.com/ros-controls/ros2_controllers/pull/434>`_).

joint_trajectory_controller/src/joint_trajectory_controller.cpp

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -918,7 +918,9 @@ controller_interface::CallbackReturn JointTrajectoryController::on_activate(
918918
// running already)
919919
trajectory_msgs::msg::JointTrajectoryPoint state;
920920
resize_joint_trajectory_point(state, dof_);
921-
if (read_state_from_command_interfaces(state))
921+
if (
922+
params_.set_last_command_interface_value_as_state_on_activation &&
923+
read_state_from_command_interfaces(state))
922924
{
923925
state_current_ = state;
924926
last_commanded_state_ = state;

joint_trajectory_controller/src/joint_trajectory_controller_parameters.yaml

Lines changed: 5 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -64,6 +64,11 @@ joint_trajectory_controller:
6464
default_value: false,
6565
description: "Allow integration in goal trajectories to accept goals without position or velocity specified",
6666
}
67+
set_last_command_interface_value_as_state_on_activation: {
68+
type: bool,
69+
default_value: true,
70+
description: "When set to true, the last command interface value is used as both the current state and the last commanded state upon activation. When set to false, the current state is used for both.",
71+
}
6772
action_monitor_rate: {
6873
type: double,
6974
default_value: 20.0,

0 commit comments

Comments
 (0)