35 import xml.dom.minidom
38 import sensor_msgs.msg
42 private =
"~%s" % name
43 if rospy.has_param(private):
44 return rospy.get_param(private)
45 elif rospy.has_param(name):
46 return rospy.get_param(name)
53 robot = robot.getElementsByTagName(
'kinematics_model')[0].getElementsByTagName(
'technique_common')[0]
54 for child
in robot.childNodes:
55 if child.nodeType
is child.TEXT_NODE:
57 if child.localName ==
'joint':
58 name = child.getAttribute(
'name')
59 if child.getElementsByTagName(
'revolute'):
60 joint = child.getElementsByTagName(
'revolute')[0]
62 rospy.logwarn(
"Unknown joint type %s", child)
66 limit = joint.getElementsByTagName(
'limits')[0]
67 minval = float(limit.getElementsByTagName(
'min')[0].childNodes[0].nodeValue)
68 maxval = float(limit.getElementsByTagName(
'max')[0].childNodes[0].nodeValue)
73 joint = {
'min':minval*math.pi/180.0,
'max':maxval*math.pi/180.0,
'zero':0,
'position':0,
'velocity':0,
'effort':0}
77 robot = robot.getElementsByTagName(
'robot')[0]
79 for child
in robot.childNodes:
80 if child.nodeType
is child.TEXT_NODE:
82 if child.localName ==
'joint':
83 jtype = child.getAttribute(
'type')
84 if jtype
in [
'fixed',
'floating',
'planar']:
86 name = child.getAttribute(
'name')
88 if jtype ==
'continuous':
93 limit = child.getElementsByTagName(
'limit')[0]
94 minval = float(limit.getAttribute(
'lower'))
95 maxval = float(limit.getAttribute(
'upper'))
97 rospy.logwarn(
"%s is not fixed, nor continuous, but limits are not specified!" % name)
100 safety_tags = child.getElementsByTagName(
'safety_controller')
101 if self.
use_small and len(safety_tags) == 1:
103 if tag.hasAttribute(
'soft_lower_limit'):
104 minval = max(minval, float(tag.getAttribute(
'soft_lower_limit')))
105 if tag.hasAttribute(
'soft_upper_limit'):
106 maxval = min(maxval, float(tag.getAttribute(
'soft_upper_limit')))
108 mimic_tags = child.getElementsByTagName(
'mimic')
109 if self.
use_mimic and len(mimic_tags) == 1:
111 entry = {
'parent': tag.getAttribute(
'joint')}
112 if tag.hasAttribute(
'multiplier'):
113 entry[
'factor'] = float(tag.getAttribute(
'multiplier'))
114 if tag.hasAttribute(
'offset'):
115 entry[
'offset'] = float(tag.getAttribute(
'offset'))
125 if minval > 0
or maxval < 0:
126 zeroval = (maxval + minval)/2
130 joint = {
'min': minval,
'max': maxval,
'zero': zeroval}
132 joint[
'position'] = zeroval
134 joint[
'velocity'] = 0.0
136 joint[
'effort'] = 0.0
138 if jtype ==
'continuous':
139 joint[
'continuous'] =
True
143 description =
get_param(
'robot_description')
144 if description
is None:
145 raise RuntimeError(
'The robot_description parameter is required and not set.')
158 robot = xml.dom.minidom.parseString(description)
159 if robot.getElementsByTagName(
'COLLADA'):
169 source_list =
get_param(
"source_list", [])
171 for source
in source_list:
172 self.
sources.append(rospy.Subscriber(source, sensor_msgs.msg.JointState, self.
source_cb))
174 self.
pub = rospy.Publisher(
'joint_states', sensor_msgs.msg.JointState, queue_size=5)
177 for i
in range(len(msg.name)):
183 position = msg.position[i]
187 velocity = msg.velocity[i]
191 effort = msg.effort[i]
196 if position
is not None:
197 joint[
'position'] = position
198 if velocity
is not None:
199 joint[
'velocity'] = velocity
200 if effort
is not None:
201 joint[
'effort'] = effort
216 while not rospy.is_shutdown():
217 msg = sensor_msgs.msg.JointState()
218 msg.header.stamp = rospy.Time.now()
228 if not has_position
and 'position' in joint:
230 if not has_velocity
and 'velocity' in joint:
232 if not has_effort
and 'effort' in joint:
237 msg.position = num_joints * [0.0]
239 msg.velocity = num_joints * [0.0]
241 msg.effort = num_joints * [0.0]
244 msg.name.append(str(name))
255 parent = param[
'parent']
256 factor = param.get(
'factor', 1)
257 offset = param.get(
'offset', 0)
259 recursive_mimic_chain_joints = [name]
261 if parent
in recursive_mimic_chain_joints:
262 error_message =
"Found an infinite recursive mimic chain"
263 rospy.logerr(
"%s: [%s, %s]", error_message,
', '.join(recursive_mimic_chain_joints), parent)
265 recursive_mimic_chain_joints.append(parent)
267 parent = param[
'parent']
268 offset += factor * param.get(
'offset', 0)
269 factor *= param.get(
'factor', 1)
272 if has_position
and 'position' in joint:
273 msg.position[i] = joint[
'position'] * factor + offset
274 if has_velocity
and 'velocity' in joint:
275 msg.velocity[i] = joint[
'velocity'] * factor
276 if has_effort
and 'effort' in joint:
277 msg.effort[i] = joint[
'effort']
279 if msg.name
or msg.position
or msg.velocity
or msg.effort:
281 self.
pub.publish(msg)
284 except rospy.exceptions.ROSTimeMovedBackwardsException:
289 forward = joint.get(
'forward',
True)
291 joint[
'position'] += delta
292 if joint[
'position'] > joint[
'max']:
293 if joint.get(
'continuous',
False):
294 joint[
'position'] = joint[
'min']
296 joint[
'position'] = joint[
'max']
297 joint[
'forward'] =
not forward
299 joint[
'position'] -= delta
300 if joint[
'position'] < joint[
'min']:
301 joint[
'position'] = joint[
'min']
302 joint[
'forward'] =
not forward