4 Software License Agreement (MIT License) 6 @copyright Copyright (c) 2017 DENSO WAVE INCORPORATED 8 Permission is hereby granted, free of charge, to any person obtaining a copy 9 of this software and associated documentation files (the "Software"), to deal 10 in the Software without restriction, including without limitation the rights 11 to use, copy, modify, merge, publish, distribute, sublicense, and/or sell 12 copies of the Software, and to permit persons to whom the Software is 13 furnished to do so, subject to the following conditions: 15 The above copyright notice and this permission notice shall be included in 16 all copies or substantial portions of the Software. 18 THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR 19 IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, 20 FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE 21 AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER 22 LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, 23 OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN 32 import roslib.packages
33 import xml.etree.ElementTree
as ET
35 if __name__ ==
"__main__":
40 print(
"Usage: install_robot_description \"robot name\" \"path of joint_limits.yaml\"")
47 if not os.path.isfile(path_limits):
48 print(path_limits +
" does not exists")
53 descs_pkg = roslib.packages.get_pkg_dir(
"denso_robot_descriptions")
54 conf_pkg = roslib.packages.get_pkg_dir(
"denso_robot_moveit_config")
55 except roslib.packages.InvalidROSPkgException
as e:
59 path_desc = descs_pkg +
"/" + rob_name +
"_description" 60 if not os.path.isdir(path_desc):
61 print(rob_name +
"_description is not exists")
64 path_urdf = path_desc +
"/" + rob_name +
".urdf" 65 if not os.path.isfile(path_urdf):
66 print(rob_name +
".urdf is not exists")
69 path_conf = conf_pkg +
"/config/" + rob_name +
"_config" 70 if not os.path.isdir(path_conf):
71 print(rob_name +
"_config is not exists")
74 et_urdf = ET.parse(path_urdf)
75 elem_joints = et_urdf.getroot().findall(
"joint")
77 r_joint = re.compile(
"(joint_\d+):")
78 r_has_vel_limit = re.compile(
"has_velocity_limits:(\w+)")
79 r_max_vel = re.compile(
"max_velocity:([\d\.]+)")
84 f_limits = open(path_limits,
"r") 85 line = f_limits.readline() 87 m = r_joint.search(line)
89 for elem
in elem_joints:
90 if elem.attrib[
"name"] == m.group(1):
96 m = r_has_vel_limit.search(line)
97 if (
not m ==
None)
and (m.group(1) ==
"false"):
98 cur_elem.find(
"limit").attrib[
"velocity"] =
"1" 102 m = r_max_vel.search(line)
104 cur_elem.find(
"limit").attrib[
"velocity"] = m.group(1)
107 line = f_limits.readline()
111 et_urdf.write(path_urdf)
114 shutil.copy(path_limits, path_conf)
115 os.remove(path_limits)