generate_urdf.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 
00003 # Copyright (C) 2014 Aldebaran Robotics
00004 #
00005 # Licensed under the Apache License, Version 2.0 (the "License");
00006 # you may not use this file except in compliance with the License.
00007 # You may obtain a copy of the License at
00008 #
00009 # http://www.apache.org/licenses/LICENSE-2.0
00010 #
00011 # Unless required by applicable law or agreed to in writing, software
00012 # distributed under the License is distributed on an "AS IS" BASIS,
00013 # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
00014 # See the License for the specific language governing permissions and
00015 # limitations under the License.
00016 #
00017 
00018 # This file takes the official URDF aldebaran files and convert them
00019 # to rep120 compliant urdf files. It also includes the meshes from nao_meshes package
00020 # allowing to display the model in RVIZ
00021 
00022 # authors: Mikael Arguedas [mikael DOT arguedas AT gmail DOT com]
00023 #TODO Get motor information from documentation and generate transmission tags automatically
00024 #TODO Generate automatically gazebo tags for every sensor
00025 #TODO Add toe frames for romeo (not supported yet by NAOqi)
00026 
00027 from __future__ import print_function
00028 import sys
00029 import argparse
00030 from naoqi_tools.urdf import URDF
00031 import copy
00032 import naoqi_tools.gazeboUrdf
00033 import naoqi_tools.urdf as ur
00034 import naoqi_tools.nao_dictionaries as dico
00035 import subprocess
00036 import os
00037 import math
00038 from xml.dom.minidom import Document
00039 
00040 NAO_XACRO_DICO= {
00041 'head':'gaze',
00042 'legs':'sole',
00043 'arms':'gripper',
00044 'torso':'torso',
00045 }
00046 
00047 ROMEO_XACRO_DICO= {
00048 'head':'gaze',
00049 'legs':'sole',
00050 'arms':'gripper',
00051 'torso':'body',
00052 'eyes':'Eye',
00053 }
00054 
00055 PEPPER_XACRO_DICO = {
00056 'head':'Head',
00057 'legs':'base_footprint',
00058 'arms':'gripper',
00059 'torso':'torso',
00060 }
00061 
00062 COLLISION_SUFFIX = '_0.10.stl'
00063 
00064 parser = argparse.ArgumentParser(usage='Load an URDF file')
00065 parser.add_argument('-i','--input', default=None, help='URDF file to load')
00066 parser.add_argument('-r','--REP120', choices=['true','false'], default='true',
00067 help='Rename the links to be REP120 compliant')
00068 parser.add_argument('-x','--xacro', choices=['urdf','robot'],
00069 default='robot', help='Chose robot part to generate. choosing urdf create a single urdf file with the entire robot. robot will OUTPUT a xacro file for every kinematic chain on the robot')
00070 
00071 ####################
00072 ##### FUNCTIONS ####
00073 ####################
00074 
00075 def define_materials():
00076     """
00077     Create a few materials to display geometrical shapes in a given color
00078     """
00079     global robot
00080     robot.add_material(ur.Material('Black',ur.Color(0.1,0.1,0.1,1)))
00081     robot.add_material(ur.Material('LightGrey',ur.Color(0.9,0.9,0.9,1)))
00082     robot.add_material(ur.Material('Grey',ur.Color(0.6,0.6,0.6,1)))
00083     robot.add_material(ur.Material('DarkGrey',ur.Color(0.3,0.3,0.3,1)))
00084 
00085 def REP120_compatibility():
00086     """
00087     Add frames defined by ROS for humanoid robots (REP120): http://www.ros.org/reps/rep-0120.html
00088     """
00089     #TODO Add toe frames for ROMEO (not supported by NAOqi yet)
00090     global robot, NAME, MESH_VERSION, VERSION, LINKS_DICO, OFFSETS_DICO
00091     print("creating and renaming joints & links to comply to REP120")
00092 
00093 
00094     # Rename links
00095     for joint in robot.joints:
00096         if robot.joints[joint].name.endswith('_joint'):
00097             robot.joints[joint].name = robot.joints[joint].name[0:-6]
00098         if robot.joints[joint].name.endswith('_actuator'):
00099             robot.joints[joint].name = robot.joints[joint].name[0:-9]
00100         if robot.joints[joint].mimic is not None:
00101             if robot.joints[joint].mimic.joint_name.endswith('_actuator'):
00102                robot.joints[joint].mimic.joint_name = robot.joints[joint].mimic.joint_name[0:-9]
00103             if robot.joints[joint].mimic.joint_name.endswith('_joint'):
00104                robot.joints[joint].mimic.joint_name = robot.joints[joint].mimic.joint_name[0:-6]
00105         try:
00106             robot.joints[joint].parent = LINKS_DICO[robot.joints[joint].parent]
00107         except KeyError:
00108             pass
00109         try:
00110             robot.joints[joint].child = LINKS_DICO[robot.joints[joint].child]
00111         except KeyError:
00112             pass
00113         for link in robot.links.keys():
00114             try:
00115                 robot.rename_link(link,LINKS_DICO[link])
00116             except KeyError, ValueError:
00117                 pass
00118 
00119     if NAME=='romeo':
00120         robot.add_link(ur.Link('gaze'))
00121         robot.add_joint(ur.Joint('gaze_joint', 'HeadRoll_link',
00122         'gaze', 'fixed', None, ur.Pose((OFFSETS_DICO['CameraLeftEyeOffsetX'],0,OFFSETS_DICO['CameraLeftEyeOffsetZ']),(0,0,0))))
00123         MESH_VERSION = ""
00124 
00125     elif NAME=="nao":
00126         robot.add_link(ur.Link('gaze'))
00127         robot.add_joint(ur.Joint('gaze_joint', 'Head',
00128         'gaze', 'fixed', None, ur.Pose((OFFSETS_DICO['CameraTopV4OffsetX'],0,OFFSETS_DICO['CameraTopV4OffsetZ']),(0,0,0))))
00129         if VERSION == 'V32':
00130             MESH_VERSION = VERSION
00131         elif VERSION == 'V33' or VERSION == 'V40' or VERSION == 'V50':
00132             MESH_VERSION = 'V40'
00133 
00134     elif NAME=="pepper":
00135         MESH_VERSION = VERSION
00136         # add base_footprint frame
00137         robot.add_link(ur.Link('base_footprint'))
00138 
00139         robot.add_joint(ur.Joint('base_footprint_joint', 'Tibia','base_footprint', 'fixed', None, ur.Pose((OFFSETS_DICO['BaseFootprintOffsetX'],OFFSETS_DICO['BaseFootprintOffsetY'],OFFSETS_DICO['BaseFootprintOffsetZ']),(OFFSETS_DICO['BaseFootprintRotX'],OFFSETS_DICO['BaseFootprintRotY'],OFFSETS_DICO['BaseFootprintRotZ']))))
00140 
00141         # rename the laser frames to sensor frames (they are actually not used for computation
00142         laser_links = [ c for c in robot.links.keys() if 'surrounding' in c.lower() ]
00143         for joint in robot.joints.values():
00144             if joint.child in laser_links:
00145                 laser_frame = joint.child
00146                 laser_device_frame = laser_frame[:-5] + 'device_frame'
00147                 # get the old joint to have the device frame as a child
00148                 joint.child = laser_device_frame
00149                 # but also create a joint with the projected frame as a child
00150                 robot.add_link(ur.Link(laser_device_frame))
00151                 joint_new = copy.deepcopy(joint)
00152                 joint_new.name = joint.name[:-17] + 'projected_sensor_fixedjoint'
00153                 joint_new.child = laser_frame
00154                 joint_new.origin.rotation[0] = 0
00155                 joint_new.origin.rotation[1] = 0
00156                 # set it on the ground
00157                 joint_new.origin.position[2] = -0.334
00158                 if 'left' in laser_frame.lower():
00159                     # the following line is a temporary fix that should be fixed upstream
00160                     joint_new.origin.rotation[2] = math.pi/2.0 + 0.1864836732051034
00161                 elif 'right' in laser_frame.lower():
00162                     # the following line is a temporary fix that should be fixed upstream
00163                     joint.origin.position[0] = -0.018
00164                     joint_new.origin.position[0] = -0.018
00165                     # the following line is a temporary fix that should be fixed upstream
00166                     joint_new.origin.rotation[2] = -math.pi/2.0 - 0.1864836732051034
00167                 elif 'front' in laser_frame.lower():
00168                     joint_new.origin.rotation[2] = 0
00169                 robot.add_joint(joint_new)
00170 
00171     # add an optical frame for each robot
00172     camera_frames = [ c for c in robot.links.keys() if 'camera' in c.lower() ]
00173     for camera_frame in camera_frames:
00174         camera_optical_frame = camera_frame[:-6] + '_optical_frame'
00175         robot.add_link(ur.Link(camera_optical_frame))
00176         robot.add_joint(ur.Joint('%s_fixedjoint' % camera_optical_frame, camera_frame, camera_optical_frame, 'fixed', None,
00177                                      ur.Pose((0,0,0),(-math.pi/2.0,0,-math.pi/2.0))))
00178 
00179     # add dummy physics for gazebo simulation
00180     add_dummy_inertia(['Finger','Thumb','gripper','Fsr'])
00181     add_dummy_collision(['Fsr'])
00182 
00183 def add_transmission_tags():
00184     global robot
00185 #TODO create all transmission elements : Cannot get them from the lib for now
00186     """
00187     This function should instanciate all transmission tags :
00188     - hardware interface
00189     - mechanical reduction ratio for each motor
00190     - joint and actuator to which the transmission tag reference
00191     for now naoTransmission.xacro has been done by hand based on the work of Konstantinos Chatzilygeroudis in his nao_dcm project https://github.com/costashatz/nao_dcm
00192     """
00193     return
00194 
00195 def add_gazebo_tags():
00196     global robot
00197 #TODO instantiate plugins according to sensors present in input urdf
00198     """
00199     This function should instanciate all gazebo tags :
00200         - sensor plugins
00201         - mimic joints plugins
00202         - ros_control plugin
00203         - disable_links plugins
00204         - gazebo reference for every link (ok)
00205     for now naoGazebo.xacro has been done by hand based on the work of Konstantinos Chatzilygeroudis in his nao_dcm project https://github.com/costashatz/nao_dcm
00206     """
00207     return
00208 
00209 def add_dummy_inertia(list):
00210     global robot
00211     for string in list:
00212         for link in robot.links:
00213             if robot.links[link].name.find(string) != -1:
00214                 robot.links[link].inertial=ur.Inertial(1.1e-9,0.0,0.0,1.1e-9,
00215                                                        0.0,1.1e-9,2e-06)
00216 
00217 def add_dummy_collision(list):
00218   """
00219   This function add a Box collision tag to every links containing keyword provided in list :
00220   """
00221   global robot
00222   for string in list:
00223     for link in robot.links:
00224       if robot.links[link].name.find(string) != -1:
00225         robot.links[link].collision=ur.Collision(ur.Box([0.01,0.01,0.005]),ur.Pose((0,0,0),(0,0,0)))
00226 
00227 ##################
00228 ##### Meshes #####
00229 ##################
00230 
00231 def create_visual_xacro():
00232     global robot
00233     """
00234     Creates a <ROBOT>_visual_collision.xacro file with xacro macros for visual and collision tags of the urdf.
00235     This function creates xacro macros for visualisation and collisions. It checks if the meshes are on the computer(nao only) and set the 'meshes_installed' property accordingly
00236     """
00237     global OUTPUT
00238     global MESH_VERSION
00239     global NAME
00240     global LINKS_DICO
00241     global VISU_DICO
00242     global OFFSETS_DICO
00243     global MESHPKG
00244     prefix = "insert_visu_"
00245     doc = Document()
00246     root = doc.createElement("robot")
00247     doc.appendChild(root)
00248     root.setAttribute("xmlns:xacro","http://www.ros.org/wiki/xacro")
00249 
00250     cmd = "rospack find "+ NAME + MESHPKG
00251     try:
00252         path_mesh_pkg = subprocess.check_output(cmd, stderr=subprocess.STDOUT, shell=True)[:-1]
00253     except:
00254         print("unable to find "+ NAME + MESHPKG + " package")
00255         sys.exit(0)
00256     # Set Mesh path
00257     if NAME =='nao':
00258         node = ur.short(doc,'xacro:property','name','PI_2')
00259         node.setAttribute('value',str(math.pi/2.0))
00260         root.appendChild(node)
00261         node = ur.short(doc,'xacro:property','name','meshes_installed')
00262 
00263         if os.path.isdir(os.path.join(path_mesh_pkg,'meshes',MESH_VERSION)):
00264             node.setAttribute('value',"true")
00265         else:
00266             node.setAttribute('value',"false")
00267         root.appendChild(node)
00268 
00269     #Insert xacro macro
00270     for link in robot.links:
00271         (tempVisu,tempCol) = adjustMeshPath(path_mesh_pkg,link)
00272         if robot.links[link].visual != None:
00273             robot.links[link].xacro = 'xacro:' + prefix + robot.links[link].name
00274             node = ur.short(doc,'xacro:macro','name', prefix + robot.links[link].name)
00275             if NAME=='nao':
00276             # add xacro condition macro to handle the absence of meshes on the system
00277                 node2 = ur.short(doc,'xacro:unless','value',"${meshes_installed}")
00278                 if tempVisu != None:
00279                     node2.appendChild(tempVisu.to_xml(doc))
00280                 if tempCol != None:
00281                     node2.appendChild(tempCol.to_xml(doc))
00282                 node.appendChild(node2)
00283                 node3 = ur.short(doc,'xacro:if','value',"${meshes_installed}")
00284                 node3.appendChild(robot.links[link].visual.to_xml(doc))
00285                 node3.appendChild(robot.links[link].collision.to_xml(doc))
00286                 node.appendChild(node3)
00287             else:
00288                 node.appendChild(robot.links[link].visual.to_xml(doc))
00289                 node.appendChild(robot.links[link].collision.to_xml(doc))
00290             root.appendChild(node)
00291             robot.links[link].visual = None
00292             robot.links[link].collision = None
00293     filename = OUTPUT[0:OUTPUT.rfind('.')] + '_visual_collisions.xacro'
00294     write_comments_in_xacro(doc, filename)
00295 
00296 
00297 #################################
00298 ######## XACRO FUNCTIONS ########
00299 #################################
00300 
00301 def export_robot_element(element):
00302     """
00303     Browse the 'elements' list of robot instance
00304     and export the ones related to the keyword 'element' given as a parameter
00305 
00306     :param : element, string in ['Transmission','Gazebo','material']
00307 
00308     The output file is <ROBOT>_<element>.xacro
00309     """
00310     global robot, OUTPUT
00311     doc = Document()
00312     root = doc.createElement("robot")
00313     doc.appendChild(root)
00314     root.setAttribute("xmlns:xacro","http://www.ros.org/wiki/xacro")
00315     for i in robot.elements:
00316         try:
00317             if element == 'Transmission':
00318                 if i.name.find(element) != -1:
00319                     root.appendChild(i.to_xml(doc))
00320             elif element == 'Gazebo':
00321                 if i.reference != None:
00322                     root.appendChild(i.to_xml(doc))
00323                 elif i.plugins != []:
00324                     root.appendChild(i.to_xml(doc))
00325             elif element == 'material':
00326                 if type(i) == naoqi_tools.urdf.Material:
00327                     root.appendChild(i.to_xml(doc))
00328         except AttributeError:
00329             pass
00330     filename = OUTPUT[0:OUTPUT.rfind('.')] + '_' + str(element) + '.xacro'
00331     print('exporting ' + element + ' xacro')
00332     write_comments_in_xacro(doc, filename)
00333 
00334 def export_robot_to_xacro_files():
00335     """
00336     Exports the entire 'robot' in several xacro files.
00337     One xacro file per kinematic chain (<ROBOT>_legs.xacro, <ROBOT>_arms.xacro, <ROBOT>_torso.xacro...)
00338     Xacro file for specific parts of the robot (<ROBOT>_fingers.xacro, <ROBOT>_sensors.xacro)
00339     One xacro file for visual elements (<ROBOT>_visual_collision.xacro, <ROBOT>_material.xacro)
00340     One xacro file per type of element needed for gazebo simulation (<ROBOT>_Gazebo.xacro, <ROBOT>_Transmission.xacro)
00341     One generic robot file which includes all the other ones (<ROBOT>_robot.xacro)
00342     """
00343     global robot, OUTPUT, NAME
00344     doc = Document()
00345     root = doc.createElement("robot")
00346     doc.appendChild(root)
00347     root.setAttribute("xmlns:xacro","http://www.ros.org/wiki/xacro")
00348     root.setAttribute("name",robot.name)
00349     root.appendChild(ur.short(doc,'xacro:include','filename', NAME + '_visual_collisions.xacro'))
00350     create_visual_xacro()
00351     for i in XACRO_DICO.keys():
00352         print("exporting " + NAME + '_' + i + '.xacro')
00353         if i.find("eye") != -1:
00354             export_kinematic_chain_to_xacro(i,'HeadRoll_link','HeadRoll_link')
00355         else:
00356             export_kinematic_chain_to_xacro(i)
00357         filenamerobot = NAME + '_' + i + '.xacro'
00358         root.appendChild(ur.short(doc,'xacro:include','filename',filenamerobot))
00359 ## Transmission elements not available from Aldebaran libraries yet
00360 #    export_robot_element('Transmission')
00361 #    root.appendChild(ur.short(doc,'xacro:include','filename', NAME + '_Transmission.xacro'))
00362 ## Gazebo Plugin not available from Aldebaran libraries yet
00363 #    export_robot_element('Gazebo')
00364 #    root.appendChild(ur.short(doc,'xacro:include','filename', NAME + '_Gazebo.xacro'))
00365     root.appendChild(ur.short(doc,'xacro:include','filename', NAME + '_sensors.xacro'))
00366     export_list_to_xacro(['_frame'],OUTPUT[0:OUTPUT.rfind('.')] + '_sensors.xacro')
00367     root.appendChild(ur.short(doc,'xacro:include','filename', NAME + '_fingers.xacro'))
00368     export_list_to_xacro(['Finger','Thumb'],OUTPUT[0:OUTPUT.rfind('.')] + '_fingers.xacro')
00369     if NAME == 'pepper':
00370         root.appendChild(ur.short(doc,'xacro:include','filename', NAME + '_wheels.xacro'))
00371         export_list_to_xacro(['Wheel'],OUTPUT[0:OUTPUT.rfind('.')] + '_wheels.xacro')
00372     if NAME == 'romeo':
00373         root.appendChild(ur.short(doc,'xacro:include','filename', 'romeo_cap.xacro'))
00374 
00375     filename = OUTPUT[0:OUTPUT.rfind('.')]+ '_robot.xacro'
00376     write_comments_in_xacro(doc,filename)
00377     print('output directory : ' + OUTPUT[0:OUTPUT.rfind('/')+1])
00378 
00379 def export_kinematic_chain_to_xacro(keyword,baseChain='base_link',tipRefChain='default'):
00380     """
00381     This function allows to export a specific kinematic chain to a xacro file
00382     :param : keyword, string defining kinematic chains to export (legs,arms,head,torso)
00383     :param : baseChain, string representing the name of the link where the reference chain starts
00384     :param : tipRefChain, string representing the name of the link where the reference chain ends
00385 
00386     """
00387     global robot, OUTPUT
00388     if tipRefChain == 'default':
00389         print("applying torso to end of ref chain")
00390         tipRefChain = XACRO_DICO['torso']
00391     chainRef = robot.get_chain(baseChain,tipRefChain)
00392     print(chainRef)
00393     doc = Document()
00394     root = doc.createElement("robot")
00395     doc.appendChild(root)
00396     root.setAttribute("xmlns:xacro","http://www.ros.org/wiki/xacro")
00397     chainNb =0
00398     try:
00399         chain1 = robot.get_chain(baseChain,'l_' + XACRO_DICO[keyword])
00400         chain2 = robot.get_chain(baseChain,'r_' + XACRO_DICO[keyword])
00401         chainNb=2
00402     except KeyError:
00403         try:
00404             chain1 = robot.get_chain(baseChain,'L' + XACRO_DICO[keyword])
00405             chain2 = robot.get_chain(baseChain,'R' + XACRO_DICO[keyword])
00406             chainNb = 2
00407         except KeyError:
00408             try:
00409                 chain1 = robot.get_chain(baseChain, XACRO_DICO[keyword])
00410                 chainNb = 1
00411             except KeyError:
00412                 print("the chain " + keyword + " cannot be found")
00413 
00414     if chainNb != 0:
00415         duplicate = 0
00416         for i in range(len(chain1)):
00417             for j in range(len(chainRef)):
00418                 if chain1[i] == chainRef[j]:
00419                     duplicate =1
00420             if duplicate == 0 or keyword == 'torso':
00421                 try:
00422                     root.appendChild(robot.links[chain1[i]].to_xml(doc))
00423                 except KeyError:
00424                     try:
00425                         root.appendChild(robot.joints[chain1[i]].to_xml(doc))
00426                     except KeyError:
00427                         print("unknown element" + chain1[i])
00428             else:
00429                 duplicate =0
00430         if chainNb ==2:
00431             for i in range(len(chain2)):
00432                 for j in range(len(chainRef)):
00433                     if chain2[i] == chainRef[j]:
00434                         duplicate =1
00435                 if duplicate == 0:
00436                     try:
00437                         root.appendChild(robot.links[chain2[i]].to_xml(doc))
00438                     except KeyError:
00439                         try:
00440                             root.appendChild(robot.joints[chain2[i]].to_xml(doc))
00441                         except KeyError:
00442                             print("unknown element" + chain2[i])
00443                 else:
00444                     duplicate =0
00445         filename = OUTPUT[0:OUTPUT.rfind('.')] + '_' + keyword + str('.xacro')
00446         write_comments_in_xacro(doc, filename)
00447 
00448 def write_comments_in_xacro(doc,filename):
00449     """
00450     Writes the content of the XML Document doc to a file named filename and add comments at the beginning of the file
00451     :param : doc, minidom Document to write
00452     :param : filename, absolute path of the file to write to
00453     """
00454     if(os.path.isdir(filename[0:filename.rfind('/')+1]) == False):
00455         os.makedirs(filename[0:filename.rfind('/')])
00456 
00457     file = open(filename,'w+')
00458     file.write(doc.toprettyxml())
00459     file.close()
00460     file = open(filename,'r')
00461     firstline, remaining = file.readline(),file.read()
00462     file.close()
00463     file = open(filename,'w')
00464     file.write(firstline)
00465     file.write('<!--******************************************************************\n'\
00466 ' ****** File automatically generated by generate_urdf.py script ******\n'\
00467 ' *********************************************************************-->\n')
00468     file.write(remaining)
00469     file.close()
00470 
00471 def export_list_to_xacro(list, filename):
00472     """
00473     export all links containing a string and its parent joint
00474 
00475     :param : list, list of strings to look for
00476     :param : filename, absolute path of the file to write to
00477     """
00478     global robot, OUTPUT
00479     doc = Document()
00480     root = doc.createElement("robot")
00481     doc.appendChild(root)
00482     root.setAttribute("xmlns:xacro","http://www.ros.org/wiki/xacro")
00483     root.setAttribute("name",robot.name)
00484     print ('exporting '+ os.path.basename(filename))
00485     for string in list:
00486         for link in robot.links:
00487             if robot.links[link].name.find(string) != -1:
00488                 root.appendChild(robot.links[link].to_xml(doc))
00489                 for joint in robot.joints:
00490                     if robot.joints[joint].child==robot.links[link].name:
00491                         root.appendChild(robot.joints[joint].to_xml(doc))
00492     write_comments_in_xacro(doc, filename)
00493 
00494 def adjustMeshPath(path_mesh_pkg,link):
00495     """
00496     Find the path of a mesh according to the link definition.
00497     Set the visual and collision element of the given link
00498     :param : path_mesh_pkg, absolute path of the package where the meshes should be located
00499     :param : link, dictionary key of the link we want to set visual and collision parameters
00500 
00501     :return : tempVisu, Visual element with the NAO visual geometrical shape for people who don't have the meshes
00502     :return : tempCol, Collision element with the NAO collision geometrical shape for people who don't have the meshes
00503     """
00504     global robot, SCALE, MESHPKG, MESH_VERSION
00505     tempVisu = None
00506     tempVisuMesh = None
00507     tempCol = None
00508     tempColMesh = None
00509     if robot.links[link].visual != None:
00510         try:
00511             meshname = str(LINKS_DICO.keys()[list(LINKS_DICO.values()).index(link)])
00512             if meshname.endswith('_link'):
00513                 meshfile = meshname[0:-5]
00514             else:
00515                 meshfile = meshname
00516         except:
00517             meshname = link
00518             meshfile = link
00519             pass
00520         if meshfile.endswith('_link'):
00521             meshfile = meshfile[0:-5]
00522         tempVisuMesh = ur.Visual(ur.Mesh('',(SCALE,SCALE,SCALE)))
00523         tempColMesh = ur.Collision(ur.Mesh('',(SCALE,SCALE,SCALE)))
00524         tempVisuMesh.origin = robot.links[link].visual.origin
00525         tempColMesh.origin = robot.links[link].visual.origin
00526         if os.path.isfile(os.path.join(path_mesh_pkg, 'meshes',MESH_VERSION, robot.links[link].visual.geometry.filename[robot.links[link].visual.geometry.filename.rfind("/")+1:])):
00527             tempVisuMesh.geometry.filename = os.path.join('package://', NAME + MESHPKG , 'meshes' , MESH_VERSION, robot.links[link].visual.geometry.filename[robot.links[link].visual.geometry.filename.rfind("/")+1:])
00528             tempColMesh.geometry.filename = tempVisuMesh.geometry.filename[0:-4] + COLLISION_SUFFIX
00529         else:
00530             tempVisuMesh.geometry.filename =  os.path.join('package://', NAME + MESHPKG , 'meshes' ,MESH_VERSION, meshfile + '.dae')
00531             tempColMesh.geometry.filename = tempVisuMesh.geometry.filename[0:-4] + COLLISION_SUFFIX
00532 
00533         if NAME=='nao':
00534             try:
00535                 tempVisu = ur.Visual(VISU_DICO[meshname], ur.Material('LightGrey'),  dico.Nao_orig[meshname])
00536                 tempCol = ur.Collision(VISU_DICO[meshname], dico.Nao_orig[meshname])
00537             except KeyError:
00538                 tempVisu = None
00539                 tempCol = None
00540         robot.links[link].visual = tempVisuMesh
00541         robot.links[link].collision = tempColMesh
00542     return (tempVisu,tempCol)
00543 
00544 ##############
00545 #### Main ####
00546 ##############
00547 
00548 args = parser.parse_args()
00549 if args.input is None:
00550     robot = URDF.from_parameter_server()
00551 else:
00552     robot = URDF.load_xml_file(args.input)
00553 
00554 if robot.name.find('V')!=-1:
00555     VERSION = robot.name[robot.name.find('V'):]
00556 else:
00557     VERSION = str(args.input)[str(args.input).find("V"):str(args.input).find("V")+3]
00558 
00559 if robot.name.lower().find('nao')!=-1:
00560     NAME ='nao'
00561     try:
00562         import naoqi_tools.nao_dictionaries as dico
00563         print("import nao dictionaries")
00564     except:
00565         print("unable to import nao dictionaries")
00566         sys.exit(0)
00567     LINKS_DICO = dico.Nao_links
00568     VISU_DICO = dico.Nao_visu
00569     OFFSETS_DICO = dico.Nao_offsets
00570     XACRO_DICO = NAO_XACRO_DICO
00571     MESHPKG = "_meshes"
00572     SCALE = 0.1
00573 elif robot.name.lower().find('romeo')!=-1:
00574     NAME ='romeo'
00575     try:
00576         import naoqi_tools.romeo_dictionaries as dico
00577     except:
00578         print("unable to import romeo dictionaries")
00579         sys.exit(0)
00580     LINKS_DICO = dico.Romeo_links
00581     OFFSETS_DICO = dico.Romeo_offsets
00582     VISU_DICO = ''
00583     XACRO_DICO = ROMEO_XACRO_DICO
00584     MESHPKG = "_description"
00585     SCALE = 1
00586 
00587 elif robot.name.lower().find('juliette') or robot.name.lower().find('pepper'):
00588     NAME ='pepper'
00589     try:
00590         import naoqi_tools.pepper_dictionaries as dico
00591     except:
00592         print("unable to import pepper dictionaries")
00593         sys.exit(0)
00594     LINKS_DICO = dico.Pepper_links
00595     OFFSETS_DICO = dico.Pepper_offsets
00596     VISU_DICO = ''
00597     XACRO_DICO = PEPPER_XACRO_DICO
00598     print("PROCESSING PEPPER ROBOT")
00599     MESHPKG = "_meshes"
00600     SCALE = 0.1
00601     VERSION = '1.0'
00602 
00603 for element in robot.elements:
00604     if type(element) == naoqi_tools.urdf.Material:
00605         robot.elements.remove(element)
00606 cmd = "rospack find "+ NAME +"_description"
00607 try:
00608     pathdescription = subprocess.check_output(cmd,
00609     stderr=subprocess.STDOUT, shell=True)[:-1]
00610 except:
00611     print("unable to find "+ NAME + "_description package")
00612     sys.exit(0)
00613 OUTPUT = os.path.join(pathdescription,'urdf', NAME + VERSION +  '_generated_urdf', NAME + '.urdf')
00614 print("processing " + NAME + " (" + VERSION + ") robot's urdf file in " + OUTPUT)
00615 cmd = "rospack find "+ NAME + MESHPKG
00616 try:
00617     path_mesh_pkg = subprocess.check_output(cmd, stderr=subprocess.STDOUT, shell=True)[:-1]
00618 except:
00619     print("unable to find "+ NAME + MESHPKG + " package")
00620     sys.exit(0)
00621 
00622 define_materials()
00623 if args.REP120=='true':
00624     REP120_compatibility()
00625 
00626 for link in robot.links:
00627     adjustMeshPath(path_mesh_pkg,link)
00628 
00629 if args.xacro == 'robot':
00630     export_robot_element('material')
00631     export_robot_to_xacro_files()
00632 elif args.xacro == 'urdf':
00633     robot.write_xml(OUTPUT)
00634 else:
00635     export_kinematic_chain_to_xacro(args.xacro)
00636 


naoqi_tools
Author(s): Mikael Arguedas
autogenerated on Thu Aug 27 2015 14:05:48