Skip to content

Commit

Permalink
ign -> gz Namespace Migration : gz-sensors (#226)
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]>

* Migrate inline namespaces

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

* Mention gz headers 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, deprecated test, and remove plugin macros

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

* Migrate more namespaces

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 gz-common logging calls

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

* Revert plugin names to ignition-gazebo

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

* Revert migration for fuel.ignitionrobotics.org

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

* Rollback osrf-migration.github.io migrations

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 d60d832 commit 55c5666
Show file tree
Hide file tree
Showing 160 changed files with 2,028 additions and 1,902 deletions.
4 changes: 1 addition & 3 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,7 @@ ign_configure_project(
#============================================================================
set (DRI_TESTS TRUE CACHE BOOL "True to enable DRI tests")

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 @@ -91,8 +91,6 @@ set(IGN_MSGS_VER ${ignition-msgs9_VERSION_MAJOR})
ign_find_package(sdformat13 REQUIRED)
set(SDF_VER ${sdformat13_VERSION_MAJOR})

set(IGN_SENSORS_PLUGIN_PATH ${CMAKE_INSTALL_PREFIX}/${CMAKE_INSTALL_LIBDIR})

#============================================================================
# Configure the build
#============================================================================
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).
260 changes: 130 additions & 130 deletions Changelog.md

Large diffs are not rendered by default.

43 changes: 24 additions & 19 deletions Migration.md
Original file line number Diff line number Diff line change
Expand Up @@ -5,23 +5,30 @@ 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 Sensors 6.0.1 to 6.1.0
## Gazebo Sensors 6.X to 7.X

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 Sensors 6.0.1 to 6.1.0

### Modifications

1. Point Cloud Density flag (**is_dense** from GpuLidarSensor) is set to **false**
if invalid points (NaN or +/-INF) are found, and **true** otherwise.


## Ignition Sensors 5.X to 6.X
## Gazebo Sensors 5.X to 6.X

1. Sensors aren't loaded as plugins anymore. Instead, downstream libraries must
link to the library of the sensor they're interested in, and instantiate
new sensors knowing their type. For example:

* `auto camera = std::make_unique<ignition::sensors::CameraSensor>();`
* `auto camera = sensorFactory.CreateSensor<ignition::sensors::CameraSensor>(_sdf);`
* `auto camera = manager.CreateSensor<ignition::sensors::CameraSensor>(_sdf);`
* `auto camera = std::make_unique<gz::sensors::CameraSensor>();`
* `auto camera = sensorFactory.CreateSensor<gz::sensors::CameraSensor>(_sdf);`
* `auto camera = manager.CreateSensor<gz::sensors::CameraSensor>(_sdf);`

1. **include/sensors/SensorFactory.hh**
+ ***Deprecation*** SensorPlugin
Expand All @@ -45,25 +52,25 @@ release will remove the deprecated code.
+ ***Deprecation*** void AddPluginPaths(const std::string &)
+ ***Replacement*** None; see above.

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

1. **include/sensors/Sensor.hh**
+ ***Deprecation*** virtual bool Update(const ignition::common::Time &)
+ ***Deprecation*** virtual bool Update(const gz::common::Time &)
+ ***Replacement*** virtual bool Update(const std::chrono::steady_clock::duration &)
+ ***Deprecation*** virtual bool Update(const ignition::common::Time &, const bool)
+ ***Deprecation*** virtual bool Update(const gz::common::Time &, const bool)
+ ***Replacement*** virtual bool Update(const std::chrono::steady_clock::duration &, const bool)
+ ***Deprecation*** ignition::common::Time NextUpdateTime() const
+ ***Deprecation*** gz::common::Time NextUpdateTime() const
+ ***Replacement*** std::chrono::steady_clock::duration NextDataUpdateTime() const

1. **include/sensors/Manager.hh**
+ ***Deprecation*** void RunOnce(const ignition::common::Time &, bool);
+ ***Deprecation*** void RunOnce(const gz::common::Time &, bool);
+ ***Replacement*** void RunOnce(const std::chrono::steady_clock::duration &, bool)

1. **include/sensors/Lidar.hh**
+ ***Deprecation*** virtual bool PublishLidarScan(const ignition::common::Time &)
+ ***Deprecation*** virtual bool PublishLidarScan(const gz::common::Time &)
+ ***Replacement*** virtual bool PublishLidarScan(const std::chrono::steady_clock::duration &)

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

### Additions

Expand All @@ -81,7 +88,7 @@ and header files. Similarly, noise models for rendering sensors need be created
using the new ImageNoiseFactory class instead of NoiseFactory by including
ImageNoise.hh.

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

### Additions

Expand All @@ -100,20 +107,18 @@ ImageNoise.hh.
+ ***Replacement*** virtual void Load(const sdf::Noise &_sdf)

1. **include/sensors/Events.hh**
+ ***Deprecation:*** public: static ignition::common::ConnectionPtr ConnectSceneChangeCallback(std::function<void(const ignition::rendering::ScenePtr &)>)
+ ***Deprecation:*** public: static gz::common::ConnectionPtr ConnectSceneChangeCallback(std::function<void(const gz::rendering::ScenePtr &)>)
+ ***Replacement:*** RenderingEvents::ConnectSceneChangeCallback

1. **include/sensors/Manager.hh**
+ ***Deprecation:*** public: bool Init(ignition::rendering::ScenePtr);
+ ***Deprecation:*** public: bool Init(gz::rendering::ScenePtr);
+ ***Replacement:*** RenderingSensor::SetScene
+ ***Deprecation:*** public: void SetRenderingScene(ignition::rendering::ScenePtr
+ ***Deprecation:*** public: void SetRenderingScene(gz::rendering::ScenePtr
+ ***Replacement:*** RenderingSensor::SetScene

+ ***Deprecation:*** public: ignition::rendering::ScenePtr RenderingScene() const
+ ***Deprecation:*** public: gz::rendering::ScenePtr RenderingScene() const
+ ***Replacement:*** RenderingSensor::Scene()

1. **include/sensors/Noise.hh**
+ ***Deprecation:*** public: virtual void SetCamera(rendering::CameraPtr)
+ ***Replacement:*** TODO (to be implemented in ImageGaussianNoiseModel)


2 changes: 1 addition & 1 deletion NEWS
Original file line number Diff line number Diff line change
@@ -1 +1 @@
http://ignitionrobotics.org
http://gazebosim.org
28 changes: 14 additions & 14 deletions README.md
Original file line number Diff line number Diff line change
@@ -1,22 +1,22 @@
# Ignition Sensors : Sensor models for simulation
# Gazebo Sensors : Sensor models for simulation

**Maintainer:** ichen AT openrobotics DOT org

[![GitHub open issues](https://img.shields.io/github/issues-raw/ignitionrobotics/ign-sensors.svg)](https://github.com/ignitionrobotics/ign-sensors/issues)
[![GitHub open pull requests](https://img.shields.io/github/issues-pr-raw/ignitionrobotics/ign-sensors.svg)](https://github.com/ignitionrobotics/ign-sensors/pulls)
[![GitHub open issues](https://img.shields.io/github/issues-raw/gazebosim/gz-sensors.svg)](https://github.com/gazebosim/gz-sensors/issues)
[![GitHub open pull requests](https://img.shields.io/github/issues-pr-raw/gazebosim/gz-sensors.svg)](https://github.com/gazebosim/gz-sensors/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-sensors/branch/main/graph/badge.svg)](https://codecov.io/gh/ignitionrobotics/ign-sensors)
Test coverage | [![codecov](https://codecov.io/gh/gazebosim/gz-sensors/branch/main/graph/badge.svg)](https://codecov.io/gh/gazebosim/gz-sensors)
Ubuntu Focal | [![Build Status](https://build.osrfoundation.org/buildStatus/icon?job=ignition_sensors-ci-main-focal-amd64)](https://build.osrfoundation.org/job/ignition_sensors-ci-main-focal-amd64)
Homebrew | [![Build Status](https://build.osrfoundation.org/buildStatus/icon?job=ignition_sensors-ci-main-homebrew-amd64)](https://build.osrfoundation.org/job/ignition_sensors-ci-main-homebrew-amd64)
Windows | [![Build Status](https://build.osrfoundation.org/job/ign_sensors-ci-win/badge/icon)](https://build.osrfoundation.org/job/ign_sensors-ci-win/)

Ignition Sensors, a component of [Ignition
Robotics](https://ignitionrobotics.org), provides numerous sensor models
designed to generate realistic data from simulation environments. Ignition Sensors is used in conjunction with [Ignition Libraries](https://ignitionrobotics/libs), and especially relies on the rendering capabilities from [Ignition Rendering](https://ignitionrobotics.org/libs/rendering) and physics simulation from [Ignition Physics](https://ignitionrobotics.org/libs/physics).
Gazebo Sensors, a component of [Ignition
Robotics](https://gazebosim.org), provides numerous sensor models
designed to generate realistic data from simulation environments. Gazebo Sensors is used in conjunction with [Gazebo Libraries](https://gazebosim/libs), and especially relies on the rendering capabilities from [Gazebo Rendering](https://gazebosim.org/libs/rendering) and physics simulation from [Gazebo Physics](https://gazebosim.org/libs/physics).

# Table of Contents

Expand Down Expand Up @@ -46,18 +46,18 @@ designed to generate realistic data from simulation environments. Ignition Senso

# Features

Ignition Sensors provides a set of sensors models that can be
Gazebo Sensors provides a set of sensors models that can be
configured at run time to mimic specific real-world sensors. A noise model
is also provided that can be used to introduce Gaussian or custom noise
models into sensor streams.

# Install

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

# Usage

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

# Folder Structure

Expand All @@ -79,17 +79,17 @@ Refer to the following table for information about important directories and fil

# 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-sensors/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-sensors/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
24 changes: 12 additions & 12 deletions examples/custom_sensor/Odometer.cc
Original file line number Diff line number Diff line change
Expand Up @@ -30,23 +30,23 @@ using namespace custom;
//////////////////////////////////////////////////
bool Odometer::Load(const sdf::Sensor &_sdf)
{
auto type = ignition::sensors::customType(_sdf);
auto type = gz::sensors::customType(_sdf);
if ("odometer" != type)
{
ignerr << "Trying to load [odometer] sensor, but got type ["
gzerr << "Trying to load [odometer] sensor, but got type ["
<< type << "] instead." << std::endl;
return false;
}

// Load common sensor params
ignition::sensors::Sensor::Load(_sdf);
gz::sensors::Sensor::Load(_sdf);

// Advertise topic where data will be published
this->pub = this->node.Advertise<ignition::msgs::Double>(this->Topic());
this->pub = this->node.Advertise<gz::msgs::Double>(this->Topic());

if (!_sdf.Element()->HasElement("ignition:odometer"))
{
igndbg << "No custom configuration for [" << this->Topic() << "]"
gzdbg << "No custom configuration for [" << this->Topic() << "]"
<< std::endl;
return true;
}
Expand All @@ -56,16 +56,16 @@ bool Odometer::Load(const sdf::Sensor &_sdf)

if (!customElem->HasElement("noise"))
{
igndbg << "No noise for [" << this->Topic() << "]" << std::endl;
gzdbg << "No noise for [" << this->Topic() << "]" << std::endl;
return true;
}

sdf::Noise noiseSdf;
noiseSdf.Load(customElem->GetElement("noise"));
this->noise = ignition::sensors::NoiseFactory::NewNoiseModel(noiseSdf);
this->noise = gz::sensors::NoiseFactory::NewNoiseModel(noiseSdf);
if (nullptr == this->noise)
{
ignerr << "Failed to load noise." << std::endl;
gzerr << "Failed to load noise." << std::endl;
return false;
}

Expand All @@ -75,8 +75,8 @@ bool Odometer::Load(const sdf::Sensor &_sdf)
//////////////////////////////////////////////////
bool Odometer::Update(const std::chrono::steady_clock::duration &_now)
{
ignition::msgs::Double msg;
*msg.mutable_header()->mutable_stamp() = ignition::msgs::Convert(_now);
gz::msgs::Double msg;
*msg.mutable_header()->mutable_stamp() = gz::msgs::Convert(_now);
auto frame = msg.mutable_header()->add_data();
frame->set_key("frame_id");
frame->add_value(this->Name());
Expand All @@ -92,7 +92,7 @@ bool Odometer::Update(const std::chrono::steady_clock::duration &_now)
}

//////////////////////////////////////////////////
void Odometer::NewPosition(const ignition::math::Vector3d &_pos)
void Odometer::NewPosition(const gz::math::Vector3d &_pos)
{
if (!isnan(this->prevPos.X()))
{
Expand All @@ -102,7 +102,7 @@ void Odometer::NewPosition(const ignition::math::Vector3d &_pos)
}

//////////////////////////////////////////////////
const ignition::math::Vector3d &Odometer::Position() const
const gz::math::Vector3d &Odometer::Position() const
{
return this->prevPos;
}
Expand Down
14 changes: 7 additions & 7 deletions examples/custom_sensor/Odometer.hh
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,7 @@ namespace custom
{
/// \brief Example sensor that publishes the total distance travelled by a
/// robot, with noise.
class Odometer : public ignition::sensors::Sensor
class Odometer : public gz::sensors::Sensor
{
/// \brief Load the sensor with SDF parameters.
/// \param[in] _sdf SDF Sensor parameters.
Expand All @@ -41,27 +41,27 @@ namespace custom
/// \brief Set the current postiion of the robot, so the odometer can
/// calculate the distance travelled.
/// \param[in] _pos Current position in world coordinates.
public: void NewPosition(const ignition::math::Vector3d &_pos);
public: void NewPosition(const gz::math::Vector3d &_pos);

/// \brief Get the latest world postiion of the robot.
/// \return The latest position given to the odometer.
public: const ignition::math::Vector3d &Position() const;
public: const gz::math::Vector3d &Position() const;

/// \brief Previous position of the robot.
private: ignition::math::Vector3d prevPos{std::nan(""), std::nan(""),
private: gz::math::Vector3d prevPos{std::nan(""), std::nan(""),
std::nan("")};

/// \brief Latest total distance.
private: double totalDistance{0.0};

/// \brief Noise that will be applied to the sensor data
private: ignition::sensors::NoisePtr noise{nullptr};
private: gz::sensors::NoisePtr noise{nullptr};

/// \brief Node for communication
private: ignition::transport::Node node;
private: gz::transport::Node node;

/// \brief Publishes sensor data
private: ignition::transport::Node::Publisher pub;
private: gz::transport::Node::Publisher pub;
};
}

Expand Down
8 changes: 4 additions & 4 deletions examples/custom_sensor/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -19,8 +19,8 @@ This will generate a shared library with the sensor called `libodometer`.

## Use

This sensor can be used with Ignition Gazebo, or with any downstream
application that uses the Ignition Sensors API. Listed here are two ways of
This sensor can be used with Gazebo, or with any downstream
application that uses the Gazebo Sensors API. Listed here are two ways of
testing this sensor, one with Gazebo and one with a custom program.

### With a custom program
Expand All @@ -29,10 +29,10 @@ The [loop_sensor](../loop_sensor) example can be used to load an SDF file with
configuration for this sensor and run it in a loop. See that example's
instructions.

### With Ignition Gazebo
### With Gazebo

The
[custom_sensor_system](https://github.com/ignitionrobotics/ign-gazebo/tree/main/examples/plugin/custom_sensor_system)
[custom_sensor_system](https://github.com/gazebosim/gz-sim/tree/main/examples/plugin/custom_sensor_system)
example can be used to load this sensor into Gazebo and update it during the
simulation.

2 changes: 1 addition & 1 deletion examples/imu_noise/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
cmake_minimum_required(VERSION 3.5 FATAL_ERROR)
project(ignition-sensors-noise-demo)

# Find the Ignition Libraries used directly by the example
# Find the Gazebo Libraries used directly by the example
find_package(ignition-sensors7 REQUIRED)

add_executable(sensor_noise main.cc)
Expand Down
2 changes: 1 addition & 1 deletion examples/imu_noise/main.cc
Original file line number Diff line number Diff line change
Expand Up @@ -115,7 +115,7 @@ generateSamples(size_t _nSamples, const NoiseParameters& _params)
noise.SetDynamicBiasCorrelationTime(_params.dynamicBiasCorrelationTime);

const double dt = 1.0 / _params.sampleFreq;
auto model = ignition::sensors::NoiseFactory::NewNoiseModel(noise);
auto model = gz::sensors::NoiseFactory::NewNoiseModel(noise);
for (size_t ii = 0; ii < _nSamples ; ++ii) {
samples.push_back(model->Apply(0.0, dt));
}
Expand Down
Loading

0 comments on commit 55c5666

Please sign in to comment.