Note: This tutorial assumes that you have completed the previous tutorials: webots_ros2_examples.
(!) Please ask about problems and questions regarding this tutorial on answers.ros.org. Don't forget to include in your question the link to this page, the versions of your OS & ROS, and also add appropriate tags.

webots_ros2_universal_robot Package

Description: Package for interfacing the Universal Robots with Webots.

Keywords: Webots, Simulator, ROS, Universal Robots

Tutorial Level: ADVANCED

This package provides an interface between ROS2 and the UR3e, UR5e and UR10e simulation models of the Universal Robots running in Webots. It includes several simulations of these robots.

universal_robot Node

This node acts as a Webots robot controller. It publishes the joint_states topics that represents the state of all the joints of the robot. And it provides the follow_joint_trajectory action server that allows you to send joint trajectory action to the robot.

Samples Simulations

The following simulations are provided within this package:

universal_robot

This simulation can be started with the following launch file:

ros2 launch webots_ros2_universal_robot universal_robot.launch.py

thumb This simulation contains one UR5e robot in a very simple environment.

universal_robot_multiple

This simulation can be started with the following launch file:

ros2 launch webots_ros2_universal_robot universal_robot_multiple.launch.py

thumb This simulation contains a UR3e and a UR5e robot in a simple factory environment. This is a very good example showcasing how to use the multi-robots support with the Webots-ROS2 interface.

Interact with the Robot

Move the Robot

The '/follow_joint_trajectory' action server can be tested directly using the ROS2 action CLI interface to move the robot:

ros2 action send_goal /follow_joint_trajectory control_msgs/action/FollowJointTrajectory "{
  trajectory: {
    joint_names: [shoulder_pan_joint, shoulder_lift_joint, elbow_joint, wrist_1_joint, wrist_2_joint, wrist_3_joint],
    points: [
      { positions: [3.02, -1.63, -1.88, 1.01, 1.51, 1.13], velocities: [0.1, 0.1, 0.1, 0.1, 0.1, 0.1], accelerations: [0.1, 0.1, 0.1, 0.1, 0.1, 0.1], time_from_start: { sec: 5, nanosec: 500 } },
      { positions: [-1.01, 0.38, -0.63, -0.88, 0.25, -1.63], velocities: [0.1, 0.1, 0.1, 0.1, 0.1, 0.1], accelerations: [0.1, 0.1, 0.1, 0.1, 0.1, 0.1], time_from_start: { sec: 6, nanosec: 500 } },
      { positions: [-1.01, 0.38, -0.63, -0.88, 0.25, 6.2], velocities: [0.1, 0.1, 0.1, 0.1, 0.1, 0.1], accelerations: [0.1, 0.1, 0.1, 0.1, 0.1, 0.1], time_from_start: { sec: 50, nanosec: 500 } }
    ]
  },
  goal_tolerance: [
    { name: shoulder_pan_joint, position: 0.01 },
    { name: shoulder_lift_joint, position: 0.01 },
    { name: elbow_joint, position: 0.01 },
    { name: wrist_1_joint, position: 0.01 },
    { name: wrist_2_joint, position: 0.01 },
    { name: wrist_3_joint, position: 0.01 }
  ]
}"

Display the Joint State

The joint state (/joint_states topic) can be displayed directly using the ROS2 topic CLI interface:

ros2 topic echo /joint_states

Wiki: webots_ros2/Tutorials/webots_ros2_universal_robot (last edited 2019-10-08 10:51:24 by DavidMansolino)