.. role:: raw-html-m2r(raw) :format: html Usage ===== Launch files ------------ For starting the driver there are two main launch files in the ``ur_robot_driver`` package. * ``ur_control.launch.py`` - starts ros2_control node including hardware interface, joint state broadcaster and a controller. This launch file also starts ``dashboard_client`` if real robot is used. * ``ur_dashboard_client.launch.py`` - start the dashboard client for UR robots. Also, there are predefined launch files for all supported types of UR robots. The arguments for launch files can be listed using ``ros2 launch ur_robot_driver .launch.py --show-args``. The most relevant arguments are the following: * ``ur_type`` (\ *mandatory* ) - a type of used UR robot (\ *ur3*\ , *ur3e*\ , *ur5*\ , *ur5e*\ , *ur10*\ , *ur10e*\ , or *ur16e*\ , *ur20*\ , *ur30*\ ). * ``robot_ip`` (\ *mandatory* ) - IP address by which the root can be reached. * ``use_mock_hardware`` (default: *false* ) - use simple hardware emulator from ros2_control. Useful for testing launch files, descriptions, etc. See explanation below. * ``initial_positions`` (default: dictionary with all joint values set to 0) - Allows passing a dictionary to set the initial joint values for the mock hardware from `ros2_control `_. It can also be set from a yaml file with the ``load_yaml`` commands as follows: .. code-block:: In this example, the **initial_positions_file** is a xacro argument that contains the absolute path to a yaml file. An example of the initial positions yaml file is as follows: .. code-block:: elbow_joint: 1.158 shoulder_lift_joint: -0.953 shoulder_pan_joint: 1.906 wrist_1_joint: -1.912 wrist_2_joint: -1.765 wrist_3_joint: 0.0 * ``mock_sensor_commands`` (default: *false* ) - enables setting sensor values for the hardware emulators. Useful for offline testing of controllers. * ``robot_controller`` (default: *joint_trajectory_controller* ) - controller for robot joints to be started. Available controllers: * joint_trajectory_controller * scaled_joint_trajectory_controller Note: *joint_state_broadcaster*\ , *speed_scaling_state_broadcaster*\ , *force_torque_sensor_broadcaster*\ , and *io_and_status_controller* will always start. *HINT* : list all loaded controllers using ``ros2 control list_controllers`` command. **NOTE**\ : The package can simulate hardware with the ros2_control ``MockSystem``. This emulator enables an environment for testing of "piping" of hardware and controllers, as well as testing robot's descriptions. For more details see `ros2_control documentation `_ for more details. Modes of operation ------------------ As mentioned in the last section the driver has two basic modes of operation: Using mock hardware or using real hardware(Or the URSim simulator, which is equivalent from the driver's perspective). Additionally, the robot can be simulated using `Gazebo `_ or `ignition `_ but that's outside of this driver's scope. .. list-table:: :header-rows: 1 * - mode - available controllers * - mock_hardware - :raw-html-m2r:`
  • joint_trajectory_controller
  • forward_velocity_controller
  • forward_position_controller
` * - real hardware / URSim - :raw-html-m2r:`
  • joint_trajectory_controller
  • scaled_joint_trajectory_controller
  • forward_velocity_controller
  • forward_position_controller
` Usage with official UR simulator ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ The easiest way to use URSim is the `Docker image `_ provided by Universal Robots (See `this link `_ for a CB3-series image). To start it, we've prepared a script: .. code-block:: bash ros2 run ur_client_library start_ursim.sh -m With this, we can spin up a driver using .. code-block:: bash ros2 launch ur_robot_driver ur_control.launch.py ur_type:= robot_ip:=192.168.56.101 launch_rviz:=true You can view the polyscope GUI by opening ``_. When we now move the robot in Polyscope, the robot's RViz visualization should move accordingly. For details on the Docker image, please see the more detailed guide :ref:`here `. Example Commands for Testing the Driver --------------------------------------- Allowed UR - Type strings: ``ur3``\ , ``ur3e``\ , ``ur5``\ , ``ur5e``\ , ``ur10``\ , ``ur10e``\ , ``ur16e``\ , ``ur20``, ``ur30``. 1. Start hardware, simulator or mockup ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ * To do test with hardware, use: .. code-block:: ros2 launch ur_robot_driver ur_control.launch.py ur_type:= robot_ip:= launch_rviz:=true For more details check the argument documentation with ``ros2 launch ur_robot_driver ur_control.launch.py --show-arguments`` After starting the launch file start the external_control URCap program from the pendant, as described above. * To do an offline test with URSim check details about it in `this section <#usage-with-official-ur-simulator>`_ * To use mocked hardware(capability of ros2_control), use ``use_mock_hardware`` argument, like: .. code-block:: ros2 launch ur_robot_driver ur_control.launch.py ur_type:=ur5e robot_ip:=yyy.yyy.yyy.yyy use_mock_hardware:=true launch_rviz:=true **NOTE**\ : Instead of using the global launch file for control stack, there are also prepeared launch files for each type of UR robots named. They accept the same arguments are the global one and are used by: .. code-block:: ros2 launch ur_robot_driver .launch.py 2. Sending commands to controllers ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ Before running any commands, first check the controllers' state using ``ros2 control list_controllers``. * Send some goal to the Joint Trajectory Controller by using a demo node from `ros2_control_demos `_ package by starting the following command in another terminal: .. code-block:: ros2 launch ur_robot_driver test_scaled_joint_trajectory_controller.launch.py After a few seconds the robot should move. * To test another controller, simply define it using ``initial_joint_controller`` argument, for example when using mock hardware: .. code-block:: ros2 launch ur_robot_driver ur_control.launch.py ur_type:=ur5e robot_ip:=yyy.yyy.yyy.yyy initial_joint_controller:=joint_trajectory_controller use_mock_hardware:=true launch_rviz:=true And send the command using demo node: .. code-block:: ros2 launch ur_robot_driver test_joint_trajectory_controller.launch.py After a few seconds the robot should move(or jump when using emulation). 3. Using only robot description ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ If you just want to test description of the UR robots, e.g., after changes you can use the following command: .. code-block:: ros2 launch ur_description view_ur.launch.py ur_type:=ur5e Using MoveIt ------------ `MoveIt! `_ support is built-in into this driver already. To test the driver with the example MoveIt-setup, first start the driver as described `above <#start-hardware-simulator-or-mockup>`_ and then start the MoveIt! nodes 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 `_. For more details, please see :ref:`ur_moveit_config`. Robot frames ------------ While most tf frames come from the URDF and are published from the ``robot_state_publisher``, there are a couple of things to know: - The ``base`` frame is the robot's base as the robot controller sees it. - The ``tool0_controller`` is the tool frame as published from the robot controller. If there is no additional tool configured on the Teach pendant (TP), this should be equivalent to ``tool0`` given that the URDF uses the specific robot's :ref:`calibration `. If a tool is configured on the TP, then the additional transformation will show in ``base`` -> ``tool0``. Custom URScript commands ------------------------ The driver's package contains a ``urscript_interface`` node that allows sending URScript snippets directly to the robot. It gets started in the driver's launchfiles by default. To use it, simply publish a message to its interface: .. code-block:: bash # simple popup ros2 topic pub /urscript_interface/script_command std_msgs/msg/String '{data: popup("hello")}' --once Be aware, that running a program on this interface (meaning publishing script code to that interface) stops any running program on the robot. Thus, the motion-interpreting program that is started by the driver gets stopped and has to be restarted again. Depending whether you use headless mode or not, you'll have to call the ``resend_program`` service or press the ``play`` button on the teach panel to start the external_control program again. .. note:: Currently, there is no feedback on the code's correctness. If the code sent to the robot is incorrect, it will silently not get executed. Make sure that you send valid URScript code! Multi-line programs ^^^^^^^^^^^^^^^^^^^ When you want to define multi-line programs, make sure to check that newlines are correctly interpreted from your message. For this purpose the driver prints the program as it is being sent to the robot. When sending a multi-line program from the command line, you can use an empty line between each statement: .. code-block:: bash ros2 topic pub --once /urscript_interface/script_command std_msgs/msg/String '{data: "def my_prog(): set_digital_out(1, True) movej(p[0.2, 0.3, 0.8, 0, 0, 3.14], a=1.2, v=0.25, r=0) textmsg(\"motion finished\") end"}' Non-interrupting programs ^^^^^^^^^^^^^^^^^^^^^^^^^ To prevent interrupting the main program, you can send certain commands as `secondary programs `_. .. code-block:: bash ros2 topic pub --once /urscript_interface/script_command std_msgs/msg/String '{data: "sec my_prog(): textmsg(\"This is a log message\") end"}'