Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

[JTC] Rename open_loop_control parameter and slightly change its scope #1525

Open
wants to merge 14 commits into
base: master
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from 1 commit
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
5 changes: 3 additions & 2 deletions joint_trajectory_controller/doc/parameters_context.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -2,8 +2,6 @@ constraints:
Default values for tolerances if no explicit values are set in the ``JointTrajectory`` message.

gains: |
Only relevant, if ``open_loop_control`` is not set.

If ``velocity`` is the only command interface for all joints or an ``effort`` command interface is configured, PID controllers are used for every joint.
This structure contains the controller gains for every joint with the control law

Expand All @@ -16,3 +14,6 @@ gains: |
i.e., the shortest rotation to the target position is the desired motion.
Otherwise :math:`e = s_d - s` is used, with the desired position :math:`s_d` and the measured
position :math:`s` from the state interface.

If you want to turn of the PIDs (open loop control), set the gains to zero.
Thieso marked this conversation as resolved.
Show resolved Hide resolved

2 changes: 1 addition & 1 deletion joint_trajectory_controller/doc/userdoc.rst
Original file line number Diff line number Diff line change
Expand Up @@ -97,7 +97,7 @@ A yaml file for using it could be:
action_monitor_rate: 20.0

allow_partial_joints_goal: false
open_loop_control: true
interpolate_from_desired_state: true
constraints:
stopped_velocity_tolerance: 0.01
goal_time: 0.0
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -192,7 +192,7 @@ controller_interface::return_type JointTrajectoryController::update(
if (!traj_external_point_ptr_->is_sampled_already())
{
first_sample = true;
if (params_.open_loop_control)
if (params_.interpolate_from_desired_state)
{
traj_external_point_ptr_->set_point_before_trajectory_msg(
time, last_commanded_state_, joints_angle_wraparound_);
Expand Down Expand Up @@ -719,8 +719,7 @@ controller_interface::CallbackReturn JointTrajectoryController::on_configure(
// if there is only velocity or if there is effort command interface
// then use also PID adapter
use_closed_loop_pid_adapter_ =
(has_velocity_command_interface_ && params_.command_interfaces.size() == 1 &&
!params_.open_loop_control) ||
(has_velocity_command_interface_ && params_.command_interfaces.size() == 1) ||
has_effort_command_interface_;

if (use_closed_loop_pid_adapter_)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -44,15 +44,15 @@ joint_trajectory_controller:
default_value: false,
description: "Allow joint goals defining trajectory for only some joints.",
}
open_loop_control: {
interpolate_from_desired_state: {
type: bool,
default_value: false,
description: "Use controller in open-loop control mode
default_value: true,
Thieso marked this conversation as resolved.
Show resolved Hide resolved
description: "Interpolate from the current desired state when receiving a new trajectory.
\n\n
* The controller ignores the states provided by hardware interface but using last commands as states for starting the trajectory interpolation.\n
* It deactivates the feedback control, see the ``gains`` structure.
\n\n
This is useful if hardware states are not following commands, i.e., an offset between those (typical for hydraulic manipulators).
Furthermore, it is necessary if you have a reference trajectory that you send over multiple messages (e.g. for MPC-style trajectory planning).
\n\n
If this flag is set, the controller tries to read the values from the command interfaces on activation.
If they have real numeric values, those will be used instead of state interfaces.
Expand Down
19 changes: 9 additions & 10 deletions joint_trajectory_controller/test/test_trajectory_controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1005,8 +1005,7 @@ TEST_P(TrajectoryControllerTestParameterized, use_closed_loop_pid)
(traj_controller_->has_velocity_command_interface() &&
!traj_controller_->has_position_command_interface() &&
!traj_controller_->has_effort_command_interface() &&
!traj_controller_->has_acceleration_command_interface() &&
!traj_controller_->is_open_loop()) ||
!traj_controller_->has_acceleration_command_interface()) ||
traj_controller_->has_effort_command_interface())
{
EXPECT_TRUE(traj_controller_->use_closed_loop_pid_adapter());
Expand Down Expand Up @@ -1685,8 +1684,8 @@ TEST_P(TrajectoryControllerTestParameterized, test_jump_when_state_tracking_erro
{
rclcpp::executors::SingleThreadedExecutor executor;
// default if false so it will not be actually set parameter
rclcpp::Parameter is_open_loop_parameters("open_loop_control", false);
SetUpAndActivateTrajectoryController(executor, {is_open_loop_parameters}, true);
rclcpp::Parameter interp_desired_state_parameter("interpolate_from_desired_state", false);
SetUpAndActivateTrajectoryController(executor, {interp_desired_state_parameter}, true);

if (traj_controller_->has_position_command_interface() == false)
{
Expand Down Expand Up @@ -1790,10 +1789,10 @@ TEST_P(TrajectoryControllerTestParameterized, test_no_jump_when_state_tracking_e
{
rclcpp::executors::SingleThreadedExecutor executor;
// set open loop to true, this should change behavior from above
rclcpp::Parameter is_open_loop_parameters("open_loop_control", true);
rclcpp::Parameter interp_desired_state_parameter("interpolate_from_desired_state", true);
rclcpp::Parameter update_rate_param("update_rate", 100);
SetUpAndActivateTrajectoryController(
executor, {is_open_loop_parameters, update_rate_param}, true);
executor, {interp_desired_state_parameter, update_rate_param}, true);

if (traj_controller_->has_position_command_interface() == false)
{
Expand Down Expand Up @@ -1893,15 +1892,15 @@ TEST_P(TrajectoryControllerTestParameterized, test_no_jump_when_state_tracking_e
TEST_P(TrajectoryControllerTestParameterized, test_hw_states_has_offset_first_controller_start)
{
rclcpp::executors::SingleThreadedExecutor executor;
rclcpp::Parameter is_open_loop_parameters("open_loop_control", true);
rclcpp::Parameter interp_desired_state_parameter("interpolate_from_desired_state", true);

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

SetUpAndActivateTrajectoryController(
executor, {is_open_loop_parameters}, true, 0., 1., initial_pos_cmd, initial_vel_cmd,
executor, {interp_desired_state_parameter}, true, 0., 1., initial_pos_cmd, initial_vel_cmd,
initial_acc_cmd);

// no call of update method, so the values should be read from state interfaces
Expand Down Expand Up @@ -1934,7 +1933,7 @@ TEST_P(TrajectoryControllerTestParameterized, test_hw_states_has_offset_first_co
TEST_P(TrajectoryControllerTestParameterized, test_hw_states_has_offset_later_controller_start)
{
rclcpp::executors::SingleThreadedExecutor executor;
rclcpp::Parameter is_open_loop_parameters("open_loop_control", true);
rclcpp::Parameter interp_desired_state_parameter("interpolate_from_desired_state", true);

// set command values to arbitrary values
std::vector<double> initial_pos_cmd, initial_vel_cmd, initial_acc_cmd;
Expand All @@ -1945,7 +1944,7 @@ TEST_P(TrajectoryControllerTestParameterized, test_hw_states_has_offset_later_co
initial_acc_cmd.push_back(0.02 + static_cast<double>(i) / 10.0);
}
SetUpAndActivateTrajectoryController(
executor, {is_open_loop_parameters}, true, 0., 1., initial_pos_cmd, initial_vel_cmd,
executor, {interp_desired_state_parameter}, true, 0., 1., initial_pos_cmd, initial_vel_cmd,
initial_acc_cmd);

// no call of update method, so the values should be read from command interfaces
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -167,8 +167,6 @@ class TestableJointTrajectoryController

bool use_closed_loop_pid_adapter() const { return use_closed_loop_pid_adapter_; }

bool is_open_loop() const { return params_.open_loop_control; }

joint_trajectory_controller::SegmentTolerances get_active_tolerances()
{
return *(active_tolerances_.readFromRT());
Expand Down