Skip to content

Commit

Permalink
ign -> gz Partial Docs Migration and Project Name Followups : gz-phys…
Browse files Browse the repository at this point in the history
…ics (#368)
  • Loading branch information
methylDragon authored Jun 28, 2022
1 parent bc5f134 commit 265b31b
Show file tree
Hide file tree
Showing 23 changed files with 70 additions and 64 deletions.
4 changes: 2 additions & 2 deletions Changelog.md
Original file line number Diff line number Diff line change
Expand Up @@ -180,7 +180,7 @@
* [Pull request #133](https://github.com/gazebosim/gz-physics/pull/133)
* [Pull request #116](https://github.com/gazebosim/gz-physics/pull/116)

1. Bump in edifice: ign-common4
1. Bump in edifice: gz-common4
* [Pull request #205](https://github.com/gazebosim/gz-physics/pull/205)

1. Constructing nested models for dartsim
Expand Down Expand Up @@ -560,7 +560,7 @@
1. Add SetJointVelocityCommand feature.
* [BitBucket pull request 100](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-physics/pull-requests/100)

1. Add `IGN_PROFILER_ENABLE` cmake option for enabling the ign-common profiler.
1. Add `IGN_PROFILER_ENABLE` cmake option for enabling the gz-common profiler.
* [BitBucket pull request 96](https://osrf-migration.github.io/ignition-gh-pages/#!/ignitionrobotics/ign-physics/pull-requests/96)

### Gazebo Physics 1.3.1 (2019-07-19)
Expand Down
10 changes: 9 additions & 1 deletion Migration.md
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,7 @@ release will remove the deprecated code.

## Gazebo Physics 5.X to 6.X

### Deprecation
### Deprecations

1. The `ignition` namespace is deprecated and will be removed in future versions. Use `gz` instead.

Expand All @@ -27,6 +27,14 @@ release will remove the deprecated code.
1. `IGNITION_UNITTEST_EXPECTDATA_ACCESS` (hard-tocked, inside test and detail headers)
1. `IGNITION_PHYSICS_DEFINE_COORDINATE_SPACE` (hard-tocked, inside detail header)

### Breaking Changes

* The project name has been changed to use the `gz-` prefix, you **must** use the `gz` prefix!
* This also means that any generated code that use the project name (e.g. CMake variables, in-source macros) would have to be migrated.
* Some non-exhaustive examples of this include:
* `GZ_<PROJECT>_<VISIBLE/HIDDEN>`
* CMake `-config` files
* Paths that depend on the project name

## Gazebo Physics 4.X to 5.X

Expand Down
5 changes: 2 additions & 3 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -14,8 +14,7 @@ Ubuntu Focal | [![Build Status](https://build.osrfoundation.org/buildStatus/icon
Homebrew | [![Build Status](https://build.osrfoundation.org/buildStatus/icon?job=ignition_physics-ci-ign-physics6-homebrew-amd64)](https://build.osrfoundation.org/job/ignition_physics-ci-ign-physics6-homebrew-amd64)
Windows | [![Build Status](https://build.osrfoundation.org/buildStatus/icon?job=ign_physics-ci-win)](https://build.osrfoundation.org/job/ign_physics-ci-win)

Gazebo Physics, a component of [Ignition
Robotics](https://gazebosim.org), provides an abstract physics interface
Gazebo Physics, a component of [Gazebo](https://gazebosim.org), provides an abstract physics interface
designed to support simulation and rapid development of robot applications.

# Table of Contents
Expand Down Expand Up @@ -97,7 +96,7 @@ You can also generate the documentation from a clone of this repository by follo
3. Configure and build the documentation.
```
cd ign-physics; mkdir build; cd build; cmake ../; make doc
cd gz-physics; mkdir build; cd build; cmake ../; make doc
```
4. View the documentation by running the following command from the build directory.
Expand Down
4 changes: 2 additions & 2 deletions api.md.in
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
## Ignition @IGN_DESIGNATION_CAP@
## Gazebo @IGN_DESIGNATION_CAP@

Ignition @IGN_DESIGNATION_CAP@ is a component in Gazebo, a set of libraries
Gazebo @IGN_DESIGNATION_CAP@ is a component in Gazebo, a set of libraries
designed to rapidly develop robot and simulation applications.

## License
Expand Down
2 changes: 1 addition & 1 deletion dartsim/src/SDFFeatures.cc
Original file line number Diff line number Diff line change
Expand Up @@ -702,7 +702,7 @@ Identity SDFFeatures::ConstructSdfJoint(
// constructed by the user instead of one obtained from an sdf::Model
// object. In this case, the joint does not have a valid frame graph and it
// cannot be used to resolve for the parent link name. However, this can
// still be a valid use case for ign-gazebo that sends DOM objects
// still be a valid use case for gz-sim that sends DOM objects
// piecemeal with all links and poses resolved.
// Since (1) is an error that should be reported and (2) might be a valid use
// case, the solution is, when an error is encountered, we first assume (2)
Expand Down
2 changes: 1 addition & 1 deletion dartsim/src/SDFFeatures_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -142,7 +142,7 @@ static sdf::JointAxis ResolveJointAxis(const sdf::JointAxis &_unresolvedAxis)
}

/////////////////////////////////////////////////
/// Downstream applications, like ign-gazebo, use this way of world construction
/// Downstream applications, like gz-sim, use this way of world construction
WorldPtr LoadWorldPiecemeal(const std::string &_world)
{
auto engine = LoadEngine();
Expand Down
2 changes: 1 addition & 1 deletion examples/hello_world_loader/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
cmake_minimum_required(VERSION 3.5 FATAL_ERROR)

project(ign-physics-hello-world-loader)
project(gz-physics-hello-world-loader)

find_package(gz-plugin2 REQUIRED COMPONENTS all)
set(GZ_PLUGIN_VER ${gz-plugin2_VERSION_MAJOR})
Expand Down
2 changes: 1 addition & 1 deletion examples/hello_world_loader/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,7 @@ plugins, according to a desired feature list.

## Build

From the root of the `ign-physics` repository, do the following to build the example:
From the root of the `gz-physics` repository, do the following to build the example:

```bash
cd examples/hello_world_loader
Expand Down
2 changes: 1 addition & 1 deletion examples/hello_world_plugin/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
cmake_minimum_required(VERSION 3.5 FATAL_ERROR)

project(ign-physics-hello-world-plugin)
project(gz-physics-hello-world-plugin)

find_package(gz-plugin2 REQUIRED COMPONENTS all)
set(GZ_PLUGIN_VER ${gz-plugin2_VERSION_MAJOR})
Expand Down
2 changes: 1 addition & 1 deletion examples/hello_world_plugin/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,7 @@ Gazebo Physics.

## Build

From the root of the `ign-physics` repository, do the following to build the example:
From the root of the `gz-physics` repository, do the following to build the example:

```bash
cd examples/hello_world_plugin
Expand Down
2 changes: 1 addition & 1 deletion examples/simple_plugin/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
cmake_minimum_required(VERSION 3.5 FATAL_ERROR)

project(ign-physics-simple-plugin)
project(gz-physics-simple-plugin)

find_package(gz-plugin2 REQUIRED COMPONENTS all)
set(GZ_PLUGIN_VER ${gz-plugin2_VERSION_MAJOR})
Expand Down
2 changes: 1 addition & 1 deletion tpe/plugin/src/FreeGroupFeatures.cc
Original file line number Diff line number Diff line change
Expand Up @@ -66,7 +66,7 @@ static tpelib::Link *FindModelRootLink(tpelib::Model *_model)
{
// assume canonical link is the first link in model
// note the canonical link of a free group is renamed to root link in
// ign-physics4. The canonical link / root link of a free group can be
// gz-physics4. The canonical link / root link of a free group can be
// different from the canonical link of a model.
// Here we treat them the same and return the model's canonical link
return static_cast<tpelib::Link *>(&_model->GetCanonicalLink());
Expand Down
4 changes: 2 additions & 2 deletions tutorials.md.in
Original file line number Diff line number Diff line change
@@ -1,8 +1,8 @@
\page tutorials Tutorials

Welcome to the Ignition @IGN_DESIGNATION_CAP@ tutorials. These tutorials
Welcome to the Gazebo @IGN_DESIGNATION_CAP@ tutorials. These tutorials
will guide you through the process of understanding the capabilities of the
Ignition @IGN_DESIGNATION_CAP@ library and how to use the library effectively.
Gazebo @IGN_DESIGNATION_CAP@ library and how to use the library effectively.


**Contents**
Expand Down
16 changes: 8 additions & 8 deletions tutorials/01_intro.md
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,7 @@ Next Tutorial: \ref installation

## Motivation

Gazebo Physics (`ign-physics`) is a library component in Ignition, a set of
Gazebo Physics (`gz-physics`) is a library component in Gazebo, a set of
libraries designed to rapidly develop robot and simulation applications.
The main goal of the library is to provide an abstraction layer to various
physics engines, which gives end-users the ability to use multiple
Expand All @@ -17,18 +17,18 @@ Gazebo Physics extensibility and modularity.

## Overview

For a big picture of the Gazebo Physics operation in Ignition ecosystem, see
For a big picture of the Gazebo Physics operation in Gazebo ecosystem, see
the abstract diagram below:

@image html img/ign-libraries.png

In general, `ign-gazebo` is the main simulation library, in which its
In general, `gz-sim` is the main simulation library, in which its
functionalities are powered by many component libraries.
For example, its graphical drawing is supported by `ign-rendering` or simulated
sensors that are defined and implemented in `ign-sensors`.
In particular, this library `ign-physics` provides an abstract interface to
For example, its graphical drawing is supported by `gz-rendering` or simulated
sensors that are defined and implemented in `gz-sensors`.
In particular, this library `gz-physics` provides an abstract interface to
physics engines, which simulates dynamic transformations and interactions of
objects in `ign-gazebo`. The libraries are connected by C++ code.
objects in `gz-sim`. The libraries are connected by C++ code.

Gazebo Physics uses a plugin architecture where each physics engine is
implemented as a plugin that can be loaded at runtime.
Expand Down Expand Up @@ -82,5 +82,5 @@ to \ref physicsplugin

### Future roadmap

Gazebo Physics evolves closely with the Ignition ecosystem.
Gazebo Physics evolves closely with the Gazebo ecosystem.
For a broader overview, please visit [Gazebo's roadmap](https://gazebosim.org/about).
20 changes: 10 additions & 10 deletions tutorials/02_installation.md
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
\page installation Installation

These instructions are for installing only Gazebo Physics.
If you're interested in using all the Ignition libraries, check out this [Ignition installation](https://gazebosim.org/docs/dome/install).
If you're interested in using all the Gazebo libraries, check out this [Gazebo installation](https://gazebosim.org/docs/dome/install).

We recommend following the Binary Installation instructions to get up and running as quickly and painlessly as possible.

Expand Down Expand Up @@ -32,7 +32,7 @@ wget http://packages.osrfoundation.org/gazebo.key -O - | sudo apt-key add -

## Binary Installation

On Ubuntu systems, `apt-get` can be used to install `ignition-plugin`:
On Ubuntu systems, `apt-get` can be used to install `gz-plugin`:
```
sudo apt-get update
sudo apt-get install libignition-physics<#>-dev
Expand All @@ -56,7 +56,7 @@ Be sure to replace `<#>` with a number value, such as `1` or `2`, depending on w

3. Configure and build
```
cd ign-physics
cd gz-physics
mkdir build
cd build
cmake ..
Expand Down Expand Up @@ -110,7 +110,7 @@ Be sure to replace `<#>` with a number value, such as `1` or `2`, depending on w

3. Configure and build
```
cd ign-physics
cd gz-physics
mkdir build
cd build
cmake ..
Expand All @@ -129,14 +129,14 @@ Only [Trivial Physics Engine (TPE)](https://community.gazebosim.org/t/announcing

## Prerequisites

First, follow the [ign-cmake](https://github.com/gazebosim/gz-cmake) tutorial for installing Conda, Visual Studio, CMake, and other prerequisites, and also for creating a Conda environment.
First, follow the [gz-cmake](https://github.com/gazebosim/gz-cmake) tutorial for installing Conda, Visual Studio, CMake, and other prerequisites, and also for creating a Conda environment.

Navigate to ``condabin`` if necessary to use the ``conda`` command (i.e., if Conda is not in your `PATH` environment variable. You can find the location of ``condabin`` in Anaconda Prompt, ``where conda``).

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
```

## Binary Installation
Expand All @@ -152,7 +152,7 @@ which version you need.

This assumes you have created and activated a Conda environment while installing the Prerequisites.

1. Install Ignition dependencies:
1. Install Gazebo dependencies:

You can view available versions and their dependencies:
```
Expand All @@ -172,7 +172,7 @@ This assumes you have created and activated a Conda environment while installing

3. Configure and build
```
cd ign-physics
cd gz-physics
mkdir build
cd build
cmake .. -DBUILD_TESTING=OFF # Optionally, -DCMAKE_INSTALL_PREFIX=path\to\install
Expand Down Expand Up @@ -202,7 +202,7 @@ You can also generate the documentation from a clone of this repository by follo

3. Configure and build the documentation.
```
cd ign-physics
cd gz-physics
mkdir build
cd build
cmake ..
Expand Down
8 changes: 4 additions & 4 deletions tutorials/03_physics_plugins.md
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,7 @@ It allows users to select from multiple supported physics engines based on their
Its plugin interface loads physics engines with requested features at runtime.
It is also possible to integrate your own selected physics engine by writing a compatible plugin interface.

To get a more in-depth understanding of how the physics plugin works in Ignition, we will start with some high level concepts and definitions.
To get a more in-depth understanding of how the physics plugin works in Gazebo, we will start with some high level concepts and definitions.

<!-- TODO: add tutorial on how to write your own physics plugin -->

Expand All @@ -19,7 +19,7 @@ Conceptually, the physics plugin can be viewed from two sides of its interface:

Each physics engine provides access to different features implemented by the Gazebo Physics engine.
The interface is made possible through the \ref gz::plugin "Gazebo Plugin" library, which instantiates \ref gz::physics::Feature "Features" in \ref gz::physics::FeatureList "FeatureLists" and supplies pointers to the selected engine.
This "user side interface" makes the Gazebo Physics library "callable" from other Ignition libraries.
This "user side interface" makes the Gazebo Physics library "callable" from other Gazebo libraries.

The implementation side interface handles specific implementations of each `Feature`.
Depending on what external physics engine we are using (DART, TPE etc.), the interface might be different.
Expand All @@ -44,7 +44,7 @@ The implementation of the physics plugin revolves around four key elements.

This class defines the concept of a `Feature`, examples like `GetWorldFromEngine`, \ref gz::physics::GetEngineInfo "GetEngineInfo" etc.
There is a pre-defined list of features in Gazebo Physics.
They are implemented by using external physics engines' APIs to fulfill simulation needs requested by Ignition.
They are implemented by using external physics engines' APIs to fulfill simulation needs requested by Gazebo.

4. \ref gz::physics::FeatureList "FeatureList"

Expand Down Expand Up @@ -82,7 +82,7 @@ The source code for Dartsim plugin can be found in [Gazebo Physics repository](h

TPE ([Trivial Physics Engine](https://github.com/gazebosim/gz-physics/tree/ign-physics6/tpe)) is an open source library created by Open Robotics that enables fast, inexpensive kinematics simulation for entities at large scale.
It supports higher-order fleet dynamics without real physics (eg. gravity, force, constraint etc.) and multi-machine synchronization.
Ignition support for TPE targets [Citadel](https://gazebosim.org/docs/citadel) and onward releases.
Gazebo support for TPE targets [Citadel](https://gazebosim.org/docs/citadel) and onward releases.
The source code for TPE plugin can be found in [Gazebo Physics repository](https://github.com/gazebosim/gz-physics/tree/ign-physics6) under the `tpe/plugin` directory.

The following is a list of features supported by each physics engine to help users select one that fits their needs.
Expand Down
4 changes: 2 additions & 2 deletions tutorials/04-switching-physics-engines.md
Original file line number Diff line number Diff line change
Expand Up @@ -46,7 +46,7 @@ For additional environment variables that Gazebo finds other plugins
or resources, you can see them by:

```bash
ign gazebo -h
gz sim -h
```

## Pointing Gazebo to physics engines
Expand Down Expand Up @@ -80,7 +80,7 @@ Alternatively, you can choose a plugin from the command line using the
`--physics-engine` option, for example:

```bash
ign gazebo --physics-engine CustomEngine
gz sim --physics-engine CustomEngine
```

### From C++ API
Expand Down
4 changes: 2 additions & 2 deletions tutorials/05_plugin_loading.md
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,7 @@ plugin using \ref gz::physics "Gazebo Physics" API.

## Write a simple loader

We will use a simplified physics plugin example for this tutorial. Source code can be found at [ign-physics/examples](https://github.com/gazebosim/gz-physics/tree/main/examples/hello_world_loader) folder.
We will use a simplified physics plugin example for this tutorial. Source code can be found at [gz-physics/examples](https://github.com/gazebosim/gz-physics/tree/main/examples/hello_world_loader) folder.

First, create a workspace for the example plugin loader.

Expand Down Expand Up @@ -62,7 +62,7 @@ engine implementing a \ref gz::physics::FeaturePolicy "FeaturePolicy" (3D
### Setup CMakeLists.txt for CMake build

Now create a file named `CMakeLists.txt` with your favorite editor and add these
lines for finding `ign-plugin` and `ign-physics` dependencies in Citadel release.
lines for finding `gz-plugin` and `gz-physics` dependencies in Citadel release.
After that, add the executable pointing to our file and add linking library so
that `cmake` can compile it.

Expand Down
Loading

0 comments on commit 265b31b

Please sign in to comment.