@@ -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