Skip to content

Commit

Permalink
ign -> gz Namespace Migration : gz-physics (#348)
Browse files Browse the repository at this point in the history
* Update header guards

Signed-off-by: methylDragon <[email protected]>

* Migrate namespaces

Signed-off-by: methylDragon <[email protected]>

* Add migration line

Signed-off-by: methylDragon <[email protected]>

* Implement deprecation trick

Signed-off-by: methylDragon <[email protected]>

* Add deprecation test

Signed-off-by: methylDragon <[email protected]>

* Include config.hh

Signed-off-by: methylDragon <[email protected]>

* Use pragma deprecation message instead

Signed-off-by: methylDragon <[email protected]>

* Ticktock config macros

Signed-off-by: methylDragon <[email protected]>

* Mention gz in migration

Signed-off-by: methylDragon <[email protected]>

* Migrate includes to gz

Signed-off-by: methylDragon <[email protected]>

* Update config.hh

Signed-off-by: methylDragon <[email protected]>

* Migrate Export.hh macros and deprecated test

Signed-off-by: methylDragon <[email protected]>

* Greedy macro migration

Signed-off-by: methylDragon <[email protected]>

* Migrate github links

Signed-off-by: methylDragon <[email protected]>

* Migrate user-facing Ignition to Gazebo

Signed-off-by: methylDragon <[email protected]>

* Migrate install dirs

Signed-off-by: methylDragon <[email protected]>

* Migrate gz-common logging calls

Signed-off-by: methylDragon <[email protected]>

* Revert plugin names to ignition-gazebo

Signed-off-by: methylDragon <[email protected]>

* Migrate "ignition.msgs" -> "gz.msgs"

Signed-off-by: methylDragon <[email protected]>

* Include config.hh in recursive directories and <lib>.hh

Signed-off-by: methylDragon <[email protected]>

* `Gazebo Robotics` -> `Gazebo`

Signed-off-by: methylDragon <[email protected]>

* `ignitionrobotics` -> `gazebosim`

Signed-off-by: methylDragon <[email protected]>

* Rollback osrf-migration.github.io migrations

Signed-off-by: methylDragon <[email protected]>

* Migrate Ignition's -> Gazebo's

Signed-off-by: methylDragon <[email protected]>

* Wording changes

Signed-off-by: methylDragon <[email protected]>

* Migrate  `igndbg` -> `gzdbg`

Signed-off-by: methylDragon <[email protected]>
  • Loading branch information
methylDragon authored May 29, 2022
1 parent ce03083 commit 0cf0e89
Show file tree
Hide file tree
Showing 347 changed files with 2,856 additions and 2,705 deletions.
6 changes: 3 additions & 3 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,7 @@ ign_configure_project(
# Set project-specific options
#============================================================================

option(ENABLE_PROFILER "Enable Ignition Profiler" FALSE)
option(ENABLE_PROFILER "Enable Gazebo Profiler" FALSE)

if(ENABLE_PROFILER)
add_definitions("-DIGN_PROFILER_ENABLE=1")
Expand Down Expand Up @@ -89,10 +89,10 @@ ign_find_package(IgnBullet

message(STATUS "-------------------------------------------\n")

set(IGNITION_PHYSICS_RESOURCE_DIR "${CMAKE_SOURCE_DIR}/resources")
set(GZ_PHYSICS_RESOURCE_DIR "${CMAKE_SOURCE_DIR}/resources")

# Plugin install dirs
set(IGNITION_PHYSICS_ENGINE_INSTALL_DIR
set(GZ_PHYSICS_ENGINE_INSTALL_DIR
${CMAKE_INSTALL_PREFIX}/${IGN_LIB_INSTALL_DIR}/ign-${IGN_DESIGNATION}-${PROJECT_VERSION_MAJOR}/engine-plugins
)

Expand Down
2 changes: 1 addition & 1 deletion CONTRIBUTING.md
Original file line number Diff line number Diff line change
@@ -1 +1 @@
See the [Ignition Robotics contributing guide](https://ignitionrobotics.org/docs/all/contributing).
See the [Gazebo contributing guide](https://gazebosim.org/docs/all/contributing).
448 changes: 224 additions & 224 deletions Changelog.md

Large diffs are not rendered by default.

21 changes: 15 additions & 6 deletions Migration.md
Original file line number Diff line number Diff line change
Expand Up @@ -5,13 +5,22 @@ Deprecated code produces compile-time warnings. These warning serve as
notification to users that their code should be upgraded. The next major
release will remove the deprecated code.

## Ignition Physics 4.X to 5.X
## Gazebo Physics 5.X to 6.X

### Deprecation

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

1. Header files under `ignition/...` are deprecated and will be removed in future versions.
Use `gz/...` instead.

## Gazebo Physics 4.X to 5.X

### Modifications

1. Depends on sdformat12.

## Ignition Physics 4.1 to 4.2
## Gazebo Physics 4.1 to 4.2

### Additions

Expand All @@ -21,15 +30,15 @@ release will remove the deprecated code.

1. TPE: Capsule and Ellipsoid shapes added.

## Ignition Physics 3.X to 4.X
## Gazebo Physics 3.X to 4.X

### Modifications

1. Depends on ignition-utils1.

1. Depends on sdformat11.

1. `ignition::physics::FindFreeGroupFeature::Implementation::GetFreeGroupCanonicalLink`
1. `ignition::physics::FindFreeGroupFeature::Implementation::GetFreeGroupCanonicalLink`
has been replaced by `ignition::physics::FindFreeGroupFeature::Implementation::GetFreeGroupRootLink`.

### Deprecations
Expand All @@ -38,13 +47,13 @@ release will remove the deprecated code.
+ **Deprecation:** `Identity ignition::physics::FreeGroup::CanonicalLink(const Identity &_groupID)`
+ **Replacement:** `Identity ignition::physics::FreeGroup::RootLink(const Identity &_groupID)`

## Ignition Physics 2.X to 3.X
## Gazebo Physics 2.X to 3.X

### Modifications

1. Depends on sdformat10.

## Ignition Physics 1.X to 2.X
## Gazebo Physics 1.X to 2.X

### Modifications

Expand Down
32 changes: 16 additions & 16 deletions README.md
Original file line number Diff line number Diff line change
@@ -1,21 +1,21 @@
# Ignition Physics : Physics classes and functions for robot applications
# Gazebo Physics : Physics classes and functions for robot applications

**Maintainer:** scpeters AT openrobotics DOT org

[![GitHub open issues](https://img.shields.io/github/issues-raw/ignitionrobotics/ign-physics.svg)](https://github.com/ignitionrobotics/ign-physics/issues)
[![GitHub open pull requests](https://img.shields.io/github/issues-pr-raw/ignitionrobotics/ign-physics.svg)](https://github.com/ignitionrobotics/ign-physics/pulls)
[![GitHub open issues](https://img.shields.io/github/issues-raw/gazebosim/gz-physics.svg)](https://github.com/gazebosim/gz-physics/issues)
[![GitHub open pull requests](https://img.shields.io/github/issues-pr-raw/gazebosim/gz-physics.svg)](https://github.com/gazebosim/gz-physics/pulls)
[![Discourse topics](https://img.shields.io/discourse/https/community.gazebosim.org/topics.svg)](https://community.gazebosim.org)
[![Hex.pm](https://img.shields.io/hexpm/l/plug.svg)](https://www.apache.org/licenses/LICENSE-2.0)

Build | Status
-- | --
Test coverage | [![codecov](https://codecov.io/gh/ignitionrobotics/ign-physics/branch/ign-physics6/graph/badge.svg)](https://codecov.io/gh/ignitionrobotics/ign-physics)
Test coverage | [![codecov](https://codecov.io/gh/gazebosim/gz-physics/branch/ign-physics6/graph/badge.svg)](https://codecov.io/gh/gazebosim/gz-physics)
Ubuntu Focal | [![Build Status](https://build.osrfoundation.org/buildStatus/icon?job=ignition_physics-ci-ign-physics6-focal-amd64)](https://build.osrfoundation.org/job/ignition_physics-ci-ign-physics6-focal-amd64)
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)

Ignition Physics, a component of [Ignition
Robotics](https://ignitionrobotics.org), provides an abstract physics interface
Gazebo Physics, a component of [Ignition
Robotics](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 @@ -43,7 +43,7 @@ designed to support simulation and rapid development of robot applications.
Many physics simulation software libraries have been designed for different
applications (gaming, robotics, science) and with different features
(rigid or deformable contact, 2d or 3d).
Ignition Physics is designed on the premise that there is not a single physics
Gazebo Physics is designed on the premise that there is not a single physics
engine that is universally best for all simulation contexts.
It should be possible to support a different set of features
for each physics engine according to its capabilities.
Expand All @@ -52,7 +52,7 @@ based on its context.

# Features

Ignition Physics provides the following functionality:
Gazebo Physics provides the following functionality:

* Granular definition of physics engine features as optional API's.
* Plugin interface for loading physics engines with requested features
Expand All @@ -70,15 +70,15 @@ Ignition Physics provides the following functionality:

# Install

See the [installation tutorial](https://ignitionrobotics.org/api/physics/5.0/installation.html).
See the [installation tutorial](https://gazebosim.org/api/physics/5.0/installation.html).

# Usage

Please refer to the [examples directory](https://github.com/ignitionrobotics/ign-physics/raw/ign-physics6/examples/).
Please refer to the [examples directory](https://github.com/gazebosim/gz-physics/raw/ign-physics6/examples/).

# Documentation

API and tutorials can be found at [https://ignitionrobotics.org/libs/physics](https://ignitionrobotics.org/libs/physics).
API and tutorials can be found at [https://gazebosim.org/libs/physics](https://gazebosim.org/libs/physics).

You can also generate the documentation from a clone of this repository by following these steps.

Expand All @@ -91,7 +91,7 @@ You can also generate the documentation from a clone of this repository by follo
2. Clone the repository
```
git clone https://github.com/ignitionrobotics/ign-physics -b ign-physics6
git clone https://github.com/gazebosim/gz-physics -b ign-physics6
```
3. Configure and build the documentation.
Expand Down Expand Up @@ -155,17 +155,17 @@ ign-physics
```
# Contributing
Please see the [contribution guide](https://ignitionrobotics.org/docs/all/contributing).
Please see the [contribution guide](https://gazebosim.org/docs/all/contributing).
# Code of Conduct
Please see
[CODE\_OF\_CONDUCT.md](https://github.com/ignitionrobotics/ign-gazebo/blob/main/CODE_OF_CONDUCT.md).
[CODE\_OF\_CONDUCT.md](https://github.com/gazebosim/gz-sim/blob/main/CODE_OF_CONDUCT.md).
# Versioning
This library uses [Semantic Versioning](https://semver.org/). Additionally, this library is part of the [Ignition Robotics project](https://ignitionrobotics.org) which periodically releases a versioned set of compatible and complimentary libraries. See the [Ignition Robotics website](https://ignitionrobotics.org) for version and release information.
This library uses [Semantic Versioning](https://semver.org/). Additionally, this library is part of the [Gazebo project](https://gazebosim.org) which periodically releases a versioned set of compatible and complimentary libraries. See the [Gazebo website](https://gazebosim.org) for version and release information.
# License
This library is licensed under [Apache 2.0](https://www.apache.org/licenses/LICENSE-2.0). See also the [LICENSE](https://github.com/ignitionrobotics/ign-physics/blob/main/LICENSE) file.
This library is licensed under [Apache 2.0](https://www.apache.org/licenses/LICENSE-2.0). See also the [LICENSE](https://github.com/gazebosim/gz-physics/blob/main/LICENSE) file.
2 changes: 1 addition & 1 deletion api.md.in
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
## Ignition @IGN_DESIGNATION_CAP@

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

## License
Expand Down
12 changes: 6 additions & 6 deletions bullet/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,7 @@ target_link_libraries(${bullet_plugin}
ignition-math${IGN_MATH_VER}::eigen3)

# Note that plugins are currently being installed in 2 places: /lib and the engine-plugins dir
install(TARGETS ${bullet_plugin} DESTINATION ${IGNITION_PHYSICS_ENGINE_INSTALL_DIR})
install(TARGETS ${bullet_plugin} DESTINATION ${GZ_PHYSICS_ENGINE_INSTALL_DIR})

# Install redirection headers
install(
Expand All @@ -41,14 +41,14 @@ if (WIN32)
# disable MSVC inherit via dominance warning
target_compile_options(${bullet_plugin} PUBLIC "/wd4250")
INSTALL(CODE "EXECUTE_PROCESS(COMMAND ${CMAKE_COMMAND} -E copy
${IGNITION_PHYSICS_ENGINE_INSTALL_DIR}\/${versioned}
${IGNITION_PHYSICS_ENGINE_INSTALL_DIR}\/${unversioned})")
${GZ_PHYSICS_ENGINE_INSTALL_DIR}\/${versioned}
${GZ_PHYSICS_ENGINE_INSTALL_DIR}\/${unversioned})")
else()
EXECUTE_PROCESS(COMMAND ${CMAKE_COMMAND} -E create_symlink ${versioned} ${unversioned})
INSTALL(FILES ${PROJECT_BINARY_DIR}/${unversioned} DESTINATION ${IGNITION_PHYSICS_ENGINE_INSTALL_DIR})
INSTALL(FILES ${PROJECT_BINARY_DIR}/${unversioned} DESTINATION ${GZ_PHYSICS_ENGINE_INSTALL_DIR})
endif()
EXECUTE_PROCESS(COMMAND ${CMAKE_COMMAND} -E create_symlink ${versioned} ${unversioned})
INSTALL(FILES ${PROJECT_BINARY_DIR}/${unversioned} DESTINATION ${IGNITION_PHYSICS_ENGINE_INSTALL_DIR})
INSTALL(FILES ${PROJECT_BINARY_DIR}/${unversioned} DESTINATION ${GZ_PHYSICS_ENGINE_INSTALL_DIR})

# Testing
ign_build_tests(
Expand All @@ -67,7 +67,7 @@ foreach(test ${tests})
target_compile_definitions(${test} PRIVATE
"bullet_plugin_LIB=\"$<TARGET_FILE:${bullet_plugin}>\""
"TEST_WORLD_DIR=\"${CMAKE_CURRENT_SOURCE_DIR}/worlds/\""
"IGNITION_PHYSICS_RESOURCE_DIR=\"${IGNITION_PHYSICS_RESOURCE_DIR}\"")
"GZ_PHYSICS_RESOURCE_DIR=\"${GZ_PHYSICS_RESOURCE_DIR}\"")

endforeach()

Expand Down
1 change: 1 addition & 0 deletions bullet/include/ignition/physics/bullet-plugin/Export.hh
Original file line number Diff line number Diff line change
Expand Up @@ -16,3 +16,4 @@
*/

#include <gz/physics/bullet-plugin/Export.hh>
#include <ignition/physics/config.hh>
16 changes: 8 additions & 8 deletions bullet/src/Base.hh
Original file line number Diff line number Diff line change
Expand Up @@ -15,8 +15,8 @@
*
*/

#ifndef IGNITION_PHYSICS_BULLET_BASE_HH_
#define IGNITION_PHYSICS_BULLET_BASE_HH_
#ifndef GZ_PHYSICS_BULLET_BASE_HH_
#define GZ_PHYSICS_BULLET_BASE_HH_

#include <btBulletDynamicsCommon.h>
#include <Eigen/Geometry>
Expand All @@ -28,11 +28,11 @@
#include <vector>
#include <map>

#include <ignition/common/Console.hh>
#include <ignition/physics/Implements.hh>
#include <ignition/math/eigen3/Conversions.hh>
#include <gz/common/Console.hh>
#include <gz/physics/Implements.hh>
#include <gz/math/eigen3/Conversions.hh>

namespace ignition {
namespace gz {
namespace physics {
namespace bullet {

Expand Down Expand Up @@ -106,7 +106,7 @@ struct JointInfo
std::size_t parentLinkId;
// cppcheck-suppress unusedStructMember
int constraintType;
ignition::math::Vector3d axis;
gz::math::Vector3d axis;
};

inline btMatrix3x3 convertMat(Eigen::Matrix3d mat)
Expand Down Expand Up @@ -261,6 +261,6 @@ class Base : public Implements3d<FeatureList<Feature>>

} // namespace bullet
} // namespace physics
} // namespace ignition
} // namespace gz

#endif
4 changes: 2 additions & 2 deletions bullet/src/EntityManagementFeatures.cc
Original file line number Diff line number Diff line change
Expand Up @@ -24,7 +24,7 @@
#include "EntityManagementFeatures.hh"
#include <BulletCollision/Gimpact/btGImpactCollisionAlgorithm.h>

namespace ignition {
namespace gz {
namespace physics {
namespace bullet {

Expand Down Expand Up @@ -170,4 +170,4 @@ bool EntityManagementFeatures::RemoveModelByName(

} // namespace bullet
} // namespace physics
} // namespace ignition
} // namespace gz
18 changes: 9 additions & 9 deletions bullet/src/EntityManagementFeatures.hh
Original file line number Diff line number Diff line change
Expand Up @@ -15,23 +15,23 @@
*
*/

#ifndef IGNITION_PHYSICS_BULLET_SRC_GETENTITIESFEATURE_HH_
#define IGNITION_PHYSICS_BULLET_SRC_GETENTITIESFEATURE_HH_
#ifndef GZ_PHYSICS_BULLET_SRC_GETENTITIESFEATURE_HH_
#define GZ_PHYSICS_BULLET_SRC_GETENTITIESFEATURE_HH_

#include <string>

#include <ignition/physics/ConstructEmpty.hh>
#include <ignition/physics/GetEntities.hh>
#include <ignition/physics/RemoveEntities.hh>
#include <ignition/physics/Implements.hh>
#include <gz/physics/ConstructEmpty.hh>
#include <gz/physics/GetEntities.hh>
#include <gz/physics/RemoveEntities.hh>
#include <gz/physics/Implements.hh>

#include "Base.hh"

namespace ignition {
namespace gz {
namespace physics {
namespace bullet {

struct EntityManagementFeatureList : ignition::physics::FeatureList<
struct EntityManagementFeatureList : gz::physics::FeatureList<
RemoveModelFromWorld,
ConstructEmptyWorldFeature
> { };
Expand Down Expand Up @@ -60,6 +60,6 @@ class EntityManagementFeatures :

} // namespace bullet
} // namespace physics
} // namespace ignition
} // namespace gz

#endif
20 changes: 10 additions & 10 deletions bullet/src/EntityManagement_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -17,33 +17,33 @@

#include <gtest/gtest.h>

#include <ignition/plugin/Loader.hh>
#include <gz/plugin/Loader.hh>

#include <ignition/math/eigen3/Conversions.hh>
#include <gz/math/eigen3/Conversions.hh>

#include <ignition/physics/RequestEngine.hh>
#include <gz/physics/RequestEngine.hh>

#include "EntityManagementFeatures.hh"
#include "JointFeatures.hh"

// ToDo(Lobotuerk): Once more tests are added into this plugin, delete line 35
// and uncomment 31~33 adding another feature list to clear the warn.
// struct TestFeatureList : ignition::physics::FeatureList<
// ignition::physics::bullet::EntityManagementFeatureList
// struct TestFeatureList : gz::physics::FeatureList<
// gz::physics::bullet::EntityManagementFeatureList
// > { };

using TestFeatureList = ignition::physics::bullet::EntityManagementFeatureList;
using TestFeatureList = gz::physics::bullet::EntityManagementFeatureList;

TEST(EntityManagement_TEST, ConstructEmptyWorld)
{
ignition::plugin::Loader loader;
gz::plugin::Loader loader;
loader.LoadLib(bullet_plugin_LIB);

ignition::plugin::PluginPtr bullet =
loader.Instantiate("ignition::physics::bullet::Plugin");
gz::plugin::PluginPtr bullet =
loader.Instantiate("gz::physics::bullet::Plugin");

auto engine =
ignition::physics::RequestEngine3d<TestFeatureList>::From(bullet);
gz::physics::RequestEngine3d<TestFeatureList>::From(bullet);
ASSERT_NE(nullptr, engine);

auto world = engine->ConstructEmptyWorld("empty world");
Expand Down
4 changes: 2 additions & 2 deletions bullet/src/FreeGroupFeatures.cc
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,7 @@

#include "FreeGroupFeatures.hh"

namespace ignition {
namespace gz {
namespace physics {
namespace bullet {

Expand Down Expand Up @@ -81,4 +81,4 @@ void FreeGroupFeatures::SetFreeGroupWorldPose(

} // namespace bullet
} // namespace physics
} // namespace ignition
} // namespace gz
Loading

0 comments on commit 0cf0e89

Please sign in to comment.