update_joint_limits.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 
3 '''
4  Software License Agreement (MIT License)
5 
6  @copyright Copyright (c) 2017 DENSO WAVE INCORPORATED
7 
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:
14 
15  The above copyright notice and this permission notice shall be included in
16  all copies or substantial portions of the Software.
17 
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
24  THE SOFTWARE.
25 '''
26 
27 import os
28 import re
29 import sys
30 import rospy
31 import shutil
32 import roslib.packages
33 import xml.etree.ElementTree as ET
34 
35 if __name__ == "__main__":
36  args = sys.argv
37 
38  # Check num of arguments
39  if len(args) < 3:
40  print("Usage: install_robot_description \"robot name\" \"path of joint_limits.yaml\"")
41  sys.exit()
42 
43  rob_name = args[1]
44  path_limits = args[2]
45 
46  # Check path exists
47  if not os.path.isfile(path_limits):
48  print(path_limits + " does not exists")
49  sys.exit()
50 
51  # Get package directory
52  try:
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:
56  print(e)
57  sys.exit()
58 
59  path_desc = descs_pkg + "/" + rob_name + "_description"
60  if not os.path.isdir(path_desc):
61  print(rob_name + "_description is not exists")
62  sys.exit()
63 
64  path_urdf = path_desc + "/" + rob_name + ".urdf"
65  if not os.path.isfile(path_urdf):
66  print(rob_name + ".urdf is not exists")
67  sys.exit()
68 
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")
72  sys.exit()
73 
74  et_urdf = ET.parse(path_urdf)
75  elem_joints = et_urdf.getroot().findall("joint")
76 
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\.]+)")
80 
81  cur_elem = None
82  new_joint = False
83 
84  f_limits = open(path_limits, "r")
85  line = f_limits.readline()
86  while line:
87  m = r_joint.search(line)
88  if not m == None:
89  for elem in elem_joints:
90  if elem.attrib["name"] == m.group(1):
91  cur_elem = elem
92  new_joint = True
93  break
94 
95  if new_joint:
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"
99  new_joint = False
100 
101  if new_joint:
102  m = r_max_vel.search(line)
103  if not m == None:
104  cur_elem.find("limit").attrib["velocity"] = m.group(1)
105  new_joint = False
106 
107  line = f_limits.readline()
108  f_limits.close()
109 
110  # Update urdf file
111  et_urdf.write(path_urdf)
112 
113  # Move joint_limits.yaml
114  shutil.copy(path_limits, path_conf)
115  os.remove(path_limits)


denso_robot_bringup
Author(s): DENSO WAVE INCORPORATED
autogenerated on Mon Jun 10 2019 13:12:25