Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
28 changes: 27 additions & 1 deletion Changelog.md
Original file line number Diff line number Diff line change
@@ -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)
Expand All @@ -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)

Expand All @@ -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)

Expand Down
41 changes: 41 additions & 0 deletions Migration.md
Original file line number Diff line number Diff line change
Expand Up @@ -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**,
Expand All @@ -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
Expand Down
55 changes: 29 additions & 26 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -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)

Expand Down Expand Up @@ -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
Expand All @@ -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
Expand Down Expand Up @@ -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
Expand Down Expand Up @@ -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
Expand Down Expand Up @@ -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<#>
```
116 changes: 115 additions & 1 deletion sdf/1.12/joint_state.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -9,11 +9,125 @@
<description>Name of the joint</description>
</attribute>

<element name="angle" type="double" default="0" required="+">
<element name="angle" type="double" default="0" required="-1">
<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 name="axis_state" required="0">
<description>
Contains the state of the first joint axis.
</description>

<element name="position" type="double" default="0" required="0">
<description>The position of the first joint axis.</description>

<attribute name="degrees" type="bool" default="false" required="0">
<description>
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.
</description>
</attribute>
</element>

<element name="velocity" type="double" default="0" required="0">
<description>The velocity of the first joint axis.</description>

<attribute name="degrees" type="bool" default="false" required="0">
<description>
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.
</description>
</attribute>
</element>

<element name="acceleration" type="double" default="0" required="0">
<description>The acceleration of the first joint axis.</description>

<attribute name="degrees" type="bool" default="false" required="0">
<description>
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.
</description>
</attribute>
</element>

<element name="effort" type="double" default="0" required="0">
<description>The effort applied at the first joint axis.</description>
</element>
</element>

<element name="axis2_state" required="0">
<description>
Contains the state of the second joint axis.
</description>

<element name="position" type="double" default="0" required="0">
<description>The position of the second joint axis.</description>

<attribute name="degrees" type="bool" default="false" required="0">
<description>
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.
</description>
</attribute>
</element>

<element name="velocity" type="double" default="0" required="0">
<description>The velocity of the second joint axis.</description>

<attribute name="degrees" type="bool" default="false" required="0">
<description>
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.
</description>
</attribute>
</element>

<element name="acceleration" type="double" default="0" required="0">
<description>The acceleration of the second joint axis.</description>

<attribute name="degrees" type="bool" default="false" required="0">
<description>
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.
</description>
</attribute>
</element>

<element name="effort" type="double" default="0" required="0">
<description>The effort applied at the second joint axis.</description>
</element>
</element>
</element> <!-- End Joint -->
Loading
Loading