Skip to content

Commit

Permalink
[JTC] Add Parameter to Toggle State Setting on Activation (#1231) (#1319
Browse files Browse the repository at this point in the history
)

* [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]>
  • Loading branch information
mergify[bot] and KentaKato authored Oct 26, 2024
1 parent b78380c commit e3c21e5
Show file tree
Hide file tree
Showing 3 changed files with 10 additions and 1 deletion.
2 changes: 2 additions & 0 deletions doc/release_notes.rst
Original file line number Diff line number Diff line change
Expand Up @@ -45,6 +45,8 @@ joint_trajectory_controller
* -1 - The tolerance is "erased". If there was a default, the joint will be
allowed to move without restriction.
* 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>`_).

pid_controller
************************
* 🚀 The PID controller was added 🎉 (`#434 <https://github.com/ros-controls/ros2_controllers/pull/434>`_).
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -918,7 +918,9 @@ controller_interface::CallbackReturn JointTrajectoryController::on_activate(
// running already)
trajectory_msgs::msg::JointTrajectoryPoint state;
resize_joint_trajectory_point(state, dof_);
if (read_state_from_command_interfaces(state))
if (
params_.set_last_command_interface_value_as_state_on_activation &&
read_state_from_command_interfaces(state))
{
state_current_ = state;
last_commanded_state_ = state;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -64,6 +64,11 @@ joint_trajectory_controller:
default_value: false,
description: "Allow integration in goal trajectories to accept goals without position or velocity specified",
}
set_last_command_interface_value_as_state_on_activation: {
type: bool,
default_value: true,
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.",
}
action_monitor_rate: {
type: double,
default_value: 20.0,
Expand Down

0 comments on commit e3c21e5

Please sign in to comment.