Skip to content

Commit

Permalink
sdf, urdf: Add/canonicalize xmlns: declarations (#16446)
Browse files Browse the repository at this point in the history
* sdf, urdf: Add/canonicalize xmlns: declarations

Relevant to: #13314

This patch makes it possible to interrogate drake-extended model files
with standard XML tools, which is useful when composing and verifying
documentation.
  • Loading branch information
rpoyner-tri committed Jan 27, 2022
1 parent ed5fdb0 commit 1293f65
Show file tree
Hide file tree
Showing 23 changed files with 23 additions and 23 deletions.
2 changes: 1 addition & 1 deletion bindings/pydrake/multibody/test/hydroelastic.sdf
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
<?xml version="1.0"?>
<sdf version="1.7">
<sdf xmlns:drake="http://drake.mit.edu" version="1.7">
<!--
This is based on the model generated by `ConstructTwoFreeBodiesPlant()`
in `inverse_kinematics_test_utilities.cc`.
Expand Down
2 changes: 1 addition & 1 deletion examples/atlas/urdf/atlas_convex_hull.urdf
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="atlas">
<robot xmlns:drake="http://drake.mit.edu" xmlns:xacro="http://www.ros.org/wiki/xacro" name="atlas">
<link name="l_clav">
<inertial>
<mass value="4.466"/>
Expand Down
2 changes: 1 addition & 1 deletion manipulation/models/franka_description/urdf/panda_arm.urdf
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@
<!-- | This document is a hand edited version of the output autogenerated by xacro | -->
<!-- | from panda_arm.urdf.xacro | -->
<!-- =================================================================================== -->
<robot name="panda">
<robot xmlns:drake="http://drake.mit.edu" name="panda">
<link name="panda_link0">
<inertial>
<mass value="2.92"/>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@
<!-- | This document is a hand edited version of the output autogenerated by xacro | -->
<!-- | from panda_arm_hand.urdf.xacro | -->
<!-- =================================================================================== -->
<robot name="panda">
<robot xmlns:drake="http://drake.mit.edu" name="panda">
<link name="panda_link0">
<inertial>
<mass value="2.92"/>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,7 @@ Later edited by hand to:
* remove damping from the joints
* use pose frame semantics to reflect URDF pose values.
-->
<sdf version="1.7">
<sdf xmlns:drake="http://drake.mit.edu" version="1.7">
<model name="iiwa14">
<link name="iiwa_link_0">
<inertial>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,7 @@ SDF automatically generated with: gz sdf -p ../urdf/iiwa14_polytope_collision.ur
Later edited by hand to rename the base link and remove damping from the joints.
-->
<sdf version="1.7">
<sdf xmlns:drake="http://drake.mit.edu" version="1.7">
<model name="iiwa14">
<link name="iiwa_link_0">
<inertial>
Expand Down
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
<?xml version="1.0"?>
<sdf version="1.6">
<sdf xmlns:drake="http://drake.mit.edu" version="1.6">
<model name="Particle">
<!-- Particle of mass m = 0.5 Kg and zero size.
In Drake we model it as a 6DOF body, with infinite moments of inertia so
Expand Down
2 changes: 1 addition & 1 deletion multibody/parsing/test/detail_scene_graph_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -390,7 +390,7 @@ GTEST_TEST(SceneGraphParserDetail, MakeMeshFromSdfGeometry) {
GTEST_TEST(SceneGraphParserDetail, MakeConvexFromSdfGeometry) {
const std::string absolute_file_path = "path/to/some/mesh.obj";
unique_ptr<sdf::Geometry> sdf_geometry = MakeSdfGeometryFromString(
"<mesh xmlns:drake='drake.mit.edu'>"
"<mesh xmlns:drake='http://drake.mit.edu'>"
" <drake:declare_convex/>"
" <uri>" + absolute_file_path + "</uri>"
" <scale> 3 3 3 </scale>"
Expand Down
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
<?xml version="1.0"?>
<sdf version="1.7">
<sdf xmlns:drake="http://drake.mit.edu" version="1.7">
<model name="test_robot">
<!-- This sdf file defines a simple test robot with multiple links so that
we can test visuals and collisions are properly added to each link.
Expand Down
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
<?xml version="1.0"?>
<robot name="test_robot">
<robot xmlns:drake="http://drake.mit.edu" name="test_robot">
<!-- This urdf file defines a simple test robot with multiple links so that
we can test visuals and collisions are properly added to each link.
Values in <inertial> are not important for this test model since
Expand Down
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
<?xml version="1.0"?>
<sdf version="1.7">
<sdf xmlns:drake="http://drake.mit.edu" version="1.7">
<model name="scoped_model">
<link name="base">
<inertial>
Expand Down
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
<?xml version="1.0"?>
<sdf version="1.7">
<sdf xmlns:drake="http://drake.mit.edu" version="1.7">
<model name="test_robot">
<!-- This sdf file defines a simple test robot with a single link that
contains one collision tag for each supported geometry type. We're
Expand Down
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
<?xml version="1.0"?>
<sdf version="1.7">
<sdf xmlns:drake="http://drake.mit.edu" version="1.7">
<model name="test_robot">
<!-- This sdf file defines a simple test robot with a single link that
contains one visual tag for each supported geometry type. We're
Expand Down
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
<?xml version="1.0"?>
<sdf version='1.7'>
<sdf xmlns:drake="http://drake.mit.edu" version='1.7'>
<model name='collision_filter_group_parsing_test'>
<link name='link1'>
<inertial>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<!--
Defines an SDF model with various types of joints used for testing the parser.
-->
<sdf version="1.7">
<sdf xmlns:drake="http://drake.mit.edu" version="1.7">
<world name="joint_parsing_test_world">
<model name="joint_parsing_test">
<link name="link1">
Expand Down
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
<?xml version="1.0"?>
<robot name="non_conflicting_materials_1">
<robot xmlns:drake="http://drake.mit.edu" name="non_conflicting_materials_1">
<material name="brown">
<color rgba="0.93333333333 0.79607843137 0.67843137254 1"/>
</material>
Expand Down
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
<?xml version="1.0"?>
<robot name="test_robot">
<robot xmlns:drake="http://drake.mit.edu" name="test_robot">
<!-- This urdf file defines a simple test robot with a single link that
contains one collision tag for each supported geometry type. We're
confirming that each geometry declaration produces a corresponding
Expand Down
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
<?xml version="1.0"?>
<robot name="test_robot">
<robot xmlns:drake="http://drake.mit.edu" name="test_robot">
<!-- This urdf file defines a simple test robot with a single link that
contains one collision tag for each supported geometry type. We're
confirming that each geometry declaration produces a corresponding
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<!--
Defines a URDF model with collision filter groups.
-->
<robot xmlns:xacro="http://ros.org/wiki/xacro" name="collision_filter_group_parsing_test">
<robot xmlns:drake="http://drake.mit.edu" xmlns:xacro="http://ros.org/wiki/xacro" name="collision_filter_group_parsing_test">
<link name="link1">
<inertial>
<mass value="1"/>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,7 @@ This URDF contains a single link with, in order:
2) A mesh that is not declared to be either, which should parse into
geometry::Mesh.
-->
<robot xmlns:drake="drake.mit.edu" name="non_conflicting_materials_2">
<robot xmlns:drake="http://drake.mit.edu" name="non_conflicting_materials_2">
<link name="base_link">
<collision>
<geometry>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<!--
Defines a URDF model with various types of joints.
-->
<robot xmlns:xacro="http://ros.org/wiki/xacro" name="joint_parsing_test">
<robot xmlns:drake="http://drake.mit.edu" xmlns:xacro="http://ros.org/wiki/xacro" name="joint_parsing_test">
<link name="link1">
<inertial>
<mass value="1"/>
Expand Down
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://ros.org/wiki/xacro" name="joint_parsing_tag_mismatch_test_1">
<robot xmlns:drake="http://drake.mit.edu" xmlns:xacro="http://ros.org/wiki/xacro" name="joint_parsing_tag_mismatch_test_1">
<link name="link1"/>
<link name="link2"/>
<drake:joint name="fixed_joint" type="fixed">
Expand Down
2 changes: 1 addition & 1 deletion multibody/plant/test/atlas_with_fixed_joints.urdf
Original file line number Diff line number Diff line change
Expand Up @@ -8,7 +8,7 @@
fine after the fix in #13953.
TODO(sherm1) Use the original file plus a patch or in-memory editing
rather than this complete copy (issue #13954). -->
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="atlas">
<robot xmlns:drake="http://drake.mit.edu" xmlns:xacro="http://www.ros.org/wiki/xacro" name="atlas">
<link name="l_clav">
<inertial>
<mass value="4.466"/>
Expand Down

0 comments on commit 1293f65

Please sign in to comment.