Skip to content

Commit 6eb6def

Browse files
author
Felix Exner
committed
Add documentation for the passthrough controller
1 parent e224dfa commit 6eb6def

File tree

1 file changed

+114
-0
lines changed

1 file changed

+114
-0
lines changed

ur_controllers/doc/index.rst

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

0 commit comments

Comments
 (0)