You are currently viewing ROS Tutorial: How to create a Moveit config for the UR5 and a gripper

ROS Tutorial: How to create a Moveit config for the UR5 and a gripper

In this tutorial we will learn how to create a Moveit config package with the UR5 robot arm and a Robotiq gripper to do motion planning in Rviz. Moveit is a very powerful motion planning framework for use in robotics. After a brief explanation of Moveit we will see how to prepare the URDF file for Moveit and create the configuration package with the Moveit Setup Assistant. I will also show you what additional modifications need to be done to the generated package and how to use the Moveit Plugin in the visualization tool Rviz.

As always if you quickly want to set up the ur5 with a gripper attached and control it with Moveit without learning more about the details of how to create the package you can skip to the Quickstart section. Otherwise let’s dive right in!

Moveit: A motion planning framework

What is motion planning? In the previous tutorials we saw how to command the robot to certain positions after we added some basic controllers for the motors. Motion planning, as the name suggests is concerned with how exactly the robot moves from a starting point to a certain desired position. This involves avoiding obstacles on the way and dealing with constraints. There are different algorithms to solve that problem which have their strengths and weaknesses under different circumstances.

Moveit is a framework that integrates these algorithms with your robot setup. Apart from that it provides support for other aspects of manipulation like grasping and perception. In recent years it has become very popular and a great community has built around it (you can find more information on the Moveit website). Now let us look at the steps to get our robot arm and the gripper up and running with Moveit.

Prepare the URDF files

First we need get one URDF that contains the robot as well as the gripper. A URDF is a file that describes the physical attributes of a robot. To learn more about it check out the URDF tutorial.

If you don’t have the universal_robots repository cloned yet then please start your Linux terminal do so with the following commands inside your catkin workspace (replace <distro> with the ROS distribution you are using):

~/catkin_ws/src$ git clone -b <distro>-devel https://github.com/ros-industrial/universal_robot.git

In addition, clone the following repository into you catkin workspace to get the Robotiq gripper description:

~/catkin_ws/src$ git clone https://github.com/filesmuggler/robotiq.git

Then download the URDF file that combines the ur5 arm and the gripper. A quick shout-out at this point to the guys at UTEC in Lima for providing the robotiq package and this URDF file. Switch to ur_description/urdf inside your universal_robots repository and execute the following command to download the raw file:

~/catkin_ws/src/universal_robot/ur_description/urdf$ wget https://raw.githubusercontent.com/utecrobotics/ur5/master/ur5_description/urdf/ur5_robotiq85_gripper.urdf.xacro

Modify line 4 in the ur5_robotiq85_gripper.urdf.xacro file you just downloaded such that it searches for the URDF file inside our ur_description package:

  <xacro:include filename="$(find ur_description)/urdf/ur5_joint_limited_robot.urdf.xacro" />

Now we need to modify the controller interfaces both for the robot and the gripper. Out of the box they are both configured as PositionJointInterface. I had problems with that interface so I changed it to EffortJointInterface. Here is what you need to modify:

First, inside the robotiq repository in robotiq_description/urdf/robotiq_85_gripper.transmission.xacro we need to change lines 9 and 14 to:

    <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
    <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>

Second, in the universal_robots repository in ur_description/urdf/ur5_joint_limited_robot.urdf.xacro, line 5 needs to be modified as follows:

  <xacro:arg name="transmission_hw_interface" default="hardware_interface/EffortJointInterface"/>

Finally we have the complete URDF which describes our robot arm with a robotiq gripper attached.

Create a Moveit configuration package with the Moveit Setup Assistant

Moveit should already be installed by default so now it is time to start the Moveit! Setup Assistant with the following command:

$ roslaunch moveit_setup_assistant setup_assistant.launch

The Setup Assistant will guide us through the necessary steps to create a Moveit configuration package from a URDF. On the Start screen we can decide if we want to create a new package or edit an existing one.

Choose Create New Moveit Configuration Package and we can select our URDF from the file system. Select /universal_robot/ur_description/urdf/ur5_robotiq85_gripper.urdf.xacro inside the universal_robot repository and click Load Files. When it is finished you should see the following success message:

Now select the next step Self-Collisions in the selection menu on the left. You can leave the settings as they are and click Generate Collision Matrix. When Moveit is doing motion planning, it checks if there would be collisions occuring between robot parts (links) during the movement. This can take quite some computation effort which is why Moveit tries to find the links that physically can not collide with each other to exclude them from the computation. When it is finished you should see something like this:

We can go on to the Virtual Joints tab. Let’s define a virtual, fixed joint in order to anchor out robot in the environment. Click on Add Virtual Joint and fill in the spaces as shown in the picture. Then click Save.

Next, move on to Planning Groups. Click on Add Group and let’s begin with the robot arm. Fill in ur5_arm as the Group Name and choose kdl_kinematics_plugin/KDLKinematicsPlugin as Kinematic Solver (we had a look at the KDL kinematics package in this tutorial).

Then click on Add Kin. Chain. Expand the frames with the small arrows on the left until you reach the ee_link. Choose base_link as Base Link and ee_link as Tip Link, then click save.

Click Add Group again to define the gripper. Type in gripper as Group Name, for the Kinematic Solver leave None and click on Add Joints. Select the robotiq_85_left_knuckle_joint in the left column and click the arrow pointing to the right so that the joint shows up in the right column, then save.

The finished Planning Groups should look like this:

After that we can go on to Robot Poses. This step is not necessary but defining basic poses can safe time in the future. Create a “home” pose by setting the joint values. The below picture shows a useful home pose for the ur5. The joint values used here are:

  • elbow_joint: 1.5447
  • shoulder_lift_joint: -1.5447
  • shoulder_pan_joint: 0.0
  • wrist_1_joint: -1.5794
  • wrist_2_joint: -1.5794
  • wrist_3_joint: 0.0

When you are satisfied with the pose you can hit save. Let’s also create poses for the gripper. Define a new pose for Planning Group gripper and call it “open”. Set the joint value to 0.1 and hit Save. Then create an additional one called “closed”, set 0.3 as joint value and hit Save again.

For defining our gripper, switch to the End Effectors tab and click Add End Effector. Give it the name robotiq_gripper and Choose the Group, Parent Link and Parent Group as shown in the picture below. Then click save.

For the gripper we got some work to do in the next step: Passive Joints. Only one joint, the robotiq_85_left_knuckle_joint is actuated so we need to add all the other gripper joints by selecting them and clicking the arrow to bring them to the right column. The passive joints are:

  • robotiq_85_left_inner_knuckle_joint
  • robotiq_85_left_finger_tip_joint
  • robotiq_85_right_inner_knuckle_joint
  • robotiq_85_right_finger_tip_joint
  • robotiq_85_right_knuckle_joint

Let’s go on to the ROS Control pane. Ros_control is a package that allows you to set up controllers for your joints easily (we previously dicussed the ros_control package in this tutorial) . In the Setup Assistant we can simply click Auto Add FollowJointsTrajctory Controllers For Each Planning Group. Later we will need to modify the generated files.

We don’t need to do anything in the Simulation pane. Moveit could generate a URDF that we can use to run our robot in the Gazebo simulation (We discussed Gazebo in this tutorial). We already have such a URDF file.

The 3D Preception Pane is meant to set parameters in case we want to use 3d sensor data. For now we leave None.

We are nearly done with the Setup Assistant! Moveit requires some Author Information about the package maintainer from us. You can type anything, it doesn’t have to be valid.

The last step is Configuration Files. You can choose path where you want to store your configuration package. In our case we want to store it inside the source folder of our catkin workspace. Then click Generate Package and Moveit will do it’s duty!

Before we can use the Moveit package, we still need to do some small modifications.

Modifications to the Moveit configuration package

If you look into the ur5_gripper_moveit_config package folder you will find a lot of generated files there. We first want to modify ros_controllers.yaml. This file contains a description of the controllers we are using for our robot joints. Let’s open the file which lives in the config subfolder. There is one mistake that ROS will complain about and to solve it we simply need to add a dash in front of the robotiq_85_left_knuckle_joint in line 42. We also need to add the controllers that are used for the simulation in Gazebo. You can add the following code snippet at the end of your file. Or you can find the completly modified ros_controllers.yaml file under this link.

ur5_arm_controller:
  type: effort_controllers/JointTrajectoryController
  joints:
    - shoulder_pan_joint
    - shoulder_lift_joint
    - elbow_joint
    - wrist_1_joint
    - wrist_2_joint
    - wrist_3_joint
  gains:
    shoulder_pan_joint:
      p: 1000
      d: 50
      i: 10
      i_clamp: 100
    shoulder_lift_joint:
      p: 5000
      d: 30
      i: 100
      i_clamp: 400
    elbow_joint:
      p: 5000
      d: 50
      i: 10
      i_clamp: 100
    wrist_1_joint:
      p: 200
      d: 20
      i: 10
      i_clamp: 100
    wrist_2_joint:
      p: 100
      d: 10
      i: 0.1
      i_clamp: 100
    wrist_3_joint:
      p: 10
      d: 1
      i: 0.1
      i_clamp: 100
gripper_controller:
  type: effort_controllers/JointTrajectoryController
  joints:
    - robotiq_85_left_knuckle_joint
  gains:
    robotiq_85_left_knuckle_joint:
      p: 40
      d: 0
      i: 0
      i_clamp: 1

The controller parameters that we use are not perfect but they do their job. The second file we need to modify is ros_controllers.launch inside the launch subfolder. In line 9, add the controllers we want to load as arguments to the controller spawner:

    output="screen" args="ur5_arm_controller gripper_controller joint_state_controller"

Lastly, we have to add an offset in gazebo.launch inside the launch folder to the spawning position of the robot as you might know from the Gazebo tutorial. The empty world we want to spawn our robot in has an invisible base plate which causes collisions with the robot. This can lead to Moveit complaining with some error message because the robot is shaking. To avoid this, add the offset to the arguments of the spawn_gazebo_model node in line 18 as follows:

18  <node name="spawn_gazebo_model" pkg="gazebo_ros" type="spawn_model" args="-urdf -param robot_description -model robot -x 0 -y 0 -z 0.1"

That’s it! Now the Moveit package is ready to be used. If for some reason you were not successful creating the package, you can clone my git repository with the the package that already has the necessary modifications:

~/catkin_ws/src$ git clone https://github.com/dairal/ur5_gripper_moveit_config

Use Moveit for motion planning in Rviz

To start Rviz as well as Gazebo execute the following command in your terminal:

$ roslaunch ur5_gripper_moveit_config demo_gazebo.launch

In both of them you should now see the UR5 robot with a gripper attached. Now we can try motion planning in Rviz. If you don’t see the MotionPlanning section in the bottom left inside Rviz, click on Add in the bottom left corner and under display_type choose MotionPlanning.

In the Planning tab you can select the Planning group. When you choose ur5_arm and and select Interact in the top left corner you should see arrows appearing at the tip of the robot arm. These allow you to interact with the robot and change its position. Drag the robot around, then hit Plan and the motion planner plans how to move to the desired position. The computed plan will be displayed in Rviz. Now you can hit Execute and the Robot will actually move.

Moveit might show a failed instead of a success message because of some deviations in the controllers.This is because we don’t have perfectly tuned control parameters. However, the robot arm still moves to the desired position with well enough accuracy.

When we choose the gripper Planning group we don’t get arrows to interact with. Nonetheless, if we switch to the joints tab (the very right tab inside the Moveit plugin) we can directly set the joint value for the gripper joint. Then we can go back to the Planning tab and plan and execute in the same fashion as for the robot arm.

That’s how easy it is to use Moveit inside Rviz! The Plugin offers more features to play with which we don’t have time to discuss right now. Moveit is an extensive and powerful tool. In the next tutorial I show how to implement a pick and place task using the Moveit C++ interface. There we will be using the Moveit configuration we just created. Also check out the other tutorials and I’m happy to receive some feedback in the comments.

Quickstart

If you don’t have the universal_robots repository cloned yet then please do so with the following commands inside your catkin workspace:

~/catkin_ws/src$ git clone -b <distro>-devel https://github.com/ros-industrial/universal_robot.git

Go ahead and clone the following repository into you catkin workspace to get the Robotiq gripper description:

~/catkin_ws/src$ git clone https://github.com/filesmuggler/robotiq.git

Then download the following URDF file and store it inside the universal_robots repository under ur_description/urdf :

~/catkin_ws/src/universal_robot/ur_description/urdf$ wget https://raw.githubusercontent.com/utecrobotics/ur5/master/ur5_description/urdf/ur5_robotiq85_gripper.urdf.xacro

Modify line 4 in the ur5_robotiq85_gripper.urdf.xacro file such that the it searches for the URDF file inside our ur_description package:

  <xacro:include filename="$(find ur_description)/urdf/ur5_joint_limited_robot.urdf.xacro" />

First, inside the robotiq repository in robotiq_description/urdf/robotiq_85_gripper.transmission.xacro we need to change lines 9 and 14 to:

    <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>

Second, in the universal_robots repository in ur_description/urdf/ur5_joint_limited_robot.urdf.xacro line 5 needs to be modified as follows:

  <xacro:arg name="transmission_hw_interface" default="hardware_interface/EffortJointInterface"/>

Now you can clone the repository which contains the generated Moveit package as well as the necessary changes:

~/catkin_ws/src$ git clone https://github.com/dairal/ur5_gripper_moveit_config

Start the gazebo demo with the following command:

$ roslaunch ur5_gripper_moveit_config demo_gazebo.launch

This Post Has 2 Comments

  1. Birhanemeskel Alamir

    I followed every step but when I run “roslaunch ur5_gripper_moveit_config demo_gazebo.launch”, I got an error;
    WARN: unrecognized ‘param’ tag in tag
    WARN: unrecognized ‘param’ tag in tag
    RLException: unused args [execution_type] for include of [/home/meskel/catkin_ws/src/ur5_gripper_moveit_config/launch/ur5_moveit_controller_manager.launch.xml]
    The traceback for the exception was written to the log file
    Could you help me?

    1. Alex

      This could be a problem with newer ROS versions.
      If your trajectory_execution.launch.xml file contains the following line:
      arg name=”execution_type” value=”$(arg execution_type)”/>
      Can you delete it and try again?

Comments are closed.