-
Notifications
You must be signed in to change notification settings - Fork 220
Commit
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
Restructure documentation for full stack documentation (#984)
* Remove indices and tables from the ur_robot_driver index * Move ur_controllers documentation to doc folder * Move ur_calibration documentation to rst so it can be re-used * Rework calibration tutorial to refer to the workcell example * Migrate all docs to rst * Add rst doc for ur_moveit_config Co-authored-by: Vincenzo Di Pentima <[email protected]>
- Loading branch information
Showing
12 changed files
with
754 additions
and
655 deletions.
There are no files selected for viewing
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,45 @@ | ||
|
||
ur_calibration | ||
============== | ||
|
||
Package for extracting the factory calibration from a UR robot and changing it to be used by ``ur_description`` to gain a correct URDF model. | ||
|
||
Each UR robot is calibrated inside the factory giving exact forward and inverse kinematics. To also | ||
make use of this in ROS, you first have to extract the calibration information from the robot. | ||
|
||
Though this step is not necessary, to control the robot using this driver, it is highly recommended | ||
to do so, as end effector positions might be off in the magnitude of centimeters. | ||
|
||
Nodes | ||
----- | ||
|
||
calibration_correction | ||
^^^^^^^^^^^^^^^^^^^^^^ | ||
|
||
This node extracts calibration information directly from a robot, calculates the URDF correction and | ||
saves it into a .yaml file. | ||
|
||
In the launch folder of the ur_calibration package is a helper script: | ||
|
||
.. code-block:: bash | ||
$ ros2 launch ur_calibration calibration_correction.launch.py \ | ||
robot_ip:=<robot_ip> target_filename:="${HOME}/my_robot_calibration.yaml" | ||
For the parameter ``robot_ip`` insert the IP address on which the ROS pc can reach the robot. As | ||
``target_filename`` provide an absolute path where the result will be saved to. | ||
|
||
With that, you can launch your specific robot with the correct calibration using | ||
|
||
.. code-block:: bash | ||
$ ros2 launch ur_robot_driver ur_control.launch.py \ | ||
ur_type:=ur5e \ | ||
robot_ip:=192.168.56.101 \ | ||
kinematics_params_file:="${HOME}/my_robot_calibration.yaml" | ||
Adapt the robot model matching to your robot. | ||
|
||
Ideally, you would create a package for your custom workcell, as explained in `the custom workcell | ||
tutorial | ||
<https://github.com/UniversalRobots/Universal_Robots_ROS2_Tutorials/blob/main/my_robot_cell/doc/start_ur_driver.rst#extract-the-calibration>`_. |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,99 @@ | ||
ur_controllers | ||
============== | ||
|
||
This package contains controllers and hardware interface for ``ros_control`` that are special to the UR | ||
robot family. Currently this contains: | ||
|
||
|
||
* A **speed_scaling_interface** to read the value of the current speed scaling into controllers. | ||
* A **scaled_joint_command_interface** that provides access to joint values and commands in | ||
combination with the speed scaling value. | ||
* A **speed_scaling_state_controller** that publishes the current execution speed as reported by | ||
the robot to a topic interface. Values are floating points between 0 and 1. | ||
* A **scaled_joint_trajectory_controller** that is similar to the *joint_trajectory_controller*\ , | ||
but it uses the speed scaling reported by the robot to reduce progress in the trajectory. | ||
|
||
About this package | ||
------------------ | ||
|
||
This package contains controllers not being available in the default ``ros_control`` set. They are | ||
created to support more features offered by the UR robot family. Any of these controllers are | ||
example implementations for certain features and are intended to be generalized and merged | ||
into the default ``ros_control`` controller set at some future point. | ||
|
||
Controller description | ||
---------------------- | ||
|
||
This packages offers a couple of specific controllers that will be explained in the following | ||
sections. | ||
|
||
ur_controllers/SpeedScalingStateBroadcaster | ||
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ | ||
|
||
This controller publishes the current actual execution speed as reported by the robot. Values are | ||
floating points between 0 and 1. | ||
|
||
In the `ur_robot_driver | ||
<https://index.ros.org/p/ur_robot_driver/github-UniversalRobots-Universal_Robots_ROS2_Driver/>`_ | ||
this is calculated by multiplying the two `RTDE | ||
<https://www.universal-robots.com/articles/ur/real-time-data-exchange-rtde-guide/>`_ data | ||
fields ``speed_scaling`` (which should be equal to the value shown by the speed slider position on the | ||
teach pendant) and ``target_speed_fraction`` (Which is the fraction to which execution gets slowed | ||
down by the controller). | ||
|
||
position_controllers/ScaledJointTrajectoryController and velocity_controllers/ScaledJointTrajectoryController | ||
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ | ||
|
||
These controllers work similar to the well-known | ||
`joint_trajectory_controller <https://control.ros.org/master/doc/ros2_controllers/joint_trajectory_controller/doc/userdoc.html>`_. | ||
|
||
However, they are extended to handle the robot's execution speed specifically. Because the default | ||
``joint_trajectory_controller`` would interpolate the trajectory with the configured time constraints (ie: always assume maximum velocity and acceleration supported by the robot), | ||
this could lead to significant path deviation due to multiple reasons: | ||
|
||
|
||
* The speed slider on the robot might not be at 100%, so motion commands sent from ROS would | ||
effectively get scaled down resulting in a slower execution. | ||
* The robot could scale down motions based on configured safety limits resulting in a slower motion | ||
than expected and therefore not reaching the desired target in a control cycle. | ||
* Motions might not be executed at all, e.g. because the robot is E-stopped or in a protective stop | ||
* Motion commands sent to the robot might not be interpreted, e.g. because there is no | ||
`external_control <https://github.com/UniversalRobots/Universal_Robots_ROS_Driver#prepare-the-robot>`_ | ||
program node running on the robot controller. | ||
* The program interpreting motion commands could be paused. | ||
|
||
The following plot illustrates the problem: | ||
|
||
.. image:: traj_without_speed_scaling.png | ||
:target: traj_without_speed_scaling.png | ||
:alt: Trajectory execution with default trajectory controller | ||
|
||
|
||
The graph shows a trajectory with one joint being moved to a target point and back to its starting | ||
point. As the joint's speed is limited to a very low setting on the teach pendant, speed scaling | ||
(black line) activates and limits the joint speed (green line). As a result, the target | ||
trajectory (light blue) doesn't get executed by the robot, but instead the pink trajectory is executed. | ||
The vertical distance between the light blue line and the pink line is the path error in each | ||
control cycle. We can see that the path deviation gets above 300 degrees at some point and the | ||
target point at -6 radians never gets reached. | ||
|
||
All of the cases mentioned above are addressed by the scaled trajectory versions. Trajectory execution | ||
can be transparently scaled down using the speed slider on the teach pendant without leading to | ||
additional path deviations. Pausing the program or hitting the E-stop effectively leads to | ||
``speed_scaling`` being 0 meaning the trajectory will not be continued until the program is continued. | ||
This way, trajectory executions can be explicitly paused and continued. | ||
|
||
With the scaled version of the trajectory controller the example motion shown in the previous diagram becomes: | ||
|
||
.. image:: traj_with_speed_scaling.png | ||
:target: traj_with_speed_scaling.png | ||
:alt: Trajectory execution with scaled_joint_trajectory_controller | ||
|
||
|
||
The deviation between trajectory interpolation on the ROS side and actual robot execution stays minimal and the | ||
robot reaches the intermediate setpoint instead of returning "too early" as in the example above. | ||
|
||
Under the hood this is implemented by proceeding the trajectory not by a full time step but only by | ||
the fraction determined by the current speed scaling. If speed scaling is currently at 50% then | ||
interpolation of the current control cycle will start half a time step after the beginning of the | ||
previous control cycle. |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,25 @@ | ||
.. _ur_moveit_config: | ||
|
||
================ | ||
ur_moveit_config | ||
================ | ||
|
||
This package contains an **example** MoveIt! configuration for Universal Robots arms. Since the | ||
default description contains only the arm, this MoveIt! configuration package also only contains the | ||
arm without any objects around it. | ||
In a real-world scenario it is recommended to create a robot_description modelling the robot with its surroundings (e.g. table where it is mounted on, objects in its environment, etc.) and to generate a | ||
*scenario_moveit_config* package from that description as explained in the :ref:`Custom workcell | ||
tutorial <custom_workcell_tutorial>`. | ||
|
||
Usage | ||
----- | ||
|
||
With a running driver (real hardware, URSim or mocked hardware), simply start the MoveIt! | ||
interaction using | ||
|
||
.. code-block:: | ||
ros2 launch ur_moveit_config ur_moveit.launch.py ur_type:=ur5e launch_rviz:=true | ||
Now you should be able to use the MoveIt Plugin in rviz2 to plan and execute trajectories with the | ||
robot as explained `here <https://moveit.picknik.ai/main/doc/tutorials/quickstart_in_rviz/quickstart_in_rviz_tutorial.html>`_. |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Oops, something went wrong.