Skip to content

Commit

Permalink
Migrate more namespaces
Browse files Browse the repository at this point in the history
Signed-off-by: methylDragon <[email protected]>
  • Loading branch information
methylDragon committed May 20, 2022
1 parent 94fa321 commit f92c7e5
Show file tree
Hide file tree
Showing 11 changed files with 42 additions and 42 deletions.
24 changes: 12 additions & 12 deletions Migration.md
Original file line number Diff line number Diff line change
Expand Up @@ -26,9 +26,9 @@ release will remove the deprecated code.
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 @@ -55,19 +55,19 @@ release will remove the deprecated code.
## Ignition 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
Expand Down Expand Up @@ -107,16 +107,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 include/gz/sensors/GpuLidarSensor.hh
Original file line number Diff line number Diff line change
Expand Up @@ -134,7 +134,7 @@ namespace gz
const std::string &/*_format*/)> _subscriber) override;

/// \brief Connect function pointer to internal GpuRays callback
/// \return ignition::common::Connection pointer
/// \return gz::common::Connection pointer
private: void OnNewLidarFrame(const float *_scan, unsigned int _width,
unsigned int _heighti, unsigned int _channels,
const std::string &_format);
Expand Down
6 changes: 3 additions & 3 deletions src/CameraSensor.cc
Original file line number Diff line number Diff line change
Expand Up @@ -215,7 +215,7 @@ bool CameraSensor::CreateCamera()
this->dataPtr->camera->SetImageFormat(gz::rendering::PF_R8G8B8);
break;
case sdf::PixelFormatType::L_INT8:
this->dataPtr->camera->SetImageFormat(ignition::rendering::PF_L8);
this->dataPtr->camera->SetImageFormat(gz::rendering::PF_L8);
break;
default:
ignerr << "Unsupported pixel format ["
Expand Down Expand Up @@ -440,8 +440,8 @@ bool CameraSensor::Update(const std::chrono::steady_clock::duration &_now)
format = gz::common::Image::RGB_INT8;
msgsPixelFormat = msgs::PixelFormatType::RGB_INT8;
break;
case ignition::rendering::PF_L8:
format = ignition::common::Image::L_INT8;
case gz::rendering::PF_L8:
format = gz::common::Image::L_INT8;
msgsPixelFormat = msgs::PixelFormatType::L_INT8;
break;
default:
Expand Down
4 changes: 2 additions & 2 deletions src/GpuLidarSensor.cc
Original file line number Diff line number Diff line change
Expand Up @@ -50,7 +50,7 @@ class gz::sensors::GpuLidarSensorPrivate

/// \brief Event that is used to trigger callbacks when a new
/// lidar frame is available
public: ignition::common::EventT<
public: gz::common::EventT<
void(const float *_scan, unsigned int _width,
unsigned int _height, unsigned int _channels,
const std::string &_format)> lidarEvent;
Expand All @@ -61,7 +61,7 @@ class gz::sensors::GpuLidarSensorPrivate
const std::string &_format);

/// \brief Connection to gpuRays new lidar frame event
public: ignition::common::ConnectionPtr lidarFrameConnection;
public: gz::common::ConnectionPtr lidarFrameConnection;

/// \brief The point cloud message.
public: msgs::PointCloudPacked pointMsg;
Expand Down
22 changes: 11 additions & 11 deletions test/integration/camera.cc
Original file line number Diff line number Diff line change
Expand Up @@ -51,10 +51,10 @@
std::mutex g_mutex;
unsigned int g_imgCounter = 0;

void OnGrayscaleImage(const ignition::msgs::Image &_msg)
void OnGrayscaleImage(const gz::msgs::Image &_msg)
{
std::lock_guard<std::mutex> lock(g_mutex);
EXPECT_EQ(ignition::msgs::PixelFormatType::L_INT8, _msg.pixel_format_type());
EXPECT_EQ(gz::msgs::PixelFormatType::L_INT8, _msg.pixel_format_type());
EXPECT_EQ(256u, _msg.width());
EXPECT_EQ(256u, _msg.height());
g_imgCounter++;
Expand Down Expand Up @@ -172,7 +172,7 @@ TEST_P(CameraSensorTest, ImagesWithBuiltinSDF)
void CameraSensorTest::ImageFormatLInt8(const std::string &_renderEngine)
{
// get the darn test data
std::string path = ignition::common::joinPaths(PROJECT_SOURCE_PATH, "test",
std::string path = gz::common::joinPaths(PROJECT_SOURCE_PATH, "test",
"sdf", "camera_sensor_l8_builtin.sdf");
sdf::SDFPtr doc(new sdf::SDF());
sdf::init(doc);
Expand All @@ -186,21 +186,21 @@ void CameraSensorTest::ImageFormatLInt8(const std::string &_renderEngine)
auto sensorPtr = linkPtr->GetElement("sensor");

// Setup ign-rendering with an empty scene
auto *engine = ignition::rendering::engine(_renderEngine);
auto *engine = gz::rendering::engine(_renderEngine);
if (!engine)
{
igndbg << "Engine '" << _renderEngine
<< "' is not supported" << std::endl;
return;
}

ignition::rendering::ScenePtr scene = engine->CreateScene("scene");
gz::rendering::ScenePtr scene = engine->CreateScene("scene");

// do the test
ignition::sensors::Manager mgr;
gz::sensors::Manager mgr;

ignition::sensors::CameraSensor *sensor =
mgr.CreateSensor<ignition::sensors::CameraSensor>(sensorPtr);
gz::sensors::CameraSensor *sensor =
mgr.CreateSensor<gz::sensors::CameraSensor>(sensorPtr);
ASSERT_NE(sensor, nullptr);
sensor->SetScene(scene);

Expand All @@ -210,15 +210,15 @@ void CameraSensorTest::ImageFormatLInt8(const std::string &_renderEngine)
EXPECT_EQ(256u, sensor->ImageHeight());

std::string topic = "/images_l8";
WaitForMessageTestHelper<ignition::msgs::Image> helper(topic);
WaitForMessageTestHelper<gz::msgs::Image> helper(topic);

// Update once to create image
mgr.RunOnce(std::chrono::steady_clock::duration::zero());

EXPECT_TRUE(helper.WaitForMessage()) << helper;

// subscribe to the camera topic
ignition::transport::Node node;
gz::transport::Node node;
node.Subscribe(topic, &OnGrayscaleImage);

// wait for a few camera frames
Expand Down Expand Up @@ -249,7 +249,7 @@ void CameraSensorTest::ImageFormatLInt8(const std::string &_renderEngine)

// Clean up
engine->DestroyScene(scene);
ignition::rendering::unloadEngine(engine->Name());
gz::rendering::unloadEngine(engine->Name());
}

//////////////////////////////////////////////////
Expand Down
2 changes: 1 addition & 1 deletion test/integration/deprecated_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,7 @@
// Make sure the ignition namespace still works
TEST(Deprecated, IgnitionNamespace)
{
ignition::sensors::Lidar lidar;
gz::sensors::Lidar lidar;
}

#undef SUPPRESS_IGNITION_HEADER_DEPRECATION
2 changes: 1 addition & 1 deletion test/integration/logical_camera.cc
Original file line number Diff line number Diff line change
Expand Up @@ -238,7 +238,7 @@ TEST_F(LogicalCameraSensorTest, DetectBox)
EXPECT_EQ(0, img.model().size());

// verify connection count and msg published to topic
WaitForMessageTestHelper<ignition::msgs::LogicalCameraImage> helper(topic);
WaitForMessageTestHelper<gz::msgs::LogicalCameraImage> helper(topic);
EXPECT_TRUE(sensor->HasConnections());
sensor->Update(std::chrono::steady_clock::duration::zero());
EXPECT_TRUE(helper.WaitForMessage()) << helper;
Expand Down
2 changes: 1 addition & 1 deletion test/integration/triggered_camera.cc
Original file line number Diff line number Diff line change
Expand Up @@ -158,7 +158,7 @@ TEST_P(TriggeredCameraTest, ImagesWithBuiltinSDF)
ImagesWithBuiltinSDF(GetParam());
}

INSTANTIATE_TEST_CASE_P(CameraSensor, CameraSensorTest,
INSTANTIATE_TEST_CASE_P(CameraSensor, TriggeredCameraTest,
RENDER_ENGINE_VALUES, gz::rendering::PrintToStringParam());

//////////////////////////////////////////////////
Expand Down
2 changes: 1 addition & 1 deletion tutorials/custom_sensors.md
Original file line number Diff line number Diff line change
Expand Up @@ -106,7 +106,7 @@ Take a look at
[ign-gazebo/examples/plugins/custom_sensor_system](https://github.com/ignitionrobotics/ign-gazebo/tree/main/examples/plugin/custom_sensor_system).
for the full code. Here are some important pointers:

* Check for new entities that have `gz::gazebo::components::CustomSensor`
* Check for new entities that have `gz::sim::components::CustomSensor`
during the `PreUpdate` callback and instantiate new sensors as they appear
in simulation.
* Don't assume all `CustomSensors` are of the type you need, be sure to check
Expand Down
8 changes: 4 additions & 4 deletions tutorials/segmentation_camera.md
Original file line number Diff line number Diff line change
Expand Up @@ -139,7 +139,7 @@ To assign a label to a model we use the label plugin in the SDF file:
<diffuse>0 0 1 1</diffuse>
<specular>0 0 0.3 1</specular>
</material>
<plugin filename="ignition-gazebo-label-system" name="gz::gazebo::systems::Label">
<plugin filename="gz-sim-label-system" name="gz::sim::systems::Label">
<label>10</label>
</plugin>
</visual>
Expand All @@ -150,7 +150,7 @@ To assign a label to a model we use the label plugin in the SDF file:
Lets zoom in the label plugin:

```xml
<plugin filename="ignition-gazebo-label-system" name="gz::gazebo::systems::Label">
<plugin filename="gz-sim-label-system" name="gz::sim::systems::Label">
<label>10</label>
</plugin>
```
Expand All @@ -167,7 +167,7 @@ You can also attach this plugin to the model's `<model>` tag:
<link name="sphere_link">
...
</link>
<plugin filename="ignition-gazebo-label-system" name="gz::gazebo::systems::Label">
<plugin filename="gz-sim-label-system" name="gz::sim::systems::Label">
<label>20</label>
</plugin>
</model>
Expand All @@ -181,7 +181,7 @@ If you're including a model from a place like [ignition fuel](https://app.igniti
<uri>
https://fuel.ignitionrobotics.org/1.0/OpenRobotics/models/Construction Cone
</uri>
<plugin filename="ignition-gazebo-label-system" name="gz::gazebo::systems::Label">
<plugin filename="gz-sim-label-system" name="gz::sim::systems::Label">
<label>30</label>
</plugin>
</include>
Expand Down
10 changes: 5 additions & 5 deletions tutorials/thermal_camera.md
Original file line number Diff line number Diff line change
Expand Up @@ -57,7 +57,7 @@ Here's an example of how to attach a thermal camera sensor to a model in a [SDF]
<topic>thermal_camera_8bit/image</topic>
<plugin
filename="ignition-gazebo-thermal-sensor-system"
name="gz::gazebo::systems::ThermalSensor">
name="gz::sim::systems::ThermalSensor">
<min_temp>253.15</min_temp>
<max_temp>673.15</max_temp>
<resolution>3.0</resolution>
Expand Down Expand Up @@ -90,7 +90,7 @@ Let's take a closer look at the portion of the code above that focuses on the th
<topic>thermal_camera_8bit/image</topic>
<plugin
filename="ignition-gazebo-thermal-sensor-system"
name="gz::gazebo::systems::ThermalSensor">
name="gz::sim::systems::ThermalSensor">
<min_temp>253.15</min_temp>
<max_temp>673.15</max_temp>
<resolution>3.0</resolution>
Expand Down Expand Up @@ -191,7 +191,7 @@ Here's an example of a box model that has a uniform temperature assigned to it:
</material>
<plugin
filename="ignition-gazebo-thermal-system"
name="gz::gazebo::systems::Thermal">
name="gz::sim::systems::Thermal">
<temperature>285.0</temperature>
</plugin>
</visual>
Expand All @@ -204,7 +204,7 @@ Most of the code above is for the model - here's the key piece for temperature a
```xml
<plugin
filename="ignition-gazebo-thermal-system"
name="gz::gazebo::systems::Thermal">
name="gz::sim::systems::Thermal">
<temperature>285.0</temperature>
</plugin>
```
Expand All @@ -222,7 +222,7 @@ If we take a look at Rescue Randy's `model.sdf`, we can see that it incorporates
```xml
<plugin
filename="ignition-gazebo-thermal-system"
name="gz::gazebo::systems::Thermal">
name="gz::sim::systems::Thermal">
<heat_signature>materials/textures/RescueRandy_Thermal.png</heat_signature>
<max_temp>310</max_temp>
</plugin>
Expand Down

0 comments on commit f92c7e5

Please sign in to comment.