Skip to content

Commit 6f074bb

Browse files
mergify[bot]urfeex
andauthored
Forward trajectory controller (backport of #944)
* Add trajectory passthrough controller (#944) This adds a controller that allows sending a complete trajectory to the robot for execution. --- Co-authored-by: Felix Exner <[email protected]>
1 parent d2876cb commit 6f074bb

26 files changed

+2013
-109
lines changed

ur_bringup/config/ur_controllers.yaml

Lines changed: 77 additions & 38 deletions
Original file line numberDiff line numberDiff line change
@@ -24,35 +24,51 @@ controller_manager:
2424
forward_position_controller:
2525
type: position_controllers/JointGroupPositionController
2626

27+
tcp_pose_broadcaster:
28+
type: pose_broadcaster/PoseBroadcaster
29+
30+
passthrough_trajectory_controller:
31+
type: ur_controllers/PassthroughTrajectoryController
32+
33+
ur_configuration_controller:
34+
type: ur_controllers/URConfigurationController
2735

2836
speed_scaling_state_broadcaster:
2937
ros__parameters:
3038
state_publish_rate: 100.0
39+
tf_prefix: "$(var tf_prefix)"
40+
41+
io_and_status_controller:
42+
ros__parameters:
43+
tf_prefix: "$(var tf_prefix)"
3144

45+
ur_configuration_controller:
46+
ros__parameters:
47+
tf_prefix: "$(var tf_prefix)"
3248

3349
force_torque_sensor_broadcaster:
3450
ros__parameters:
35-
sensor_name: tcp_fts_sensor
51+
sensor_name: $(var tf_prefix)tcp_fts_sensor
3652
state_interface_names:
3753
- force.x
3854
- force.y
3955
- force.z
4056
- torque.x
4157
- torque.y
4258
- torque.z
43-
frame_id: tool0
59+
frame_id: $(var tf_prefix)tool0
4460
topic_name: ft_data
4561

4662

4763
joint_trajectory_controller:
4864
ros__parameters:
4965
joints:
50-
- shoulder_pan_joint
51-
- shoulder_lift_joint
52-
- elbow_joint
53-
- wrist_1_joint
54-
- wrist_2_joint
55-
- wrist_3_joint
66+
- $(var tf_prefix)shoulder_pan_joint
67+
- $(var tf_prefix)shoulder_lift_joint
68+
- $(var tf_prefix)elbow_joint
69+
- $(var tf_prefix)wrist_1_joint
70+
- $(var tf_prefix)wrist_2_joint
71+
- $(var tf_prefix)wrist_3_joint
5672
command_interfaces:
5773
- position
5874
state_interfaces:
@@ -64,23 +80,23 @@ joint_trajectory_controller:
6480
constraints:
6581
stopped_velocity_tolerance: 0.2
6682
goal_time: 0.0
67-
shoulder_pan_joint: { trajectory: 0.2, goal: 0.1 }
68-
shoulder_lift_joint: { trajectory: 0.2, goal: 0.1 }
69-
elbow_joint: { trajectory: 0.2, goal: 0.1 }
70-
wrist_1_joint: { trajectory: 0.2, goal: 0.1 }
71-
wrist_2_joint: { trajectory: 0.2, goal: 0.1 }
72-
wrist_3_joint: { trajectory: 0.2, goal: 0.1 }
83+
$(var tf_prefix)shoulder_pan_joint: { trajectory: 0.2, goal: 0.1 }
84+
$(var tf_prefix)shoulder_lift_joint: { trajectory: 0.2, goal: 0.1 }
85+
$(var tf_prefix)elbow_joint: { trajectory: 0.2, goal: 0.1 }
86+
$(var tf_prefix)wrist_1_joint: { trajectory: 0.2, goal: 0.1 }
87+
$(var tf_prefix)wrist_2_joint: { trajectory: 0.2, goal: 0.1 }
88+
$(var tf_prefix)wrist_3_joint: { trajectory: 0.2, goal: 0.1 }
7389

7490

7591
scaled_joint_trajectory_controller:
7692
ros__parameters:
7793
joints:
78-
- shoulder_pan_joint
79-
- shoulder_lift_joint
80-
- elbow_joint
81-
- wrist_1_joint
82-
- wrist_2_joint
83-
- wrist_3_joint
94+
- $(var tf_prefix)shoulder_pan_joint
95+
- $(var tf_prefix)shoulder_lift_joint
96+
- $(var tf_prefix)elbow_joint
97+
- $(var tf_prefix)wrist_1_joint
98+
- $(var tf_prefix)wrist_2_joint
99+
- $(var tf_prefix)wrist_3_joint
84100
command_interfaces:
85101
- position
86102
state_interfaces:
@@ -92,30 +108,53 @@ scaled_joint_trajectory_controller:
92108
constraints:
93109
stopped_velocity_tolerance: 0.2
94110
goal_time: 0.0
95-
shoulder_pan_joint: { trajectory: 0.2, goal: 0.1 }
96-
shoulder_lift_joint: { trajectory: 0.2, goal: 0.1 }
97-
elbow_joint: { trajectory: 0.2, goal: 0.1 }
98-
wrist_1_joint: { trajectory: 0.2, goal: 0.1 }
99-
wrist_2_joint: { trajectory: 0.2, goal: 0.1 }
100-
wrist_3_joint: { trajectory: 0.2, goal: 0.1 }
111+
$(var tf_prefix)shoulder_pan_joint: { trajectory: 0.2, goal: 0.1 }
112+
$(var tf_prefix)shoulder_lift_joint: { trajectory: 0.2, goal: 0.1 }
113+
$(var tf_prefix)elbow_joint: { trajectory: 0.2, goal: 0.1 }
114+
$(var tf_prefix)wrist_1_joint: { trajectory: 0.2, goal: 0.1 }
115+
$(var tf_prefix)wrist_2_joint: { trajectory: 0.2, goal: 0.1 }
116+
$(var tf_prefix)wrist_3_joint: { trajectory: 0.2, goal: 0.1 }
117+
speed_scaling_interface_name: $(var tf_prefix)speed_scaling/speed_scaling_factor
118+
119+
passthrough_trajectory_controller:
120+
ros__parameters:
121+
tf_prefix: "$(var tf_prefix)"
122+
joints:
123+
- $(var tf_prefix)shoulder_pan_joint
124+
- $(var tf_prefix)shoulder_lift_joint
125+
- $(var tf_prefix)elbow_joint
126+
- $(var tf_prefix)wrist_1_joint
127+
- $(var tf_prefix)wrist_2_joint
128+
- $(var tf_prefix)wrist_3_joint
129+
state_interfaces:
130+
- position
131+
- velocity
132+
speed_scaling_interface_name: $(var tf_prefix)speed_scaling/speed_scaling_factor
101133

102134
forward_velocity_controller:
103135
ros__parameters:
104136
joints:
105-
- shoulder_pan_joint
106-
- shoulder_lift_joint
107-
- elbow_joint
108-
- wrist_1_joint
109-
- wrist_2_joint
110-
- wrist_3_joint
137+
- $(var tf_prefix)shoulder_pan_joint
138+
- $(var tf_prefix)shoulder_lift_joint
139+
- $(var tf_prefix)elbow_joint
140+
- $(var tf_prefix)wrist_1_joint
141+
- $(var tf_prefix)wrist_2_joint
142+
- $(var tf_prefix)wrist_3_joint
111143
interface_name: velocity
112144

113145
forward_position_controller:
114146
ros__parameters:
115147
joints:
116-
- shoulder_pan_joint
117-
- shoulder_lift_joint
118-
- elbow_joint
119-
- wrist_1_joint
120-
- wrist_2_joint
121-
- wrist_3_joint
148+
- $(var tf_prefix)shoulder_pan_joint
149+
- $(var tf_prefix)shoulder_lift_joint
150+
- $(var tf_prefix)elbow_joint
151+
- $(var tf_prefix)wrist_1_joint
152+
- $(var tf_prefix)wrist_2_joint
153+
- $(var tf_prefix)wrist_3_joint
154+
155+
tcp_pose_broadcaster:
156+
ros__parameters:
157+
frame_id: $(var tf_prefix)base
158+
pose_name: $(var tf_prefix)tcp_pose
159+
tf:
160+
child_frame_id: $(var tf_prefix)tool0_controller

ur_controllers/CMakeLists.txt

Lines changed: 14 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -19,6 +19,10 @@ find_package(std_srvs REQUIRED)
1919
find_package(ur_dashboard_msgs REQUIRED)
2020
find_package(ur_msgs REQUIRED)
2121
find_package(generate_parameter_library REQUIRED)
22+
find_package(trajectory_msgs REQUIRED)
23+
find_package(control_msgs REQUIRED)
24+
find_package(action_msgs REQUIRED)
25+
2226

2327
set(THIS_PACKAGE_INCLUDE_DEPENDS
2428
angles
@@ -34,6 +38,9 @@ set(THIS_PACKAGE_INCLUDE_DEPENDS
3438
ur_dashboard_msgs
3539
ur_msgs
3640
generate_parameter_library
41+
control_msgs
42+
trajectory_msgs
43+
action_msgs
3744
)
3845

3946
include_directories(include)
@@ -54,6 +61,11 @@ generate_parameter_library(
5461
src/scaled_joint_trajectory_controller_parameters.yaml
5562
)
5663

64+
generate_parameter_library(
65+
passthrough_trajectory_controller_parameters
66+
src/passthrough_trajectory_controller_parameters.yaml
67+
)
68+
5769
generate_parameter_library(
5870
ur_configuration_controller_parameters
5971
src/ur_configuration_controller_parameters.yaml
@@ -63,6 +75,7 @@ add_library(${PROJECT_NAME} SHARED
6375
src/scaled_joint_trajectory_controller.cpp
6476
src/speed_scaling_state_broadcaster.cpp
6577
src/gpio_controller.cpp
78+
src/passthrough_trajectory_controller.cpp
6679
src/ur_configuration_controller.cpp)
6780

6881
target_include_directories(${PROJECT_NAME} PRIVATE
@@ -72,6 +85,7 @@ target_link_libraries(${PROJECT_NAME}
7285
gpio_controller_parameters
7386
speed_scaling_state_broadcaster_parameters
7487
scaled_joint_trajectory_controller_parameters
88+
passthrough_trajectory_controller_parameters
7589
ur_configuration_controller_parameters
7690
)
7791
ament_target_dependencies(${PROJECT_NAME}

ur_controllers/controller_plugins.xml

Lines changed: 5 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -14,6 +14,11 @@
1414
This controller publishes the Tool IO.
1515
</description>
1616
</class>
17+
<class name="ur_controllers/PassthroughTrajectoryController" type="ur_controllers::PassthroughTrajectoryController" base_class_type="controller_interface::ControllerInterface">
18+
<description>
19+
This controller forwards a joint-based trajectory to the robot controller for interpolation.
20+
</description>
21+
</class>
1722
<class name="ur_controllers/URConfigurationController" type="ur_controllers::URConfigurationController" base_class_type="controller_interface::ControllerInterface">
1823
<description>
1924
Controller used to get and change the configuration of the robot

ur_controllers/doc/index.rst

Lines changed: 129 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -135,3 +135,132 @@ Advertised services
135135
* ``~/set_speed_slider [ur_msgs/srv/SetSpeedSliderFraction]``: Set the value of the speed slider.
136136
* ``~/zero_ftsensor [std_srvs/srv/Trigger]``: Zeroes the reported wrench of the force torque
137137
sensor.
138+
139+
.. _passthrough_trajectory_controller:
140+
141+
ur_controllers/PassthroughTrajectoryController
142+
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
143+
144+
This controller uses a ``control_msgs/FollowJointTrajectory`` action but instead of interpolating
145+
the trajectory on the ROS pc it forwards the complete trajectory to the robot controller for
146+
interpolation and execution. This way, the realtime requirements for the control PC can be
147+
massively decreased, since the robot always "knows" what to do next. That means that you should be
148+
able to run a stable driver connection also without a real-time patched kernel.
149+
150+
Interpolation depends on the robot controller's implementation, but in conjunction with the
151+
ur_robot_driver it defaults to mimicking ros2_control's spline interpolation. So, any trajectory
152+
planned e.g. with MoveIt! will be executed following the trajectory exactly.
153+
154+
A trajectory sent to the controller's action server will be forwarded to the robot controller and
155+
executed there. Once all setpoints are transferred to the robot, the controller goes into a waiting
156+
state where it waits for the trajectory to be finished. While waiting, the controller tracks the
157+
time spent on the trajectory to ensure the robot isn't stuck during execution.
158+
159+
This controller also supports **speed scaling** such that and scaling down of the trajectory done
160+
by the robot, for example due to safety settings on the robot or simply because a slower execution
161+
is configured on the teach pendant. This will be considered, during execution monitoring, so the
162+
controller basically tracks the scaled time instead of the real time.
163+
164+
.. note::
165+
166+
When using this controller with the URSim simulator execution times can be slightly larger than
167+
the expected time depending on the simulation host's resources. This effect will not be present
168+
when using a real UR arm.
169+
170+
.. note::
171+
172+
This controller can currently only be used with URSim or a real UR robot. Neither mock hardware
173+
nor gazebo support this type of trajectory interfaces at the time being.
174+
175+
Tolerances
176+
""""""""""
177+
178+
Currently, the trajectory passthrough controller only supports goal tolerances and goal time
179+
tolerances passed in the action directly. Please make sure that the tolerances are completely
180+
filled with all joint names.
181+
182+
A **goal time tolerance** of ``0.0`` means that no goal time tolerance is set and the action will
183+
not fail when execution takes too long.
184+
185+
Action interface / usage
186+
""""""""""""""""""""""""
187+
188+
To use this controller, publish a goal to the ``~/follow_joint_trajectory`` action interface
189+
similar to the `joint_trajectory_controller <https://control.ros.org/master/doc/ros2_controllers/joint_trajectory_controller/doc/userdoc.html>`_.
190+
191+
Currently, the controller doesn't support replacing a running trajectory action. While a trajectory
192+
is being executed, goals will be rejected until the action has finished. If you want to replace it,
193+
first cancel the running action and then send a new one.
194+
195+
Parameters
196+
""""""""""
197+
198+
The trajectory passthrough controller uses the following parameters:
199+
200+
+----------------------------------+--------------+----------------------------------------+------------------------------------------------------------------------------------------------------------------+
201+
| Parameter name | Type | Default value | Description |
202+
| | | | |
203+
+----------------------------------+--------------+----------------------------------------+------------------------------------------------------------------------------------------------------------------+
204+
| ``joints`` (required) | string_array | <empty> | Joint names to listen to |
205+
+----------------------------------+--------------+----------------------------------------+------------------------------------------------------------------------------------------------------------------+
206+
| ``state_interfaces`` (required) | string_array | <empty> | State interfaces provided by the hardware for all joints. Subset of ``["position", "velocity", "acceleration"]`` |
207+
+----------------------------------+--------------+----------------------------------------+------------------------------------------------------------------------------------------------------------------+
208+
| ``speed_scaling_interface_name`` | string | ``speed_scaling/speed_scaling_factor`` | Fully qualified name of the speed scaling interface name. |
209+
+----------------------------------+--------------+----------------------------------------+------------------------------------------------------------------------------------------------------------------+
210+
| ``tf_prefix`` | string | <empty> | Urdf prefix of the corresponding arm |
211+
+----------------------------------+--------------+----------------------------------------+------------------------------------------------------------------------------------------------------------------+
212+
213+
Interfaces
214+
""""""""""
215+
216+
In order to use this, the hardware has to export a command interface for passthrough operations for each joint. It always has
217+
to export position, velocity and acceleration interfaces in order to be able to project the full
218+
JointTrajectory definition. This is why there are separate fields used, as for passthrough mode
219+
accelerations might be relevant also for robots that don't support commanding accelerations
220+
directly to their joints.
221+
222+
.. code:: xml
223+
224+
<gpio name="${tf_prefix}trajectory_passthrough">
225+
<command_interface name="setpoint_positions_0"/>
226+
<command_interface name="setpoint_positions_1"/>
227+
<command_interface name="setpoint_positions_2"/>
228+
<command_interface name="setpoint_positions_3"/>
229+
<command_interface name="setpoint_positions_4"/>
230+
<command_interface name="setpoint_positions_5"/>
231+
<command_interface name="setpoint_velocities_0"/>
232+
<command_interface name="setpoint_velocities_1"/>
233+
<command_interface name="setpoint_velocities_2"/>
234+
<command_interface name="setpoint_velocities_3"/>
235+
<command_interface name="setpoint_velocities_4"/>
236+
<command_interface name="setpoint_velocities_5"/>
237+
<command_interface name="setpoint_accelerations_0"/>
238+
<command_interface name="setpoint_accelerations_1"/>
239+
<command_interface name="setpoint_accelerations_2"/>
240+
<command_interface name="setpoint_accelerations_3"/>
241+
<command_interface name="setpoint_accelerations_4"/>
242+
<command_interface name="setpoint_accelerations_5"/>
243+
<command_interface name="transfer_state"/>
244+
<command_interface name="time_from_start"/>
245+
<command_interface name="abort"/>
246+
</gpio>
247+
248+
.. note::
249+
250+
The hardware component has to take care that the passthrough command interfaces cannot be
251+
activated in parallel to the streaming command interfaces.
252+
253+
Implementation details / dataflow
254+
"""""""""""""""""""""""""""""""""
255+
256+
* A trajectory passed to the controller will be sent to the hardware component one by one.
257+
* The controller will send one setpoint and then wait for the hardware to acknowledge that it can
258+
take a new setpoint.
259+
* This happens until all setpoints have been transferred to the hardware. Then, the controller goes
260+
into a waiting state where it monitors execution time and waits for the hardware to finish
261+
execution.
262+
* If execution takes longer than anticipated, a warning will be printed.
263+
* If execution finished taking longer than expected (plus the goal time tolerance), the action will fail.
264+
* When the hardware reports that execution has been aborted (The ``passthrough_trajectory_abort``
265+
command interface), the action will be aborted.
266+
* When the action is preempted, execution on the hardware is preempted.

0 commit comments

Comments
 (0)