Skip to content

Commit fcaa035

Browse files
[JTC] Rename open_loop_control parameter and slightly change its scope (#1525)
Co-authored-by: Christoph Froehlich <[email protected]>
1 parent 11ed083 commit fcaa035

File tree

8 files changed

+41
-22
lines changed

8 files changed

+41
-22
lines changed

doc/migration.rst

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -20,3 +20,4 @@ joint_trajectory_controller
2020
* Angle wraparound behavior (continuous joints) was added from the current state to the first segment of the incoming trajectory (`#796 <https://github.com/ros-controls/ros2_controllers/pull/796>`_).
2121
* The URDF is now parsed for continuous joints and angle wraparound is automatically activated now (`#949 <https://github.com/ros-controls/ros2_controllers/pull/949>`_). Remove the ``angle_wraparound`` parameter from the configuration and set continuous joint type in the URDF of the respective joint.
2222
* Tolerances sent with the action goal were not used before, but are now processed and used for the upcoming action. (`#716 <https://github.com/ros-controls/ros2_controllers/pull/716>`_). Adaptions to the action goal might be necessary.
23+
* Parameter ``open_loop_control`` is replaced by ``interpolate_from_desired_state`` and setting the feedback gains to zero (`#1525 <https://github.com/ros-controls/ros2_controllers/pull/1525>`_).

doc/release_notes.rst

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -52,6 +52,7 @@ joint_trajectory_controller
5252
allowed to move without restriction.
5353
5454
* 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>`_).
55+
* Parameter ``open_loop_control`` is replaced by ``interpolate_from_desired_state`` and setting the feedback gains to zero (`#1525 <https://github.com/ros-controls/ros2_controllers/pull/1525>`_).
5556

5657
mecanum_drive_controller
5758
************************

joint_trajectory_controller/doc/parameters_context.yaml

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -2,8 +2,6 @@ constraints:
22
Default values for tolerances if no explicit values are set in the ``JointTrajectory`` message.
33

44
gains: |
5-
Only relevant, if ``open_loop_control`` is not set.
6-
75
If ``velocity`` is the only command interface for all joints or an ``effort`` command interface is configured, PID controllers are used for every joint.
86
This structure contains the controller gains for every joint with the control law
97
@@ -16,3 +14,5 @@ gains: |
1614
i.e., the shortest rotation to the target position is the desired motion.
1715
Otherwise :math:`e = s_d - s` is used, with the desired position :math:`s_d` and the measured
1816
position :math:`s` from the state interface.
17+
18+
If you want to turn off the PIDs (open loop control), set the feedback gains to zero.

joint_trajectory_controller/doc/userdoc.rst

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -97,7 +97,7 @@ A yaml file for using it could be:
9797
action_monitor_rate: 20.0
9898
9999
allow_partial_joints_goal: false
100-
open_loop_control: true
100+
interpolate_from_desired_state: true
101101
constraints:
102102
stopped_velocity_tolerance: 0.01
103103
goal_time: 0.0

joint_trajectory_controller/src/joint_trajectory_controller.cpp

Lines changed: 11 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -188,7 +188,7 @@ controller_interface::return_type JointTrajectoryController::update(
188188
if (!current_trajectory_->is_sampled_already())
189189
{
190190
first_sample = true;
191-
if (params_.open_loop_control)
191+
if (params_.interpolate_from_desired_state || params_.open_loop_control)
192192
{
193193
if (std::abs(last_commanded_time_.seconds()) < std::numeric_limits<float>::epsilon())
194194
{
@@ -655,6 +655,16 @@ controller_interface::CallbackReturn JointTrajectoryController::on_configure(
655655
{
656656
auto logger = get_node()->get_logger();
657657

658+
// START DEPRECATE
659+
if (params_.open_loop_control)
660+
{
661+
RCLCPP_WARN(
662+
logger,
663+
"[deprecated] 'open_loop_control' parameter is deprecated. Instead, set the feedback gains "
664+
"to zero and use 'interpolate_from_desired_state' parameter");
665+
}
666+
// END DEPRECATE
667+
658668
// update the dynamic map parameters
659669
param_listener_->refresh_dynamic_parameters();
660670

joint_trajectory_controller/src/joint_trajectory_controller_parameters.yaml

Lines changed: 10 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -47,12 +47,18 @@ joint_trajectory_controller:
4747
open_loop_control: {
4848
type: bool,
4949
default_value: false,
50-
description: "Use controller in open-loop control mode
50+
description: "deprecated: use ``interpolate_from_desired_state`` and set feedback gains to zero instead",
51+
read_only: true,
52+
}
53+
interpolate_from_desired_state: {
54+
type: bool,
55+
default_value: false,
56+
description: "Interpolate from the current desired state when receiving a new trajectory.
5157
\n\n
52-
* The controller ignores the states provided by hardware interface but using last commands as states for starting the trajectory interpolation.\n
53-
* It deactivates the feedback control, see the ``gains`` structure.
58+
The controller ignores the states provided by hardware interface but using last commands as states for starting the trajectory interpolation.
5459
\n\n
5560
This is useful if hardware states are not following commands, i.e., an offset between those (typical for hydraulic manipulators).
61+
Furthermore, it is necessary if you have a reference trajectory that you send over multiple messages (e.g. for MPC-style trajectory planning).
5662
\n\n
5763
If this flag is set, the controller tries to read the values from the command interfaces on activation.
5864
If they have real numeric values, those will be used instead of state interfaces.
@@ -72,7 +78,7 @@ joint_trajectory_controller:
7278
action_monitor_rate: {
7379
type: double,
7480
default_value: 20.0,
75-
description: "Rate to monitor status changes when the controller is executing action (control_msgs::action::FollowJointTrajectory)",
81+
description: "Rate to monitor status changes when the controller is executing action (``control_msgs::action::FollowJointTrajectory``)",
7682
read_only: true,
7783
validation: {
7884
gt_eq: [0.1]

joint_trajectory_controller/test/test_trajectory_controller.cpp

Lines changed: 13 additions & 14 deletions
Original file line numberDiff line numberDiff line change
@@ -971,8 +971,7 @@ TEST_P(TrajectoryControllerTestParameterized, use_closed_loop_pid)
971971
(traj_controller_->has_velocity_command_interface() &&
972972
!traj_controller_->has_position_command_interface() &&
973973
!traj_controller_->has_effort_command_interface() &&
974-
!traj_controller_->has_acceleration_command_interface() &&
975-
!traj_controller_->is_open_loop()) ||
974+
!traj_controller_->has_acceleration_command_interface()) ||
976975
traj_controller_->has_effort_command_interface())
977976
{
978977
EXPECT_TRUE(traj_controller_->use_closed_loop_pid_adapter());
@@ -1650,9 +1649,9 @@ TEST_P(TrajectoryControllerTestParameterized, test_execute_partial_traj_in_futur
16501649
TEST_P(TrajectoryControllerTestParameterized, test_jump_when_state_tracking_error_updated)
16511650
{
16521651
rclcpp::executors::SingleThreadedExecutor executor;
1653-
// default if false so it will not be actually set parameter
1654-
rclcpp::Parameter is_open_loop_parameters("open_loop_control", false);
1655-
SetUpAndActivateTrajectoryController(executor, {is_open_loop_parameters}, true);
1652+
// default is false so it will not be actually set parameter
1653+
rclcpp::Parameter interp_desired_state_parameter("interpolate_from_desired_state", false);
1654+
SetUpAndActivateTrajectoryController(executor, {interp_desired_state_parameter}, true);
16561655

16571656
if (traj_controller_->has_position_command_interface() == false)
16581657
{
@@ -1681,7 +1680,7 @@ TEST_P(TrajectoryControllerTestParameterized, test_jump_when_state_tracking_erro
16811680
traj_controller_->wait_for_trajectory(executor);
16821681
auto end_time = updateControllerAsync(rclcpp::Duration::from_seconds(1.1));
16831682

1684-
// JTC is NOT executing trajectory in open-loop therefore:
1683+
// JTC is NOT executing trajectory with interpolate_from_desired_state, therefore:
16851684
// - internal state does not have to be updated (in this test-case it shouldn't)
16861685
// - internal command is updated
16871686
EXPECT_NEAR(INITIAL_POS_JOINT1, joint_state_pos_[0], COMMON_THRESHOLD);
@@ -1755,11 +1754,11 @@ TEST_P(TrajectoryControllerTestParameterized, test_jump_when_state_tracking_erro
17551754
TEST_P(TrajectoryControllerTestParameterized, test_no_jump_when_state_tracking_error_not_updated)
17561755
{
17571756
rclcpp::executors::SingleThreadedExecutor executor;
1758-
// set open loop to true, this should change behavior from above
1759-
rclcpp::Parameter is_open_loop_parameters("open_loop_control", true);
1757+
// set interpolate_from_desired_state to true, this should change behavior from above
1758+
rclcpp::Parameter interp_desired_state_parameter("interpolate_from_desired_state", true);
17601759
rclcpp::Parameter update_rate_param("update_rate", 100);
17611760
SetUpAndActivateTrajectoryController(
1762-
executor, {is_open_loop_parameters, update_rate_param}, true);
1761+
executor, {interp_desired_state_parameter, update_rate_param}, true);
17631762

17641763
if (traj_controller_->has_position_command_interface() == false)
17651764
{
@@ -1785,7 +1784,7 @@ TEST_P(TrajectoryControllerTestParameterized, test_no_jump_when_state_tracking_e
17851784
traj_controller_->wait_for_trajectory(executor);
17861785
auto end_time = updateControllerAsync(rclcpp::Duration::from_seconds(1.1));
17871786

1788-
// JTC is executing trajectory in open-loop therefore:
1787+
// JTC is executing trajectory with interpolate_from_desired_state therefore:
17891788
// - internal state does not have to be updated (in this test-case it shouldn't)
17901789
// - internal command is updated
17911790
EXPECT_NEAR(INITIAL_POS_JOINT1, joint_state_pos_[0], COMMON_THRESHOLD);
@@ -1859,15 +1858,15 @@ TEST_P(TrajectoryControllerTestParameterized, test_no_jump_when_state_tracking_e
18591858
TEST_P(TrajectoryControllerTestParameterized, test_hw_states_has_offset_first_controller_start)
18601859
{
18611860
rclcpp::executors::SingleThreadedExecutor executor;
1862-
rclcpp::Parameter is_open_loop_parameters("open_loop_control", true);
1861+
rclcpp::Parameter interp_desired_state_parameter("interpolate_from_desired_state", true);
18631862

18641863
// set command values to NaN
18651864
std::vector<double> initial_pos_cmd{3, std::numeric_limits<double>::quiet_NaN()};
18661865
std::vector<double> initial_vel_cmd{3, std::numeric_limits<double>::quiet_NaN()};
18671866
std::vector<double> initial_acc_cmd{3, std::numeric_limits<double>::quiet_NaN()};
18681867

18691868
SetUpAndActivateTrajectoryController(
1870-
executor, {is_open_loop_parameters}, true, 0., 1., initial_pos_cmd, initial_vel_cmd,
1869+
executor, {interp_desired_state_parameter}, true, 0., 1., initial_pos_cmd, initial_vel_cmd,
18711870
initial_acc_cmd);
18721871

18731872
// no call of update method, so the values should be read from state interfaces
@@ -1900,7 +1899,7 @@ TEST_P(TrajectoryControllerTestParameterized, test_hw_states_has_offset_first_co
19001899
TEST_P(TrajectoryControllerTestParameterized, test_hw_states_has_offset_later_controller_start)
19011900
{
19021901
rclcpp::executors::SingleThreadedExecutor executor;
1903-
rclcpp::Parameter is_open_loop_parameters("open_loop_control", true);
1902+
rclcpp::Parameter interp_desired_state_parameter("interpolate_from_desired_state", true);
19041903

19051904
// set command values to arbitrary values
19061905
std::vector<double> initial_pos_cmd, initial_vel_cmd, initial_acc_cmd;
@@ -1911,7 +1910,7 @@ TEST_P(TrajectoryControllerTestParameterized, test_hw_states_has_offset_later_co
19111910
initial_acc_cmd.push_back(0.02 + static_cast<double>(i) / 10.0);
19121911
}
19131912
SetUpAndActivateTrajectoryController(
1914-
executor, {is_open_loop_parameters}, true, 0., 1., initial_pos_cmd, initial_vel_cmd,
1913+
executor, {interp_desired_state_parameter}, true, 0., 1., initial_pos_cmd, initial_vel_cmd,
19151914
initial_acc_cmd);
19161915

19171916
// no call of update method, so the values should be read from command interfaces

joint_trajectory_controller/test/test_trajectory_controller_utils.hpp

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -167,7 +167,9 @@ class TestableJointTrajectoryController
167167

168168
bool use_closed_loop_pid_adapter() const { return use_closed_loop_pid_adapter_; }
169169

170+
// START DEPRECATE
170171
bool is_open_loop() const { return params_.open_loop_control; }
172+
// END DEPRECATE
171173

172174
joint_trajectory_controller::SegmentTolerances get_active_tolerances()
173175
{

0 commit comments

Comments
 (0)