Skip to content

Commit 90a9674

Browse files
VladimirIvanchristophfroehlichsaikishor
authored
[JTC] Enable feed-forward effort trajectories (#1200)
Co-authored-by: Christoph Froehlich <[email protected]> Co-authored-by: Sai Kishor Kothakota <[email protected]>
1 parent fcaa035 commit 90a9674

File tree

8 files changed

+262
-65
lines changed

8 files changed

+262
-65
lines changed

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+
* Feed-forward effort trajectories are supported now (`#1200 <https://github.com/ros-controls/ros2_controllers/pull/1200>`_).
5556
* 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>`_).
5657

5758
mecanum_drive_controller

joint_trajectory_controller/doc/trajectory.rst

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -49,6 +49,8 @@ The spline interpolator uses the following interpolation strategies depending on
4949

5050
Trajectories with velocity fields only, velocity and acceleration only, or acceleration fields only can be processed and are accepted, if ``allow_integration_in_goal_trajectories`` is true. Position (and velocity) is then integrated from velocity (or acceleration, respectively) by Heun's method.
5151

52+
Effort trajectories are allowed for controllers that claim the ``effort`` command interface and they are treated as feed-forward effort that is added to the position feedback. Effort is handled separately from position, velocity and acceleration. We use linear interpolation for effort when the ``spline`` interpolation method is selected.
53+
5254
Visualized Examples
5355
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
5456
To visualize the difference of the different interpolation methods and their inputs, different trajectories defined at a 0.5s grid and are sampled at a rate of 10ms.

joint_trajectory_controller/doc/userdoc.rst

Lines changed: 4 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -24,12 +24,15 @@ Currently, joints with hardware interface types ``position``, ``velocity``, ``ac
2424
* ``position``, ``velocity``, ``acceleration``
2525
* ``velocity``
2626
* ``effort``
27+
* ``position``, ``effort``
2728

2829
This means that the joints can have one or more command interfaces, where the following control laws are applied at the same time:
2930

3031
* For command interfaces ``position``, the desired positions are simply forwarded to the joints,
3132
* For command interfaces ``acceleration``, desired accelerations are simply forwarded to the joints.
3233
* For ``velocity`` (``effort``) command interfaces, the position+velocity trajectory following error is mapped to ``velocity`` (``effort``) commands through a PID loop if it is configured (:ref:`parameters`).
34+
* For ``effort`` command interface (without ``position`` command interface), if the trajectory contains effort, this will be added to the PID commands as a feed forward effort.
35+
* For ``position, effort`` command interface, if the trajectory contains effort, this will be passed directly to the ``effort`` interface (PID won't be used) while the positions will be passed to the ``position`` interface.
3336

3437
This leads to the following allowed combinations of command and state interfaces:
3538

@@ -38,7 +41,7 @@ This leads to the following allowed combinations of command and state interfaces
3841

3942
* if command interface ``velocity`` is the only one, state interfaces must include ``position, velocity`` .
4043

41-
* With command interface ``effort``, state interfaces must include ``position, velocity``.
44+
* With command interface ``effort`` or ``position, effort``, state interfaces must include ``position, velocity``.
4245

4346
* With command interface ``acceleration``, state interfaces must include ``position, velocity``.
4447

joint_trajectory_controller/include/joint_trajectory_controller/validate_jtc_parameters.hpp

Lines changed: 7 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -32,7 +32,8 @@ tl::expected<void, std::string> command_interface_type_combinations(
3232
// Check if command interfaces combination is valid. Valid combinations are:
3333
// 1. effort
3434
// 2. velocity
35-
// 2. position [velocity, [acceleration]]
35+
// 3. position [velocity, [acceleration]]
36+
// 4. position, effort
3637

3738
if (
3839
rsl::contains<std::vector<std::string>>(interface_types, "velocity") &&
@@ -56,9 +57,12 @@ tl::expected<void, std::string> command_interface_type_combinations(
5657

5758
if (
5859
rsl::contains<std::vector<std::string>>(interface_types, "effort") &&
59-
interface_types.size() > 1)
60+
!(interface_types.size() == 1 ||
61+
(interface_types.size() == 2 &&
62+
rsl::contains<std::vector<std::string>>(interface_types, "position"))))
6063
{
61-
return tl::make_unexpected("'effort' command interface has to be used alone");
64+
return tl::make_unexpected(
65+
"'effort' command interface has to be used alone or with a 'position' interface");
6266
}
6367

6468
return {};

joint_trajectory_controller/src/joint_trajectory_controller.cpp

Lines changed: 48 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -293,7 +293,10 @@ controller_interface::return_type JointTrajectoryController::update(
293293
// Update PIDs
294294
for (auto i = 0ul; i < dof_; ++i)
295295
{
296+
// If effort interface only, add desired effort as feed forward
297+
// If velocity interface, ignore desired effort
296298
tmp_command_[i] = (command_next_.velocities[i] * ff_velocity_scale_[i]) +
299+
(has_effort_command_interface_ ? command_next_.effort[i] : 0.0) +
297300
pids_[i]->compute_command(
298301
state_error_.positions[i], state_error_.velocities[i], period);
299302
}
@@ -321,7 +324,15 @@ controller_interface::return_type JointTrajectoryController::update(
321324
}
322325
if (has_effort_command_interface_)
323326
{
324-
assign_interface_from_point(joint_command_interface_[3], tmp_command_);
327+
if (use_closed_loop_pid_adapter_)
328+
{
329+
assign_interface_from_point(joint_command_interface_[3], tmp_command_);
330+
}
331+
else
332+
{
333+
// If position and effort command interfaces, only pass desired effort
334+
assign_interface_from_point(joint_command_interface_[3], state_desired_.effort);
335+
}
325336
}
326337

327338
// store the previous command and time used in open-loop control mode
@@ -459,6 +470,11 @@ void JointTrajectoryController::read_state_from_state_interfaces(JointTrajectory
459470
state.velocities.clear();
460471
state.accelerations.clear();
461472
}
473+
// No state interface for now, use command interface
474+
if (has_effort_command_interface_)
475+
{
476+
assign_point_from_interface(state.effort, joint_command_interface_[3]);
477+
}
462478
}
463479

464480
bool JointTrajectoryController::read_state_from_command_interfaces(JointTrajectoryPoint & state)
@@ -527,6 +543,20 @@ bool JointTrajectoryController::read_state_from_command_interfaces(JointTrajecto
527543
state.accelerations.clear();
528544
}
529545

546+
// Effort state always comes from last command
547+
if (has_effort_command_interface_)
548+
{
549+
if (interface_has_values(joint_command_interface_[3]))
550+
{
551+
assign_point_from_interface(state.effort, joint_command_interface_[3]);
552+
}
553+
else
554+
{
555+
state.effort.clear();
556+
has_values = false;
557+
}
558+
}
559+
530560
return has_values;
531561
}
532562

@@ -725,13 +755,14 @@ controller_interface::CallbackReturn JointTrajectoryController::on_configure(
725755
use_closed_loop_pid_adapter_ =
726756
(has_velocity_command_interface_ && params_.command_interfaces.size() == 1 &&
727757
!params_.open_loop_control) ||
728-
has_effort_command_interface_;
758+
(has_effort_command_interface_ && params_.command_interfaces.size() == 1);
759+
760+
tmp_command_.resize(dof_, 0.0);
729761

730762
if (use_closed_loop_pid_adapter_)
731763
{
732764
pids_.resize(dof_);
733765
ff_velocity_scale_.resize(dof_);
734-
tmp_command_.resize(dof_, 0.0);
735766

736767
update_pids();
737768
}
@@ -768,15 +799,17 @@ controller_interface::CallbackReturn JointTrajectoryController::on_configure(
768799
return CallbackReturn::FAILURE;
769800
}
770801

771-
// effort is always used alone so no need for size check
802+
// effort only or effort and position command interfaces require position and velocity state
772803
if (
773804
has_effort_command_interface_ &&
805+
(params_.command_interfaces.size() == 1 ||
806+
(params_.command_interfaces.size() == 2 && has_position_command_interface_)) &&
774807
(!has_velocity_state_interface_ || !has_position_state_interface_))
775808
{
776809
RCLCPP_ERROR(
777810
logger,
778-
"'effort' command interface can only be used alone if 'velocity' and "
779-
"'position' state interfaces are present");
811+
"'effort' command interface can only be used alone or with 'position' command interface "
812+
"if 'velocity' and 'position' state interfaces are present");
780813
return CallbackReturn::FAILURE;
781814
}
782815

@@ -1495,10 +1528,12 @@ bool JointTrajectoryController::validate_trajectory_msg(
14951528
return false;
14961529
}
14971530
// reject effort entries
1498-
if (!points[i].effort.empty())
1531+
if (!has_effort_command_interface_ && !points[i].effort.empty())
14991532
{
15001533
RCLCPP_ERROR(
1501-
get_node()->get_logger(), "Trajectories with effort fields are currently not supported.");
1534+
get_node()->get_logger(),
1535+
"Trajectories with effort fields are only supported for "
1536+
"controllers using the 'effort' command interface.");
15021537
return false;
15031538
}
15041539
}
@@ -1569,6 +1604,7 @@ void JointTrajectoryController::resize_joint_trajectory_point(
15691604
{
15701605
point.accelerations.resize(size, 0.0);
15711606
}
1607+
point.effort.resize(size, 0.0);
15721608
}
15731609

15741610
void JointTrajectoryController::resize_joint_trajectory_point_command(
@@ -1637,6 +1673,10 @@ void JointTrajectoryController::init_hold_position_msg()
16371673
// add velocity, so that trajectory sampling returns acceleration points in any case
16381674
hold_position_msg_ptr_->points[0].accelerations.resize(dof_, 0.0);
16391675
}
1676+
if (has_effort_command_interface_)
1677+
{
1678+
hold_position_msg_ptr_->points[0].effort.resize(dof_, 0.0);
1679+
}
16401680
}
16411681

16421682
} // namespace joint_trajectory_controller

joint_trajectory_controller/src/trajectory.cpp

Lines changed: 33 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -199,6 +199,10 @@ bool Trajectory::sample(
199199
{
200200
output_state.accelerations.resize(output_state.positions.size(), 0.0);
201201
}
202+
if (output_state.effort.empty())
203+
{
204+
output_state.effort.resize(output_state.positions.size(), 0.0);
205+
}
202206
return true;
203207
}
204208

@@ -214,6 +218,7 @@ void Trajectory::interpolate_between_points(
214218
output.positions.resize(dim, 0.0);
215219
output.velocities.resize(dim, 0.0);
216220
output.accelerations.resize(dim, 0.0);
221+
output.effort.resize(dim, 0.0);
217222

218223
auto generate_powers = [](int n, double x, double * powers)
219224
{
@@ -226,6 +231,7 @@ void Trajectory::interpolate_between_points(
226231

227232
bool has_velocity = !state_a.velocities.empty() && !state_b.velocities.empty();
228233
bool has_accel = !state_a.accelerations.empty() && !state_b.accelerations.empty();
234+
bool has_effort = !state_a.effort.empty() && !state_b.effort.empty();
229235
if (duration_so_far.seconds() < 0.0)
230236
{
231237
duration_so_far = rclcpp::Duration::from_seconds(0.0);
@@ -240,6 +246,25 @@ void Trajectory::interpolate_between_points(
240246
double t[6];
241247
generate_powers(5, duration_so_far.seconds(), t);
242248

249+
if (has_effort)
250+
{
251+
// do linear interpolation
252+
for (size_t i = 0; i < dim; ++i)
253+
{
254+
double start_effort = state_a.effort[i];
255+
double end_effort = state_b.effort[i];
256+
257+
double coefficients[2] = {0.0, 0.0};
258+
coefficients[0] = start_effort;
259+
if (duration_btwn_points.seconds() != 0.0)
260+
{
261+
coefficients[1] = (end_effort - start_effort) / duration_btwn_points.seconds();
262+
}
263+
264+
output.effort[i] = t[0] * coefficients[0] + t[1] * coefficients[1];
265+
}
266+
}
267+
243268
if (!has_velocity && !has_accel)
244269
{
245270
// do linear interpolation
@@ -338,6 +363,14 @@ void Trajectory::deduce_from_derivatives(
338363
trajectory_msgs::msg::JointTrajectoryPoint & first_state,
339364
trajectory_msgs::msg::JointTrajectoryPoint & second_state, const size_t dim, const double delta_t)
340365
{
366+
if (first_state.effort.empty())
367+
{
368+
first_state.effort.assign(dim, 0.0);
369+
}
370+
if (second_state.effort.empty())
371+
{
372+
second_state.effort.assign(dim, 0.0);
373+
}
341374
if (second_state.positions.empty())
342375
{
343376
second_state.positions.resize(dim);

0 commit comments

Comments
 (0)