update_joint_limits.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 
00003 '''
00004  Software License Agreement (MIT License)
00005 
00006  @copyright Copyright (c) 2017 DENSO WAVE INCORPORATED
00007 
00008  Permission is hereby granted, free of charge, to any person obtaining a copy
00009  of this software and associated documentation files (the "Software"), to deal
00010  in the Software without restriction, including without limitation the rights
00011  to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
00012  copies of the Software, and to permit persons to whom the Software is
00013  furnished to do so, subject to the following conditions:
00014 
00015  The above copyright notice and this permission notice shall be included in
00016  all copies or substantial portions of the Software.
00017 
00018  THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
00019  IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
00020  FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
00021  AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
00022  LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
00023  OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
00024  THE SOFTWARE.
00025 '''
00026 
00027 import os
00028 import re
00029 import sys
00030 import rospy
00031 import shutil
00032 import roslib.packages
00033 import xml.etree.ElementTree as ET
00034 
00035 if __name__ == "__main__":
00036     args = sys.argv
00037 
00038     # Check num of arguments
00039     if len(args) < 3:
00040         print("Usage: install_robot_description \"robot name\" \"path of joint_limits.yaml\"")
00041         sys.exit()
00042 
00043     rob_name = args[1]
00044     path_limits = args[2]
00045 
00046     # Check path exists
00047     if not os.path.isfile(path_limits):
00048         print(path_limits + " does not exists")
00049         sys.exit()
00050 
00051     # Get package directory
00052     try:
00053         descs_pkg = roslib.packages.get_pkg_dir("denso_robot_descriptions")
00054         conf_pkg  = roslib.packages.get_pkg_dir("denso_robot_moveit_config")
00055     except roslib.packages.InvalidROSPkgException as e:
00056         print(e)
00057         sys.exit()
00058 
00059     path_desc = descs_pkg + "/" + rob_name + "_description"
00060     if not os.path.isdir(path_desc):
00061         print(rob_name + "_description is not exists")
00062         sys.exit()
00063 
00064     path_urdf = path_desc + "/" + rob_name + ".urdf"
00065     if not os.path.isfile(path_urdf):
00066         print(rob_name + ".urdf is not exists")
00067         sys.exit()
00068 
00069     path_conf = conf_pkg + "/config/" + rob_name + "_config"
00070     if not os.path.isdir(path_conf):
00071         print(rob_name + "_config is not exists")
00072         sys.exit()
00073 
00074     et_urdf = ET.parse(path_urdf)
00075     elem_joints = et_urdf.getroot().findall("joint")
00076 
00077     r_joint = re.compile("(joint_\d+):")
00078     r_has_vel_limit = re.compile("has_velocity_limits:(\w+)")
00079     r_max_vel = re.compile("max_velocity:([\d\.]+)")
00080     
00081     cur_elem = None
00082     new_joint = False
00083     
00084     f_limits = open(path_limits, "r")
00085     line = f_limits.readline()
00086     while line:
00087         m = r_joint.search(line)
00088         if not m == None:
00089             for elem in elem_joints:
00090                 if elem.attrib["name"] == m.group(1):
00091                     cur_elem = elem
00092                     new_joint = True                    
00093                     break
00094 
00095         if new_joint:
00096             m = r_has_vel_limit.search(line)
00097             if (not m == None) and (m.group(1) == "false"):
00098                 cur_elem.find("limit").attrib["velocity"] = "1"
00099                 new_joint = False
00100 
00101         if new_joint:
00102             m = r_max_vel.search(line)
00103             if not m == None:
00104                 cur_elem.find("limit").attrib["velocity"] = m.group(1)
00105                 new_joint = False
00106 
00107         line = f_limits.readline()
00108     f_limits.close()
00109 
00110     # Update urdf file
00111     et_urdf.write(path_urdf)
00112 
00113     # Move joint_limits.yaml
00114     shutil.copy(path_limits, path_conf)
00115     os.remove(path_limits)


denso_robot_bringup
Author(s): DENSO WAVE INCORPORATED
autogenerated on Thu Jun 6 2019 21:00:10