Skip to content

Commit 612f610

Browse files
destoglbmagyar
andauthored
[JointTrajectoryController] Enable position, velocity and acceleration interfaces (#140)
* Test position only version of JTC for KUKA RSI robots. * All changes in JTC added * Don't freak out when wait set can't be established * Test should expect that before a run, controller is unconfigured as well as after an unsuccessful configure call * joint_trajectory_controller should not go into FINALIZED state when fails to configure, remain in UNCONFIGURED Co-authored-by: Bence Magyar <[email protected]>
1 parent f04c5a1 commit 612f610

File tree

12 files changed

+778
-170
lines changed

12 files changed

+778
-170
lines changed

doc/controllers_index.rst

Lines changed: 33 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -1,5 +1,38 @@
11
.. _controllers:
22

3+
========================
4+
ros2_controllers
5+
========================
6+
7+
`GitHub Repository <https://github.com/ros-controls/ros2_controllers>`_
8+
9+
Nomenclature
10+
-------------
11+
The ros2_control framework uses namespaces to sort controller according to the type of command interface they are using.
12+
The controllers are using `common hardware interface definitions`_.
13+
The controllers' namespaces are commanding the following command interface types:
14+
15+
- ``position_controllers``: ``hardware_interface::HW_IF_POSITION``
16+
- ``velocity_controller``: ``hardware_interface::HW_IF_VELOCITY``
17+
- ``effort_controllers``: ``hardware_interface::HW_IF_EFFORT``
18+
- ...
19+
20+
21+
Controllers
22+
--------------
23+
24+
The following standard controllers are implemented:
25+
26+
- `Joint Trajectory Controller <joint_trajectory_controller/docs/index.rst>`_ - provided a list of waypoints or target point defined with position, velocity and acceleration, the controller interpolates joint trajectories through it.
27+
- ... <the list is not complete> ...
28+
29+
30+
31+
32+
.. _common hardware interface definitions: https://github.com/ros-controls/ros2_control/blob/master/hardware_interface/include/hardware_interface/types/hardware_interface_type_values.hpp
33+
34+
35+
336
Controllers user documentation
437
==============================
538

forward_command_controller/src/forward_command_controller.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -65,7 +65,7 @@ CallbackReturn ForwardCommandController::on_configure(
6565
return CallbackReturn::ERROR;
6666
}
6767

68-
// Specialized, child controllers set interfaces before calling init function.
68+
// Specialized, child controllers set interfaces before calling configure function.
6969
if (interface_name_.empty()) {
7070
interface_name_ = node_->get_parameter("interface_name").as_string();
7171
}

joint_trajectory_controller/CMakeLists.txt

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -72,6 +72,7 @@ if(BUILD_TESTING)
7272
ament_add_gtest(test_trajectory_controller
7373
test/test_trajectory_controller.cpp
7474
ENV config_file=${CMAKE_CURRENT_SOURCE_DIR}/test/config/test_joint_trajectory_controller.yaml)
75+
set_tests_properties(test_trajectory_controller PROPERTIES TIMEOUT 120)
7576
target_include_directories(test_trajectory_controller PRIVATE include)
7677
target_link_libraries(test_trajectory_controller
7778
joint_trajectory_controller
Lines changed: 5 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,5 @@
1+
# joint_trajectory_controllers package
2+
3+
The package implements controllers to interpolate joint's trajectory.
4+
5+
For detailed documentation check the `docs` folder or [ros2_control documentation](https://ros-controls.github.io/control.ros.org/).

joint_trajectory_controller/doc/userdoc.rst

Lines changed: 77 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -30,4 +30,80 @@ Other features
3030

3131
Proper handling of wrapping (continuous) joints.
3232

33-
Robust to system clock changes: Discontinuous system clock changes do not cause discontinuities in the execution of already queued trajectory segments.
33+
Robust to system clock changes: Discontinuous system clock changes do not cause discontinuities in the execution of already queued trajectory segments.
34+
35+
36+
Using Joint Trajectory Controller(s)
37+
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
38+
39+
The controller expects at least position feedback from the hardware.
40+
Joint velocities and accelerations are optional.
41+
Currently the controller does not internally integrate velocity from acceleration and position from velocity.
42+
Therefore if the hardware provides only acceleration or velocity states they have to be integrated in the hardware-interface implementation of velocity and position to use these controllers.
43+
44+
The generic version of Joint Trajectory controller is implemented in this package.
45+
A yaml file for using it could be:
46+
47+
.. code-block:: yaml
48+
49+
controller_manager:
50+
ros__parameters:
51+
joint_trajectory_controller:
52+
type: "joint_trajectory_controller/JointTrajectoryController"
53+
54+
joint_trajectory_controller:
55+
ros__parameters:
56+
joints:
57+
- joint0
58+
- joint1
59+
- joint2
60+
- joint3
61+
- joint4
62+
- joint5
63+
64+
command_interfaces:
65+
- position
66+
67+
state_interfaces:
68+
- position
69+
- velocity
70+
71+
state_publish_rate: 50.0 # Defaults to 50
72+
action_monitor_rate: 20.0 # Defaults to 20
73+
74+
allow_partial_joints_goal: false # Defaults to false
75+
hardware_state_has_offset: true
76+
deduce_states_from_derivatives: true
77+
constraints:
78+
stopped_velocity_tolerance: 0.01 # Defaults to 0.01
79+
goal_time: 0.0 # Defaults to 0.0 (start immediately)
80+
81+
82+
Specialized versions of JointTrajectoryController (TBD in ...)
83+
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
84+
85+
The controller types are placed into namespaces according to their command types for the hardware (see `general introduction into controllers <../../index.rst>`_).
86+
87+
The following version of the Joint Trajectory Controller are available mapping the following interfaces:
88+
89+
- position_controllers::JointTrajectoryController
90+
- Input: position, [velocity, [acceleration]]
91+
- Output: position
92+
- position_velocity_controllers::JointTrajectoryController
93+
- Input: position, [velocity, [acceleration]]
94+
- Output: position and velocity
95+
- position_velocity_acceleration_controllers::JointTrajectoryController
96+
- Input: position, [velocity, [acceleration]]
97+
- Output: position, velocity and acceleration
98+
.. - velocity_controllers::JointTrajectoryController
99+
.. - Input: position, [velocity, [acceleration]]
100+
.. - Output: velocity
101+
.. TODO(anyone): would it be possible to output velocty and acceleration?
102+
.. (to have an vel_acc_controllers)
103+
.. - effort_controllers::JointTrajectoryController
104+
.. - Input: position, [velocity, [acceleration]]
105+
.. - Output: effort
106+
107+
The controller uses `common hardware interface definitions`_.
108+
109+
(*Not implemented yet*) When using pure ``velocity`` or ``effort`` controllers a command is generated using the desired state and state error using a velocity feedforward term plus a corrective PID term. (#171)

joint_trajectory_controller/include/joint_trajectory_controller/joint_trajectory_controller.hpp

Lines changed: 46 additions & 18 deletions
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,4 @@
1-
// Copyright 2017 Open Source Robotics Foundation, Inc.
1+
// Copyright (c) 2021 ros2_control Development Team
22
//
33
// Licensed under the Apache License, Version 2.0 (the "License");
44
// you may not use this file except in compliance with the License.
@@ -24,6 +24,7 @@
2424
#include "control_msgs/msg/joint_trajectory_controller_state.hpp"
2525
#include "control_msgs/action/follow_joint_trajectory.hpp"
2626
#include "controller_interface/controller_interface.hpp"
27+
#include "hardware_interface/types/hardware_interface_type_values.hpp"
2728
#include "joint_trajectory_controller/tolerances.hpp"
2829
#include "joint_trajectory_controller/visibility_control.h"
2930
#include "rclcpp/duration.hpp"
@@ -41,10 +42,6 @@
4142
#include "trajectory_msgs/msg/joint_trajectory.hpp"
4243
#include "trajectory_msgs/msg/joint_trajectory_point.hpp"
4344

44-
namespace hardware_interface
45-
{
46-
class RobotHardware;
47-
} // namespace hardware_interface
4845
namespace rclcpp_action
4946
{
5047
template<typename ActionT>
@@ -74,14 +71,16 @@ class JointTrajectoryController : public controller_interface::ControllerInterfa
7471
* interfaces for the controlled joints
7572
*/
7673
JOINT_TRAJECTORY_CONTROLLER_PUBLIC
77-
controller_interface::InterfaceConfiguration command_interface_configuration() const override;
74+
controller_interface::InterfaceConfiguration
75+
command_interface_configuration() const override;
7876

7977
/**
8078
* @brief command_interface_configuration This controller requires the position and velocity
8179
* state interfaces for the controlled joints
8280
*/
8381
JOINT_TRAJECTORY_CONTROLLER_PUBLIC
84-
controller_interface::InterfaceConfiguration state_interface_configuration() const override;
82+
controller_interface::InterfaceConfiguration
83+
state_interface_configuration() const override;
8584

8685
JOINT_TRAJECTORY_CONTROLLER_PUBLIC
8786
controller_interface::return_type
@@ -113,15 +112,35 @@ class JointTrajectoryController : public controller_interface::ControllerInterfa
113112

114113
protected:
115114
std::vector<std::string> joint_names_;
116-
117-
// For convenience, we have ordered the interfaces so i-th position matches i-th index
118-
// in joint_names_
119-
std::vector<std::reference_wrapper<hardware_interface::LoanedCommandInterface>>
120-
joint_position_command_interface_;
121-
std::vector<std::reference_wrapper<hardware_interface::LoanedStateInterface>>
122-
joint_position_state_interface_;
123-
std::vector<std::reference_wrapper<hardware_interface::LoanedStateInterface>>
124-
joint_velocity_state_interface_;
115+
std::vector<std::string> command_interface_types_;
116+
std::vector<std::string> state_interface_types_;
117+
118+
// To reduce number of variables and to make the code shorter the interfaces are ordered in types
119+
// as the following constants
120+
const std::vector<std::string> allowed_interface_types_ = {
121+
hardware_interface::HW_IF_POSITION,
122+
hardware_interface::HW_IF_VELOCITY,
123+
hardware_interface::HW_IF_ACCELERATION,
124+
hardware_interface::HW_IF_EFFORT,
125+
};
126+
127+
// The interfaces are defined as the types in 'allowed_interface_types_' member.
128+
// For convenience, for each type the interfaces are ordered so that i-th position
129+
// matches i-th index in joint_names_
130+
template<typename T>
131+
using InterfaceReferences = std::vector<std::vector<std::reference_wrapper<T>>>;
132+
133+
InterfaceReferences<hardware_interface::LoanedCommandInterface> joint_command_interface_;
134+
InterfaceReferences<hardware_interface::LoanedStateInterface> joint_state_interface_;
135+
136+
bool has_velocity_state_interface_ = false;
137+
bool has_acceleration_state_interface_ = false;
138+
bool has_position_command_interface_ = false;
139+
bool has_velocity_command_interface_ = false;
140+
bool has_acceleration_command_interface_ = false;
141+
142+
/// If true, a velocity feedforward term plus corrective PID term is used
143+
bool use_closed_loop_pid_adapter = false;
125144

126145
// TODO(karsten1987): eventually activate and deactive subscriber directly when its supported
127146
bool subscriber_is_active_ = false;
@@ -135,7 +154,9 @@ class JointTrajectoryController : public controller_interface::ControllerInterfa
135154
realtime_tools::RealtimeBuffer<std::shared_ptr<trajectory_msgs::msg::JointTrajectory>>
136155
traj_msg_external_point_ptr_;
137156

138-
bool is_halted = false;
157+
// The controller should be in halted state after creation otherwise memory corruption
158+
// TODO(anyone): Is the variable relevant, since we are using lifecycle?
159+
bool is_halted_ = true;
139160

140161
using ControllerStateMsg = control_msgs::msg::JointTrajectoryControllerState;
141162
using StatePublisher = realtime_tools::RealtimePublisher<ControllerStateMsg>;
@@ -188,13 +209,20 @@ class JointTrajectoryController : public controller_interface::ControllerInterfa
188209
void set_hold_position();
189210

190211
bool reset();
191-
void halt();
192212

193213
using JointTrajectoryPoint = trajectory_msgs::msg::JointTrajectoryPoint;
194214
void publish_state(
195215
const JointTrajectoryPoint & desired_state,
196216
const JointTrajectoryPoint & current_state,
197217
const JointTrajectoryPoint & state_error);
218+
219+
private:
220+
bool contains_interface_type(
221+
const std::vector<std::string> & interface_type_list, const std::string & interface_type)
222+
{
223+
return std::find(interface_type_list.begin(), interface_type_list.end(), interface_type) !=
224+
interface_type_list.end();
225+
}
198226
};
199227

200228
} // namespace joint_trajectory_controller

joint_trajectory_controller/include/joint_trajectory_controller/tolerances.hpp

Lines changed: 4 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -152,8 +152,10 @@ inline bool check_state_tolerance_per_joint(
152152
{
153153
using std::abs;
154154
const double error_position = state_error.positions[joint_idx];
155-
const double error_velocity = state_error.velocities[joint_idx];
156-
const double error_acceleration = state_error.accelerations[joint_idx];
155+
const double error_velocity = state_error.velocities.empty() ?
156+
0.0 : state_error.velocities[joint_idx];
157+
const double error_acceleration = state_error.accelerations.empty() ?
158+
0.0 : state_error.accelerations[joint_idx];
157159

158160
const bool is_valid =
159161
!(state_tolerance.position > 0.0 && abs(error_position) > state_tolerance.position) &&

0 commit comments

Comments
 (0)