Search icon
Arrow left icon
All Products
Best Sellers
New Releases
Books
Videos
Audiobooks
Learning Hub
Newsletters
Free Learning
Arrow right icon
Mastering ROS for Robotics Programming

You're reading from  Mastering ROS for Robotics Programming

Product type Book
Published in Dec 2015
Publisher Packt
ISBN-13 9781783551798
Pages 480 pages
Edition 1st Edition
Languages
Concepts
Author (1):
Lentin Joseph Lentin Joseph
Profile icon Lentin Joseph

Table of Contents (19) Chapters

Mastering ROS for Robotics Programming
Credits
About the Author
About the Reviewers
www.PacktPub.com
Preface
Introduction to ROS and Its Package Management Working with 3D Robot Modeling in ROS Simulating Robots Using ROS and Gazebo Using the ROS MoveIt! and Navigation Stack Working with Pluginlib, Nodelets, and Gazebo Plugins Writing ROS Controllers and Visualization Plugins Interfacing I/O Boards, Sensors, and Actuators to ROS Programming Vision Sensors using ROS, Open-CV, and PCL Building and Interfacing Differential Drive Mobile Robot Hardware in ROS Exploring the Advanced Capabilities of ROS-MoveIt! ROS for Industrial Robots Troubleshooting and Best Practices in ROS Index

Chapter 11. ROS for Industrial Robots

In the previous chapter, we have seen some advanced concepts in ROS-MoveIt! Until now, we have been discussing mainly about interfacing personal and research robots with ROS, but one of the main areas where robots are extensively used are industries. Does ROS support industrial robots? Do any of the companies use ROS for the manufacturing process? The ROS-Industrial packages comes with a solution to interface industrial robot manipulators to ROS and controlling it using the power of ROS, such as MoveIt!, Gazebo, RViz, and so on.

In this chapter, we will discuss the following topics:

  • Understanding ROS-Industrial packages

  • Installing ROS-Industrial packages in ROS

  • Block diagram of ROS-Industrial packages

  • Creating URDF for an industrial robot

  • Creating the MoveIt! interface for an industrial robot

  • Installing ROS-Industrial packages of Universal robotic arms

  • Understanding MoveIt! configuration of a universal robotic arm

  • Working with MoveIt! configuration of ABB robots...

Understanding ROS-Industrial packages


ROS-Industrial basically extends the advanced capabilities of ROS software to industrial robots working in the production process. ROS-Industrial consists of many software packages, which can be used for interfacing industrial robots. These packages are BSD (legacy) / Apache 2.0 (preferred) licensed program, which contain libraries, drivers, and tools for industrial hardware. The ROS-Industrial is now guided by the ROS-Industrial Consortium. The official website of ROS-I is http://rosindustrial.org/. The following diagram is the logo of ROS-I:

Figure 1: Logo of ROS-Industrial

Goals of ROS-Industrial

The main goals behind developing ROS-Industrial are given as follows:

  • Combine strengths of ROS to the existing industrial technologies for exploring advanced capabilities of ROS in the manufacturing process

  • Developing a reliable and robust software for industrial robots application.

  • Provide an easy way for doing research and development in industrial robotics

  • Create...

Installing ROS-Industrial packages


Installing ROS-I packages can be done using package managers or building from the source code. If we have installed the ros-desktop-full installation, we can use the following command to install ROS-Industrial packages on Ubuntu 14.04.3. The following command will install ROS-Industrial packages on ROS Indigo:

$ sudo apt-get install ros-indigo-industrial-core ros-indigo-open-industrial-ros-controllers

The preceding command will install the core packages of ROS-Industrial packages. The industrial-core stack includes the following set of ROS packages:

  • industrial-core: This stack contains packages and libraries for supporting industrial robotic systems. The stack consists of nodes for communicating with industrial robot controllers, industrial robot simulators, and also provides ROS controllers for industrial robots.

  • industrial_deprecated: This package contains nodes, launch files, and so on that are going to be deprecated. The files inside this package will...

Block diagram of ROS-Industrial packages


The following diagram a simple block diagram representation of ROS-I packages, which are organized on top of ROS. We can see the ROS-I layer on top of the ROS layers. We can see a brief description of each of the layers for better understanding. The following diagram is taken from ROS-I wiki page (http://wiki.ros.org/Industrial).

Figure 2: The block diagram of ROS-Industrial

  • The ROS GUI: This layer includes the ROS plugin-based GUI tools layer, which consists of tools such as RViz, rqt_gui, and so on

  • The ROS-I GUI: These GUIs are standard industrial UI for working with industrial robots which may be implemented in the future

  • The ROS Layer: This is the base layer in which all communications are taking place

  • The MoveIt! Layer: The MoveIt! layer provides a direct solution to industrial manipulators in planning, kinematics, and pick and place

  • The ROS-I Application Layer: This layer consists of an industrial process planner, which is used to plan what is...

Creating URDF for an industrial robot


Creating the URDF file for an ordinary robot and industrial robot are the same, but in industrial robots, there are some standards that should be strictly followed during its URDF modeling, which are as follows:

  • Simplify the URDF design: The URDF file should be simple and readable and only need the important tags

  • Common design: Developing a common design formula for all industrial robots by various vendors

  • Modularizing URDF: The URDF needs to modularize using XACRO macros and it can be included in a large URDF file without much hassle.

The following points are the main difference in the URDF design followed by ROS-I.

  • Collision-Aware: The industrial robot IK planners are collision aware so the URDF should contain accurate collision 3D mesh for each link. Every link in the robot should export to STL or DAE with a proper coordinate system. The coordinate system which ROS-I is following are X-axis pointing forward and Z-axis pointing up when each joint is...

Creating MoveIt! configuration for an industrial robot


The procedure for creating the MoveIt! interface for industrial robots are same as the other ordinary robot manipulators except in some standard conventions. The following procedures give a clear idea about these standard conventions:

  • Launch the MoveIt! setup assistant using the following command:

    $ roslaunch moveit_setup_assistant setup_assistant.launch
    
  • Load the URDF from the robot description folder or convert xacro to URDF and load to the setup assistant

  • Create a Self-Collision matrix with Sampling Density about ~ 80,000. This value can increase the collision checking in the arm

  • Add a Virtual Joint matrix as shown in the following screenshot. Here the virtual and parent frame names are arbitrary.

    Figure 3: Adding MoveIt! - Virtual joints

  • In the next step, we are adding Planning Groups for manipulator and End Effector, here also the group names are arbitrary. The default plugin is KDL, we can change it even after creating the MoveIt! configuration...

Installing ROS-Industrial packages of universal robotic arm


The Universal Robots (http://www.universal-robots.com/) is an industrial robot manufacturer based in Denmark. The company mainly manufactures three arms UR3, UR5, and UR10. The robots are shown in the following screenshot:

Figure 7: UR-3, UR-5, and UR-10 robots

The smaller one is UR-3, UR-5 is the one in the center, and the big one is UR-10. The specifications of these robots are given in the following table:

Robot

UR-3

UR-5

UR-10

Working radius

500 mm

850 mm

1300 mm

Payload

3 kg

5 kg

10 kg

Weight

11 kg

18.4 kg

28.9 kg

Footprint

118 mm

149 mm

190 mm

We are mainly discussing ROS interfacing of UR-5 and UR-10 using ROS-I packages.

We can install the packages of these robots and can work with the MoveIt! interface and simulation interface of these robots in Gazebo.

Installing the ROS interface of universal robots

We can install the latest packages of the universal robot using the source installation.

Create a...

Understanding the Moveit! configuration of a universal robotic arm


The changes that we need to make in the industrial MoveIt! configuration are almost the same as the arm we already worked with.

First, we have to define the controller.yaml file, which has to create inside ur10_moveit_config/config. Here is the definition of the controller.yaml of UR-10:

controller_list:
  - name: ""
    action_ns: follow_joint_trajectory
    type: FollowJointTrajectory
    joints:
      - shoulder_pan_joint
      - shoulder_lift_joint
      - elbow_joint
      - wrist_1_joint
      - wrist_2_joint
      - wrist_3_joint

The kinematics.yaml file inside the config folder contains the IK solvers used for this arm; we can use the following IK solvers. The contents of this file are given as follows:

#manipulator:
#  kinematics_solver: ur_kinematics/UR10KinematicsPlugin
#  kinematics_solver_search_resolution: 0.005
#  kinematics_solver_timeout: 0.005
#  kinematics_solver_attempts: 3
manipulator:
  kinematics_solver...

Working with MoveIt! configuration of ABB robots


We will work with the motion planning of the popular ABB industrial robot models such as IRB 2400 and IRB 6640. The following are the images of these two robots and their specifications.

Figure 11: ABB IRB 2400 and IRB 6640

The arm specification of the IRB 2400-10 and 6640-130 models are given in the following table:

Robot

IRB 2400-10

IRB 6640-130

Working radius

1.55 m

3.2 m

Payload

12 kg

130 kg

Weight

380 kg

1310-1405 kg

Footprint

723x600 mm

1107 x 720 mm

To work with ABB packages, clone the ROS packages of the robot into the catkin workspace. We can use the following command to do this task:

$ git clone https://github.com/ros-industrial/abb

We can also install packages using the Ubuntu binary packages. The following package will install a complete set of ABB robot packages:

$ sudo apt-get install ros-<distro>-abb

Build the source packages using catkin_make and the following command will launch ABB IRB 6640 in RViz...

Understanding the ROS-Industrial robot support packages


The ROS-I robot support packages are a new convention followed for industrial robots. The aim of these support packages are to standardize the ways of maintaining ROS packages for a wide variety of industrial robot types of different vendors. Because of a standardized way of keeping files inside support packages, we don't have any confusion in accessing the files inside it. We can demonstrate a support package of an ABB robot and can see the folders and files and its uses.

We have already cloned the ABB robot packages and inside this folder we can see three support packages that support three variety of ABB robots. Here we are taking the ABB IRB 2,400 model support package: abb_irb2400_support. This is the support package of the ABB industrial robot model called IRB 2400. The following list shows the folders and files inside this package:

  • config: As the name of the folder, this contains the configuration files of joint names, RViz configuration...

ROS-Industrial robot client package


The industrial robot client nodes are responsible for sending robot position/trajectory data from ROS MoveIt! to the industrial robot controller. The industrial robot client converts the trajectory data to simple_message and communicates to the robot controller using the simple_message protocol. The industrial robot controller running a server and industrial robot client nodes are connecting to this server and start communicating with this server.

Designing industrial robot client nodes

The industrial_robot_client package contains various classes to implement industrial robot client nodes. The main functionalities that a client should have is, it can update the robot current state from the robot controller, and also it can send joint trajectories/joint position message to the controller.

There are two main nodes that are responsible for getting robot state and sending joint trajectory/position values.

  • The robot_state node: This node is responsible for publishing...

ROS-Industrial robot driver package


In this section, we can discuss the industrial robot driver package. If we take the ABB robot as an example, it has a package called abb_driver. This package is responsible for communicating with the industrial robot controller. The package contains industrial robot clients and launches the file to start communicating with the controller.

We can check what's inside the abb_driver/launch folder. The following is a definition of a launch file called robot_interface.launch:

<launch>

  <!-- robot_ip: IP-address of the robot's socket-messaging server -->
  <arg name="robot_ip" />

  <!-- J23_coupled: set TRUE to apply correction for J2/J3 parallel linkage -->
  <arg name="J23_coupled" default="false" />

  <!-- copy the specified arguments to the Parameter Server, for use by nodes below -->
  <param name="robot_ip_address" type="str" value="$(arg robot_ip)"/>
  <param name="J23_coupled" type="bool" value="$(arg J23_coupled...

Understanding MoveIt! IKFast plugin


One of the default numerical IK solvers in ROS is KDL. KDL is mainly using DOF > 6. In robots DOF <= 6, we can use analytic solvers, which is much faster than numerical solvers such as KDL. Most of the industrial arms are having DOF <= 6, so it will be good if we make an analytical solver plugin for each arm.

The robot will work on the KDL solver too, but if we want fast IK solution, we can choose something such as the IKFast module to generate analytical solver-based plugins for MoveIt!. We can check which all are the IKFast plugin packages present in the robot, for example, universal robots and ABB.

  • ur_kinematics: This package contains IKFast solver plugins of UR-5 and UR-10 robots from universal robotics

  • abb_irb2400_moveit_plugins/irb2400_kinematics: This package contains IKFast solver plugins for the ABB robot model IRB 2400

We can go through the procedures to build an IKFast plugin for MoveIt!. It will be useful when we create an IK solver...

Creating the MoveIt! IKFast plugin for the ABB-IRB6640 robot


We have seen the MoveIt! package for the ABB robot IRB 6640 model. But the robot is working using the KDL plugin, which is a default numerical solver. For generating IK solver plugin using IKFast, we can follow the procedure mentioned in this section. At the end of this section, we can run the MoveIt! demo of this robot using our custom moveit-ikfast plugin.

In short, we will build an IKFast MoveIt! plugin for robot ABB -IRB 66400. This plugin can be selected during the MoveIt! setup wizard or we can mention it in the config/kinematics.yaml file of the moveit-config package

Prerequisites for developing the MoveIt! IKFast plugin

The following is the configuration we have used for developing the MoveIt! IKFast plugin:

  • Ubuntu 14.04.3 LTS x86_64 bit

  • ROS-Indigo desktop-full, Version 1.11.13

  • Open-Rave 0.9

OpenRave and IK Fast Module

OpenRave is a set of command line and GUI tools for developing, testing, and deploying motion planning algorithms...

Creating the COLLADA file of a robot to work with OpenRave


In this section, we can discuss how to convert the robot URDF model to the collada file (.dae) format to work with OpenRave. There is a ROS package called collada_urdf, which contains nodes to convert URDF into collada files. The URDF file of ABB-IRB 6640 model is on abb_irb6600_support/urdf folder named irb6640.urdf. Copy this file into your working folder and run the following command for the conversion:

Start roscore
$ roscore

Run the conversion command. We need to mention the URDF file and the output DAE file:

$ rosrun collada_urdf urdf_to_collada irb6640.urdf irb6640.dae

Tip

In most of the cases, this command fails because most of the URDF file contains STL meshes and it may not convert into DAE as we expected. If the robot meshes in, in DAE format, it will work fine. If it happens, follow this procedure:

  • Install Meshlab tool for viewing and editing meshes using the following command:

  • Open meshes present at abb_irb6600_support...

Generating the IKFast CPP file for the IRB 6640 robot


After getting the link info, we can start generating the IK solver CPP file for handling the IK of this robot.

Use the following command to generate the IK solver for the IRB 6640 robot:

$ python `openrave-config --python-dir`/openravepy/_openravepy_/ikfast.py --robot=irb6640.dae --iktype=transform6d --baselink=1 --eelink=8 --savefile=output_ikfast61.cpp

The preceding command generates a CPP file called output_ikfast61.cpp in which the IK type is transform6d, the position of the baselink is 1, and the end effector link is 8. We need to mention the robot DAE file as the robot argument.

We can test this file using the following procedure:

  1. Download the IKFast demo code file from http://kaist-ros-pkg.googlecode.com/svn/trunk/arm_kinematics_tools/src/ikfastdemo/ikfastdemo.cpp.

  2. Also, copy IKFast.h to the current folder. This file is present in the cloned file of OpenRave. We will get this header from openrave/python.

  3. After getting output_ikfast61...

Questions


Here are some common questions that will help you better learn and understand this chapter:

  • What are the main benefits in using ROS-Industrial packages?

  • What are the conventions followed by ROS-I in designing URDF for industrial robots?

  • What is the purpose of ROS's support packages?

  • What is the purpose of ROS's driver packages?

  • Why we need an IKFast plugin for our industrial robot rather than the default KDL plugin?

Summary


In this chapter, we have been discussing a new interface of ROS for industrial robots called ROS-Industrial. We have seen the basic concepts in developing the industrial packages and installed it on Ubuntu. After installation, we have seen the block diagram of this stack and started discussing about developing the URDF model for industrial robots and also about creating the MoveIt! interface for an industrial robot. After discussing a lot on these topics, we have installed some industrial robot packages of universal robots and ABB. We have learned the structure of the MoveIt! package and then shifted to the ROS-Industrial support packages. We have discussed in detail and switched onto concepts such as the industrial robot client and about how to create MoveIt! IKFast plugin. In the end, we have used the developed plugin in the ABB robot.

In the next chapter, we look at the troubleshooting and best practices in ROS software development.

lock icon The rest of the chapter is locked
You have been reading a chapter from
Mastering ROS for Robotics Programming
Published in: Dec 2015 Publisher: Packt ISBN-13: 9781783551798
Register for a free Packt account to unlock a world of extra content!
A free Packt account unlocks extra newsletters, articles, discounted offers, and much more. Start advancing your knowledge today.
Unlock this book and the full library FREE for 7 days
Get unlimited access to 7000+ expert-authored eBooks and videos courses covering every tech area you can think of
Renews at $15.99/month. Cancel anytime}