diff --git a/Migration.md b/Migration.md index aedddd29b..341816cf2 100644 --- a/Migration.md +++ b/Migration.md @@ -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 diff --git a/sdf/1.12/CMakeLists.txt b/sdf/1.12/CMakeLists.txt index 08b4bf240..82d9ebf71 100644 --- a/sdf/1.12/CMakeLists.txt +++ b/sdf/1.12/CMakeLists.txt @@ -26,6 +26,7 @@ set (sdfs imu.sdf inertial.sdf joint.sdf + joint_state.sdf lidar.sdf light.sdf light_state.sdf diff --git a/sdf/1.12/joint_state.sdf b/sdf/1.12/joint_state.sdf new file mode 100644 index 000000000..2b64d832c --- /dev/null +++ b/sdf/1.12/joint_state.sdf @@ -0,0 +1,19 @@ + + + + The joint state element encapsulates variables within a joint that may + change over time, currently limited to the joint angle. + + + + Name of the joint + + + + + Index of the axis. + + + Angle of an axis + + diff --git a/sdf/1.12/light_state.sdf b/sdf/1.12/light_state.sdf index 673efcdb4..54bebb02f 100644 --- a/sdf/1.12/light_state.sdf +++ b/sdf/1.12/light_state.sdf @@ -1,6 +1,9 @@ - - Light state + + + The light state element encapsulates variables within a light that may + change over time, currently limited to its pose. + Name of the light diff --git a/sdf/1.12/link_state.sdf b/sdf/1.12/link_state.sdf index 28fff465d..e59d9e0f1 100644 --- a/sdf/1.12/link_state.sdf +++ b/sdf/1.12/link_state.sdf @@ -1,6 +1,10 @@ - - Link state + + + 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. + Name of the link @@ -27,7 +31,7 @@ - + Collision state diff --git a/sdf/1.12/model_state.sdf b/sdf/1.12/model_state.sdf index 3fd296ff2..cbbbfd0de 100644 --- a/sdf/1.12/model_state.sdf +++ b/sdf/1.12/model_state.sdf @@ -1,28 +1,18 @@ - - Model state + + + 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. + Name of the model - - Joint angle + - - Name of the joint - - - - - Index of the axis. - - - Angle of an axis - - - - + A nested model state element Name of the model. diff --git a/sdf/1.12/state.sdf b/sdf/1.12/state.sdf index 6a13e28bf..30fbd4e42 100644 --- a/sdf/1.12/state.sdf +++ b/sdf/1.12/state.sdf @@ -1,5 +1,12 @@ + + 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. + + Name of the world this state applies to @@ -22,13 +29,14 @@ - A list containing the entire description of entities inserted. + A list containing the entire description of entities inserted into the world. + - A list of names of deleted entities/ + A list of names of entities deleted from the world./ The name of a deleted entity. @@ -38,4 +46,6 @@ + + diff --git a/test/integration/frame.cc b/test/integration/frame.cc index 1ed67cd3a..b080ae5d5 100644 --- a/test/integration/frame.cc +++ b/test/integration/frame.cc @@ -213,18 +213,18 @@ TEST(Frame, StateFrame) sdfStr << "" << "" << "" - << "" + << "" << " " << " 1 0 2 0 0 0" << " " << " 3 3 9 0 0 0" - << " " + << " " << " 111 3 0 0 0 0" - << " " - << "" - << "" + << " " + << "" + << "" << " 99 0 22 0 0 0" - << "" + << "" << "" << "" << ""; @@ -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")); @@ -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("name"), "my_link"); @@ -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")); diff --git a/test/integration/nested_model.cc b/test/integration/nested_model.cc index 0c63cbc43..813d04021 100644 --- a/test/integration/nested_model.cc +++ b/test/integration/nested_model.cc @@ -114,33 +114,33 @@ TEST(NestedModel, State) sdfStr << "" << "" << "" - << "" + << "" << " 0 0 0.5 0 0 0" - << " " + << " " << " 0 0 0.5 0 0 0" << " 0.001 0 0 0 0 0" << " 0 0.006121 0 0.012288 0 0.001751" << " 0 0.006121 0 0 0 0" - << " " - << " " + << " " + << " " << " 1 0 0.5 0 0 0" - << " " + << " " << " 1.25 0 0.5 0 0 0" << " 0 -0.001 0 0 0 0" << " 0 0.000674 0 -0.001268 0 0" << " 0 0.000674 0 0 0 0" - << " " - << " " + << " " + << " " << " 1 1 0.5 0 0 0" - << " " + << " " << " 1.25 1 0.5 0 0 0" << " 0 0 0.001 0 0 0" << " 0 0 0 0 0 0" << " 0 0 0 0 0 0" - << " " - << " " - << " " - << "" + << " " + << " " + << " " + << "" << "" << "" << ""; @@ -154,9 +154,9 @@ 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")); @@ -164,11 +164,12 @@ TEST(NestedModel, State) EXPECT_TRUE(modelStateElem->HasElement("pose")); EXPECT_EQ(modelStateElem->Get("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("name"), "link_00"); EXPECT_TRUE(linkStateElem->HasElement("pose")); @@ -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("name"), "model_01"); EXPECT_TRUE(nestedModelStateElem->HasElement("pose")); EXPECT_EQ(nestedModelStateElem->Get("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("name"), "link_01"); EXPECT_TRUE(nestedLinkStateElem->HasElement("pose")); @@ -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("name"), "model_02"); EXPECT_TRUE(nestedModelStateElem->HasElement("pose")); EXPECT_EQ(nestedModelStateElem->Get("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("name"), "link_02"); EXPECT_TRUE(nestedLinkStateElem->HasElement("pose"));