Skip to content

Commit

Permalink
Add _state suffix to //state subelements (#1455)
Browse files Browse the repository at this point in the history
Also move definition of //joint_state to its own file
and include joint_state.sdf from model_state.sdf
and state.sdf for //world/joint states.

Signed-off-by: Steve Peters <[email protected]>
  • Loading branch information
scpeters authored Aug 18, 2024
1 parent 6483c25 commit c8c4a6f
Show file tree
Hide file tree
Showing 9 changed files with 111 additions and 64 deletions.
17 changes: 17 additions & 0 deletions Migration.md
Original file line number Diff line number Diff line change
Expand Up @@ -628,6 +628,23 @@ ABI was broken for `sdf::Element`, and restored on version 11.2.1.

## SDFormat specification 1.11 to 1.12

### Modifications

1. **state.sdf**, **model_state.sdf**, **joint_state.sdf**, **link_state.sdf**,
**light_state.sdf**: A `_state` suffix has been added to state element names
to match the `.sdf` file names and for consistency.
+ `//state/light` renamed to `//state/light_state`
+ `//state/model` renamed to `//state/model_state`
+ `//state/model/joint` renamed to `//state/model_state/joint_state`
+ `//state/model/light` renamed to `//state/model_state/light_state`
+ `//state/model/link` renamed to `//state/model_state/link_state`
+ `//state/model/model` renamed to `//state/model_state/model_state`
+ `//state/model/link/collision` renamed to `//state/model_state/link_state/collision_state`

1. **state.sdf**: `//state/joint_state` has been added to represent the state of a
`//world/joint` and `//state/insertions/joint` can represent inserted
`//world/joint` elements.

## SDFormat specification 1.10 to 1.11

### Additions
Expand Down
1 change: 1 addition & 0 deletions sdf/1.12/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -26,6 +26,7 @@ set (sdfs
imu.sdf
inertial.sdf
joint.sdf
joint_state.sdf
lidar.sdf
light.sdf
light_state.sdf
Expand Down
19 changes: 19 additions & 0 deletions sdf/1.12/joint_state.sdf
Original file line number Diff line number Diff line change
@@ -0,0 +1,19 @@
<!-- State information for a joint -->
<element name="joint_state" required="*">
<description>
The joint state element encapsulates variables within a joint that may
change over time, currently limited to the joint angle.
</description>

<attribute name="name" type="string" default="__default__" required="1">
<description>Name of the joint</description>
</attribute>

<element name="angle" type="double" default="0" required="+">
<attribute name="axis" type="unsigned int" default="0" required="1">
<description>Index of the axis.</description>
</attribute>

<description>Angle of an axis</description>
</element>
</element> <!-- End Joint -->
7 changes: 5 additions & 2 deletions sdf/1.12/light_state.sdf
Original file line number Diff line number Diff line change
@@ -1,6 +1,9 @@
<!-- State information for a light -->
<element name="light" required="*">
<description>Light state</description>
<element name="light_state" required="*">
<description>
The light state element encapsulates variables within a light that may
change over time, currently limited to its pose.
</description>

<attribute name="name" type="string" default="__default__" required="1">
<description>Name of the light</description>
Expand Down
10 changes: 7 additions & 3 deletions sdf/1.12/link_state.sdf
Original file line number Diff line number Diff line change
@@ -1,6 +1,10 @@
<!-- State information for a link -->
<element name="link" required="*">
<description>Link state</description>
<element name="link_state" required="*">
<description>
The link state element encapsulates variables within a link that may
change over time, including pose, velocity, acceleration, applied wrench,
and the state of attached collisions.
</description>

<attribute name="name" type="string" default="__default__" required="1">
<description>Name of the link</description>
Expand All @@ -27,7 +31,7 @@
</description>
</element>

<element name="collision" required="*">
<element name="collision_state" required="*">
<description>Collision state</description>

<attribute name="name" type="string" default="__default__" required="1">
Expand Down
26 changes: 8 additions & 18 deletions sdf/1.12/model_state.sdf
Original file line number Diff line number Diff line change
@@ -1,28 +1,18 @@
<!-- State information for a model -->
<element name="model" required="*">
<description>Model state</description>
<element name="model_state" required="*">
<description>
The model state element encapsulates variables within a model that may
change over time, including object poses, the states of its nested models
and links and joints, and changes in model scale.
</description>

<attribute name="name" type="string" default="__default__" required="1">
<description>Name of the model</description>
</attribute>

<element name="joint" required="*">
<description>Joint angle</description>
<include filename="joint_state.sdf" required="*"/>

<attribute name="name" type="string" default="__default__" required="1">
<description>Name of the joint</description>
</attribute>

<element name="angle" type="double" default="0" required="+">
<attribute name="axis" type="unsigned int" default="0" required="1">
<description>Index of the axis.</description>
</attribute>

<description>Angle of an axis</description>
</element>
</element>

<element name="model" ref="model_state" required="*">
<element name="model_state" ref="model_state" required="*">
<description>A nested model state element</description>
<attribute name="name" type="string" default="__default__" required="1">
<description>Name of the model. </description>
Expand Down
14 changes: 12 additions & 2 deletions sdf/1.12/state.sdf
Original file line number Diff line number Diff line change
@@ -1,5 +1,12 @@
<!-- State Info -->
<element name="state" required="*">
<description>
The state element encapsulates variables within a world that may change
over time, including object poses, dynamic states such as velocity and
acceleration, a description of objects added to the world, and a list
of objects deleted from the world.
</description>

<!-- Name of the world this state applies to -->
<attribute name="world_name" type="string" default="__default__" required="1">
<description>Name of the world this state applies to</description>
Expand All @@ -22,13 +29,14 @@
</element>

<element name="insertions" required="0">
<description>A list containing the entire description of entities inserted.</description>
<description>A list containing the entire description of entities inserted into the world.</description>
<include filename="model.sdf" required="+"/>
<include filename="light.sdf" required="+"/>
<include filename="joint.sdf" required="+"/>
</element>

<element name="deletions" required="0">
<description>A list of names of deleted entities/</description>
<description>A list of names of entities deleted from the world./</description>
<element name="name" type="string" default="__default__" required="+">
<description>The name of a deleted entity.</description>
</element>
Expand All @@ -38,4 +46,6 @@

<include filename="light_state.sdf" required="*"/>

<include filename="joint_state.sdf" required="*"/>

</element> <!-- End State -->
24 changes: 12 additions & 12 deletions test/integration/frame.cc
Original file line number Diff line number Diff line change
Expand Up @@ -213,18 +213,18 @@ TEST(Frame, StateFrame)
sdfStr << "<sdf version ='" << SDF_VERSION << "'>"
<< "<world name='default'>"
<< "<state world_name='default'>"
<< "<model name='my_model'>"
<< "<model_state name='my_model'>"
<< " <frame name='mframe'>"
<< " <pose relative_to='/world'>1 0 2 0 0 0</pose>"
<< " </frame>"
<< " <pose relative_to='mframe'>3 3 9 0 0 0</pose>"
<< " <link name='my_link'>"
<< " <link_state name='my_link'>"
<< " <pose relative_to='lframe'>111 3 0 0 0 0</pose>"
<< " </link>"
<< "</model>"
<< "<light name='my_light'>"
<< " </link_state>"
<< "</model_state>"
<< "<light_state name='my_light'>"
<< " <pose relative_to='lframe'>99 0 22 0 0 0</pose>"
<< "</light>"
<< "</light_state>"
<< "</state>"
<< "</world>"
<< "</sdf>";
Expand All @@ -239,8 +239,8 @@ TEST(Frame, StateFrame)
EXPECT_TRUE(worldElem->HasElement("state"));
sdf::ElementPtr stateElem = worldElem->GetElement("state");

EXPECT_TRUE(stateElem->HasElement("model"));
sdf::ElementPtr modelStateElem = stateElem->GetElement("model");
EXPECT_TRUE(stateElem->HasElement("model_state"));
sdf::ElementPtr modelStateElem = stateElem->GetElement("model_state");

// model
EXPECT_TRUE(modelStateElem->HasAttribute("name"));
Expand Down Expand Up @@ -271,8 +271,8 @@ TEST(Frame, StateFrame)
}

// link
EXPECT_TRUE(modelStateElem->HasElement("link"));
sdf::ElementPtr linkStateElem = modelStateElem->GetElement("link");
EXPECT_TRUE(modelStateElem->HasElement("link_state"));
sdf::ElementPtr linkStateElem = modelStateElem->GetElement("link_state");
EXPECT_TRUE(linkStateElem->HasAttribute("name"));
EXPECT_EQ(linkStateElem->Get<std::string>("name"), "my_link");

Expand All @@ -286,8 +286,8 @@ TEST(Frame, StateFrame)
gz::math::Pose3d(111, 3, 0, 0, 0, 0));
}

EXPECT_TRUE(stateElem->HasElement("light"));
sdf::ElementPtr lightStateElem = stateElem->GetElement("light");
EXPECT_TRUE(stateElem->HasElement("light_state"));
sdf::ElementPtr lightStateElem = stateElem->GetElement("light_state");

// light
EXPECT_TRUE(lightStateElem->HasAttribute("name"));
Expand Down
57 changes: 30 additions & 27 deletions test/integration/nested_model.cc
Original file line number Diff line number Diff line change
Expand Up @@ -114,33 +114,33 @@ TEST(NestedModel, State)
sdfStr << "<sdf version ='" << SDF_VERSION << "'>"
<< "<world name='default'>"
<< "<state world_name='default'>"
<< "<model name='model_00'>"
<< "<model_state name='model_00'>"
<< " <pose>0 0 0.5 0 0 0</pose>"
<< " <link name='link_00'>"
<< " <link_state name='link_00'>"
<< " <pose>0 0 0.5 0 0 0</pose>"
<< " <velocity>0.001 0 0 0 0 0</velocity>"
<< " <acceleration>0 0.006121 0 0.012288 0 0.001751</acceleration>"
<< " <wrench>0 0.006121 0 0 0 0</wrench>"
<< " </link>"
<< " <model name='model_01'>"
<< " </link_state>"
<< " <model_state name='model_01'>"
<< " <pose>1 0 0.5 0 0 0</pose>"
<< " <link name='link_01'>"
<< " <link_state name='link_01'>"
<< " <pose>1.25 0 0.5 0 0 0</pose>"
<< " <velocity>0 -0.001 0 0 0 0</velocity>"
<< " <acceleration>0 0.000674 0 -0.001268 0 0</acceleration>"
<< " <wrench>0 0.000674 0 0 0 0</wrench>"
<< " </link>"
<< " <model name='model_02'>"
<< " </link_state>"
<< " <model_state name='model_02'>"
<< " <pose>1 1 0.5 0 0 0</pose>"
<< " <link name='link_02'>"
<< " <link_state name='link_02'>"
<< " <pose>1.25 1 0.5 0 0 0</pose>"
<< " <velocity>0 0 0.001 0 0 0</velocity>"
<< " <acceleration>0 0 0 0 0 0</acceleration>"
<< " <wrench>0 0 0 0 0 0</wrench>"
<< " </link>"
<< " </model>"
<< " </model>"
<< "</model>"
<< " </link_state>"
<< " </model_state>"
<< " </model_state>"
<< "</model_state>"
<< "</state>"
<< "</world>"
<< "</sdf>";
Expand All @@ -154,21 +154,22 @@ TEST(NestedModel, State)
sdf::ElementPtr worldElem = sdfParsed->Root()->GetElement("world");
EXPECT_TRUE(worldElem->HasElement("state"));
sdf::ElementPtr stateElem = worldElem->GetElement("state");
EXPECT_TRUE(stateElem->HasElement("model"));
EXPECT_TRUE(stateElem->HasElement("model_state"));

sdf::ElementPtr modelStateElem = stateElem->GetElement("model");
sdf::ElementPtr modelStateElem = stateElem->GetElement("model_state");

// model sdf
EXPECT_TRUE(modelStateElem->HasAttribute("name"));
EXPECT_EQ(modelStateElem->Get<std::string>("name"), "model_00");
EXPECT_TRUE(modelStateElem->HasElement("pose"));
EXPECT_EQ(modelStateElem->Get<gz::math::Pose3d>("pose"),
gz::math::Pose3d(0, 0, 0.5, 0, 0, 0));
EXPECT_TRUE(!modelStateElem->HasElement("joint"));
EXPECT_FALSE(modelStateElem->HasElement("joint"));
EXPECT_FALSE(modelStateElem->HasElement("joint_state"));

// link sdf
EXPECT_TRUE(modelStateElem->HasElement("link"));
sdf::ElementPtr linkStateElem = modelStateElem->GetElement("link");
EXPECT_TRUE(modelStateElem->HasElement("link_state"));
sdf::ElementPtr linkStateElem = modelStateElem->GetElement("link_state");
EXPECT_TRUE(linkStateElem->HasAttribute("name"));
EXPECT_EQ(linkStateElem->Get<std::string>("name"), "link_00");
EXPECT_TRUE(linkStateElem->HasElement("pose"));
Expand All @@ -185,20 +186,21 @@ TEST(NestedModel, State)
gz::math::Pose3d(0, 0.006121, 0, 0, 0, 0));

// nested model sdf
EXPECT_TRUE(modelStateElem->HasElement("model"));
EXPECT_TRUE(modelStateElem->HasElement("model_state"));
sdf::ElementPtr nestedModelStateElem =
modelStateElem->GetElement("model");
modelStateElem->GetElement("model_state");
EXPECT_TRUE(nestedModelStateElem->HasAttribute("name"));
EXPECT_EQ(nestedModelStateElem->Get<std::string>("name"), "model_01");
EXPECT_TRUE(nestedModelStateElem->HasElement("pose"));
EXPECT_EQ(nestedModelStateElem->Get<gz::math::Pose3d>("pose"),
gz::math::Pose3d(1, 0, 0.5, 0, 0, 0));
EXPECT_TRUE(!nestedModelStateElem->HasElement("joint"));
EXPECT_FALSE(nestedModelStateElem->HasElement("joint"));
EXPECT_FALSE(nestedModelStateElem->HasElement("joint_state"));

// nested model's link sdf
EXPECT_TRUE(nestedModelStateElem->HasElement("link"));
EXPECT_TRUE(nestedModelStateElem->HasElement("link_state"));
sdf::ElementPtr nestedLinkStateElem =
nestedModelStateElem->GetElement("link");
nestedModelStateElem->GetElement("link_state");
EXPECT_TRUE(nestedLinkStateElem->HasAttribute("name"));
EXPECT_EQ(nestedLinkStateElem->Get<std::string>("name"), "link_01");
EXPECT_TRUE(nestedLinkStateElem->HasElement("pose"));
Expand All @@ -215,18 +217,19 @@ TEST(NestedModel, State)
gz::math::Pose3d(0, 0.000674, 0, 0, 0, 0));

// double nested model sdf
EXPECT_TRUE(nestedModelStateElem->HasElement("model"));
nestedModelStateElem = nestedModelStateElem->GetElement("model");
EXPECT_TRUE(nestedModelStateElem->HasElement("model_state"));
nestedModelStateElem = nestedModelStateElem->GetElement("model_state");
EXPECT_TRUE(nestedModelStateElem->HasAttribute("name"));
EXPECT_EQ(nestedModelStateElem->Get<std::string>("name"), "model_02");
EXPECT_TRUE(nestedModelStateElem->HasElement("pose"));
EXPECT_EQ(nestedModelStateElem->Get<gz::math::Pose3d>("pose"),
gz::math::Pose3d(1, 1, 0.5, 0, 0, 0));
EXPECT_TRUE(!nestedModelStateElem->HasElement("joint"));
EXPECT_FALSE(nestedModelStateElem->HasElement("joint"));
EXPECT_FALSE(nestedModelStateElem->HasElement("joint_state"));

// double nested model's link sdf
EXPECT_TRUE(nestedModelStateElem->HasElement("link"));
nestedLinkStateElem = nestedModelStateElem->GetElement("link");
EXPECT_TRUE(nestedModelStateElem->HasElement("link_state"));
nestedLinkStateElem = nestedModelStateElem->GetElement("link_state");
EXPECT_TRUE(nestedLinkStateElem->HasAttribute("name"));
EXPECT_EQ(nestedLinkStateElem->Get<std::string>("name"), "link_02");
EXPECT_TRUE(nestedLinkStateElem->HasElement("pose"));
Expand Down

0 comments on commit c8c4a6f

Please sign in to comment.