Skip to content

Commit

Permalink
Renamed Ignition and ign to Gazebo or gz (#81)
Browse files Browse the repository at this point in the history
Signed-off-by: ahcorde <[email protected]>
  • Loading branch information
ahcorde authored Oct 27, 2022
1 parent 96654ca commit 7c709f1
Show file tree
Hide file tree
Showing 12 changed files with 57 additions and 58 deletions.
28 changes: 14 additions & 14 deletions composition/merge_proposal.md
Original file line number Diff line number Diff line change
Expand Up @@ -103,7 +103,7 @@ to be merged and assigned the pose specified in `//model/include/pose`.
If no `//model/@placement_frame` or `//include/placement_frame` is specified,
the raw pose may simply be copied, but in general the model to be merged should
be loaded into an `sdf::Root` object so that graphs are constructed and
the model pose can be resolved (see code in [parser.cc](https://github.com/ignitionrobotics/sdformat/blob/sdformat12_12.4.0/src/parser.cc#L263-L277)).
the model pose can be resolved (see code in [parser.cc](https://github.com/gazebosim/sdformat/blob/sdformat12_12.4.0/src/parser.cc#L263-L277)).
For the entities to be merged, any explicit references to the
implicit `__model__` frame are replaced with references to the proxy frame.
Additionally, the name of the proxy frame is inserted anywhere there is an
Expand Down Expand Up @@ -177,7 +177,7 @@ which is the canonical link of `test_model`.

The following is an abridged version of a Clearpath Husky skid-steer with
sensors mounted on a pan-tilt gimbal used in the DARPA Subterranean Challenge
([MARBLE HUSKY SENSOR CONFIG 3](https://app.ignitionrobotics.org/OpenRobotics/fuel/models/MARBLE_HUSKY_SENSOR_CONFIG_3/10)):
([MARBLE HUSKY SENSOR CONFIG 3](https://app.gazebosim.org/OpenRobotics/fuel/models/MARBLE_HUSKY_SENSOR_CONFIG_3/10)):

~~~
<sdf version="1.7">
Expand Down Expand Up @@ -262,24 +262,24 @@ sensors mounted on a pan-tilt gimbal used in the DARPA Subterranean Challenge
</joint>
<!-- Gimbal Joints Plugins -->
<plugin
filename="libignition-gazebo-joint-controller-system.so"
name="ignition::gazebo::systems::JointController">
filename="libgz-gazebo-joint-controller-system.so"
name="gz::sim::systems::JointController">
<joint_name>pan_gimbal_joint</joint_name>
<use_force_commands>true</use_force_commands>
<p_gain>0.4</p_gain>
<i_gain>10</i_gain>
</plugin>
<plugin
filename="libignition-gazebo-joint-controller-system.so"
name="ignition::gazebo::systems::JointController">
filename="libgz-gazebo-joint-controller-system.so"
name="gz::sim::systems::JointController">
<joint_name>tilt_gimbal_joint</joint_name>
<use_force_commands>true</use_force_commands>
<p_gain>0.4</p_gain>
<i_gain>10</i_gain>
</plugin>
<plugin
filename="libignition-gazebo-joint-state-publisher-system.so"
name="ignition::gazebo::systems::JointStatePublisher">
filename="libgz-gazebo-joint-state-publisher-system.so"
name="gz::sim::systems::JointStatePublisher">
<joint_name>pan_gimbal_joint</joint_name>
<joint_name>tilt_gimbal_joint</joint_name>
</plugin>
Expand Down Expand Up @@ -376,24 +376,24 @@ violate encapsulation to include it in either file):
</joint>
<!-- Gimbal Joints Plugins -->
<plugin
filename="libignition-gazebo-joint-controller-system.so"
name="ignition::gazebo::systems::JointController">
filename="libgz-gazebo-joint-controller-system.so"
name="gz::sim::systems::JointController">
<joint_name>pan_gimbal_joint</joint_name>
<use_force_commands>true</use_force_commands>
<p_gain>0.4</p_gain>
<i_gain>10</i_gain>
</plugin>
<plugin
filename="libignition-gazebo-joint-controller-system.so"
name="ignition::gazebo::systems::JointController">
filename="libgz-gazebo-joint-controller-system.so"
name="gz::sim::systems::JointController">
<joint_name>tilt_gimbal_joint</joint_name>
<use_force_commands>true</use_force_commands>
<p_gain>0.4</p_gain>
<i_gain>10</i_gain>
</plugin>
<plugin
filename="libignition-gazebo-joint-state-publisher-system.so"
name="ignition::gazebo::systems::JointStatePublisher">
filename="libgz-gazebo-joint-state-publisher-system.so"
name="gz::sim::systems::JointStatePublisher">
<joint_name>pan_gimbal_joint</joint_name>
<joint_name>tilt_gimbal_joint</joint_name>
</plugin>
Expand Down
12 changes: 6 additions & 6 deletions composition/proposal.md
Original file line number Diff line number Diff line change
Expand Up @@ -609,7 +609,7 @@ reserved `::` delimiter in an invalid fashion (to define a link, joint, etc.).

This would not be an issue if this flattened XML were a transient artifact
(e.g. temporary serialization for communicating models from a Gazebo server to
a client). However, users could have converted their models with `ign sdf`, and
a client). However, users could have converted their models with `gz sdf`, and
thus there would be "data at rest" in this format.

To work around this, the conversion from SDFormat 1.7 to 1.8 should have an
Expand Down Expand Up @@ -993,7 +993,7 @@ returning an error code if errors are found during parsing:
- `sdf::readFile` and `sdf::readString` APIs perform parsing Stage 1
- `sdf::Root::Load` performs most parsing stages, but skips some of the more expensive checks
- `ign sdf --check` performs all parsing stages, including more expensive checks
- `gz sdf --check` performs all parsing stages, including more expensive checks
1. **XML parsing and schema validation:**
Parse model file from XML into a tree data structure,
Expand Down Expand Up @@ -1033,7 +1033,7 @@ returning an error code if errors are found during parsing:
in [Model::Load](https://github.com/osrf/sdformat/blob/sdformat9_9.2.0/src/Model.cc#L323-L340),
returning a `DUPLICATE_NAME` error code if non-unique names are detected.
2.3 The `ign sdf --check` command loads all DOM elements and also
2.3 The `gz sdf --check` command loads all DOM elements and also
recursively checks for name uniqueness among all sibling elements
using the [recursiveSiblingUniqueNames](https://github.com/osrf/sdformat/blob/sdformat9_9.2.0/src/parser.cc#L1633-L1655)
helper function.
Expand All @@ -1046,7 +1046,7 @@ returning an error code if errors are found during parsing:
then the joint is attached to a fixed reference frame.
In `libsdformat9`, these checks are all performed by the helper function
[checkJointParentChildLinkNames](https://github.com/osrf/sdformat/blob/4fd00c795bafb6f10a7a36356fe3f61a93c961c8/src/parser.cc#L1814-L1911),
which is invoked by `ign sdf --check`.
which is invoked by `gz sdf --check`.
A subset of these checks are performed by
[Joint::Load](https://github.com/osrf/sdformat/blob/sdformat9_9.2.0/src/Joint.cc#L199-L213)
(checking that parent and child ~~link~~ names are different and that
Expand Down Expand Up @@ -1129,7 +1129,7 @@ returning an error code if errors are found during parsing:
*6.8 Verify that the parent and child frames of each joint resolve to*
*different values. This check can be skipped in the special case that*
*"world" is the joint's parent frame since that frame is not in a*
*model's `FrameAttachedToGraph` (checked in `libsdformat11` by `ign sdf --check`, see*
*model's `FrameAttachedToGraph` (checked in `libsdformat11` by `gz sdf --check`, see*
*[Joint::ResolveParentLink](https://github.com/osrf/sdformat/blob/44cab95014e61849f508ec92a613100301512aaf/src/Joint.cc#L407-L418)*
*and [parser.cc:1895-1930](https://github.com/osrf/sdformat/blob/44cab95014e61849f508ec92a613100301512aaf/src/parser.cc#L1895-L1930)).*
Expand Down Expand Up @@ -1270,7 +1270,7 @@ There are seven phases for validating the kinematics data in a world:
in [World::Load](https://github.com/osrf/sdformat/blob/sdformat9_9.2.0/src/World.cc#L347-L362),
returning a `DUPLICATE_NAME` error code if non-unique names are detected.
2.3 The `ign sdf --check` command loads all DOM elements and also
2.3 The `gz sdf --check` command loads all DOM elements and also
recursively checks for name uniqueness among all sibling elements
using the [recursiveSiblingUniqueNames](https://github.com/osrf/sdformat/blob/sdformat9_9.2.0/src/parser.cc#L1633-L1655)
helper function.
Expand Down
14 changes: 7 additions & 7 deletions developers/roadmap.md
Original file line number Diff line number Diff line change
Expand Up @@ -16,17 +16,17 @@ version supported by the given release of the library:
* `libsdformat7`:
* 7.0.0 (*not released*): C++14, SDFormat 1.7. *This was an intermediate
version that will not be released.*
* `libsdformat8`: For use in Ignition Blueprint.
* `libsdformat8`: For use in Gazebo Blueprint.
* 8.5.0 (**released**): C++17, SDFormat 1.6.
* `libsdformat9`: For use in Gazebo 11, Ignition Citadel.
* `libsdformat9`: For use in Gazebo 11, Gazebo Citadel.
* 9.0.0 (**released**): C++17, SDFormat 1.7.
* `libsdformat10`: For use in Ignition Dome.
* `libsdformat10`: For use in Gazebo Dome.
* 10.0.0 (**released**): C++17, SDFormat 1.7.
* `libsdformat11`: For use in Ignition Edifice.
* `libsdformat11`: For use in Gazebo Edifice.
* 11.0.0 (**released**): C++17, SDFormat 1.8.
* `libsdformat12`: For use in Ignition Fortress.
* `libsdformat12`: For use in Gazebo Fortress.
* 12.0.0 (**released**): C++17, SDFormat 1.9.
* `libsdformat13`: For use in Ignition Garden.
* `libsdformat13`: For use in Gazebo Garden.
* 13.0.0 (**planned**): C++17, TBD

## Downstream Library Support
Expand All @@ -40,7 +40,7 @@ specification (as well as the caveats):
* 9 (**released**): libsdformat6, SDFormat 1.6
* 10 (**released**): libsdformat6, SDFormat 1.6
* 11 (**released**): libsdformat9, SDFormat 1.7
* [Ignition](https://ignitionrobotics.org)
* [Gazebo](https://gazebosim.org)
* Blueprint (**released**): libsdformat8, SDFormat 1.6, but supports only a subset:
* Does not support directly nested models
* Citadel (**released**): libsdformat9, SDFormat 1.7, but only a subset:
Expand Down
16 changes: 8 additions & 8 deletions install/tutorial_12.md
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,7 @@ which version you need.

On macOS, add OSRF packages:

ruby -e "$(curl -fsSL https://raw.githubusercontent.com/Homebrew/install/master/install)"
/bin/bash -c "$(curl -fsSL https://raw.githubusercontent.com/Homebrew/install/HEAD/install.sh)"
brew tap osrf/simulation

Install sdformat:
Expand All @@ -37,8 +37,8 @@ Miniconda suffices.

Create if necessary, and activate a Conda environment:

conda create -n ign-ws
conda activate ign-ws
conda create -n gz-ws
conda activate gz-ws

Install `sdformat`:

Expand Down Expand Up @@ -95,7 +95,7 @@ shell scripts for setting the necessary environment variables.

mkdir ~/sdf_source
cd ~/sdf_source/
git clone https://github.com/ignitionrobotics/sdformat
git clone https://github.com/gazebosim/sdformat

2. Change directory into the sdformat repository and switch to the sdf<#> branch

Expand Down Expand Up @@ -146,7 +146,7 @@ If you need to uninstall SDF or switch back to a debian-based install of SDF whe

Clone the repository

git clone https://github.com/ignitionrobotics/sdformat -b sdf<#>
git clone https://github.com/gazebosim/sdformat -b sdf<#>

Be sure to replace `<#>` with a number value, such as 9 or 10, depending on
which version you need.
Expand Down Expand Up @@ -183,14 +183,14 @@ Miniconda suffices.

Create if necessary, and activate a Conda environment:

conda create -n ign-ws
conda activate ign-ws
conda create -n gz-ws
conda activate gz-ws

Install prerequisites:

conda install urdfdom --channel conda-forge

Install Ignition dependencies:
Install Gazebo dependencies:

You can view lists of dependencies:

Expand Down
2 changes: 1 addition & 1 deletion install/tutorial_2-0.md
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,7 @@ Install prerequisites. A clean Ubuntu system will need:

mkdir ~/sdf_source
cd ~/sdf_source/
git clone https://github.com/ignitionrobotics/sdformat
git clone https://github.com/gazebosim/sdformat

1. Change directory into the sdformat repository and switch to the 2.0 branch

Expand Down
2 changes: 1 addition & 1 deletion install/tutorial_6-x.md
Original file line number Diff line number Diff line change
Expand Up @@ -59,7 +59,7 @@ shell scripts for setting the necessary environment variables.

mkdir ~/sdf_source
cd ~/sdf_source/
git clone https://github.com/ignitionrobotics/sdformat
git clone https://github.com/gazebosim/sdformat

1. Change directory into the sdformat repository and switch to the sdf6 branch

Expand Down
16 changes: 8 additions & 8 deletions install/tutorial_9_later.md
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,7 @@ which version you need.

On macOS, add OSRF packages:

ruby -e "$(curl -fsSL https://raw.githubusercontent.com/Homebrew/install/master/install)"
/bin/bash -c "$(curl -fsSL https://raw.githubusercontent.com/Homebrew/install/HEAD/install.sh)"
brew tap osrf/simulation

Install sdformat:
Expand All @@ -36,8 +36,8 @@ Miniconda suffices.

Create if necessary, and activate a Conda environment:

conda create -n ign-ws
conda activate ign-ws
conda create -n gz-ws
conda activate gz-ws

Install `sdformat`:

Expand Down Expand Up @@ -96,7 +96,7 @@ shell scripts for setting the necessary environment variables.

mkdir ~/sdf_source
cd ~/sdf_source/
git clone https://github.com/ignitionrobotics/sdformat
git clone https://github.com/gazebosim/sdformat

2. Change directory into the sdformat repository and switch to the sdf<#> branch

Expand Down Expand Up @@ -143,7 +143,7 @@ If you need to uninstall SDF or switch back to a debian-based install of SDF whe

Clone the repository

git clone https://github.com/ignitionrobotics/sdformat -b sdf<#>
git clone https://github.com/gazebosim/sdformat -b sdf<#>

Be sure to replace `<#>` with a number value, such as 9 or 10, depending on
which version you need.
Expand Down Expand Up @@ -180,14 +180,14 @@ Miniconda suffices.

Create if necessary, and activate a Conda environment:

conda create -n ign-ws
conda activate ign-ws
conda create -n gz-ws
conda activate gz-ws

Install prerequisites:

conda install urdfdom --channel conda-forge

Install Ignition dependencies:
Install Gazebo dependencies:

You can view lists of dependencies:

Expand Down
2 changes: 1 addition & 1 deletion param_passing/proposal.md
Original file line number Diff line number Diff line change
Expand Up @@ -47,7 +47,7 @@ The motivation behind this proposal is to avoid duplication when constructing
models. For example, in [SubT's robots](
https://github.com/osrf/subt/wiki/Robots), X1 has 8-10 different sensor
configurations but all have the same base. If we take a look at all the
different configurations in [Fuel](https://app.ignitionrobotics.org/), we see
different configurations in [Fuel](https://app.gazebosim.org/), we see
that they are essentially copies of each other but with different parameters for
these sensors.

Expand Down
8 changes: 4 additions & 4 deletions pose_frame_semantics/proposal.md
Original file line number Diff line number Diff line change
Expand Up @@ -1548,7 +1548,7 @@ returning an error code if errors are found during parsing:

- `sdf::readFile` and `sdf::readString` APIs perform parsing Stage 1
- `sdf::Root::Load` performs most parsing stages, but skips some of the more expensive checks
- `ign sdf --check` performs all parsing stages, including more expensive checks
- `gz sdf --check` performs all parsing stages, including more expensive checks

1. **XML parsing and schema validation:**
Parse model file from XML into a tree data structure,
Expand Down Expand Up @@ -1588,7 +1588,7 @@ returning an error code if errors are found during parsing:
*in [Model::Load](https://github.com/osrf/sdformat/blob/sdformat9_9.2.0/src/Model.cc#L323-L340),*
*returning a `DUPLICATE_NAME` error code if non-unique names are detected.*

2.3 *The `ign sdf --check` command loads all DOM elements and also*
2.3 *The `gz sdf --check` command loads all DOM elements and also*
*recursively checks for name uniqueness among all sibling elements*
*using the [recursiveSiblingUniqueNames](https://github.com/osrf/sdformat/blob/sdformat9_9.2.0/src/parser.cc#L1633-L1655)*
*helper function.*
Expand All @@ -1604,7 +1604,7 @@ returning an error code if errors are found during parsing:
then the joint is attached to a fixed reference frame.
*In `libsdformat9`, these checks are all performed by the helper function*
*[checkJointParentChildLinkNames](https://github.com/osrf/sdformat/blob/sdformat9_9.2.0/src/parser.cc#L1820-L1885),*
*which is invoked by `ign sdf --check`.*
*which is invoked by `gz sdf --check`.*
*A subset of these checks are performed by*
*[Joint::Load](https://github.com/osrf/sdformat/blob/sdformat9_9.2.0/src/Joint.cc#L199-L213)*
*(checking that parent and child link names are different and that*
Expand Down Expand Up @@ -1834,7 +1834,7 @@ There are *seven* phases for validating the kinematics data in a world:
*in [World::Load](https://github.com/osrf/sdformat/blob/sdformat9_9.2.0/src/World.cc#L347-L362),*
*returning a `DUPLICATE_NAME` error code if non-unique names are detected.*

2.3 *The `ign sdf --check` command loads all DOM elements and also*
2.3 *The `gz sdf --check` command loads all DOM elements and also*
*recursively checks for name uniqueness among all sibling elements*
*using the [recursiveSiblingUniqueNames](https://github.com/osrf/sdformat/blob/sdformat9_9.2.0/src/parser.cc#L1633-L1655)*
*helper function.*
Expand Down
4 changes: 2 additions & 2 deletions quickstart/tutorial_2-0.md
Original file line number Diff line number Diff line change
Expand Up @@ -103,7 +103,7 @@ if (!sdf::readFile(sdfPath, sdfElement))
}
```

Given an `sdf_path` , `sdf::readFile` will attempt to parse such file into our `sdf_element`. If it fails to do so, either because the file could not be accessed or it was not a valid SDF or URDF (yes, sdformat handles both formats seamlessly!), it will return `false` .
Given an `sdf_path` , `sdf::readFile` will attempt to parse such file into our `sdf_element`. If it fails to do so, either because the file could not be accessed or it was not a valid SDF or URDF (yes, sdformat handles both formats seamlessly!), it will return `false` .

----------------

Expand Down Expand Up @@ -154,7 +154,7 @@ std::cout << "Joint " << jointName << " connects " << parentLinkName

```
As you might guess, we're getting the `name` attribute of the current `joint_element` and then retrieving its `parent` and `child` elements' values. It is interesting to note all `Get()` method's use cases: `Get()` is a template method that returns the given attribute value or the element value itself (that is, the plain text in between tags) if called with no arguments. To this end, it has been specialized to parse such value accordingly into primitive types (i.e. `double`), common std types (i.e. `std::string`) or [`ignition::math`](http://ignitionrobotics.org/libraries/math) types for the most complex ones (like poses).
As you might guess, we're getting the `name` attribute of the current `joint_element` and then retrieving its `parent` and `child` elements' values. It is interesting to note all `Get()` method's use cases: `Get()` is a template method that returns the given attribute value or the element value itself (that is, the plain text in between tags) if called with no arguments. To this end, it has been specialized to parse such value accordingly into primitive types (i.e. `double`), common std types (i.e. `std::string`) or [`ignition::math`](http://gazebosim.org/libraries/math) types for the most complex ones (like poses).
### Building the code
Expand Down
3 changes: 1 addition & 2 deletions specify_pose/proposal.md
Original file line number Diff line number Diff line change
Expand Up @@ -295,8 +295,7 @@ really hard (and annoying) to support an already complex specification.

#### 1.1.1 Re-describe API Implications, potential sources of numerical error

The `ignition::math::Pose3d` stores its rotation as
`ignition::math::Quaternion`.
The `gz::math::Pose3d` stores its rotation as `gz::math::Quaternion`.

Therefore, when storing quaternions, users should be aware of what numeric
changes happen to their data (e.g. normalization), so they should generally
Expand Down
8 changes: 4 additions & 4 deletions specify_pose/tutorial.md
Original file line number Diff line number Diff line change
Expand Up @@ -64,13 +64,13 @@ which both share the same definition of roll, pitch, and yaw angles:

For a command-line utility to convert between roll-pitch-yaw angles,
quaternions, and rotation matrices, please see the
[quaternion\_from\_euler](https://github.com/ignitionrobotics/ign-math/blob/ign-math4/examples/quaternion_from_euler.cc)
and [quaternion\_to\_euler](https://github.com/ignitionrobotics/ign-math/blob/ign-math4/examples/quaternion_to_euler.cc)
example programs in ignition math.
[quaternion\_from\_euler](https://github.com/gazebosim/gz-math/blob/ign-math4/examples/quaternion_from_euler.cc)
and [quaternion\_to\_euler](https://github.com/gazebosim/gz-math/blob/ign-math4/examples/quaternion_to_euler.cc)
example programs in Gazebo math.

Software implementations for converting between this Euler angle convention and
quaternions can be found in
[ignition::math::Quaternion](https://github.com/ignitionrobotics/ign-math/blob/ignition-math4_4.0.0/include/ignition/math/Quaternion.hh#L308-L398)
[gz::math::Quaternion](https://github.com/gazebosim/gz-math/blob/gz-math7/include/gz/math/Quaternion.hh#L309-L399)
C++ class, and the [urdf::Rotation](https://github.com/ros/urdfdom_headers/blob/1.0.3/urdf_model/include/urdf_model/pose.h#L103-L155) C++ class.

Some other implementations:
Expand Down

0 comments on commit 7c709f1

Please sign in to comment.