Skip to content

Conversation

k-okada
Copy link
Contributor

@k-okada k-okada commented May 1, 2019

add test to check building robot model using from urdf_parser_py.urdf.Robot class, for example

        robot = urdf.Robot(name = 'test')
        link = urdf.Link(name = 'link',
                         visual = urdf.Visual(geometry = urdf.Cylinder(length = 1, radius = 1),
                                              material = urdf.Material(name = 'mat')))
        robot.add_link(link)

@k-okada k-okada mentioned this pull request May 1, 2019
@k-okada
Copy link
Contributor Author

k-okada commented May 1, 2019

Failing http://build.ros.org/job/Mpr__urdfdom_py__ubuntu_bionic_amd64/11/console is expected, because eaea61f cause regressio on creating robot model with visual and collisions.
When we output URDF from the robot model built with #45 (comment) , it misses visual and collision tags like

<robot name="test">
   <link name="link"/>
</robot>
13:47:31 ======================================================================
13:47:31 FAIL: test_link_material_missing_color_and_texture (test_urdf.TestURDFParser)
13:47:31 ----------------------------------------------------------------------
13:47:31 Traceback (most recent call last):
13:47:31   File "/tmp/ws/src/urdfdom_py/test/test_urdf.py", line 188, in test_link_material_missing_color_and_texture
13:47:31     self.xml_and_compare(robot, xml)
13:47:31   File "/tmp/ws/src/urdfdom_py/test/test_urdf.py", line 38, in xml_and_compare
13:47:31     self.assertTrue(xml_matches(robot_xml, orig_xml))
13:47:31 AssertionError: False is not true
13:47:31 -------------------- >> begin captured stdout << ---------------------
13:47:31 Match failed:
13:47:31 <robot name="test">
13:47:31   <link name="link"/>
13:47:31 </robot>()
13:47:31 ==============================================================================
13:47:31 <robot name="test">
13:47:31   <link name="link">
13:47:31     <visual>
13:47:31       <geometry>
13:47:31         <cylinder length="1" radius="1"/>
13:47:31       </geometry>
13:47:31       <material name="mat"/>
13:47:31     </visual>
13:47:31   </link>
13:47:31 </robot>()

@sloretz
Copy link
Contributor

sloretz commented Mar 9, 2020

It looks these changes are also in #47, so I'll close this.

@sloretz sloretz closed this Mar 9, 2020
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment

Labels

None yet

Projects

None yet

Development

Successfully merging this pull request may close these issues.

2 participants