8 from xml.dom.minidom
import parseString
17 if c.nodeType == xml.dom.Node.ELEMENT_NODE:
25 if c.nodeType == xml.dom.Node.ELEMENT_NODE:
31 if len(a.attributes) != len(b.attributes):
32 print(
"Different number of attributes")
34 a_atts = [(a.attributes.item(i).name, a.attributes.item(i).value)
for i
in range(len(a.attributes))]
35 b_atts = [(b.attributes.item(i).name, b.attributes.item(i).value)
for i
in range(len(b.attributes))]
38 for i
in range(len(a_atts)):
39 if a_atts[i][0] != b_atts[i][0]:
40 print(
"Different attribute names: %s and %s" % (a_atts[i][0], b_atts[i][0]))
43 if abs(float(a_atts[i][1]) - float(b_atts[i][1])) > 1.0e-9:
44 print(
"Different attribute values: %s and %s" % (a_atts[i][1], b_atts[i][1]))
47 if a_atts[i][1] != b_atts[i][1]:
48 print(
"Different attribute values: %s and %s" % (a_atts[i][1], b_atts[i][1]))
57 if a.nodeType != b.nodeType:
58 print(
"Different node types: %d and %d" % (a.nodeType, b.nodeType))
60 if a.nodeName != b.nodeName:
61 print(
"Different element names: %s and %s" % (a.nodeName, b.nodeName))
72 if isinstance(a, str):
73 return xml_matches(parseString(a).documentElement, b)
74 if isinstance(b, str):
75 return xml_matches(a, parseString(b).documentElement)
76 if a.nodeType == xml.dom.Node.DOCUMENT_NODE:
78 if b.nodeType == xml.dom.Node.DOCUMENT_NODE:
81 print(
"Match failed:")
82 a.writexml(sys.stdout)
85 b.writexml(sys.stdout)
95 <robot name="myrobot"> 100 <chain base_link="robot_base" tip_link="robot_tip" /> 103 <group_state name="zero" group="body"> 104 <joint name="J1" value="0" /> 105 <joint name="J2" value="0" /> 106 <joint name="J3" value="0" /> 108 <end_effector name="tip_ee" parent_link="tip" group="arm" parent_group="body" /> 109 <end_effector name="othertip_ee" parent_link="othertip" group="arm" /> 110 <virtual_joint name="virtual_joint" type="floating" parent_frame="body_frame" child_link="arm" /> 111 <disable_collisions link1="link1" link2="link3" /> 112 <disable_collisions reason="Adjacent" link1="link1" link2="link2" /> 113 <link_sphere_approximation link="link1" /> 114 <link_sphere_approximation link="link2" > 115 <sphere center="1.0 2.0 3.0" radius="1.0" /> 116 <sphere center="1.0 2.0 4.0" radius="2.0" /> 117 </link_sphere_approximation> 121 <robot name="myrobot"> 126 <chain base_link="robot_base" tip_link="robot_tip"/> 129 <group_state name="zero" group="body"> 130 <joint name="J1" value="0" /> 131 <joint name="J2" value="0" /> 132 <joint name="J3" value="0" /> 134 <end_effector group="arm" name="tip_ee" parent_group="body" parent_link="tip"/> 135 <end_effector name="othertip_ee" parent_link="othertip" group="arm" /> 136 <virtual_joint child_link="arm" name="virtual_joint" parent_frame="body_frame" type="floating" /> 137 <disable_collisions link1="link1" link2="link3" /> 138 <disable_collisions link1="link1" link2="link2" reason="Adjacent" /> 139 <link_sphere_approximation link="link1" /> 140 <link_sphere_approximation link="link2" > 141 <sphere center="1.0 2.0 3.0" radius="1.0" /> 142 <sphere center="1.0 2.0 4.0" radius="2.0" /> 143 </link_sphere_approximation> 146 robot = SRDF.from_xml_string(srdf_data)
147 self.assertTrue(
xml_matches(robot.to_xml_string(),expected))
150 datadir=rospkg.RosPack().get_path(
'srdfdom')+
"/test/res/" 151 stream = open(datadir+
'pr2_desc.1.srdf',
'r') 152 robot = SRDF.from_xml_string(stream.read()) 154 self.assertTrue(len(robot.virtual_joints)==0) 155 self.assertTrue(len(robot.groups)==0) 156 self.assertTrue(len(robot.group_states)==0) 157 self.assertTrue(len(robot.disable_collisionss)==0) 158 self.assertTrue(len(robot.end_effectors)==0) 160 stream = open(datadir+'pr2_desc.2.srdf',
'r') 161 robot = SRDF.from_xml_string(stream.read()) 163 self.assertTrue(len(robot.virtual_joints)==1) 164 self.assertTrue(len(robot.groups)==1) 165 self.assertTrue(len(robot.group_states)==0) 166 self.assertTrue(len(robot.disable_collisionss)==0) 167 self.assertTrue(len(robot.end_effectors)==0) 170 datadir=rospkg.RosPack().get_path(
'srdfdom')+
"/test/res/" 171 stream = open(datadir+
'pr2_desc.3.srdf',
'r') 172 robot = SRDF.from_xml_string(stream.read()) 174 self.assertTrue(len(robot.virtual_joints)==1) 175 self.assertTrue(len(robot.groups)==7) 176 self.assertTrue(len(robot.group_states)==2) 177 self.assertTrue(len(robot.disable_collisionss)==2) 178 self.assertTrue(robot.disable_collisionss[0].reason=="adjacent")
179 self.assertTrue(len(robot.end_effectors)==2)
181 self.assertTrue(robot.virtual_joints[0].name==
"world_joint")
182 self.assertTrue(robot.virtual_joints[0].type==
"planar")
184 for group
in robot.groups:
185 if (group.name ==
"left_arm" or group.name ==
"right_arm" ):
186 self.assertTrue(len(group.chains)==1)
187 if group.name ==
"arms":
188 self.assertTrue(len(group.subgroups)==2)
189 if group.name ==
"base":
190 self.assertTrue(len(group.joints)==1)
191 if (group.name ==
"l_end_effector" or group.name ==
"r_end_effector" ):
192 self.assertTrue(len(group.links)==1)
193 self.assertTrue(len(group.joints)==9)
194 if group.name ==
"whole_body" :
195 self.assertTrue(len(group.joints)==1)
196 self.assertTrue(len(group.subgroups)==2)
199 if robot.group_states[0].group !=
"arms":
202 self.assertTrue(robot.group_states[index].group ==
"arms")
203 self.assertTrue(robot.group_states[index].name ==
"tuck_arms")
204 self.assertTrue(robot.group_states[1-index].group ==
"base")
205 self.assertTrue(robot.group_states[1-index].name ==
"home")
207 v=next((joint.value
for joint
in robot.group_states[index].joints
if joint.name==
"l_shoulder_pan_joint"),
None)
208 self.assertTrue(len(v) == 1)
209 self.assertTrue(v[0] ==0.2)
211 w=next((joint.value
for joint
in robot.group_states[1-index].joints
if joint.name==
"world_joint"),
None)
212 self.assertTrue(len(w) == 3)
213 self.assertTrue(w[0] ==0.4)
214 self.assertTrue(w[1] ==0)
215 self.assertTrue(w[2] ==-1)
217 index = 0
if (robot.end_effectors[0].name[0] ==
'r') else 1 218 self.assertTrue(robot.end_effectors[index].name == 'r_end_effector')
219 self.assertTrue(robot.end_effectors[index].group ==
'r_end_effector')
220 self.assertTrue(robot.end_effectors[index].parent_link ==
'r_wrist_roll_link')
223 if __name__ ==
'__main__':
225 rostest.rosrun(PKG,
'srdf_python_parser_test', TestSRDFParser)
def first_child_element(elt)
def all_attributes_match(a, b)
def test_full_srdf(self)
test valid srdf
def next_sibling_element(elt)
A python unit test for srdf.
def test_complex_srdf(self)
def test_simple_srdf(self)