Skip to content

Commit

Permalink
ign -> gz Migrate Ignition Headers : gz-sensors (#260)
Browse files Browse the repository at this point in the history
* Migrate headers

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

* Add redirection headers

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

* Migrate include statements

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

* Leave ignition as primary in headers to fix ABI

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

* Update ignition names

Signed-off-by: Nate Koenig <[email protected]>

* tweaks

Signed-off-by: Nate Koenig <[email protected]>

Signed-off-by: methylDragon <[email protected]>
Signed-off-by: Nate Koenig <[email protected]>
Co-authored-by: Nate Koenig <[email protected]>
  • Loading branch information
methylDragon and Nate Koenig authored Nov 30, 2022
1 parent 5a82b76 commit 36f5d84
Show file tree
Hide file tree
Showing 118 changed files with 4,356 additions and 3,610 deletions.
6 changes: 4 additions & 2 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -13,14 +13,16 @@ find_package(ignition-cmake2 2.13 REQUIRED)
#============================================================================
# Configure the project
#============================================================================
ign_configure_project()
ign_configure_project(
REPLACE_IGNITION_INCLUDE_PATH gz/sensors
)

#============================================================================
# Set project-specific options
#============================================================================
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
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).
178 changes: 89 additions & 89 deletions Changelog.md

Large diffs are not rendered by default.

12 changes: 6 additions & 6 deletions Migration.md
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,7 @@ notification to users that their code should be upgraded. The next major
release will remove the deprecated code.


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

### Additions

Expand All @@ -24,7 +24,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 @@ -43,16 +43,16 @@ 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**
Expand Down
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
4 changes: 2 additions & 2 deletions api.md.in
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
## Ignition @GZ_DESIGNATION_CAP@
## Gazebo @GZ_DESIGNATION_CAP@

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

## License
Expand Down
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-sensors3 REQUIRED)

add_executable(sensor_noise main.cc)
Expand Down
8 changes: 4 additions & 4 deletions examples/imu_noise/main.cc
Original file line number Diff line number Diff line change
Expand Up @@ -20,9 +20,9 @@

#include <sdf/sdf.hh>

#include <ignition/sensors/Noise.hh>
#include <ignition/sensors/GaussianNoiseModel.hh>
#include <ignition/sensors/SensorFactory.hh>
#include <gz/sensors/Noise.hh>
#include <gz/sensors/GaussianNoiseModel.hh>
#include <gz/sensors/SensorFactory.hh>

static constexpr double kSampleFrequency = 100.0;
// 16-bit ADC
Expand Down 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
2 changes: 1 addition & 1 deletion examples/save_image/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-camera-demo)

# Find the Ignition Libraries used directly by the example
# Find the Gazebo Libraries used directly by the example
find_package(ignition-rendering3 REQUIRED OPTIONAL_COMPONENTS ogre ogre2)
find_package(ignition-sensors3 REQUIRED COMPONENTS rendering camera)

Expand Down
64 changes: 32 additions & 32 deletions examples/save_image/main.cc
Original file line number Diff line number Diff line change
Expand Up @@ -21,49 +21,49 @@
#include <sdf/Noise.hh>
#include <sdf/Sensor.hh>

#include <ignition/common/Image.hh>
#include <ignition/common/Console.hh>
#include <ignition/math/Helpers.hh>
#include <gz/common/Image.hh>
#include <gz/common/Console.hh>
#include <gz/math/Helpers.hh>

// TODO(louise) Remove these pragmas once ign-rendering is disabling the
// warnings
#ifdef _WIN32
#pragma warning(push)
#pragma warning(disable: 4251)
#endif
#include <ignition/rendering/Material.hh>
#include <ignition/rendering/RenderEngine.hh>
#include <ignition/rendering/RenderingIface.hh>
#include <ignition/rendering/Scene.hh>
#include <ignition/rendering/Visual.hh>
#include <gz/rendering/Material.hh>
#include <gz/rendering/RenderEngine.hh>
#include <gz/rendering/RenderingIface.hh>
#include <gz/rendering/Scene.hh>
#include <gz/rendering/Visual.hh>
#ifdef _WIN32
#pragma warning(pop)
#endif

#include <ignition/sensors.hh>
#include <gz/sensors.hh>

void OnImageFrame(const ignition::msgs::Image &_image)
void OnImageFrame(const gz::msgs::Image &_image)
{
const unsigned char *data = reinterpret_cast<const unsigned char*>(
_image.data().c_str());
auto format = static_cast<ignition::common::Image::PixelFormatType>(
auto format = static_cast<gz::common::Image::PixelFormatType>(
_image.pixel_format_type());
ignition::common::Image image;
gz::common::Image image;
image.SetFromData(data, _image.width(), _image.height(), format);
std::cout << "Saving image.png\n";
image.SavePNG("image.png");
}

void BuildScene(ignition::rendering::ScenePtr _scene);
void BuildScene(gz::rendering::ScenePtr _scene);

int main()
{
// Setup ign-rendering with a scene
#ifdef WITH_OGRE
auto engine = ignition::rendering::engine("ogre");
auto engine = gz::rendering::engine("ogre");
#else
#ifdef WITH_OGRE2
auto engine = ignition::rendering::engine("ogre2");
auto engine = gz::rendering::engine("ogre2");
#endif
#endif

Expand All @@ -72,13 +72,13 @@ int main()
std::cerr << "Failed to load ogre\n";
return 1;
}
ignition::rendering::ScenePtr scene = engine->CreateScene("scene");
gz::rendering::ScenePtr scene = engine->CreateScene("scene");

// Add stuff to take a picture of
BuildScene(scene);

// Create a sensor manager
ignition::sensors::Manager mgr;
gz::sensors::Manager mgr;

// Create SDF describing a camera sensor
const std::string name = "ExampleCamera";
Expand Down Expand Up @@ -113,7 +113,7 @@ int main()
sensorSdf.SetCameraSensor(cameraSdf);

// Create a CameraSensor
auto cameraSensor = mgr.CreateSensor<ignition::sensors::CameraSensor>(
auto cameraSensor = mgr.CreateSensor<gz::sensors::CameraSensor>(
sensorSdf);

if (!cameraSensor)
Expand All @@ -124,63 +124,63 @@ int main()
cameraSensor->SetScene(scene);

// Set a callback on the camera sensor to get a camera frame
ignition::common::ConnectionPtr connection =
gz::common::ConnectionPtr connection =
cameraSensor->ConnectImageCallback(&OnImageFrame);

// Force the camera to generate an image
mgr.RunOnce(ignition::common::Time::Zero, true);
mgr.RunOnce(gz::common::Time::Zero, true);

return 0;
}

// Copy/paste from an ignition-rendering example
void BuildScene(ignition::rendering::ScenePtr _scene)
void BuildScene(gz::rendering::ScenePtr _scene)
{
// initialize _scene
_scene->SetAmbientLight(0.3, 0.3, 0.3);
ignition::rendering::VisualPtr root = _scene->RootVisual();
gz::rendering::VisualPtr root = _scene->RootVisual();

// create directional light
ignition::rendering::DirectionalLightPtr light0 =
gz::rendering::DirectionalLightPtr light0 =
_scene->CreateDirectionalLight();
light0->SetDirection(-0.5, 0.5, -1);
light0->SetDiffuseColor(0.5, 0.5, 0.5);
light0->SetSpecularColor(0.5, 0.5, 0.5);
root->AddChild(light0);

// create point light
ignition::rendering::PointLightPtr light2 = _scene->CreatePointLight();
gz::rendering::PointLightPtr light2 = _scene->CreatePointLight();
light2->SetDiffuseColor(0.5, 0.5, 0.5);
light2->SetSpecularColor(0.5, 0.5, 0.5);
light2->SetLocalPosition(3, 5, 5);
root->AddChild(light2);

// create green material
ignition::rendering::MaterialPtr green = _scene->CreateMaterial();
gz::rendering::MaterialPtr green = _scene->CreateMaterial();
green->SetAmbient(0.0, 0.5, 0.0);
green->SetDiffuse(0.0, 0.7, 0.0);
green->SetSpecular(0.5, 0.5, 0.5);
green->SetShininess(50);
green->SetReflectivity(0);

// create center visual
ignition::rendering::VisualPtr center = _scene->CreateVisual();
gz::rendering::VisualPtr center = _scene->CreateVisual();
center->AddGeometry(_scene->CreateSphere());
center->SetLocalPosition(3, 0, 0);
center->SetLocalScale(0.1, 0.1, 0.1);
center->SetMaterial(green);
root->AddChild(center);

// create red material
ignition::rendering::MaterialPtr red = _scene->CreateMaterial();
gz::rendering::MaterialPtr red = _scene->CreateMaterial();
red->SetAmbient(0.5, 0.0, 0.0);
red->SetDiffuse(1.0, 0.0, 0.0);
red->SetSpecular(0.5, 0.5, 0.5);
red->SetShininess(50);
red->SetReflectivity(0);

// create sphere visual
ignition::rendering::VisualPtr sphere = _scene->CreateVisual();
gz::rendering::VisualPtr sphere = _scene->CreateVisual();
sphere->AddGeometry(_scene->CreateSphere());
sphere->SetOrigin(0.0, -0.5, 0.0);
sphere->SetLocalPosition(3, 0, 0);
Expand All @@ -190,15 +190,15 @@ void BuildScene(ignition::rendering::ScenePtr _scene)
root->AddChild(sphere);

// create blue material
ignition::rendering::MaterialPtr blue = _scene->CreateMaterial();
gz::rendering::MaterialPtr blue = _scene->CreateMaterial();
blue->SetAmbient(0.0, 0.0, 0.3);
blue->SetDiffuse(0.0, 0.0, 0.8);
blue->SetSpecular(0.5, 0.5, 0.5);
blue->SetShininess(50);
blue->SetReflectivity(0);

// create box visual
ignition::rendering::VisualPtr box = _scene->CreateVisual();
gz::rendering::VisualPtr box = _scene->CreateVisual();
box->AddGeometry(_scene->CreateBox());
box->SetOrigin(0.0, 0.5, 0.0);
box->SetLocalPosition(3, 0, 0);
Expand All @@ -208,14 +208,14 @@ void BuildScene(ignition::rendering::ScenePtr _scene)
root->AddChild(box);

// create white material
ignition::rendering::MaterialPtr white = _scene->CreateMaterial();
gz::rendering::MaterialPtr white = _scene->CreateMaterial();
white->SetAmbient(0.5, 0.5, 0.5);
white->SetDiffuse(0.8, 0.8, 0.8);
white->SetReceiveShadows(true);
white->SetReflectivity(0);

// create sphere visual
ignition::rendering::VisualPtr plane = _scene->CreateVisual();
gz::rendering::VisualPtr plane = _scene->CreateVisual();
plane->AddGeometry(_scene->CreatePlane());
plane->SetLocalScale(5, 8, 1);
plane->SetLocalPosition(3, 0, -0.5);
Expand Down
3 changes: 2 additions & 1 deletion include/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1 +1,2 @@
add_subdirectory(ignition)
add_subdirectory(gz)
install(DIRECTORY ignition DESTINATION ${IGN_INCLUDE_INSTALL_DIR_FULL})
File renamed without changes.
Loading

0 comments on commit 36f5d84

Please sign in to comment.