(!) 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.

Porting Arm Navigation Package from Fuerte to Groovy (Implementation Notes)

Description:

Keywords: Arm Navigation

Tutorial Level: ADVANCED

Overview

There were changes made between Fuerte and Groovy that broke parts of arm navigation. The two big issues are:

  1. Auto generated arm navigation packages (i.e. <robot>_arm_navigation packages) from Fuerte must be modified in order to run in Groovy

  2. The arm navigation wizard in Groovy does not capture these changes (it generates the same package as Fuerte)

Arm navigation is deprecated in Groovy, which may be why these issues exist. Until patches are made, the follow instructions can be used to manually migrate.

Summary of Required Changes

Changes to auto generated <robot>_arm navigation packages are required. Some of these changes refer to a newly created industrial_deprecated package. This package patches issue with the planning environment package. Once the planning environment package is pathced, the industrial deprecated should no longer be needed.

Arm Navigation Stack Patch

NOTE: This patch is not needed if the industrial deprecated package is used. It is kept here just in case the information is required A utility program called faketime.py in the planning environment package must be modified. The packages that it imports is now gone. Here is the patch:

diff -r 757e854b93b9 planning_environment/test/fake_time.py
--- a/planning_environment/test/fake_time.py    Wed Nov 14 19:16:17 2012 -0800
+++ b/planning_environment/test/fake_time.py    Sun Feb 24 23:13:14 2013 -0600
@@ -37,7 +37,7 @@
 This publishes wall clock to the /clock topic to test simulated time routines
 """
 
-import roslib; roslib.load_manifest('test_ros')
+import roslib;
 
 import time
 import rospy

Auto Generated Arm Navigation Package Patch

The following summarizes the changes that were required to migrate an <robot>_arm_navigation package from Fuerte to Groovy. Not all changes were a result of arm navigation deprecation (Rviz config file format changes for example)

Summary

Changes required to run arm navigation under Groovy. NOTE: These changes are updated from the last commit (rev 1125). These new changes make use of the industrial_deprecated package which contains patched launch files and nodes for the planning_scene package. For a detailed diff see this section.

Changes required in order to get arm navigation to work with groovy release. These changes are required for any *_arm_navigation package to be used under groovy. Other packages remain and must be updated, which is why this is so detailed

  1. CMakeLists.txt - Added rosbuild_add_roslaunch_check(launch) unit test in order to catch these problems in the future.
  2. planning_components_visualizer/planning_scene_warehouse_viewer.rviz - updated from vcg to new rviz format. The changes were manually done (there isn't a script to automatically converent). These config files are basically the same regardless of the robot, accept for the fixed frame which could be passed in by rviz command line arg.
  3. planning_components_visualizer.launch
    1. changed "planning_environment_visualization_prerequisites.launch" from planning environment to industrial_deprecated (required until arm_navigation stack is patched)
    2. changed rviz config file from .vcg to .rviz
  4. planning_scene_warehouse_viewer_M16iB20.launch

    1. mongodb node moved to a new
    2. changed package for fake_time.py from planning_environment to industrial_deprecated (required until arm_navigation stack is patched) package and was renamed to a different type.
    3. changed rviz config file from .vcg to .rviz
  5. manifest.xml - updated with missing dependencies (thanks to the new unit test). These dependencies will be needed for any arm_navigation package.

Verification

Use the following steps to veify that the arm navigation packages have been correctly ported. Launch each of the following and verify that there aren't any critical errors and the applicaitons run as expected.

  1. roslaunch <robot>_arm_navigation planning_scene_warehouse_viewer_<robot>.launch

The following are common errors that occur then the porting process has not been done correctly:

  1. [ERROR] [1362411543.461139992]: [registerPublisher] Failed to contact master at [localhost:11311].  Retrying...: This is not an error related to porting. This error is OK and will eventually correct itself.

  2. Rviz comes up blank: This is due to a missing *.rviz configuration file.
  3. Missing/broken faketime.py node: The faketime node has been moved to the industrial_deprecated package.

Example Patch

The following patch was used in ROS-Industrial to migrate the Fanuc M16iB20 robot to Groovy:

Index: /home/sedwards/ros/groovy/ros_industrial_trunk/fanuc/m10iA_arm_navigation/manifest.xml
===================================================================
--- /home/sedwards/ros/groovy/ros_industrial_trunk/fanuc/m10iA_arm_navigation/manifest.xml      (revision 1140)
+++ /home/sedwards/ros/groovy/ros_industrial_trunk/fanuc/m10iA_arm_navigation/manifest.xml      (revision 1159)
@@ -15,6 +15,12 @@
   <depend package="trajectory_filter_server"/>
   <depend package="constraint_aware_spline_smoother"/>
   <depend package="move_arm"/>
+  <depend package="warehouse_ros"/>
+  <depend package="robot_state_publisher"/>
+  <depend package="interpolated_ik_motion_planner"/>
+  <depend package="rviz"/>
+  <depend package="move_arm_warehouse"/>
+  <depend package="industrial_deprecated"/>
 
 </package>
 
Index: /home/sedwards/ros/groovy/ros_industrial_trunk/fanuc/m10iA_arm_navigation/launch/planning_components_visualizer.launch
===================================================================
--- /home/sedwards/ros/groovy/ros_industrial_trunk/fanuc/m10iA_arm_navigation/launch/planning_components_visualizer.launch      (revision 1140)
+++ /home/sedwards/ros/groovy/ros_industrial_trunk/fanuc/m10iA_arm_navigation/launch/planning_components_visualizer.launch      (revision 1159)
@@ -1,10 +1,10 @@
 <launch>
     <include file="$(find m10iA_arm_navigation)/launch/m10iA_planning_environment.launch" />
-    <include file="$(find planning_environment)/launch/planning_environment_visualization_prerequisites.launch" />
+    <include file="$(find industrial_deprecated)/launch/planning_environment_visualization_prerequisites.launch" />
     <include file="$(find m10iA_arm_navigation)/launch/constraint_aware_kinematics.launch" />
     <include file="$(find m10iA_arm_navigation)/launch/ompl_planning.launch" />
     <include file="$(find m10iA_arm_navigation)/launch/trajectory_filter_server.launch" />
-    <node pkg="rviz" type="rviz" name="rviz_planning_components" args="-d $(find m10iA_arm_navigation)/config/planning_components_visualizer.vcg" />
+    <node pkg="rviz" type="rviz" name="rviz_planning_components" args="-d $(find m10iA_arm_navigation)/config/planning_components_visualizer.rviz" />
     <node pkg="move_arm" type="planning_components_visualizer" name="planning_components_visualizer" output="screen" />
     <node pkg="robot_state_publisher" type="state_publisher" name="rob_st_pub" />
 </launch>
Index: /home/sedwards/ros/groovy/ros_industrial_trunk/fanuc/m10iA_arm_navigation/launch/planning_scene_warehouse_viewer_m10iA.launch
===================================================================
--- /home/sedwards/ros/groovy/ros_industrial_trunk/fanuc/m10iA_arm_navigation/launch/planning_scene_warehouse_viewer_m10iA.launch       (revision 1140)
+++ /home/sedwards/ros/groovy/ros_industrial_trunk/fanuc/m10iA_arm_navigation/launch/planning_scene_warehouse_viewer_m10iA.launch       (revision 1159)
@@ -1,11 +1,11 @@
 <launch>
   <param name="/use_sim_time" value="true" />
   <include file="$(find m10iA_arm_navigation)/launch/m10iA_planning_environment.launch" />
-  <node pkg="planning_environment" name="wall_clock_server" type="fake_time.py" />
+  <node pkg="industrial_deprecated" name="wall_clock_server" type="fake_time.py" />
 
   <param name="warehouse_host" value="localhost"/>
   <param name="warehouse_port" value="27020"/>
-  <node name="mongo" type="wrapper.py" pkg="mongodb">
+  <node name="mongo" type="mongo_wrapper_ros.py" pkg="warehouse_ros">
     <param name="overwrite" value="false"/>
     <param name="database_path" value="arm_navigation_dbs/m10iA"/>
   </node>
@@ -31,7 +31,7 @@
     <param name="consistent_angle" type="double" value="1.05"/>
   </node>
 
-  <node pkg="rviz" type="rviz" name='rviz_warehouse_viewer' args="-d $(find m10iA_arm_navigation)/config/planning_scene_warehouse_viewer.vcg" />
+  <node pkg="rviz" type="rviz" name='rviz_warehouse_viewer' args="-d $(find m10iA_arm_navigation)/config/planning_scene_warehouse_viewer.rviz" />
   
   <!-- Called when left arm executes trajectory using controllers -->
   <param name="execute_left_trajectory" value="none" />
Index: /home/sedwards/ros/groovy/ros_industrial_trunk/fanuc/m10iA_arm_navigation/CMakeLists.txt
===================================================================
--- /home/sedwards/ros/groovy/ros_industrial_trunk/fanuc/m10iA_arm_navigation/CMakeLists.txt    (revision 1140)
+++ /home/sedwards/ros/groovy/ros_industrial_trunk/fanuc/m10iA_arm_navigation/CMakeLists.txt    (revision 1159)
@@ -11,6 +11,9 @@
 
 rosbuild_init()
 
+#Add unit test to check roslaunch dependencies.
+rosbuild_add_roslaunch_check(launch)
+
 #set the default path for built executables to the "bin" directory
 set(EXECUTABLE_OUTPUT_PATH ${PROJECT_SOURCE_DIR}/bin)
 #set the default path for built libraries to the "lib" directory

Wiki: Industrial/Tutorials/Port_Arm_Nav_from_Fuerte_to_Groovy (last edited 2013-03-04 17:37:48 by ShaunEdwards)