Skip to content

Commit

Permalink
deploy: d83aabb
Browse files Browse the repository at this point in the history
  • Loading branch information
fmauch committed Nov 12, 2024
1 parent c0b65bd commit 16894ba
Show file tree
Hide file tree
Showing 4 changed files with 263 additions and 1 deletion.
129 changes: 129 additions & 0 deletions _sources/doc/ur_robot_driver/ur_controllers/doc/index.rst.txt
Original file line number Diff line number Diff line change
Expand Up @@ -135,3 +135,132 @@ Advertised services
* ``~/set_speed_slider [ur_msgs/srv/SetSpeedSliderFraction]``: Set the value of the speed slider.
* ``~/zero_ftsensor [std_srvs/srv/Trigger]``: Zeroes the reported wrench of the force torque
sensor.

.. _passthrough_trajectory_controller:

ur_controllers/PassthroughTrajectoryController
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

This controller uses a ``control_msgs/FollowJointTrajectory`` action but instead of interpolating
the trajectory on the ROS pc it forwards the complete trajectory to the robot controller for
interpolation and execution. This way, the realtime requirements for the control PC can be
massively decreased, since the robot always "knows" what to do next. That means that you should be
able to run a stable driver connection also without a real-time patched kernel.

Interpolation depends on the robot controller's implementation, but in conjunction with the
ur_robot_driver it defaults to mimicking ros2_control's spline interpolation. So, any trajectory
planned e.g. with MoveIt! will be executed following the trajectory exactly.

A trajectory sent to the controller's action server will be forwarded to the robot controller and
executed there. Once all setpoints are transferred to the robot, the controller goes into a waiting
state where it waits for the trajectory to be finished. While waiting, the controller tracks the
time spent on the trajectory to ensure the robot isn't stuck during execution.

This controller also supports **speed scaling** such that and scaling down of the trajectory done
by the robot, for example due to safety settings on the robot or simply because a slower execution
is configured on the teach pendant. This will be considered, during execution monitoring, so the
controller basically tracks the scaled time instead of the real time.

.. note::

When using this controller with the URSim simulator execution times can be slightly larger than
the expected time depending on the simulation host's resources. This effect will not be present
when using a real UR arm.

.. note::

This controller can currently only be used with URSim or a real UR robot. Neither mock hardware
nor gazebo support this type of trajectory interfaces at the time being.

Tolerances
""""""""""

Currently, the trajectory passthrough controller only supports goal tolerances and goal time
tolerances passed in the action directly. Please make sure that the tolerances are completely
filled with all joint names.

A **goal time tolerance** of ``0.0`` means that no goal time tolerance is set and the action will
not fail when execution takes too long.

Action interface / usage
""""""""""""""""""""""""

To use this controller, publish a goal to the ``~/follow_joint_trajectory`` action interface
similar to the `joint_trajectory_controller <https://control.ros.org/master/doc/ros2_controllers/joint_trajectory_controller/doc/userdoc.html>`_.

Currently, the controller doesn't support replacing a running trajectory action. While a trajectory
is being executed, goals will be rejected until the action has finished. If you want to replace it,
first cancel the running action and then send a new one.

Parameters
""""""""""

The trajectory passthrough controller uses the following parameters:

+----------------------------------+--------------+----------------------------------------+------------------------------------------------------------------------------------------------------------------+
| Parameter name | Type | Default value | Description |
| | | | |
+----------------------------------+--------------+----------------------------------------+------------------------------------------------------------------------------------------------------------------+
| ``joints`` (required) | string_array | <empty> | Joint names to listen to |
+----------------------------------+--------------+----------------------------------------+------------------------------------------------------------------------------------------------------------------+
| ``state_interfaces`` (required) | string_array | <empty> | State interfaces provided by the hardware for all joints. Subset of ``["position", "velocity", "acceleration"]`` |
+----------------------------------+--------------+----------------------------------------+------------------------------------------------------------------------------------------------------------------+
| ``speed_scaling_interface_name`` | string | ``speed_scaling/speed_scaling_factor`` | Fully qualified name of the speed scaling interface name. |
+----------------------------------+--------------+----------------------------------------+------------------------------------------------------------------------------------------------------------------+
| ``tf_prefix`` | string | <empty> | Urdf prefix of the corresponding arm |
+----------------------------------+--------------+----------------------------------------+------------------------------------------------------------------------------------------------------------------+

Interfaces
""""""""""

In order to use this, the hardware has to export a command interface for passthrough operations for each joint. It always has
to export position, velocity and acceleration interfaces in order to be able to project the full
JointTrajectory definition. This is why there are separate fields used, as for passthrough mode
accelerations might be relevant also for robots that don't support commanding accelerations
directly to their joints.

.. code:: xml
<gpio name="${tf_prefix}trajectory_passthrough">
<command_interface name="setpoint_positions_0"/>
<command_interface name="setpoint_positions_1"/>
<command_interface name="setpoint_positions_2"/>
<command_interface name="setpoint_positions_3"/>
<command_interface name="setpoint_positions_4"/>
<command_interface name="setpoint_positions_5"/>
<command_interface name="setpoint_velocities_0"/>
<command_interface name="setpoint_velocities_1"/>
<command_interface name="setpoint_velocities_2"/>
<command_interface name="setpoint_velocities_3"/>
<command_interface name="setpoint_velocities_4"/>
<command_interface name="setpoint_velocities_5"/>
<command_interface name="setpoint_accelerations_0"/>
<command_interface name="setpoint_accelerations_1"/>
<command_interface name="setpoint_accelerations_2"/>
<command_interface name="setpoint_accelerations_3"/>
<command_interface name="setpoint_accelerations_4"/>
<command_interface name="setpoint_accelerations_5"/>
<command_interface name="transfer_state"/>
<command_interface name="time_from_start"/>
<command_interface name="abort"/>
</gpio>
.. note::

The hardware component has to take care that the passthrough command interfaces cannot be
activated in parallel to the streaming command interfaces.

Implementation details / dataflow
"""""""""""""""""""""""""""""""""

* A trajectory passed to the controller will be sent to the hardware component one by one.
* The controller will send one setpoint and then wait for the hardware to acknowledge that it can
take a new setpoint.
* This happens until all setpoints have been transferred to the hardware. Then, the controller goes
into a waiting state where it monitors execution time and waits for the hardware to finish
execution.
* If execution takes longer than anticipated, a warning will be printed.
* If execution finished taking longer than expected (plus the goal time tolerance), the action will fail.
* When the hardware reports that execution has been aborted (The ``passthrough_trajectory_abort``
command interface), the action will be aborted.
* When the action is preempted, execution on the hardware is preempted.
Loading

0 comments on commit 16894ba

Please sign in to comment.