Skip to content

Commit

Permalink
Merge pull request #706 from scpeters/merge_11_12
Browse files Browse the repository at this point in the history
Merge 11 -> 12
  • Loading branch information
scpeters authored Sep 21, 2021
2 parents ef2bc64 + 2229b96 commit 4449749
Show file tree
Hide file tree
Showing 11 changed files with 212 additions and 28 deletions.
80 changes: 79 additions & 1 deletion Changelog.md
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,85 @@

## libsdformat 11.X

### libsdformat 11.X.X (202X-XX-XX)
### libsdformat 11.3.0 (2021-09-10)

1. Fix world-complete.sdf and add particle_scatter_ratio to v1.8
* [Pull request #695](https://github.com/ignitionrobotics/sdformat/pull/695)

1. Parse URDF continuous joint effort/velocity limits
* [Pull request #684](https://github.com/ignitionrobotics/sdformat/pull/684)

1. Add `enable_orientation` SDF element to imu
* [Pull request #651](https://github.com/ignitionrobotics/sdformat/pull/651)

1. Add a codecheck make target
* [Pull request #682](https://github.com/ignitionrobotics/sdformat/pull/682)

1. Refactor sdf::readXml
* [Pull request #681](https://github.com/ignitionrobotics/sdformat/pull/681)

1. Upgrade cpplint and fix new errors
* [Pull request #680](https://github.com/ignitionrobotics/sdformat/pull/680)

1. Infrastructure and documentation
* [Pull request #679](https://github.com/ignitionrobotics/sdformat/pull/679)
* [Pull request #678](https://github.com/ignitionrobotics/sdformat/pull/678)
* [Pull request #676](https://github.com/ignitionrobotics/sdformat/pull/676)
* [Pull request #673](https://github.com/ignitionrobotics/sdformat/pull/673)
* [Pull request #630](https://github.com/ignitionrobotics/sdformat/pull/630)

1. Added comment reminder to update functions
* [Pull request #677](https://github.com/ignitionrobotics/sdformat/pull/677)

1. BUG: add missing plugin element to include
* [Pull request #668](https://github.com/ignitionrobotics/sdformat/pull/668)
* [Pull request #675](https://github.com/ignitionrobotics/sdformat/pull/675)

1. Adds `enable_metrics` flag to Sensor.
* [Pull request #665](https://github.com/ignitionrobotics/sdformat/pull/665)

1. BUG: make time type string [s ns]
* [Pull request #662](https://github.com/ignitionrobotics/sdformat/pull/662)

1. Add GPS sensor to sdf9
* [Pull request #453](https://github.com/ignitionrobotics/sdformat/pull/453)

1. Spec change booleans from 0/1 to false/true
* [Pull request #663](https://github.com/ignitionrobotics/sdformat/pull/663)

1. Support parsing elements that are not part of the schema
* [Pull request #638](https://github.com/ignitionrobotics/sdformat/pull/638)

1. Add lightmap to 1.7 spec and PBR material DOM
* [Pull request #429](https://github.com/ignitionrobotics/sdformat/pull/429)

1. Fix urdf link extension tags
* [Pull request #628](https://github.com/ignitionrobotics/sdformat/pull/628)

1. Fix unreported invalid model when reference frame is unavailable
* [Pull request #636](https://github.com/ignitionrobotics/sdformat/pull/636)

1. Updated material spec
* [Pull request #644](https://github.com/ignitionrobotics/sdformat/pull/644)

1. BUG: add missing sdf files to CMakeLists
* [Pull request #631](https://github.com/ignitionrobotics/sdformat/pull/631)

1. Update build system to allow overriding CXX flags and using clang on Linux
* [Pull request #621](https://github.com/ignitionrobotics/sdformat/pull/621)

1. Error: move << operator from .hh to .cc file
* [Pull request #623](https://github.com/ignitionrobotics/sdformat/pull/623)
* [Pull request #625](https://github.com/ignitionrobotics/sdformat/pull/625)

1. Add Element::FindElement as an alternative to Element::GetElement
* [Pull request #620](https://github.com/ignitionrobotics/sdformat/pull/620)

1. Parameter passing prototype
* [Pull request #413](https://github.com/ignitionrobotics/sdformat/pull/413)

1. Port particle scatter ratio param to sdf 1.6
* [Pull request #595](https://github.com/ignitionrobotics/sdformat/pull/595)

### libsdformat 11.2.2 (2021-07-01)

Expand Down
26 changes: 21 additions & 5 deletions sdf/1.7/frame.sdf
Original file line number Diff line number Diff line change
@@ -1,16 +1,32 @@
<!-- Frame -->
<element name="frame" required="*">
<description>A frame of reference to which a pose is relative.</description>
<description>A frame of reference in which poses may be expressed.</description>

<attribute name="name" type="string" default="" required="1">
<description>Name of the frame. This name must not match another frame defined inside the parent that this frame is attached to.</description>
<description>
Name of the frame. It must be unique whithin its scope (model/world),
i.e., it must not match the name of another frame, link, joint, or model
within the same scope.
</description>
</attribute>

<attribute name="attached_to" type="string" default="" required="*">
<description>
Name of the link or frame to which this frame is attached.
If a frame is specified, recursively following the attached_to attributes
of the specified frames must lead to the name of a link, a model, or the world frame.
If specified, this frame is attached to the specified frame. The specified
frame must be within the same scope and may be defined implicitly, i.e.,
the name of any //frame, //model, //joint, or //link within the same scope
may be used.

If missing, this frame is attached to the containing scope's frame. Within
a //world scope this is the implicit world frame, and within a //model
scope this is the implicit model frame.

A frame moves jointly with the frame it is @attached_to. This is different
from //pose/@relative_to. @attached_to defines how the frame is attached
to a //link, //model, or //world frame, while //pose/@relative_to defines
how the frame's pose is represented numerically. As a result, following
the chain of @attached_to attributes must always lead to a //link,
//model, //world, or //joint (implicitly attached_to its child //link).
</description>
</attribute>

Expand Down
7 changes: 6 additions & 1 deletion sdf/1.7/model.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,12 @@
<description>The model element defines a complete robot or any other physical object.</description>

<attribute name="name" type="string" default="__default__" required="1">
<description>A unique name for the model. This name must not match another model in the world.</description>
<description>
The name of the model and its implicit frame. This name must be unique
among all elements defining frames within the same scope, i.e., it must
not match another //model, //frame, //joint, or //link within the same
scope.
</description>
</attribute>

<attribute name="canonical_link" type="string" default="" required="*">
Expand Down
15 changes: 13 additions & 2 deletions sdf/1.7/pose.sdf
Original file line number Diff line number Diff line change
@@ -1,10 +1,21 @@
<!-- Pose -->
<element name="pose" type="pose" default="0 0 0 0 0 0" required="0">
<description>A position(x,y,z) and orientation(roll, pitch yaw) with respect to the frame named in the relative_to attribute.</description>
<description>A position(x,y,z) and orientation(roll, pitch yaw) with respect
to the frame named in the relative_to attribute.</description>

<attribute name="relative_to" type="string" default="" required="*">
<description>
Name of frame relative to which the pose is applied.
If specified, this pose is expressed in the named frame. The named frame
must be declared within the same scope (world/model) as the element that
has its pose specified by this tag.

If missing, the pose is expressed in the frame of the parent XML element
of the element that contains the pose. For exceptions to this rule and
more details on the default behavior, see
http://sdformat.org/tutorials?tut=pose_frame_semantics.

Note that @relative_to merely affects an element's initial pose and
does not affect the element's dynamic movement thereafter.
</description>
</attribute>

Expand Down
26 changes: 21 additions & 5 deletions sdf/1.8/frame.sdf
Original file line number Diff line number Diff line change
@@ -1,16 +1,32 @@
<!-- Frame -->
<element name="frame" required="*">
<description>A frame of reference to which a pose is relative.</description>
<description>A frame of reference in which poses may be expressed.</description>

<attribute name="name" type="string" default="" required="1">
<description>Name of the frame. This name must not match another frame defined inside the parent that this frame is attached to.</description>
<description>
Name of the frame. It must be unique whithin its scope (model/world),
i.e., it must not match the name of another frame, link, joint, or model
within the same scope.
</description>
</attribute>

<attribute name="attached_to" type="string" default="" required="*">
<description>
Name of the link or frame to which this frame is attached.
If a frame is specified, recursively following the attached_to attributes
of the specified frames must lead to the name of a link, a model, or the world frame.
If specified, this frame is attached to the specified frame. The specified
frame must be within the same scope and may be defined implicitly, i.e.,
the name of any //frame, //model, //joint, or //link within the same scope
may be used.

If missing, this frame is attached to the containing scope's frame. Within
a //world scope this is the implicit world frame, and within a //model
scope this is the implicit model frame.

A frame moves jointly with the frame it is @attached_to. This is different
from //pose/@relative_to. @attached_to defines how the frame is attached
to a //link, //model, or //world frame, while //pose/@relative_to defines
how the frame's pose is represented numerically. As a result, following
the chain of @attached_to attributes must always lead to a //link,
//model, //world, or //joint (implicitly attached_to its child //link).
</description>
</attribute>

Expand Down
7 changes: 6 additions & 1 deletion sdf/1.8/model.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,12 @@
<description>The model element defines a complete robot or any other physical object.</description>

<attribute name="name" type="string" default="__default__" required="1">
<description>A unique name for the model. This name must not match another model in the world.</description>
<description>
The name of the model and its implicit frame. This name must be unique
among all elements defining frames within the same scope, i.e., it must
not match another //model, //frame, //joint, or //link within the same
scope.
</description>
</attribute>

<attribute name="canonical_link" type="string" default="" required="*">
Expand Down
19 changes: 17 additions & 2 deletions sdf/1.8/pose.sdf
Original file line number Diff line number Diff line change
@@ -1,10 +1,25 @@
<!-- Pose -->
<element name="pose" type="pose" default="0 0 0 0 0 0" required="0">
<description>A position(x,y,z) and orientation(roll, pitch yaw) with respect to the frame named in the relative_to attribute.</description>
<description>A position (x,y,z) and orientation (roll, pitch yaw) with respect
to the frame named in the relative_to attribute.</description>

<attribute name="relative_to" type="string" default="" required="*">
<description>
Name of frame relative to which the pose is applied.
If specified, this pose is expressed in the named frame. The named frame
must be declared within the same scope (world/model) as the element that
has its pose specified by this tag.

If missing, the pose is expressed in the frame of the parent XML element
of the element that contains the pose. For exceptions to this rule and
more details on the default behavior, see
http://sdformat.org/tutorials?tut=pose_frame_semantics.

Note that @relative_to merely affects an element's initial pose and
does not affect the element's dynamic movement thereafter.

New in v1.8: @relative_to may use frames of nested scopes. In this case,
the frame is specified using `::` as delimiter to define the scope of the
frame, e.g. `nested_model_A::nested_model_B::awesome_frame`.
</description>
</attribute>

Expand Down
26 changes: 21 additions & 5 deletions sdf/1.9/frame.sdf
Original file line number Diff line number Diff line change
@@ -1,16 +1,32 @@
<!-- Frame -->
<element name="frame" required="*">
<description>A frame of reference to which a pose is relative.</description>
<description>A frame of reference in which poses may be expressed.</description>

<attribute name="name" type="string" default="" required="1">
<description>Name of the frame. This name must not match another frame defined inside the parent that this frame is attached to.</description>
<description>
Name of the frame. It must be unique whithin its scope (model/world),
i.e., it must not match the name of another frame, link, joint, or model
within the same scope.
</description>
</attribute>

<attribute name="attached_to" type="string" default="" required="*">
<description>
Name of the link or frame to which this frame is attached.
If a frame is specified, recursively following the attached_to attributes
of the specified frames must lead to the name of a link, a model, or the world frame.
If specified, this frame is attached to the specified frame. The specified
frame must be within the same scope and may be defined implicitly, i.e.,
the name of any //frame, //model, //joint, or //link within the same scope
may be used.

If missing, this frame is attached to the containing scope's frame. Within
a //world scope this is the implicit world frame, and within a //model
scope this is the implicit model frame.

A frame moves jointly with the frame it is @attached_to. This is different
from //pose/@relative_to. @attached_to defines how the frame is attached
to a //link, //model, or //world frame, while //pose/@relative_to defines
how the frame's pose is represented numerically. As a result, following
the chain of @attached_to attributes must always lead to a //link,
//model, //world, or //joint (implicitly attached_to its child //link).
</description>
</attribute>

Expand Down
7 changes: 6 additions & 1 deletion sdf/1.9/model.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,12 @@
<description>The model element defines a complete robot or any other physical object.</description>

<attribute name="name" type="string" default="__default__" required="1">
<description>A unique name for the model. This name must not match another model in the world.</description>
<description>
The name of the model and its implicit frame. This name must be unique
among all elements defining frames within the same scope, i.e., it must
not match another //model, //frame, //joint, or //link within the same
scope.
</description>
</attribute>

<attribute name="canonical_link" type="string" default="" required="*">
Expand Down
25 changes: 21 additions & 4 deletions sdf/1.9/pose.sdf
Original file line number Diff line number Diff line change
@@ -1,12 +1,29 @@
<!-- Pose -->
<element name="pose" type="pose" default="0 0 0 0 0 0" required="0">
<description>
A pose (translation, rotation) expressed in the frame named by @relative_to. The first three components (x, y, z) represent the position of the element's origin (in the @relative_to frame). The rotation component represents the orientation of the element as either a sequence of Euler rotations (r, p, y), see http://sdformat.org/tutorials?tut=specify_pose, or as a quaternion (x, y, z, w), where w is the real component.
</description>
<description>A pose (translation, rotation) expressed in the frame named by
@relative_to. The first three components (x, y, z) represent the position of
the element's origin (in the @relative_to frame). The rotation component
represents the orientation of the element as either a sequence of Euler
rotations (r, p, y), see http://sdformat.org/tutorials?tut=specify_pose,
or as a quaternion (x, y, z, w), where w is the real component.</description>

<attribute name="relative_to" type="string" default="" required="0">
<description>
Name of frame relative to which the pose is applied.
If specified, this pose is expressed in the named frame. The named frame
must be declared within the same scope (world/model) as the element that
has its pose specified by this tag.

If missing, the pose is expressed in the frame of the parent XML element
of the element that contains the pose. For exceptions to this rule and
more details on the default behavior, see
http://sdformat.org/tutorials?tut=pose_frame_semantics.

Note that @relative_to merely affects an element's initial pose and
does not affect the element's dynamic movement thereafter.

New in v1.8: @relative_to may use frames of nested scopes. In this case,
the frame is specified using `::` as delimiter to define the scope of the
frame, e.g. `nested_model_A::nested_model_B::awesome_frame`.
</description>
</attribute>

Expand Down
2 changes: 1 addition & 1 deletion test/sdf/world_complete.sdf
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
<?xml version="1.0" ?>
<sdf version="1.7">
<sdf version="1.8">
<world name="default">
<physics name="my_physics" type="bullet">
<max_step_size>0.1</max_step_size>
Expand Down

0 comments on commit 4449749

Please sign in to comment.