Note: This tutorial assumes that you have completed the previous tutorials: Arm Navigation Tutorials, URDFs for Industrial Robots.
(!) 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.

Create an Arm Navigation Package for an Industrial Robot

Description: Walks through the steps of creating an arm naviagation package for an industrial robot. The arm navigation package provides collision aware path planning for the robot.

Keywords: arm_navigation, industrial, manipulator

Tutorial Level: INTERMEDIATE

Tutorial based on IROS 2011 arm navigation tutorial. Clarification on the steps within this tutorial can be found there.

This tutorial gives an overview of the planning components configuration wizard. This wizard generates an arm navigation package for the robot described by the URDF. THE WIZARD SHOULD BE EXECUTED WHENEVER THE URDF CHANGES.

Once you have completed this tutorial you will have a package that enabled interactive motion planning for your robot in simulation and on actual hardware.

Run Arm Navigation Wizard

From a terminal window:

$ roslaunch planning_environment planning_description_configuration_wizard.launch urdf_package:=<robot package> urdf_path:=<urdf path relative to package>

This will launch Rviz which will show a visualization of your URDF. It will also lunch the planning components configuration wizard GUI

Wizard Options

In the wizaru GUI select the following:

  • Mode: Advanced
  • Self-collision sampling density: Very dense

Both of these options are related to collision checking. Because of the dangerous nature of industrial systems, these options are set to their highest fidelity.

Kinematic Chains/Groups

The next step requires you to define kinematic chains and joint groups. See the IROS 2011 tutorial for more description of these two items. For most industrial robotic system, this step requires you to select “kinematic chain” The kinematic chain for your robot should include the robot base link to the tool point. It is helpful, although not required if the tool point is the one that will be most used for positioning the manipulator. As a convention, the chain name for a single arm should be called “manipulator” A dialogue box will appear asking you if you want to add more groups or continue (in the case of a single manipulator, select “Done adding groups”)

Joint Limits

The next step will ask you to verify the upper and lower joint bounds to sample for collisions. These values are taken from the URDF and should be verified to be correct. Care should be taken if ranges smaller than the joints allowable travel are used. This is only suggested when the soft limits of the robot have been adjusted to match the smaller range. ==== Adjacent Link Collisions === The next step generates the list of links that are adjacent and therefore always in collision. Select “Generate List”. Generally the results of this step can be accepted as is, select “Next”. Enabling collision checking of adjacent joints (i.e. joints always in collision) can slow down arm path planning. ==== Links always in collision ==== This step identifies links that aren't adjacent on the chain tree, but none the less are always in collsion. Select “Generate List”. This steps sometimes takes a while. This list should be small or empty. These collisions are ok across fixed joints in the chain tree. If collisions occur across movable joints, this is an indication of something wrong. Select “Next” ==== Links in collision in default state ==== This step identifies the remaining joints that are in collision in the default state (i.e. the zero position). This list should be empty. Select “Next” ==== Links often in collision ==== This step identifies links that are often in collision. For purposes of planning these joints are disabled. Select “Generate List”. This steps sometimes takes a while. This list should be empty. (I cannot think of a good reason why this list should have any items in it, feel free to chime in). Select “Next”

Select “Generate List”. This steps takes a long time (on the order of several hours). The terminal window should show the following log messages. These indicate this step is working.

[ INFO] [1331004878.667414891, 1331004878.666099071]: On iteration 10000
[ INFO] [1331004926.351221934, 1331004926.342298984]: On iteration 20000
.
.

Without knowledge to the contrary the results of this step can be accepted as, select “Next”. Sometimes this step catches link collisions that physically cannot occur. Industrial robots are often designed so that the default manipulator cannot run into itself (when kept within joint limits). This is not the case when an end effector is added to the robot

Generate the package

Select the directory in which you want your arm navigation package to be created. This is generally the stack directory for you robot. Select generate package. This will generate a package called <robot_name>_arm_navigation. The robot_name is taken from the urdf. Exit the wizard.

Arm Warehouse View

In the previous steps that <robot_name>_arm_navigation package was created, which contains the files that describe the robot arm kinematics and geometry. This next step generates launch files that load the arm information into the are warehouse viewer, which allows for interactive motion planning.

Configure the warehouse viewer

Run the following command line:

$ rosrun move_arm_warehouse create_launch_files.py <robot_name>

This command will create the following launch file that can be used to launch the warehouse viewer for a simulated robot, planning_scene_warehouse_viewer_<robot_name>.launch

Warehouse Viewer (Simulation Mode)

Experiment with the warehouse view in the safety of simulation. Run the following command line:

$ roslaunch <robot_name>_arm_navigation planning_scene_warehouse_viewer_<robot_name>.launch

Real Robot Integration

In order perform motion planning with a real platform, small changes are required to the launch file created in the previous step. Copy the launch file from the previous step to: planning_scene_warehouse_viewer_<robot_name>_real.launch

Wiki: Industrial/Create_a_Arm_Nav_Pkg_for_an_Industrial_Robot (last edited 2012-07-01 03:09:28 by ShaunEdwards)