Skip to content

Commit

Permalink
Remove //inertial/pose/@relative_to from SDFormat 1.8 spec (#480)
Browse files Browse the repository at this point in the history
* error when //inertial/pose/@relative_to is non-default

Signed-off-by: Jenn Nguyen <[email protected]>

* moved //inertial/pose/@relative_to test to integration test

Signed-off-by: Jenn Nguyen <[email protected]>

* updated inertial pose spec

Signed-off-by: Jenn Nguyen <[email protected]>

* removed invalid attribute error

Signed-off-by: Jenn Nguyen <[email protected]>

* removed sdf/Migration.md

Signed-off-by: Jenn Nguyen <[email protected]>

* added //inertial/pose/@relative_to deprecation

Signed-off-by: Jenn Nguyen <[email protected]>

* changed phrasing

Signed-off-by: Jenn Nguyen <[email protected]>

Co-authored-by: Addisu Z. Taddese <[email protected]>
  • Loading branch information
jennuine and azeey authored Feb 3, 2021
1 parent 105bf22 commit 93f8c56
Show file tree
Hide file tree
Showing 4 changed files with 119 additions and 124 deletions.
77 changes: 53 additions & 24 deletions Migration.md
Original file line number Diff line number Diff line change
@@ -1,8 +1,8 @@
# Migration Guide for SDF Protocol
# Migration Guide for SDFormat Specification
This document contains information about migrating
between different versions of the SDF protocol.
The SDF protocol version number is specified in the `version` attribute
of the `sdf` element (1.4, 1.5, 1.6, etc.)
between different versions of the SDFormat specification.
The SDFormat specification version number is specified in the `version`
attribute of the `sdf` element (1.4, 1.5, 1.6, etc.)
and is distinct from sdformat library version
(2.3, 3.0, 4.0, etc.).

Expand Down Expand Up @@ -266,7 +266,7 @@ but with improved human-readability..

### Additions

1. **New SDF protocol version 1.6**
1. **New SDFormat specification version 1.6**
+ Details about the 1.5 to 1.6 transition are explained below in this same
document

Expand All @@ -276,27 +276,11 @@ but with improved human-readability..
+ All boost pointers, boost::function in the public API have been replaced
by their std:: equivalents (C++11 standard)

1. **`gravity` and `magnetic_field` elements are moved from `physics` to `world`**
+ In physics element: gravity and `magnetic_field` tags have been moved
from Physics to World element.
+ [BitBucket pull request 247](https://osrf-migration.github.io/sdformat-gh-pages/#!/osrf/sdformat/pull-requests/247)
+ [BitBucket gazebo pull request 2090](https://osrf-migration.github.io/gazebo-gh-pages/#!/osrf/gazebo/pull-requests/2090)

1. **New noise for IMU**
+ A new style for representing the noise properties of an `imu` was implemented
in [BitBucket pull request 199](https://osrf-migration.github.io/sdformat-gh-pages/#!/osrf/sdformat/pull-requests/199)
for sdf 1.5 and the old style was declared as deprecated.
The old style has been removed from sdf 1.6 with the conversion script
updating to the new style.
+ [BitBucket pull request 199](https://osrf-migration.github.io/sdformat-gh-pages/#!/osrf/sdformat/pull-requests/199)
+ [BitBucket pull request 243](https://osrf-migration.github.io/sdformat-gh-pages/#!/osrf/sdformat/pull-requests/243)
+ [BitBucket pull request 244](https://osrf-migration.github.io/sdformat-gh-pages/#!/osrf/sdformat/pull-requests/244)

1. **Lump:: prefix in link names**
+ Changed to `_fixed_joint_lump__` to avoid confusion with scoped names
+ [BitBucket pull request 245](https://osrf-migration.github.io/sdformat-gh-pages/#!/osrf/sdformat/pull-requests/245)

## SDF protocol 1.7 to 1.8
## SDFormat specification 1.7 to 1.8

### Additions

Expand All @@ -317,9 +301,12 @@ but with improved human-readability..

### Deprecations

1. **inerial.sdf** `//inertial/pose/@relative_to` attribute is removed
+ [Pull request 480](https://github.com/osrf/sdformat/pull/480)

1. **joint.sdf** `initial_position` element in `<joint><axis>` and `<joint><axis2>` is deprecated

## SDF protocol 1.6 to 1.7
## SDFormat specification 1.6 to 1.7

### Additions

Expand Down Expand Up @@ -446,7 +433,7 @@ but with improved human-readability..
1. **world.sdf** `//world/joint` was removed as it has never been used.
+ [BitBucket pull request 637](https://osrf-migration.github.io/sdformat-gh-pages/#!/osrf/sdformat/pull-requests/637)

## SDF protocol 1.5 to 1.6
## SDFormat specification 1.5 to 1.6

### Additions

Expand All @@ -470,6 +457,16 @@ but with improved human-readability..
+ description: Camera intrinsic parameters for setting a custom perspective projection matrix.
+ [BitBucket pull request 496](https://osrf-migration.github.io/sdformat-gh-pages/#!/osrf/sdformat/pull-requests/496)

1. **heightmap_shape.sdf** `sampling` element
+ description: Samples per heightmap datum.
For rasterized heightmaps, this indicates the number of samples to take per pixel.
Using a lower value, e.g. 1, will generally improve the performance
of the heightmap but lower the heightmap quality.
+ type: unsigned int
+ default: 2
+ required: 0
+ [Bitbucket pull request 293](https://osrf-migration.github.io/sdformat-gh-pages/#!/osrf/sdformat/pull-requests/293)

1. **link.sdf** `enable_wind` element
+ description: If true, the link is affected by the wind
+ type: bool
Expand Down Expand Up @@ -513,6 +510,20 @@ but with improved human-readability..
+ required: 0
+ [BitBucket pull request 369](https://osrf-migration.github.io/sdformat-gh-pages/#!/osrf/sdformat/pull-requests/369)

1. **physics.sdf** `friction_model` element
+ description: Name of ODE friction model to use. Valid values include:
+ pyramid_model: (default) friction forces limited in two directions
in proportion to normal force.
+ box_model: friction forces limited to constant in two directions.
+ cone_model: friction force magnitude limited in proportion to normal force.
See [gazebo pull request 1522](https://osrf-migration.github.io/gazebo-gh-pages/#!/osrf/gazebo/pull-request/1522)
(merged in [gazebo 8c05ad64967c](https://github.com/osrf/gazebo/commit/968dccafdfbfca09c9b3326f855612076fed7e6f))
for the implementation of this feature.
+ type: string
+ default: "pyramid_model"
+ required: 0
+ [Bitbucket pull request 294](https://osrf-migration.github.io/sdformat-gh-pages/#!/osrf/sdformat/pull-requests/294)

1. **physics.sdf** `island_threads` element under `ode::solver`
+ description: Number of threads to use for "islands" of disconnected models.
+ type: int
Expand Down Expand Up @@ -557,3 +568,21 @@ but with improved human-readability..
+ default: "0 0 0"
+ required: 0
+ [BitBucket pull request 240](https://osrf-migration.github.io/sdformat-gh-pages/#!/osrf/sdformat/pull-requests/240)

### Modifications

1. **`gravity` and `magnetic_field` elements are moved from `physics` to `world`**
+ In physics element: gravity and `magnetic_field` tags have been moved
from Physics to World element.
+ [BitBucket pull request 247](https://osrf-migration.github.io/sdformat-gh-pages/#!/osrf/sdformat/pull-requests/247)
+ [BitBucket gazebo pull request 2090](https://osrf-migration.github.io/gazebo-gh-pages/#!/osrf/gazebo/pull-requests/2090)

1. **New noise for IMU**
+ A new style for representing the noise properties of an `imu` was implemented
in [BitBucket pull request 199](https://osrf-migration.github.io/sdformat-gh-pages/#!/osrf/sdformat/pull-requests/199)
for sdf 1.5 and the old style was declared as deprecated.
The old style has been removed from sdf 1.6 with the conversion script
updating to the new style.
+ [BitBucket pull request 199](https://osrf-migration.github.io/sdformat-gh-pages/#!/osrf/sdformat/pull-requests/199)
+ [BitBucket pull request 243](https://osrf-migration.github.io/sdformat-gh-pages/#!/osrf/sdformat/pull-requests/243)
+ [BitBucket pull request 244](https://osrf-migration.github.io/sdformat-gh-pages/#!/osrf/sdformat/pull-requests/244)
6 changes: 3 additions & 3 deletions sdf/1.8/inertial.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -6,9 +6,9 @@
<description>The mass of the link.</description>
</element>

<include filename="pose.sdf" required="0">
<description>This is the pose of the inertial reference frame, relative to the specified reference frame. The origin of the inertial reference frame needs to be at the center of gravity. The axes of the inertial reference frame do not need to be aligned with the principal axes of the inertia.</description>
</include>
<element name="pose" type="pose" default="0 0 0 0 0 0" required="0">
<description>This is the pose of the inertial reference frame. The origin of the inertial reference frame needs to be at the center of gravity. The axes of the inertial reference frame do not need to be aligned with the principal axes of the inertia.</description>
</element>

<element name="inertia" required="0">
<description>The 3x3 rotational inertia matrix. Because the rotational inertia matrix is symmetric, only 6 above-diagonal elements of this matrix are specified here, using the attributes ixx, ixy, ixz, iyy, iyz, izz.</description>
Expand Down
97 changes: 0 additions & 97 deletions sdf/Migration.md

This file was deleted.

63 changes: 63 additions & 0 deletions test/integration/link_dom.cc
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,7 @@
*
*/

#include <sstream>
#include <string>
#include <gtest/gtest.h>

Expand Down Expand Up @@ -682,3 +683,65 @@ TEST(DOMLink, LoadInvalidLinkPoseRelativeTo)
// errors[3]
// errors[4]
}

/////////////////////////////////////////////////
TEST(DOMLink, ValidInertialPoseRelTo)
{
std::ostringstream stream;
stream << "<?xml version=\"1.0\"?>"
<< "<sdf version='1.8'>"
<< " <model name='A'>"
<< " <link name='B'>"
<< " <inertial>"
<< " <pose relative_to=''>0.1 1 0.2 0 0 -0.52</pose>"
<< " </inertial>"
<< " </link>"
<< " </model>"
<< "</sdf>";

sdf::Root root;
sdf::Errors errors = root.LoadSdfString(stream.str());
EXPECT_TRUE(errors.empty());

const sdf::Model *model = root.Model();
ASSERT_NE(model, nullptr);

const sdf::Link *link = model->LinkByName("B");
ASSERT_NE(link, nullptr);

EXPECT_EQ(link->Inertial().Pose(),
ignition::math::Pose3d(0.1, 1, 0.2, 0, 0, -0.52));
}

/////////////////////////////////////////////////
TEST(DOMLink, InvalidInertialPoseRelTo)
{
std::ostringstream stream;
stream << "<?xml version=\"1.0\"?>"
<< "<sdf version='1.8'>"
<< " <model name='A'>"
<< " <frame name='C'>"
<< " <pose>0 0 1 0 0 0</pose>"
<< " </frame>"
<< " <link name='B'>"
<< " <inertial>"
<< " <pose relative_to='C'>0.1 1 0.2 0 0 -0.52</pose>"
<< " </inertial>"
<< " </link>"
<< " </model>"
<< "</sdf>";

sdf::Root root;
sdf::Errors errors = root.LoadSdfString(stream.str());

// TODO(anyone) add test for warnings once it's implemented

const sdf::Model *model = root.Model();
ASSERT_NE(model, nullptr);

const sdf::Link *link = model->LinkByName("B");
ASSERT_NE(link, nullptr);

EXPECT_EQ(link->Inertial().Pose(),
ignition::math::Pose3d(0.1, 1, 0.2, 0, 0, -0.52));
}

0 comments on commit 93f8c56

Please sign in to comment.