My Robotic Manipulator #04: URDF/Transmission + Gazebo Controllers

My Robotic Manipulator #04: URDF/Transmission + Gazebo Controllers

URDF/Transmission + Gazebo Controllers

Hey ROS developers! In this post, we will make our robot able to be spawned into Gazebo simulator. Based on the YouTube video series, we’ll show in this format the steps to achieve the final result of the series!

In this post number #4, I’m gonna create the Transmissions and controllers to some of our joints using the same XACROs files we have been working with. Up to the end of the post, we’ll have part of our model controllers by gazebo controllers!

 

Step 1 – Simplifying the robot

It turns out we have a very complex robot, with 6 links and 5 joints. I want to make it simpler in order to show how to use gazebo controller plugin.

Let’s start opening the file mrm.xacro and comment leave only the first links of the robot (the rest, we will comment). It will look like below:

<?xml version="1.0" ?>

<robot name="mrm" xmlns:xacro="http://www.ros.org/wiki/xacro">

  <!-- BGN - Include -->
  <xacro:include filename="$(find mrm_description)/urdf/links_joints.xacro" />
  <xacro:include filename="$(find mrm_description)/urdf/robot_parameters.xacro" />
  <!-- END - Include -->

  <!-- BGN - Robot description -->
  <m_link_box name="${link_00_name}"
           origin_rpy="0 0 0" origin_xyz="0 0 0"
           mass="1024"
           ixx="170.667" ixy="0" ixz="0"
           iyy="170.667" iyz="0"
           izz="170.667"
           size="1 1 1" />

  <m_joint name="${link_00_name}__${link_01_name}" type="revolute"
           axis_xyz="0 0 1"
           origin_rpy="0 0 0" origin_xyz="0 0 0.5"
           parent="${link_00_name}" child="${link_01_name}" />

  <m_link_cylinder name="${link_01_name}"
           origin_rpy="0 0 0" origin_xyz="0 0 0.2"
           mass="157.633"
           ixx="13.235" ixy="0" ixz="0"
           iyy="13.235" iyz="0"
           izz="9.655"
           length="0.4" radius="0.35" />

  <m_joint name="${link_01_name}__${link_02_name}" type="revolute"
           axis_xyz="0 1 0"
           origin_rpy="0 0 0" origin_xyz="0 0 0.4"
           parent="${link_01_name}" child="${link_02_name}" />

  <m_link_cylinder name="${link_02_name}"
           origin_rpy="0 0 0" origin_xyz="0 0 0.4"
           mass="57.906"
           ixx="12.679" ixy="0" ixz="0"
           iyy="12.679" iyz="0"
           izz="0.651"
           radius="0.15" length="0.8" />

<!--
  <m_joint name="${link_02_name}__${link_03_name}" type="revolute"
           axis_xyz="0 1 0"
           origin_rpy="0 0 0" origin_xyz="0 0 0.8"
           parent="${link_02_name}" child="${link_03_name}" />

  <m_link_cylinder name="${link_03_name}"
           origin_rpy="0 0 0" origin_xyz="0 0 0.4"
           mass="57.906"
           ixx="12.679" ixy="0" ixz="0"
           iyy="12.679" iyz="0"
           izz="0.651"
           radius="0.15" length="0.8" />

  <m_joint name="${link_03_name}__${link_04_name}" type="revolute"
           axis_xyz="0 1 0"
           origin_rpy="0 0 0" origin_xyz="0 0 0.8"
           parent="${link_03_name}" child="${link_04_name}" />

  <m_link_cylinder name="${link_04_name}"
           origin_rpy="0 0 0" origin_xyz="0 0 0.4"
           mass="57.906"
           ixx="12.679" ixy="0" ixz="0"
           iyy="12.679" iyz="0"
           izz="0.651"
           radius="0.15" length="0.8" />

  <m_joint name="${link_04_name}__${link_05_name}" type="revolute"
           axis_xyz="0 0 1"
           origin_rpy="0 0 0" origin_xyz="0 0 0.8"
           parent="${link_04_name}" child="${link_05_name}" />

  <m_link_cylinder name="${link_05_name}"
           origin_rpy="0 0 0" origin_xyz="0 0 0.125"
           mass="18.056"
           ixx="0.479" ixy="0" ixz="0"
           iyy="0.479" iyz="0"
           izz="0.204"
           radius="0.15" length="0.25" />
-->
  <!-- END - Robot description -->

</robot>

Start an empty world simulation and launch the robot from a web shell:

roslaunch mrm_description spawn.launch

Great! These are the parts we are going to control!

 

Step 2 – Adding gazebo controller dependencies

We need to modify two of our package files, in order to include the dependencies. They are:

CMakeLists.txt

In the command find_package, let’s add some new values:

find_package(catkin REQUIRED COMPONENTS
  urdf
  controller_manager
  joint_state_controller
  robot_state_publisher
)

And in the package.xml file, make sure you have the following instructions:

  <build_depend>urdf</build_depend>
  <build_depend>controller_manager</build_depend>
  <build_depend>joint_state_controller</build_depend>
  <build_depend>robot_state_publisher</build_depend>

  <build_export_depend>urdf</build_export_depend>
  <build_export_depend>controller_manager</build_export_depend>
  <build_export_depend>joint_state_controller</build_export_depend>
  <build_export_depend>robot_state_publisher</build_export_depend>

  <exec_depend>urdf</exec_depend>
  <exec_depend>controller_manager</exec_depend>
  <exec_depend>joint_state_controller</exec_depend>
  <exec_depend>robot_state_publisher</exec_depend>

 

Step 3 – Adding transmissions to the robot model

Next thing, we need some transmissions elements in our robot model.

Let’s get back to the URDF file: mrm.xacro

  <m_link_box name="${link_00_name}"
           origin_rpy="0 0 0" origin_xyz="0 0 0"
           mass="1024"
           ixx="170.667" ixy="0" ixz="0"
           iyy="170.667" iyz="0"
           izz="170.667"
           size="1 1 1" />

  <m_joint name="${link_00_name}__${link_01_name}" type="revolute"
           axis_xyz="0 0 1"
           origin_rpy="0 0 0" origin_xyz="0 0 0.5"
           parent="${link_00_name}" child="${link_01_name}" />

  <transmission name="trans_${link_00_name}__${link_01_name}">
    <type>transmission_interface/SimpleTransmission</type>
    <joint name="${link_00_name}__${link_01_name}">
        <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
    </joint>
    <actuator name="motor_${link_00_name}__${link_01_name}">
        <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
        <mechanicalReduction>1</mechanicalReduction>
    </actuator>
  </transmission>

  <m_link_cylinder name="${link_01_name}"
           origin_rpy="0 0 0" origin_xyz="0 0 0.2"
           mass="157.633"
           ixx="13.235" ixy="0" ixz="0"
           iyy="13.235" iyz="0"
           izz="9.655"
           length="0.4" radius="0.35" />

  <m_joint name="${link_01_name}__${link_02_name}" type="revolute"
           axis_xyz="0 1 0"
           origin_rpy="0 0 0" origin_xyz="0 0 0.4"
           parent="${link_01_name}" child="${link_02_name}" />

  <transmission name="trans_${link_01_name}__${link_02_name}">
    <type>transmission_interface/SimpleTransmission</type>
    <joint name="${link_01_name}__${link_02_name}">
        <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
    </joint>
    <actuator name="motor_${link_01_name}__${link_02_name}">
        <hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
        <mechanicalReduction>1</mechanicalReduction>
    </actuator>
  </transmission>

  <m_link_cylinder name="${link_02_name}"
           origin_rpy="0 0 0" origin_xyz="0 0 0.4"
           mass="57.906"
           ixx="12.679" ixy="0" ixz="0"
           iyy="12.679" iyz="0"
           izz="0.651"
           radius="0.15" length="0.8" />

You can notice we have added a new element with the transmission tag.

What are we describing there?

First, we have a transmission for each joint. Then we define the type of the transmission, which in this case is just a SimpleTransmission.

Then, the joint we are referencing with the transmission.

Further, the actuator type, which is an Effort Joint Interface, in this case. And the mechanical reduction.

We do this for both joints we have left (in this simplified version of the robot).

 

Step 4 – Setup gazebo controllers on URDF model

Still on the same file, let’s add to the end of the description the tags related to gazebo controller plugin.

Just simple as below, append to the end of the file, just before the </robot>:

<gazebo>
    <plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so">
    </plugin>
</gazebo>

 

Step 5 – Describe controller YAML file

This is something necessary for the gazebo controller, we must define some control variables (PID) to apply to our transmissions.

In order to do that, let’s create a new file: ~/simulation_ws/src/mrm_description/config/joints.yaml

It goes like that:

# Publish all joint states -----------------------------------
joint_state_controller:
  type: joint_state_controller/JointStateController
  publish_rate: 50

# Position Controllers ---------------------------------------
joint1_position_controller:
  type: effort_controllers/JointPositionController
  joint: base_link__link_01
  pid: {p: 2000.0, i: 100, d: 500.0}
joint2_position_controller:
  type: effort_controllers/JointPositionController
  joint: link_01__link_02
  pid: {p: 50000.0, i: 100, d: 2000.0}

We are defining the joint_state_publisher as reference.

Then tuning each one of the transmissions we have defined in our model. We need again the nametypejoint name and the PID values

 

Step 6 – Launch Gazebo Controllers

Now, let’s modify our launch file.

It goes like:

<?xml version="1.0" encoding="UTF-8"?>
<launch>
    <group ns="/mrm">

        <!-- Robot model -->
        <param name="robot_description" command="$(find xacro)/xacro --inorder '$(find mrm_description)/urdf/mrm.xacro'" />
        <arg name="x" default="0" />
        <arg name="y" default="0" />
        <arg name="z" default="0.5" />

        <!-- Spawn the robot model -->
        <node name="mybot_spawn" pkg="gazebo_ros" type="spawn_model" output="screen"
            args="-urdf -param robot_description -model mrm -x $(arg x) -y $(arg y) -z $(arg z)" />

        <!-- Load controllers -->
        <rosparam command="load" file="$(find mrm_description)/config/joints.yaml" />

        <node name="controller_spawner" pkg="controller_manager" type="spawner"
              respawn="false" output="screen" ns="/mrm"
              args="--namespace=/mrm
              joint_state_controller
              joint1_position_controller
              joint2_position_controller
              --timeout 60">
        </node>
    </group>
</launch>

First main modification is the group tag, where we define a namespace (mrm) for our robot processes. Everything inside this tag inherits the namespace. It’s necessary for the controller plugin.

Then, in the secion Load controllers we have a new parameter, that loads the config.yml file we have just created.

Finally, a new node to run the controller process.

 

Step 7 – Testing!

Great! Now we have already configured the controllers, you can spawn the robot again! Same commands as before, but this time you will notice the last link won’t fall down! This is very important to achieve since the controllers are already actuating.

Check the shell, you can see the controllers being loaded in the logs!

process[mrm/mybot_spawn-1]: started with pid [4817]
process[mrm/controller_spawner-2]: started with pid [4822]
[INFO] [1567187158.002693, 0.000000]: Controller Spawner: Waiting for service /mrm/controller_manager/load_controller
the rosdep view is empty: call 'sudo rosdep init' and 'rosdep update'
SpawnModel script started
[INFO] [1567187165.292282, 0.000000]: Loading model XML from ros parameter
[INFO] [1567187165.303925, 0.000000]: Waiting for service /gazebo/spawn_urdf_model
[INFO] [1567187165.312998, 0.000000]: Calling service /gazebo/spawn_urdf_model
[INFO] [1567187165.504207, 904.010000]: Spawn status: SpawnModel: Successfullyspawned entity
[mrm/mybot_spawn-1] process has finished cleanly
log file: /home/user/.ros/log/cfa21f58-cb4b-11e9-9ca9-0a2504d14030/mrm-mybot_spawn-1*.log
[INFO] [1567187166.829017, 904.050000]: Controller Spawner: Waiting for service /mrm/controller_manager/switch_controller
[INFO] [1567187166.831181, 904.050000]: Controller Spawner: Waiting for service /mrm/controller_manager/unload_controller
[INFO] [1567187166.848968, 904.070000]: Loading controller: joint_state_controller
[INFO] [1567187167.000380, 904.220000]: Loading controller: joint1_position_controller
[INFO] [1567187167.268639, 904.500000]: Loading controller: joint2_position_controller
[INFO] [1567187167.345849, 904.570000]: Controller Spawner: Loaded controllers: joint_state_controller, joint1_position_controller, joint2_position_controller
[INFO] [1567187167.355672, 904.590000]: Started controllers: joint_state_controller, joint1_position_controller, joint2_position_controller

We have also new ROS topics related to the controllers:

user:~$ rostopic list
/clock
/gazebo/link_states
/gazebo/model_states
/gazebo/parameter_descriptions
/gazebo/parameter_updates
/gazebo/set_link_state
/gazebo/set_model_state
/mrm/joint1_position_controller/command
/mrm/joint1_position_controller/pid/parameter_descriptions
/mrm/joint1_position_controller/pid/parameter_updates
/mrm/joint1_position_controller/state
/mrm/joint2_position_controller/command
/mrm/joint2_position_controller/pid/parameter_descriptions
/mrm/joint2_position_controller/pid/parameter_updates
/mrm/joint2_position_controller/state
/mrm/joint_states
/rosout
/rosout_agg

As a final test, let’s send a reference to the second joint:

rostopic pub -1 /mrm/joint2_position_controller/command std_msgs/Float64 "data: 0.7"

You must have the robot like:

In order to put it back to the original position, execute the command below:

rostopic pub -1 /mrm/joint2_position_controller/command std_msgs/Float64 "data: 0.0"

 

Related courses

Robot-creation-URDF Course Cover - ROS Online Courses - Robot Ignite Academy

URDF for Robot Modeling

ROS Manipulation Course Cover - ROS Online Courses - Robot Ignite Academy

ROS Manipulation

ROS Industrial robots Course Cover - ROS Online Courses - Robot Ignite Academy

ROS for Industrial Robots

Step 8 – Conclusion

Great! If you missed any of the steps or something just didn’t work, you can check the original project just clicking on the link: http://www.rosject.io/l/c1ed2ee/

See you in the next post!

[ROS Q&A] 143 – How to connect MoveIt to the Robot

In this tutorial of ROS Q&A Series, we’re going to see how to connect movit to the (simulated, in this case) robot.

This is a video trying to answer the following question posted at the ROS answers forum: https://answers.ros.org/question/298508/how-do-i-interact-the-actual-robot-with-visualization-by-rviz-in-moveit/

Step 1. Create a project in ROS Development Studio(ROSDS)

ROSDS helps you follow our tutorial in a fast pace without dealing without setting up an environment locally. If you haven’t had an account yet, you can create a free account here. Let’s create a new project and call it moveit_real.

Step 2. Use the moveit package

In this tutorial, we have already preconfigured the Sia Robot and moveit package for it. If you want to know how to configure the moveit package, please check our ROS-Industrial 101 course. If you launch the moveit package, you’ll see that no matter what trajectory you are planning in the moveit, it won’t affect the real robot(we use a simulation as an example here). That’s because of missing controllers. To apply the controller, a file called controller.yaml should be created in the config folder of the robot. We also have to specify the controller type in the sia10f.urdf file.  In order to use the controller, a transmission tag should be added to the urdf. You’ll also need a joint_names.yaml file in the config folder which defines the joints will be controlled. In the end, you’ll need to create launch files to launch the package.

Step 3. Plan the trajectory

After launching the controller, you can plan the trajectory with moveit package. The robot should move as the planning in the moveit package.

Want to learn more?

If you are interested in this topic and want to learn how to configure the moveit package and all the files you need to move the robot, please check our ROS-Industrial 101 course.

 

Edit by: Tony Huang

 

Related Courses

ROS Manipulation Course Cover - ROS Online Courses - Robot Ignite Academy

ROS Manipulation Course


Feedback

Did you like this video? Do you have questions about what is explained? Whatever the case, please leave a comment on the comments section below, so we can interact and learn from each other.

If you want to learn about other ROS topics, please let us know on the comments area and we will do a video about it.

ROS Developers LIVE-Class #20: Simulate an Industrial Environment

ROS Developers LIVE-Class #20: Simulate an Industrial Environment

 

In this Live Class we are going to see how to apply all that we have learnt in the previous classes about Gazebo. We are going to execute ARIAC simulation made by the OSRF. We are going to learn how to manage that simulation in order to make the robots perform useful tasks in the environment. We will indicate where Gazebo plugins were applied, how SDF was used to create the environment, were ROS control was applied, where ROS navigation was applied, etc. We will see how to create a simple Python program that allows us to make the robots do useful things.

A new ROS Live Class every Tuesday at 18:00 CET/CEST.
This is a LIVE Class on how to develop with ROS. In Live Classes you practice with me at the same time that I explain, with the provided free ROS material.

IMPORTANT: Remember to be on time for the class because at the beginning of the class we will share the code with the attendants.

IMPORTANT 2: in order to start practicing quickly, we are using the ROS Development Studio for doing the practice. You will need a free account to attend the class. Go to http://rds.theconstructsim.com and create an account prior to the class.

// RELATED LINKS

* ARIAC competition: http://gazebosim.org/ariac
* ROS Development Studio: https://www.theconstruct.ai/rds-ros-development-studio/
* Robot Ignite Academy: https://wp.me/P9Rthq-1sB

[ROS Q&A] 117 – How to Launch a ROS Industrial Robots Simulation

 

In this video we will see how to launch a complex industrial environment with several robots in it, including ROS industrial robots and service robots.

The simulation contains a UR5 industrial robot and a couple of mobile bases. Also, many types of sensors include, including lasers cameras, and even a conveyor belt simulation.

This amazing simulation was created by the OSRF for their ARIAC competition 2017 using Gazebo simulator

 

[irp posts=”8409″ name=”RDP 006: Using ROS for Industrial Projects With Carlos Rosales”]

Step 1. Create a project in ROS Development Studio(ROSDS)

ROSDS helps you follow our tutorial in a fast pace without dealing without setting up an environment locally. If you haven’t had an account yet, you can create a free account here. You can get the shared project through this link .

Step 2. Run the simulation

We prebuilt the package for this project. You can run the simulation with the following command

source ~/simulation_ws/install/setup.bash
rosrun osrf_gear gear.py --development-mode -f /home/user/simulation_ws/install/share/osrf_gear/config/sample.yaml

You can then open the gazebo simulation from Tools->Gazebo. You should see the whole simulation of a warehouse.

Step 3. Demo

We prepared a demo which you can simply launch with the following command

./catkin_ws/src/demo.sh

After executing, you should see the robots are moving around.

We will use this simulation in a future ROS Developers Live Class #20 for playing with robots in industrial environments:

[irp posts=”9470″ name=”ROS Developers LIVE-Class #20: Simulate an Industrial Environment”]

 

Edit by: Tony Huang

RELATED LINKS
▸ OSRF: https://www.osrfoundation.org/
▸ ARIAC competition: http://gazebosim.org/ariac

Robot Ignite Academy
ROS Industrial online course
ROS Development Studio


 

How_To_Launch_ROS_Industrial_Robots_Simulation_post_course_banner

 

 

What is moveit_ros? All about Movelt! ROS

What is moveit_ros? All about Movelt! ROS

What is moveit_ros?

ROS MoveIt!: All You Need to Know To Start

I remember when we participated at the Robocup At Home competition in 2013 with the Pal Robotics team (actually that project was the germen of current The Construct company). At that competition, we used a humanoid robot to do home tasks like bringing stuff to the owner, detecting emergency situations or just following its owner around. The most complicated of all the tasks was to bring something to the owner.

In order for a robot to bring you something, a lot of systems are required to be put in place:

  1. You need the speech recognition system to understand what you are asking to it. We did it with those ROS modules.
  2. You need the navigation system to go to the place where the item must be located. We did it with those ROS modules.
  3. You need the recognition system to identify the object in the location. We did it with those ROS modules.
  4. You need to be able to grasp the object. Done with… wait how do we do that?!?!

Exactly! At that time (2013) ROS did not have any package that dealt with the grasping problem. Luckily, today we have the moveit_ros packages that handle that procedure… and they do it quite well!


Let’s see what moveit ros can do for us and how can we set it up.

 

Arm navigation

The basic task of the MoveIt! system is to provide the necessary trajectories for the arm of a robot to put the end effector in a given place.

What does that mean?

When we want to grasp something with a robot arm, we need to move all the joints of the arm so that the final part of the arm, the one that has the gripper or hand (which is called the end effector),  can be at the proper location of to grasp the object.

Moving the arm to achieve that position is a non-trivial task because you have to produce the sequence of values that every joint of the arm must follow (in coordination with the other joints), so the end effector moves from its current place to the desired place. This task is called motion planning. The result of a motion planning is the sequence of movements that all the joints of the arm have to perform in order to move from current location to the desired one. The following video greatly describes what is it all involved in the making of motion planning:

How to solve the problem of calculating the motion plan is a VERY DIFFICULT problem. Fortunately for us, that is what MoveIt! is an expert at. MoveIt! provides us the plan that the joints have to follow to move an arm from one position to another. In the following gif animation, you can see how a plan for making Fetch extend its arm is provided by MoveIt! MoveIt! provides this animation as a way of showing you how the planned trajectory will look like when executed by the robot (the animation is provided by the MoveIt! control page, more later).

what is ros moveit ros movelt post image fetch robot simulation

Once we have that plan, it is only a matter of sending it properly to the ROS controlled joints. Fortunately, MoveIt! can also take charge of executing the plan in the robot (it is up to you if you want it just to provide you the plan, or plan+execution). In this gif animation, we show you how the simulated robot executes the plan created by MoveIt! on the previous step (you can make MoveIt! send the trajectory to either the simulated or real robot).

what is ros moveit ros movelt post image fetch robot simulation

Different planners

The code that generates the motion plan is called the planner. Being motion planning a difficult problem, we cannot consider that it has been solved. There is not the best solution to find the joints movement for any robot arm. Because of that, there exist different approaches (different planners) to the calculation of the plans.

Move provides off-the-shelf several planners, each one with its advantages and drawbacks. You can read the full list of provided planners here.

Additionally, to that list, you can develop your own planner too and provide it to MoveIt! as a plugin. You can learn more about moveit plugins here. It is quite a subject, so in case you would like us to do a tutorial on MoveIt! plugins, just let us know below in the comments of the post.

Configuring moveit ros for your robot

In order to be able to use moveit ros with your robot, first, you have to configure it. Fortunately, the configuration of a robotics arm is very simple, provided that you have a URDF file describing your robot. That is a basic requirement. You need to specify someway how your robot is composed, length of the different parts of the arm, which joints it contains, among other things. If you don’t know how to create the URDF of your robot, take this online course to learn how to do it.

Armed with your URDF, you only have to launch the MoveIt! assistant. That is a beautiful piece of configuration that simplifies A LOT the setup of your arm robot (I remember the old days…).

Assuming that you have moveit ros installed in your system (very simple step, watch this page to learn how to install it), now you can launch the assistant with the following command:

> roslaunch moveit_setup_assistant setup_assistant.launch

Let’s do now a simple example of the configuration.

Configuring a Motoman robot

Let’s configure the robot of the figure.

what is ros moveit ros movelt post image ros development studio

If you do not have that robot to practice with, you can use the simulation of it. Watch this video to learn how to have that simulation running in your computer in only 5 minutes (really, that quick).

For the rest of the tutorial, we are going to assume that you either have the ROS packages of that robot installed in your computer (watch installation tutorial here), or that you are using the simulation as explained in the previous paragraph.

We highly recommend you to do the simulation path!! It is dangerous to do experiments with the real robot when you still don’t know how it works.

  • For that, just open the MoveIt! assistant as explained above and let’s go through the different configuration screens.
  • Click on the Create New MoveIt Configuration Package button. A new section like this will appear:

what is ros moveit ros movelt post image load xacro

  • Now, just click the Browse button, select the xacro (URDF) file you the robot, and click on the Load Files button. You should now see this:

what is ros moveit ros movelt post image xacro loaded

  •  Go to the Self-Collisions tab, and click on the Regenerate Default Collision Matrix button. You will end with something like this:

what is ros moveit ros movelt post image collision matrix

  • Here, you are just defining some pairs of links that don’t need to be considered when performing collision checking. For instance, because they are adjacent links, so they will always be in collision.
  • Next, move to the Virtual Joints tab. Here, you will define a virtual joint for the base of the robot. Click the Add Virtual Joint button, and set the name of this joint to FixedBase, and the parent to world. Just like this:

what is ros moveit ros movelt post image virtual joint

  • Finally, click the Save button. Basically, what you are doing here is to create an imaginary joint that will connect the base of your robot with the simulated world.
  • Now, open the Planning Groups tab and click the Add Group button. Now, you will create a new group called manipulator, which uses the KDLKinematicsPlugin. Just like this:

what is ros moveit ros movelt post image plan group1

  • Next, you will click on the Add Kin Chain button, and you will select the base_link as Base Link, and the link_tool0 as Tip Link. Just like this:

what is ros moveit ros movelt post image plan group2

  • Finally, click the “Save” button and you will end up with something like this:

what is ros moveit ros movelt post image plan group3

  • So now, you’ve defined a group of links for performing Motion Planning with, and you’ve defined the plugin you want to use to calculate those Plans.
  • Now, you are going to create a couple of predefined poses for your robot. Go to the Robot Poses tab and click on the Add Pose button. Your robot will appear with all its joints to “0”. So, you will name this pose as allZeros, and click the Save button.

what is ros moveit ros movelt post image allzeros

  • Now, repeat the operation, but this time adjusting the position of the joints so that the robot is in a specific position that we will call home. You can set the joints as you want, but I recommend you to set the robot in a position that is not complicated. For instance, something like this:

what is ros moveit ros post movelt home page

  • This is very useful, for instance, when you know that there are some poses that your robot will have to go many times
  • Now, just enter your name and e-mail at the Author Information tab.
  • Finally, go to the Configuration Files tab and click the Browse button. Navigate to your catkin_ws/src directory, create a new directory, and name it myrobot_moveit_config. Choose the directory you’ve just created.
  • Now, click the Generate Package button. If everything goes well, you should see something like this:
what is ros moveit ros movelt post image conf files2
And that’s it! You have just created a moveit package for your industrial robot.

 Creating a plan

Now you are ready to make moveit ros create a plan for that robot. Remember that moveit ros has two separated functions: create the plan and send the plan to the robot. Here we deal with the first. On the next section below you will learn how to send it to the robot.

  • Let’s start the moveit ros Rviz configuration environment with the configuration file we generated:

> roslaunch myrobot_moveit_config demo.launch
what is ros moveit ros movelt post image rviz

  • Now, move to the Planning tab. Here:
what is ros moveit ros movelt post image moveit rviz planning
  • Before start Planning anything, it is always a good practice to update the current state. Click on Select Start State at the Query section and press the Update button.
  • Clicking on the Select Goal State, you can choose the random valid option and click on the Update button. Your robot scene will be updated with the new random position that has been selected (your position may differ from the figure because it is a random one).
what is ros moveit ros movelt post image scene updated
  • Now, you can click on the Plan button at the Commands section. The robot will begin to plan a trajectory to reach that random point.
 giphy ros moveit movelt post

Sending the plan to the robot

Now that you have a plan for the robot, and that the plan is visualized in the planner window, it is time to send the plan to the robot. The instructions for getting the simulated (or real) robot executing the trajectory are the following:

  • Create a file to define how you will control the joints of your robot. Inside the config folder of your moveit package, create a new file named controllers.yaml. Copy the following content inside it:
controller_list:
- name: sia10f/joint_trajectory_controller
action_ns: "follow_joint_trajectory"
type: FollowJointTrajectory
joints: [joint_s, joint_l, joint_e, joint_u, joint_r, joint_b, joint_t]

Basically, here you are defining the Action Server (and the type of message that it will use) that you will use for controlling the joints of your robot.

  • Next, you’ll have to create a file to define the names of the joints of your robot. Again inside the config directory, create a new file called joint_names.yaml, and copy the following content in it:
controller_joint_names: [joint_s, joint_l, joint_e, joint_u, joint_r, joint_b, joint_t]
  • Now, if you open the myrobot_moveit_controller_manager.launch.xml, which is inside the launch directory, you’ll see that it’s empty. Put the next content inside it:
<launch>
<rosparam file="$(find myrobot_moveit_config)/config/controllers.yaml"/>
<param name="use_controller_manager" value="false"/>
<param name="trajectory_execution/execution_duration_monitoring" value="false"/>
<param name="moveit_controller_manager" value="moveit_simple_controller_manager/MoveItSimpleControllerManager"/>
</launch>
  •  Finally, you will have to create a new launch file that sets up all the system to control your robot. So, inside the launch directory, create a new launch file called myrobot_planning_execution.launch
<launch>


<rosparam command="load" file="$(find myrobot_moveit_config)/config/joint_names.yaml"/>
<include file="$(find myrobot_moveit_config)/launch/planning_context.launch" >
<arg name="load_robot_description" value="true" />
</include>


<node name="joint_state_publisher" pkg="joint_state_publisher" type="joint_state_publisher">
<param name="/use_gui" value="false"/>
<rosparam param="/source_list">[/sia10f/joint_states]</rosparam>
</node>


<include file="$(find myrobot_moveit_config)/launch/move_group.launch">
<arg name="publish_monitored_planning_scene" value="true" />
</include>


<include file="$(find myrobot_moveit_config)/launch/moveit_rviz.launch">
<arg name="config" value="true"/>
</include>
</launch>

  •  Finally, you just have to launch this file and Plan a trajectory, just as you learned to do above. Once the trajectory is planned, you can press the Execute button in order to execute the trajectory in the simulated robot. You should see something like this (actual movement will depend on the selected random trajectory):

move code ros movelt moveit post

 

Based on the knowledge above, I invite you to experiment with the other options that the moveit ros Rviz tools have and try to generate the specific poses that we configured during the assistant launch.

Avoiding obstacles

Up to this point, you have used moveit ros with a robot that is isolated from the world. This means that the robot cannot collide with anything but itself. However, that is not the real situation of most of the robots. We want robots to be able to plan in an environment where other objects are around.

MoveIt! allows to introduce known obstacles in a prior step to planning, so the planning algorithm can take it into account and do not generate trajectories that would collide with the objects around.

what is ros moveit ros movelt post image moveit object

In the previous figure, moveit ros is taking into account the table that it is detecting with a Kinect sensor.

The inclusion of obstacles in the trajectory planning is something delicated that cannot be described here now, specially if you want to embed that into a full grasping pipeline, where the robot has to do actual grasps of objects (that at the end, that is what we are making all this for). In case you are interested in learning how to include obstacles in the planning trajectories, and how to actually grasp the objects, please take a look at this course that teaches that subject.

ROS Industrial

Of course, one of the first applications to practical things of MoveIt! is to industrial robots. Industrial robots are based on path planning. Basically, that is the only thing they are required to do. So when MoveIt! came out, the first application was for that kind of robots. This has lead to the creation of the ROS Industrial consortium, a group of people and institutions that try to spread ROS into the industrial sector. Remember that at present ROS is more focused into service robots for which there is no actual industry or market yet. The only robotics market that actually exists is the industrial one. So the move makes perfect sense, since the industrial robotics market is the one closer to provide some revenue.

Under the ROS Industrial umbrella, the consortium makes extensive use of MoveIt! for the control of already existing commercial robots like Kuka, Universal Robots, Motoman, ABB or Fanuc robots. The ROS Industrial packages provide, not only the connection to MoveIt! but also the drivers to ROSify those robots. That means that, by using the ROS Industrial packages you can control those commercial robots with ROS and with MoveIt!

You can download the ROS Industrial packages from their GitHub.

You can have a good practical introduction to ROS Industrial with this course.

Final considerations

moveit ros is so great package for finding trajectories that can also be used for generating 3D trajectories for other systems that are not robotic arms, like for example for drones. Since drones have to move in a 3D environment while avoiding the obstacles in its way, having a generated plan by MoveIt! makes it a lot easier. For instance, this course teaches how to make a drone navigate using MoveIt! Next animation shows how to use MoveIt! for generating a simple trajectory of a drone.

drone_plan1_ros_moveit_post

 

Conclusion

moveit ros package is the way to go to control robotic arms (either industrial or humanoid robot arms). With its plugin interface for planners, you can attach your own planner if you don’t like what already provided off-the-shelf, and keep using the ROS infrastructure. It is without doubt, the fastest way to use your robotics manipulator. Give it a try and let us know what your experience has been.

To learn more about moveit ros check the following tutorials:

  1. Official tutorial of moveit ros Very complete but very dry.
  2. Online course on ROS Manipulation with MoveIt! Uses online simulations to teach you how to use moveit ros with service robots.
  3. Online course on ROS Industrial with MoveIt! Also uses online simulations to teach you how to use moveit ros with industrial robots. (Additionally, in case you like it, you can use the discount coupon 32C3F924 for a 10% discount)
  4. Official ROS industrial tutorial. Very complete, but very dry

Homework for you

Now, what I would like to hear is what do you think of moveit ros? Answer the following questions below in the comments:

  • Have you used moveit ros for a ROS project?
  • What do you like the most?
  • What are you missing in it?

 

···


ros-industrial-ros-moveit-movelt-course

Pin It on Pinterest