create_ikfast_moveit_plugin.py
Go to the documentation of this file.
00001 #! /usr/bin/env python
00002 '''
00003 IKFast Plugin Generator for MoveIt!
00004 
00005 Creates a kinematics plugin using the output of IKFast from OpenRAVE.
00006 This plugin and the move_group node can be used as a general
00007 kinematics service, from within the moveit planning environment, or in
00008 your own ROS node.
00009 
00010 Author: Dave Coleman, CU Boulder
00011         Based heavily on the arm_kinematic_tools package by Jeremy Zoss, SwRI
00012         and the arm_navigation plugin generator by David Butterworth, KAIST
00013 Date: March 2013
00014 
00015 '''
00016 '''
00017 Copyright (c) 2013, Jeremy Zoss, SwRI
00018 All rights reserved.
00019 
00020 Redistribution and use in source and binary forms, with or without
00021 modification, are permitted provided that the following conditions are met:
00022 
00023 * Redistributions of source code must retain the above copyright
00024 notice, this list of conditions and the following disclaimer.
00025 * Redistributions in binary form must reproduce the above copyright
00026 notice, this list of conditions and the following disclaimer in the
00027 documentation and/or other materials provided with the distribution.
00028 * Neither the name of the Willow Garage, Inc. nor the names of its
00029 contributors may be used to endorse or promote products derived from
00030 this software without specific prior written permission.
00031 
00032 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00033 AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00034 IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00035 ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00036 IABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00037 CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00038 SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00039 INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00040 CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00041 ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00042 POSSIBILITY OF SUCH DAMAGE.
00043 '''
00044 
00045 import glob
00046 import sys
00047 import roslib
00048 import re
00049 import os
00050 import yaml
00051 from lxml import etree
00052 import shutil
00053 
00054 plugin_gen_pkg = 'moveit_kinematics'  # package containing this file
00055 # Allowed search modes, see SEARCH_MODE enum in template file
00056 search_modes = ['OPTIMIZE_MAX_JOINT', 'OPTIMIZE_FREE_JOINT' ]
00057 
00058 if __name__ == '__main__':
00059    # Check input arguments
00060    try:
00061       robot_name = sys.argv[1]
00062       planning_group_name = sys.argv[2]
00063       moveit_plugin_pkg = sys.argv[3]
00064       if len(sys.argv) == 6:
00065          ikfast_output_file = sys.argv[5]
00066          search_mode = sys.argv[4]
00067          if search_mode not in search_modes:
00068             print 'Invalid search mode. Allowed values: ', search_modes
00069             raise Exception()
00070       elif len(sys.argv) == 5:
00071          search_mode = search_modes[0];
00072          print "Warning: The default search has changed from OPTIMIZE_FREE_JOINT to now %s!" % (search_mode)
00073          ikfast_output_file = sys.argv[4]
00074       else:
00075          raise Exception()
00076    except:
00077       print("\nUsage: create_ikfast_plugin.py <yourrobot_name> <planning_group_name> <moveit_plugin_pkg> [<search_mode>] <ikfast_output_path>\n")
00078       sys.exit(-1)
00079    print '\nIKFast Plugin Generator'
00080 
00081    # Setup key package directories
00082    try:
00083       plan_pkg = robot_name + '_moveit_config'
00084       plan_pkg_dir = roslib.packages.get_pkg_dir(plan_pkg)
00085       print 'Loading robot from \''+plan_pkg+'\' package ... '
00086    except:
00087       print '\nERROR: can\'t find package '+plan_pkg+'\n'
00088       sys.exit(-1)
00089    try:
00090       plugin_pkg = moveit_plugin_pkg
00091       plugin_pkg_dir = roslib.packages.get_pkg_dir(plugin_pkg)
00092       print 'Creating plugin in \''+plugin_pkg+'\' package ... '
00093    except:
00094       print '\nERROR: can\'t find package '+plugin_pkg+'\n'
00095       sys.exit(-1)
00096 
00097    # Check for at least 1 planning group
00098    try:
00099       srdf_files = glob.glob(plan_pkg_dir+'/config/*.srdf')
00100       if (len(srdf_files) == 1):
00101          srdf_file_name = srdf_files[0]
00102       else:
00103          srdf_file_name = plan_pkg_dir + '/config/' + robot_name + '.srdf'
00104       srdf = etree.parse(srdf_file_name).getroot()
00105    except:
00106       print("\nERROR: unable to parse robot configuration file\n" + srdf_file_name + "\n")
00107       sys.exit(-1)
00108    try:
00109       if (robot_name != srdf.get('name')):
00110          print '\nERROR: non-matching robot name found in ' + srdf_file_name + '.' \
00111              + '  Expected \'' + robot_name + '\',' + ' found \''+srdf.get('name')+'\''
00112          raise
00113 
00114       groups = srdf.findall('group')
00115       if(len(groups) < 1) : # No groups
00116          raise
00117       if groups[0].get('name') == None: # Group name is blank
00118          raise
00119    except:
00120       print("\nERROR: need at least 1 planning group in robot planning description ")
00121       print srdf_file_name + '\n'
00122       sys.exit(-1)
00123    print '  found ' + str(len(groups)) + ' planning groups: ' \
00124        + ", ".join([g.get('name') for g in groups])
00125 
00126    # Select manipulator arm group
00127    planning_group = None
00128    for g in groups:
00129       foundName  = (g.get('name').lower() == planning_group_name.lower())
00130 
00131       if (foundName):
00132          planning_group = g
00133          break
00134    if planning_group is None:
00135       print '\nERROR: could not find planning group ' + planning_group_name + ' in SRDF.\n'
00136       sys.exit(-1)
00137    print '  found group \'' + planning_group_name + '\''
00138 
00139    # Create src and include folders in target package
00140    plugin_pkg_src_dir = plugin_pkg_dir+'/src/'
00141    plugin_pkg_include_dir = plugin_pkg_dir+'/include/'
00142 
00143    if not os.path.exists(plugin_pkg_src_dir):
00144       os.makedirs(plugin_pkg_src_dir)
00145    if not os.path.exists(plugin_pkg_include_dir):
00146       os.makedirs(plugin_pkg_include_dir)
00147 
00148    # Check for source code generated by IKFast
00149    if not os.path.exists(ikfast_output_file):
00150       print '\nERROR: can\'t find IKFast source code at \'' + \
00151           ikfast_output_file + '\'\n'
00152       print 'Make sure this input argument is correct \n'
00153       sys.exit(-1)
00154 
00155    # Copy the source code generated by IKFast into our src folder
00156    solver_file_name = plugin_pkg_dir+'/src/'+robot_name+'_'+planning_group_name+'_ikfast_solver.cpp'
00157    # Check if they are the same file - if so, skip
00158    skip = False
00159    if os.path.exists(ikfast_output_file) & os.path.exists(solver_file_name):
00160       if os.path.samefile(ikfast_output_file, solver_file_name):
00161          print 'Skipping copying ' + solver_file_name + ' since it is already in the correct location'
00162          skip = True
00163    if not skip:
00164       shutil.copy2(ikfast_output_file,solver_file_name)
00165    # Error check
00166    if not os.path.exists(solver_file_name):
00167       print '\nERROR: Unable to copy IKFast source code from \'' + ikfast_output_file + '\'' + ' to \'' + solver_file_name + '\''
00168       print 'Manually copy the source file generated by IKFast to this location \n'
00169       sys.exit(-1)
00170 
00171    # Detect version of IKFast used to generate solver code
00172    solver_version = 0
00173    with open(solver_file_name,'r') as src:
00174       for line in src:
00175          if line.startswith('/// ikfast version'):
00176             line_search = re.search('ikfast version (.*) generated', line)
00177             if line_search:
00178                solver_version = int(line_search.group(1), 0)
00179             break
00180    print '  found source code generated by IKFast version ' + str(solver_version)
00181 
00182    # Get template folder location
00183    try:
00184       plugin_gen_dir = roslib.packages.get_pkg_dir(plugin_gen_pkg)
00185    except:
00186       print '\nERROR: can\'t find package '+plugin_gen_pkg+' \n'
00187       sys.exit(-1)
00188 
00189    # Chose template depending on IKFast version
00190    if solver_version >= 56:
00191       template_version = 61
00192    else:
00193       print '\nERROR this converter is not made for IKFast 54 or anything but 61'
00194       sys.exit(-1)
00195 
00196    # Check if IKFast header file exists
00197    template_header_file = plugin_gen_dir + '/templates/ikfast.h'
00198    if not os.path.exists(template_header_file):
00199       print '\nERROR: can\'t find ikfast header file at \'' + template_header_file + '\'\n'
00200       sys.exit(-1)
00201 
00202    # Copy the IKFast header file into the include directory
00203    header_file_name = plugin_pkg_dir+'/include/ikfast.h'
00204    shutil.copy2(template_header_file,header_file_name)
00205    if not os.path.exists(header_file_name):
00206       print '\nERROR: Unable to copy IKFast header file from \'' + \
00207           template_header_file + '\'' + ' to \'' + header_file_name + '\' \n'
00208       print 'Manually copy ikfast.h to this location \n'
00209       sys.exit(-1)
00210 
00211    # Check if template exists
00212    template_file_name = plugin_gen_dir + '/templates/ikfast' + str(template_version) + '_moveit_plugin_template.cpp'
00213 
00214    if not os.path.exists(template_file_name):
00215       print '\nERROR: can\'t find template file at \'' + template_file_name + '\'\n'
00216       sys.exit(-1)
00217 
00218    # Create plugin source from template
00219    template_file_data = open(template_file_name, 'r')
00220    template_text = template_file_data.read()
00221    template_text = re.sub('_ROBOT_NAME_', robot_name, template_text)
00222    template_text = re.sub('_GROUP_NAME_', planning_group_name, template_text)
00223    template_text = re.sub('_SEARCH_MODE_', search_mode, template_text)
00224    plugin_file_base = robot_name + '_' + planning_group_name + '_ikfast_moveit_plugin.cpp'
00225 
00226    plugin_file_name = plugin_pkg_dir + '/src/' + plugin_file_base
00227    with open(plugin_file_name,'w') as f:
00228       f.write(template_text)
00229    print '\nCreated plugin file at \'' + plugin_file_name + '\''
00230 
00231    # Create plugin definition .xml file
00232    ik_library_name = robot_name + "_" + planning_group_name + "_moveit_ikfast_plugin"
00233    plugin_name = robot_name + '_' + planning_group_name + \
00234        '_kinematics/IKFastKinematicsPlugin'
00235    plugin_def = etree.Element("library", path="lib/lib"+ik_library_name)
00236    cl = etree.SubElement(plugin_def, "class")
00237    cl.set("name", plugin_name)
00238    cl.set("type", 'ikfast_kinematics_plugin::IKFastKinematicsPlugin')
00239    cl.set("base_class_type", "kinematics::KinematicsBase")
00240    desc = etree.SubElement(cl, "description")
00241    desc.text = 'IKFast'+str(template_version)+' plugin for closed-form kinematics'
00242 
00243    # Write plugin definition to file
00244    def_file_base = ik_library_name + "_description.xml"
00245    def_file_name = plugin_pkg_dir + "/" + def_file_base
00246    with open(def_file_name,'w') as f:
00247       etree.ElementTree(plugin_def).write(f, xml_declaration=True, pretty_print=True)
00248    print '\nCreated plugin definition at: \''+def_file_name+'\''
00249 
00250 
00251 
00252 
00253    # Check if CMakeLists file exists
00254    cmake_template_file = plugin_gen_dir+"/templates/CMakeLists.txt"
00255    if not os.path.exists(cmake_template_file):
00256       print '\nERROR: can\'t find CMakeLists template file at \'' + cmake_template_file + '\'\n'
00257       sys.exit(-1)
00258 
00259    # Create new CMakeLists file
00260    cmake_file = plugin_pkg_dir+'/CMakeLists.txt'
00261 
00262    # Create plugin source from template
00263    template_file_data = open(cmake_template_file, 'r')
00264    template_text = template_file_data.read()
00265    template_text = re.sub('_ROBOT_NAME_', robot_name, template_text)
00266    template_text = re.sub('_GROUP_NAME_', planning_group_name, template_text)
00267    template_text = re.sub('_PACKAGE_NAME_', moveit_plugin_pkg, template_text)
00268    template_text = re.sub('_LIBRARY_NAME_', ik_library_name, template_text)
00269 
00270    with open(cmake_file,'w') as f:
00271       f.write(template_text)
00272    print '\nOverwrote CMakeLists file at \'' + cmake_file + '\''
00273 
00274    # Add plugin export to package manifest
00275    parser = etree.XMLParser(remove_blank_text=True)
00276    package_file_name = plugin_pkg_dir+"/package.xml"
00277    package_xml = etree.parse(package_file_name, parser)
00278 
00279    # Make sure at least all required dependencies are in the depends lists
00280    build_deps = ["liblapack-dev", "moveit_core", "pluginlib", "roscpp", "tf_conversions"]
00281    run_deps   = ["liblapack-dev", "moveit_core", "pluginlib", "roscpp", "tf_conversions"]
00282 
00283    def update_deps(reqd_deps, req_type, e_parent):
00284       curr_deps = [e.text for e in e_parent.findall(req_type)]
00285       missing_deps = set(reqd_deps) - set(curr_deps)
00286       for d in missing_deps:
00287          etree.SubElement(e_parent, req_type).text = d
00288       return missing_deps
00289 
00290    # empty sets evaluate to false
00291    modified_pkg  = update_deps(build_deps, "build_depend", package_xml.getroot())
00292    modified_pkg |= update_deps(run_deps, "run_depend", package_xml.getroot())
00293 
00294    if modified_pkg:
00295       with open(package_file_name,"w") as f:
00296          package_xml.write(f, xml_declaration=True, pretty_print=True)
00297 
00298       print '\nModified package.xml at \''+package_file_name+'\''
00299 
00300    # Check that plugin definition file is in the export list
00301    new_export = etree.Element("moveit_core", \
00302                                  plugin="${prefix}/"+def_file_base)
00303    export_element = package_xml.getroot().find("export")
00304    if export_element == None:
00305       export_element = etree.SubElement(package_xml.getroot(), "export")
00306    found = False
00307    for el in export_element.findall("moveit_core"):
00308       found = (etree.tostring(new_export) == etree.tostring(el))
00309       if found: break
00310 
00311    if not found:
00312       export_element.append(new_export)
00313       with open(package_file_name,"w") as f:
00314          package_xml.write(f, xml_declaration=True, pretty_print=True)
00315       print '\nModified package.xml at \''+package_file_name+'\''
00316 
00317    # Modify kinematics.yaml file
00318    kin_yaml_file_name = plan_pkg_dir+"/config/kinematics.yaml"
00319    with open(kin_yaml_file_name, 'r') as f:
00320       kin_yaml_data = yaml.safe_load(f)
00321    kin_yaml_data[planning_group_name]["kinematics_solver"] = plugin_name
00322    with open(kin_yaml_file_name, 'w') as f:
00323       yaml.dump(kin_yaml_data, f,default_flow_style=False)
00324    print '\nModified kinematics.yaml at ' + kin_yaml_file_name
00325 
00326    # Create a script for easily updating the plugin in the future in case the plugin needs to be updated
00327    easy_script_file_name = "update_ikfast_plugin.sh"
00328    easy_script_file_path = plugin_pkg_dir + "/" + easy_script_file_name
00329    with open(easy_script_file_path,'w') as f:
00330       f.write("rosrun moveit_kinematics create_ikfast_moveit_plugin.py"
00331               + " " + robot_name
00332               + " " + planning_group_name
00333               + " " + plugin_pkg
00334               + " " + solver_file_name )
00335 
00336    print '\nCreated update plugin script at '+easy_script_file_path


moveit_kinematics
Author(s): Dave Coleman , Ioan Sucan , Sachin Chitta
autogenerated on Mon Jul 24 2017 02:21:29