diff --git a/Changelog.md b/Changelog.md index 0d74e90df..211119ff2 100644 --- a/Changelog.md +++ b/Changelog.md @@ -1,6 +1,23 @@ ## libsdformat 15.X -### libsdformat 15.0.0 (2024-09-XX) +### libsdformat 15.0.0 (2024-09-25) + +1. **Baseline:** this includes all changes from 14.5.0 and earlier. + +1. Use colcon for Windows building compilation + * [Pull request #1481](https://github.com/gazebosim/sdformat/pull/1481) + +1. Spec 1.12: link_state, joint_state changes + * [Pull request #1461](https://github.com/gazebosim/sdformat/pull/1461) + +1. Fix symbol checking test when compiled with debug symbols + * [Pull request #1474](https://github.com/gazebosim/sdformat/pull/1474) + +1. README: update badges for sdf15 + * [Pull request #1472](https://github.com/gazebosim/sdformat/pull/1472) + +1. Ionic Changelog + * [Pull request #1471](https://github.com/gazebosim/sdformat/pull/1471) 1. Spec 1.12: add `_state` suffix to //state subelements * [Pull request #1455](https://github.com/gazebosim/sdformat/pull/1455) @@ -27,6 +44,10 @@ 1. Print auto inertial values with `gz sdf --print --expand-auto-inertials` * [Pull request #1422](https://github.com/gazebosim/sdformat/pull/1422) +1. Add cone shape to SDFormat spec + * [Pull request #1418](https://github.com/gazebosim/sdformat/pull/1418) + * [Pull request #1434](https://github.com/gazebosim/sdformat/pull/1434) + 1. Enable 24.04 CI, remove distutils dependency * [Pull request #1408](https://github.com/gazebosim/sdformat/pull/1408) @@ -38,6 +59,11 @@ * [Pull request #1399](https://github.com/gazebosim/sdformat/pull/1399) * [Pull request #1462](https://github.com/gazebosim/sdformat/pull/1462) +1. Spec 1.11+: add `//mesh/@optimization`, `//mesh/convex_decomposition` + * [Pull request #1382](https://github.com/gazebosim/sdformat/pull/1382) + * [Pull request #1386](https://github.com/gazebosim/sdformat/pull/1386) + * [Pull request #1403](https://github.com/gazebosim/sdformat/pull/1403) + 1. Copy 1.11 spec to 1.12 for libsdformat15 * [Pull request #1375](https://github.com/gazebosim/sdformat/pull/1375) diff --git a/Migration.md b/Migration.md index 341816cf2..5d036b71b 100644 --- a/Migration.md +++ b/Migration.md @@ -628,6 +628,33 @@ ABI was broken for `sdf::Element`, and restored on version 11.2.1. ## SDFormat specification 1.11 to 1.12 +### Additions + +1. **joint_state.sdf**: + + `//joint_state/axis_state/position` + + `//joint_state/axis_state/velocity` + + `//joint_state/axis_state/acceleration` + + `//joint_state/axis_state/effort` + + `//joint_state/axis2_state/position` + + `//joint_state/axis2_state/velocity` + + `//joint_state/axis2_state/acceleration` + + `//joint_state/axis2_state/effort` + +1. **link_state.sdf**: + + `//link_state/linear_velocity` + + `//link_state/angular_velocity` + + `//link_state/linear_acceleration` + + `//link_state/angular_acceleration` + + `//link_state/force` + + `//link_state/torque` + +1. **model.sdf**: + + `//model/model_state` + + `//model/include/model_state` + +1. **world.sdf**: + + `//world/include/model_state` + ### Modifications 1. **state.sdf**, **model_state.sdf**, **joint_state.sdf**, **link_state.sdf**, @@ -645,6 +672,20 @@ ABI was broken for `sdf::Element`, and restored on version 11.2.1. `//world/joint` and `//state/insertions/joint` can represent inserted `//world/joint` elements. +### Deprecations + +1. **joint_state.sdf**: + + `//joint_state/angle` is deprecated in favor of `//joint_state/axis_state/position` + and `//joint_state/axis2_state/position`. + +1. **link_state.sdf**: + + `//link_state/velocity` is deprecated in favor of `//link_state/angular_velocity` + and `//link_state/linear_velocity`. + + `//link_state/acceleration` is deprecated in favor of `//link_state/angular_acceleration` + and `//link_state/linear_acceleration`. + + `//link_state/wrench` is deprecated in favor of `//link_state/torque` + and `//link_state/force`. + ## SDFormat specification 1.10 to 1.11 ### Additions diff --git a/README.md b/README.md index 373f69fee..299292297 100644 --- a/README.md +++ b/README.md @@ -11,7 +11,7 @@ Note: The branch name in the codecov URL & library version should be updated whe Build | Status -- | -- Test coverage | [![codecov](https://codecov.io/gh/gazebosim/sdformat/tree/main/graph/badge.svg)](https://codecov.io/gh/gazebosim/sdformat/tree/main) -Ubuntu Jammy | [![Build Status](https://build.osrfoundation.org/buildStatus/icon?job=sdformat-ci-main-jammy-amd64)](https://build.osrfoundation.org/job/sdformat-ci-main-jammy-amd64) +Ubuntu Jammy | [![Build Status](https://build.osrfoundation.org/buildStatus/icon?job=sdformat-ci-main-noble-amd64)](https://build.osrfoundation.org/job/sdformat-ci-main-noble-amd64) Homebrew | [![Build Status](https://build.osrfoundation.org/buildStatus/icon?job=sdformat-ci-main-homebrew-amd64)](https://build.osrfoundation.org/job/sdformat-ci-main-homebrew-amd64) Windows | [![Build Status](https://build.osrfoundation.org/buildStatus/icon?job=sdformat-main-win)](https://build.osrfoundation.org/job/sdformat-main-win) @@ -66,7 +66,7 @@ sudo apt-get update sudo apt install libsdformat<#>-dev libsdformat<#> ``` -Be sure to replace `<#>` with a number value, such as 2 or 3, depending on +Be sure to replace `<#>` with a number value, such as 14 or 15, depending on which version you need, or leave it empty for version 1. ### macOS @@ -82,7 +82,7 @@ Install sdformat: brew install sdformat<#> ``` -Be sure to replace `<#>` with a number value, such as 1 or 2, depending on +Be sure to replace `<#>` with a number value, such as 14 or 15, depending on which version you need. ### Windows @@ -126,7 +126,7 @@ Clone the repository ```sh git clone https://github.com/gazebosim/sdformat -b sdf<#> ``` -Be sure to replace `<#>` with a number value, such as 1 or 2, depending on +Be sure to replace `<#>` with a number value, such as 14 or 15, depending on which version you need. ### Build from Source @@ -168,7 +168,7 @@ Clone the repository ```sh git clone https://github.com/gazebosim/sdformat -b sdf<#> ``` -Be sure to replace `<#>` with a number value, such as 1 or 2, depending on +Be sure to replace `<#>` with a number value, such as 14 or 15, depending on which version you need. Install dependencies @@ -213,34 +213,37 @@ conda activate gz-ws Install prerequisites: ``` -conda install tinyxml2 urdfdom --channel conda-forge +conda install cmake git vcstool colcon-common-extensions ^ +tinyxml2 urdfdom pybind11 -channel conda-forge ``` -Install Gazebo dependencies: +### Getting the sources and building from Source -You can view lists of dependencies: -``` -conda search libsdformat --channel conda-forge --info -``` +Be sure to replace `<#>` with a number value, such as 14 or 15, depending on +which version you need. + +1. Getting the sources -Install dependencies, replacing `<#>` with the desired versions: ``` -conda install libgz-cmake<#> libgz-math<#> libgz-tools<#> libgz-utils<#> --channel conda-forge +mkdir ws\src +cd ws +vcs import src --input https://raw.githubusercontent.com/gazebo-tooling/gazebodistro/master/sdformat<#>.yaml ``` -### Build from Source +2. Build from source -This assumes you have created and activated a Conda environment while installing the Prerequisites. +Note: the Gazebo library dependencies are going to be compiled from source +with sdformat although it should be possible to install them from +conda-forge on stable Gazebo releases using the standard conda install +command. -1. Configure and build - ``` - mkdir build - cd build - cmake .. -DBUILD_TESTING=OFF # Optionally, -DCMAKE_INSTALL_PREFIX=path\to\install - cmake --build . --config Release - ``` +Build the gazebo libraries needed as dependencies (skip testing to speed up the compilation) +using the [colcon](https://colcon.readthedocs.io/en/released/) tool: +``` + colcon build --cmake-args -DBUILD_TESTING=OFF --merge-install --packages-skip sdformat<#> +``` -2. Install - ``` - cmake --install . --config Release - ``` +Build sdformat with its test suite: +``` + colcon build --cmake-args -DBUILD_TESTING=ON --merge-install --packages-select sdformat<#> +``` diff --git a/sdf/1.12/joint_state.sdf b/sdf/1.12/joint_state.sdf index 2b64d832c..096b56965 100644 --- a/sdf/1.12/joint_state.sdf +++ b/sdf/1.12/joint_state.sdf @@ -9,11 +9,125 @@ Name of the joint - + Index of the axis. Angle of an axis + + + + Contains the state of the first joint axis. + + + + The position of the first joint axis. + + + + If this is a rotational axis and this attribute is true, + the joint position is expressed in units of degrees [deg], + otherwise it is expressed in radians [rad]. + If this axis is translational (such as a prismatic joint), the + units will be interpreted in meters [m] regardless of the value of + this attribute. + + + + + + The velocity of the first joint axis. + + + + If this is a rotational axis and this attribute is true, + the joint velocity is expressed in units of degrees per + second [deg/s], otherwise it is expressed in radians per second + [rad/s]. + If this axis is translational (such as a prismatic joint), the + units will be interpreted in meters per second [m/s] regardless of + the value of this attribute. + + + + + + The acceleration of the first joint axis. + + + + If this is a rotational axis and this attribute is true, + the joint acceleration is expressed in units of degrees per + second per second [deg/s^2], otherwise it is expressed in radians per + second per second [rad/s^2]. + If this axis is translational (such as a prismatic joint), the + units will be interpreted in meters per second per second [m/s^2] + regardless of the value of this attribute. + + + + + + The effort applied at the first joint axis. + + + + + + Contains the state of the second joint axis. + + + + The position of the second joint axis. + + + + If this is a rotational axis and this attribute is true, + the joint position is expressed in units of degrees [deg], + otherwise it is expressed in radians [rad]. + If this axis is translational (such as a prismatic joint), the + units will be interpreted in meters [m] regardless of the value of + this attribute. + + + + + + The velocity of the second joint axis. + + + + If this is a rotational axis and this attribute is true, + the joint velocity is expressed in units of degrees per + second [deg/s], otherwise it is expressed in radians per second + [rad/s]. + If this axis is translational (such as a prismatic joint), the + units will be interpreted in meters per second [m/s] regardless of + the value of this attribute. + + + + + + The acceleration of the second joint axis. + + + + If this is a rotational axis and this attribute is true, + the joint acceleration is expressed in units of degrees per + second per second [deg/s^2], otherwise it is expressed in radians per + second per second [rad/s^2]. + If this axis is translational (such as a prismatic joint), the + units will be interpreted in meters per second per second [m/s^2] + regardless of the value of this attribute. + + + + + + The effort applied at the second joint axis. + + diff --git a/sdf/1.12/link_state.sdf b/sdf/1.12/link_state.sdf index e59d9e0f1..d086e4856 100644 --- a/sdf/1.12/link_state.sdf +++ b/sdf/1.12/link_state.sdf @@ -10,21 +10,69 @@ Name of the link - + + Angular velocity of the link frame relative to the world frame. + + + + + If true, the angular velocity is expressed in units of degrees per + second [deg/s], otherwise it is expressed in radians per second [rad/s]. + + + + + + Linear velocity of the link frame relative to the world frame. + + + + Velocity of the link. The x, y, z components of the pose correspond to the linear velocity of the link, and the roll, pitch, yaw components correspond to the angular velocity of the link - + + + Angular acceleration of the link frame relative to the world frame. + + + + + If true, the angular acceleration is expressed in units of degrees per + second per second [deg/s^2], otherwise it is expressed in radians per + second per second [rad/s^2]. + + + + + + + Linear acceleration of the link frame relative to the world frame. + + + + Acceleration of the link. The x, y, z components of the pose correspond to the linear acceleration of the link, and the roll, pitch, yaw components correspond to the angular acceleration of the link - + + Torque acting on the link relative to the world frame. + + + + + + Force acting on the link at the link frame relative to the world frame. + + + + Force and torque applied to the link. The x, y, z components of the pose correspond to the force applied to the link, and the roll, pitch, yaw components correspond to the torque applied to the link diff --git a/sdf/1.12/model.sdf b/sdf/1.12/model.sdf index 57dc83a01..de8b43130 100644 --- a/sdf/1.12/model.sdf +++ b/sdf/1.12/model.sdf @@ -62,6 +62,7 @@ URI to a resource, such as a model + @@ -85,6 +86,8 @@ + + If set to true, all links in the model will be affected by the wind. Can be overriden by the link wind property. diff --git a/sdf/1.12/world.sdf b/sdf/1.12/world.sdf index 6235e193b..d39ad8819 100644 --- a/sdf/1.12/world.sdf +++ b/sdf/1.12/world.sdf @@ -40,6 +40,7 @@ Override the static value of the included entity. + diff --git a/test/integration/nested_model.cc b/test/integration/nested_model.cc index 813d04021..54859c95e 100644 --- a/test/integration/nested_model.cc +++ b/test/integration/nested_model.cc @@ -118,25 +118,34 @@ TEST(NestedModel, State) << " 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" + << " 0.001 0 0" + << " -0.1 5.0 -0.1" + << " 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" + << " 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" + << " 0 0 0.001" + << " 0 0 0" + << " 0 0 0" + << " 0 0 0" + << " 0 0 0" + << " 0 0 0" << " " << " " << " " @@ -175,15 +184,27 @@ TEST(NestedModel, State) EXPECT_TRUE(linkStateElem->HasElement("pose")); EXPECT_EQ(linkStateElem->Get("pose"), gz::math::Pose3d(0, 0, 0.5, 0, 0, 0)); - EXPECT_TRUE(linkStateElem->HasElement("velocity")); - EXPECT_EQ(linkStateElem->Get("velocity"), - gz::math::Pose3d(0.001, 0, 0, 0, 0, 0)); - EXPECT_TRUE(linkStateElem->HasElement("acceleration")); - EXPECT_EQ(linkStateElem->Get("acceleration"), - gz::math::Pose3d(0, 0.006121, 0, 0.012288, 0, 0.001751)); - EXPECT_TRUE(linkStateElem->HasElement("wrench")); - EXPECT_EQ(linkStateElem->Get("wrench"), - gz::math::Pose3d(0, 0.006121, 0, 0, 0, 0)); + EXPECT_FALSE(linkStateElem->HasElement("velocity")); + EXPECT_TRUE(linkStateElem->HasElement("angular_velocity")); + EXPECT_TRUE(linkStateElem->HasElement("linear_velocity")); + EXPECT_EQ(linkStateElem->Get("linear_velocity"), + gz::math::Vector3d(0.001, 0, 0)); + EXPECT_EQ(linkStateElem->Get("angular_velocity"), + gz::math::Vector3d(-0.1, 5.0, -0.1)); + EXPECT_FALSE(linkStateElem->HasElement("acceleration")); + EXPECT_TRUE(linkStateElem->HasElement("angular_acceleration")); + EXPECT_TRUE(linkStateElem->HasElement("linear_acceleration")); + EXPECT_EQ(linkStateElem->Get("linear_acceleration"), + gz::math::Vector3d(0, 0.006121, 0)); + EXPECT_EQ(linkStateElem->Get("angular_acceleration"), + gz::math::Vector3d(0.012288, 0, 0.001751)); + EXPECT_FALSE(linkStateElem->HasElement("wrench")); + EXPECT_TRUE(linkStateElem->HasElement("torque")); + EXPECT_TRUE(linkStateElem->HasElement("force")); + EXPECT_EQ(linkStateElem->Get("force"), + gz::math::Vector3d(0, 0.006121, 0)); + EXPECT_EQ(linkStateElem->Get("torque"), + gz::math::Vector3d(0, 0, 0)); // nested model sdf EXPECT_TRUE(modelStateElem->HasElement("model_state")); @@ -206,15 +227,29 @@ TEST(NestedModel, State) EXPECT_TRUE(nestedLinkStateElem->HasElement("pose")); EXPECT_EQ(nestedLinkStateElem->Get("pose"), gz::math::Pose3d(1.25, 0, 0.5, 0, 0, 0)); - EXPECT_TRUE(nestedLinkStateElem->HasElement("velocity")); - EXPECT_EQ(nestedLinkStateElem->Get("velocity"), - gz::math::Pose3d(0, -0.001, 0, 0, 0, 0)); - EXPECT_TRUE(nestedLinkStateElem->HasElement("acceleration")); - EXPECT_EQ(nestedLinkStateElem->Get("acceleration"), - gz::math::Pose3d(0, 0.000674, 0, -0.001268, 0, 0)); - EXPECT_TRUE(nestedLinkStateElem->HasElement("wrench")); - EXPECT_EQ(nestedLinkStateElem->Get("wrench"), - gz::math::Pose3d(0, 0.000674, 0, 0, 0, 0)); + EXPECT_FALSE(nestedLinkStateElem->HasElement("velocity")); + EXPECT_TRUE(nestedLinkStateElem->HasElement("angular_velocity")); + EXPECT_TRUE(nestedLinkStateElem->HasElement("linear_velocity")); + EXPECT_EQ(nestedLinkStateElem->Get("linear_velocity"), + gz::math::Vector3d(0, -0.001, 0)); + EXPECT_EQ(nestedLinkStateElem->Get("angular_velocity"), + gz::math::Vector3d(0, 0, 0)); + EXPECT_FALSE(nestedLinkStateElem->HasElement("acceleration")); + EXPECT_TRUE(nestedLinkStateElem->HasElement("angular_acceleration")); + EXPECT_TRUE(nestedLinkStateElem->HasElement("linear_acceleration")); + EXPECT_EQ( + nestedLinkStateElem->Get("linear_acceleration"), + gz::math::Vector3d(0, 0.000674, 0)); + EXPECT_EQ( + nestedLinkStateElem->Get("angular_acceleration"), + gz::math::Vector3d(-0.001268, 0, 0)); + EXPECT_FALSE(nestedLinkStateElem->HasElement("wrench")); + EXPECT_TRUE(nestedLinkStateElem->HasElement("torque")); + EXPECT_TRUE(nestedLinkStateElem->HasElement("force")); + EXPECT_EQ(nestedLinkStateElem->Get("force"), + gz::math::Vector3d(0, 0.000674, 0)); + EXPECT_EQ(nestedLinkStateElem->Get("torque"), + gz::math::Vector3d(0, 0, 0)); // double nested model sdf EXPECT_TRUE(nestedModelStateElem->HasElement("model_state")); @@ -235,15 +270,29 @@ TEST(NestedModel, State) EXPECT_TRUE(nestedLinkStateElem->HasElement("pose")); EXPECT_EQ(nestedLinkStateElem->Get("pose"), gz::math::Pose3d(1.25, 1, 0.5, 0, 0, 0)); - EXPECT_TRUE(nestedLinkStateElem->HasElement("velocity")); - EXPECT_EQ(nestedLinkStateElem->Get("velocity"), - gz::math::Pose3d(0, 0, 0.001, 0, 0, 0)); - EXPECT_TRUE(nestedLinkStateElem->HasElement("acceleration")); - EXPECT_EQ(nestedLinkStateElem->Get("acceleration"), - gz::math::Pose3d(0, 0, 0, 0, 0, 0)); - EXPECT_TRUE(nestedLinkStateElem->HasElement("wrench")); - EXPECT_EQ(nestedLinkStateElem->Get("wrench"), - gz::math::Pose3d(0, 0, 0, 0, 0, 0)); + EXPECT_FALSE(nestedLinkStateElem->HasElement("velocity")); + EXPECT_TRUE(nestedLinkStateElem->HasElement("angular_velocity")); + EXPECT_TRUE(nestedLinkStateElem->HasElement("linear_velocity")); + EXPECT_EQ(nestedLinkStateElem->Get("linear_velocity"), + gz::math::Vector3d(0, 0, 0.001)); + EXPECT_EQ(nestedLinkStateElem->Get("angular_velocity"), + gz::math::Vector3d(0, 0, 0)); + EXPECT_FALSE(nestedLinkStateElem->HasElement("acceleration")); + EXPECT_TRUE(nestedLinkStateElem->HasElement("angular_acceleration")); + EXPECT_TRUE(nestedLinkStateElem->HasElement("linear_acceleration")); + EXPECT_EQ( + nestedLinkStateElem->Get("linear_acceleration"), + gz::math::Vector3d(0, 0, 0)); + EXPECT_EQ( + nestedLinkStateElem->Get("angular_acceleration"), + gz::math::Vector3d(0, 0, 0)); + EXPECT_FALSE(nestedLinkStateElem->HasElement("wrench")); + EXPECT_TRUE(nestedLinkStateElem->HasElement("torque")); + EXPECT_TRUE(nestedLinkStateElem->HasElement("force")); + EXPECT_EQ(nestedLinkStateElem->Get("force"), + gz::math::Vector3d(0, 0, 0)); + EXPECT_EQ(nestedLinkStateElem->Get("torque"), + gz::math::Vector3d(0, 0, 0)); } ////////////////////////////////////////