Skip to content

Commit

Permalink
Migrate ->
Browse files Browse the repository at this point in the history
Signed-off-by: methylDragon <methylDragon@gmail.com>
  • Loading branch information
methylDragon committed May 25, 2022
1 parent bcea846 commit 4faf38c
Show file tree
Hide file tree
Showing 24 changed files with 50 additions and 50 deletions.
4 changes: 2 additions & 2 deletions examples/custom_sensor/Odometer.cc
Original file line number Diff line number Diff line change
Expand Up @@ -46,7 +46,7 @@ bool Odometer::Load(const sdf::Sensor &_sdf)

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,7 +56,7 @@ 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;
}

Expand Down
2 changes: 1 addition & 1 deletion src/AirPressureSensor.cc
Original file line number Diff line number Diff line change
Expand Up @@ -122,7 +122,7 @@ bool AirPressureSensor::Load(const sdf::Sensor &_sdf)
return false;
}

igndbg << "Air pressure for [" << this->Name() << "] advertised on ["
gzdbg << "Air pressure for [" << this->Name() << "] advertised on ["
<< this->Topic() << "]" << std::endl;

// Load the noise parameters
Expand Down
2 changes: 1 addition & 1 deletion src/AltimeterSensor.cc
Original file line number Diff line number Diff line change
Expand Up @@ -100,7 +100,7 @@ bool AltimeterSensor::Load(const sdf::Sensor &_sdf)
return false;
}

igndbg << "Altimeter data for [" << this->Name() << "] advertised on ["
gzdbg << "Altimeter data for [" << this->Name() << "] advertised on ["
<< this->Topic() << "]" << std::endl;

// Load the noise parameters
Expand Down
10 changes: 5 additions & 5 deletions src/CameraSensor.cc
Original file line number Diff line number Diff line change
Expand Up @@ -294,7 +294,7 @@ bool CameraSensor::Load(const sdf::Sensor &_sdf)
return false;
}

igndbg << "Camera images for [" << this->Name() << "] advertised on ["
gzdbg << "Camera images for [" << this->Name() << "] advertised on ["
<< this->Topic() << "]" << std::endl;

if (_sdf.CameraSensor()->Triggered())
Expand All @@ -318,7 +318,7 @@ bool CameraSensor::Load(const sdf::Sensor &_sdf)
this->dataPtr->node.Subscribe(this->dataPtr->triggerTopic,
&CameraSensorPrivate::OnTrigger, this->dataPtr.get());

igndbg << "Camera trigger messages for [" << this->Name() << "] subscribed"
gzdbg << "Camera trigger messages for [" << this->Name() << "] subscribed"
<< " on [" << this->dataPtr->triggerTopic << "]" << std::endl;
this->dataPtr->isTriggeredCamera = true;
}
Expand Down Expand Up @@ -401,7 +401,7 @@ bool CameraSensor::Update(const std::chrono::steady_clock::duration &_now)
{
if (this->dataPtr->generatingData)
{
igndbg << "Disabling camera sensor: '" << this->Name() << "' data "
gzdbg << "Disabling camera sensor: '" << this->Name() << "' data "
<< "generation. " << std::endl;;
this->dataPtr->generatingData = false;
}
Expand All @@ -412,7 +412,7 @@ bool CameraSensor::Update(const std::chrono::steady_clock::duration &_now)
{
if (!this->dataPtr->generatingData)
{
igndbg << "Enabling camera sensor: '" << this->Name() << "' data "
gzdbg << "Enabling camera sensor: '" << this->Name() << "' data "
<< "generation." << std::endl;;
this->dataPtr->generatingData = true;
}
Expand Down Expand Up @@ -595,7 +595,7 @@ bool CameraSensor::AdvertiseInfo(const std::string &_topic)
}
else
{
igndbg << "Camera info for [" << this->Name() << "] advertised on ["
gzdbg << "Camera info for [" << this->Name() << "] advertised on ["
<< this->dataPtr->infoTopic << "]" << std::endl;
}

Expand Down
4 changes: 2 additions & 2 deletions src/DepthCameraSensor.cc
Original file line number Diff line number Diff line change
Expand Up @@ -284,7 +284,7 @@ bool DepthCameraSensor::Load(const sdf::Sensor &_sdf)
return false;
}

igndbg << "Depth images for [" << this->Name() << "] advertised on ["
gzdbg << "Depth images for [" << this->Name() << "] advertised on ["
<< this->Topic() << "]" << std::endl;

if (!this->AdvertiseInfo())
Expand All @@ -301,7 +301,7 @@ bool DepthCameraSensor::Load(const sdf::Sensor &_sdf)
return false;
}

igndbg << "Points for [" << this->Name() << "] advertised on ["
gzdbg << "Points for [" << this->Name() << "] advertised on ["
<< this->Topic() << "/points]" << std::endl;

// Initialize the point message.
Expand Down
2 changes: 1 addition & 1 deletion src/GpuLidarSensor.cc
Original file line number Diff line number Diff line change
Expand Up @@ -161,7 +161,7 @@ bool GpuLidarSensor::Load(const sdf::Sensor &_sdf)
return false;
}

igndbg << "Lidar points for [" << this->Name() << "] advertised on ["
gzdbg << "Lidar points for [" << this->Name() << "] advertised on ["
<< this->Topic() << "]" << std::endl;

this->initialized = true;
Expand Down
2 changes: 1 addition & 1 deletion src/ImuSensor.cc
Original file line number Diff line number Diff line change
Expand Up @@ -145,7 +145,7 @@ bool ImuSensor::Load(const sdf::Sensor &_sdf)
return false;
}

igndbg << "IMU data for [" << this->Name() << "] advertised on ["
gzdbg << "IMU data for [" << this->Name() << "] advertised on ["
<< this->Topic() << "]" << std::endl;

const std::map<SensorNoiseType, sdf::Noise> noises = {
Expand Down
4 changes: 2 additions & 2 deletions src/Lidar.cc
Original file line number Diff line number Diff line change
Expand Up @@ -119,7 +119,7 @@ bool Lidar::Load(const sdf::Sensor &_sdf)
return false;
}

igndbg << "Laser scans for [" << this->Name() << "] advertised on ["
gzdbg << "Laser scans for [" << this->Name() << "] advertised on ["
<< this->Topic() << "]" << std::endl;

// Load ray atributes
Expand Down Expand Up @@ -245,7 +245,7 @@ bool Lidar::PublishLidarScan(const std::chrono::steady_clock::duration &_now)
const int numRays = this->RayCount() * this->VerticalRayCount();
if (this->dataPtr->laserMsg.ranges_size() != numRays)
{
// igndbg << "Size mismatch; allocating memory\n";
// gzdbg << "Size mismatch; allocating memory\n";
this->dataPtr->laserMsg.clear_ranges();
this->dataPtr->laserMsg.clear_intensities();
for (int i = 0; i < numRays; ++i)
Expand Down
2 changes: 1 addition & 1 deletion src/LogicalCameraSensor.cc
Original file line number Diff line number Diff line change
Expand Up @@ -115,7 +115,7 @@ bool LogicalCameraSensor::Load(sdf::ElementPtr _sdf)
return false;
}

igndbg << "Logical images for [" << this->Name() << "] advertised on ["
gzdbg << "Logical images for [" << this->Name() << "] advertised on ["
<< this->Topic() << "]" << std::endl;

this->dataPtr->initialized = true;
Expand Down
2 changes: 1 addition & 1 deletion src/MagnetometerSensor.cc
Original file line number Diff line number Diff line change
Expand Up @@ -114,7 +114,7 @@ bool MagnetometerSensor::Load(const sdf::Sensor &_sdf)
return false;
}

igndbg << "Magnetometer data for [" << this->Name() << "] advertised on ["
gzdbg << "Magnetometer data for [" << this->Name() << "] advertised on ["
<< this->Topic() << "]" << std::endl;

// Load the noise parameters
Expand Down
6 changes: 3 additions & 3 deletions src/RgbdCameraSensor.cc
Original file line number Diff line number Diff line change
Expand Up @@ -219,7 +219,7 @@ bool RgbdCameraSensor::Load(const sdf::Sensor &_sdf)
return false;
}

igndbg << "RGB images for [" << this->Name() << "] advertised on ["
gzdbg << "RGB images for [" << this->Name() << "] advertised on ["
<< this->Topic() << "/image]" << std::endl;

// Create the depth image publisher
Expand All @@ -233,7 +233,7 @@ bool RgbdCameraSensor::Load(const sdf::Sensor &_sdf)
return false;
}

igndbg << "Depth images for [" << this->Name() << "] advertised on ["
gzdbg << "Depth images for [" << this->Name() << "] advertised on ["
<< this->Topic() << "/depth_image]" << std::endl;

// Create the point cloud publisher
Expand All @@ -247,7 +247,7 @@ bool RgbdCameraSensor::Load(const sdf::Sensor &_sdf)
return false;
}

igndbg << "Points for [" << this->Name() << "] advertised on ["
gzdbg << "Points for [" << this->Name() << "] advertised on ["
<< this->Topic() << "/points]" << std::endl;

if (!this->AdvertiseInfo(this->Topic() + "/camera_info"))
Expand Down
6 changes: 3 additions & 3 deletions src/SegmentationCameraSensor.cc
Original file line number Diff line number Diff line change
Expand Up @@ -202,7 +202,7 @@ bool SegmentationCameraSensor::Load(const sdf::Sensor &_sdf)
return false;
}

igndbg << "Colored map image for [" << this->Name() << "] advertised on ["
gzdbg << "Colored map image for [" << this->Name() << "] advertised on ["
<< this->Topic() << this->dataPtr->topicColoredMapSuffix << "]\n";

// Create the segmentation labels map image publisher
Expand All @@ -217,7 +217,7 @@ bool SegmentationCameraSensor::Load(const sdf::Sensor &_sdf)
return false;
}

igndbg << "Segmentation labels map image for [" << this->Name()
gzdbg << "Segmentation labels map image for [" << this->Name()
<< "] advertised on [" << this->Topic()
<< this->dataPtr->topicLabelsMapSuffix << "]\n";

Expand Down Expand Up @@ -285,7 +285,7 @@ bool SegmentationCameraSensor::CreateCamera()
this->dataPtr->type = rendering::SegmentationType::ST_PANOPTIC;
else
{
igndbg << "Wrong type [" << type <<
gzdbg << "Wrong type [" << type <<
"], type should be semantic or instance or panoptic" << std::endl;
return false;
}
Expand Down
2 changes: 1 addition & 1 deletion src/Sensor.cc
Original file line number Diff line number Diff line change
Expand Up @@ -386,7 +386,7 @@ void SensorPrivate::SetRate(const gz::msgs::Double &_rate)
}
}

igndbg << "Setting update rate of sensor " << this->name << " to " << rate
gzdbg << "Setting update rate of sensor " << this->name << " to " << rate
<< " Hz" << std::endl;

this->updateRate = rate;
Expand Down
2 changes: 1 addition & 1 deletion src/ThermalCameraSensor.cc
Original file line number Diff line number Diff line change
Expand Up @@ -220,7 +220,7 @@ bool ThermalCameraSensor::Load(const sdf::Sensor &_sdf)
return false;
}

igndbg << "Thermal images for [" << this->Name() << "] advertised on ["
gzdbg << "Thermal images for [" << this->Name() << "] advertised on ["
<< this->Topic() << "]" << std::endl;

if (!this->AdvertiseInfo())
Expand Down
6 changes: 3 additions & 3 deletions src/WideAngleCameraSensor.cc
Original file line number Diff line number Diff line change
Expand Up @@ -188,7 +188,7 @@ bool WideAngleCameraSensor::Load(const sdf::Sensor &_sdf)
return false;
}

igndbg << "Wide angle camera images for [" << this->Name()
gzdbg << "Wide angle camera images for [" << this->Name()
<< "] advertised on [" << this->Topic() << "]" << std::endl;

if (!this->AdvertiseInfo())
Expand Down Expand Up @@ -418,7 +418,7 @@ bool WideAngleCameraSensor::Update(
{
if (this->dataPtr->generatingData)
{
igndbg << "Disabling camera sensor: '" << this->Name() << "' data "
gzdbg << "Disabling camera sensor: '" << this->Name() << "' data "
<< "generation. " << std::endl;;
this->dataPtr->generatingData = false;
}
Expand All @@ -429,7 +429,7 @@ bool WideAngleCameraSensor::Update(
{
if (!this->dataPtr->generatingData)
{
igndbg << "Enabling camera sensor: '" << this->Name() << "' data "
gzdbg << "Enabling camera sensor: '" << this->Name() << "' data "
<< "generation." << std::endl;;
this->dataPtr->generatingData = true;
}
Expand Down
4 changes: 2 additions & 2 deletions test/integration/camera.cc
Original file line number Diff line number Diff line change
Expand Up @@ -96,7 +96,7 @@ void CameraSensorTest::ImagesWithBuiltinSDF(const std::string &_renderEngine)
auto *engine = gz::rendering::engine(_renderEngine);
if (!engine)
{
igndbg << "Engine '" << _renderEngine
gzdbg << "Engine '" << _renderEngine
<< "' is not supported" << std::endl;
return;
}
Expand Down Expand Up @@ -189,7 +189,7 @@ void CameraSensorTest::ImageFormatLInt8(const std::string &_renderEngine)
auto *engine = gz::rendering::engine(_renderEngine);
if (!engine)
{
igndbg << "Engine '" << _renderEngine
gzdbg << "Engine '" << _renderEngine
<< "' is not supported" << std::endl;
return;
}
Expand Down
4 changes: 2 additions & 2 deletions test/integration/depth_camera.cc
Original file line number Diff line number Diff line change
Expand Up @@ -186,7 +186,7 @@ void DepthCameraSensorTest::ImagesWithBuiltinSDF(
if ((_renderEngine.compare("ogre") != 0) &&
(_renderEngine.compare("ogre2") != 0))
{
igndbg << "Engine '" << _renderEngine
gzdbg << "Engine '" << _renderEngine
<< "' doesn't support depth cameras" << std::endl;
return;
}
Expand All @@ -195,7 +195,7 @@ void DepthCameraSensorTest::ImagesWithBuiltinSDF(
auto *engine = gz::rendering::engine(_renderEngine);
if (!engine)
{
igndbg << "Engine '" << _renderEngine
gzdbg << "Engine '" << _renderEngine
<< "' is not supported" << std::endl;
return;
}
Expand Down
4 changes: 2 additions & 2 deletions test/integration/distortion_camera.cc
Original file line number Diff line number Diff line change
Expand Up @@ -80,7 +80,7 @@ void DistortionCameraSensorTest::ImagesWithBuiltinSDF(

if (_renderEngine == "ogre2")
{
igndbg << "Distortion camera not supported yet in rendering engine: "
gzdbg << "Distortion camera not supported yet in rendering engine: "
<< _renderEngine << std::endl;
return;
}
Expand All @@ -89,7 +89,7 @@ void DistortionCameraSensorTest::ImagesWithBuiltinSDF(
auto *engine = gz::rendering::engine(_renderEngine);
if (!engine)
{
igndbg << "Engine '" << _renderEngine
gzdbg << "Engine '" << _renderEngine
<< "' is not supported" << std::endl;
return;
}
Expand Down
12 changes: 6 additions & 6 deletions test/integration/gpu_lidar_sensor.cc
Original file line number Diff line number Diff line change
Expand Up @@ -199,7 +199,7 @@ void GpuLidarSensorTest::CreateGpuLidar(const std::string &_renderEngine)
auto *engine = gz::rendering::engine(_renderEngine);
if (!engine)
{
igndbg << "Engine '" << _renderEngine
gzdbg << "Engine '" << _renderEngine
<< "' is not supported" << std::endl;
return;
}
Expand Down Expand Up @@ -318,7 +318,7 @@ void GpuLidarSensorTest::DetectBox(const std::string &_renderEngine)
gz::rendering::engine(_renderEngine);
if (!engine)
{
igndbg << "Engine '" << _renderEngine
gzdbg << "Engine '" << _renderEngine
<< "' is not supported" << std::endl;
return;
}
Expand Down Expand Up @@ -472,7 +472,7 @@ void GpuLidarSensorTest::TestThreeBoxes(const std::string &_renderEngine)
gz::rendering::engine(_renderEngine);
if (!engine)
{
igndbg << "Engine '" << _renderEngine
gzdbg << "Engine '" << _renderEngine
<< "' is not supported" << std::endl;
return;
}
Expand Down Expand Up @@ -613,7 +613,7 @@ void GpuLidarSensorTest::VerticalLidar(const std::string &_renderEngine)
gz::rendering::engine(_renderEngine);
if (!engine)
{
igndbg << "Engine '" << _renderEngine
gzdbg << "Engine '" << _renderEngine
<< "' is not supported" << std::endl;
return;
}
Expand Down Expand Up @@ -744,7 +744,7 @@ void GpuLidarSensorTest::ManualUpdate(const std::string &_renderEngine)
gz::rendering::engine(_renderEngine);
if (!engine)
{
igndbg << "Engine '" << _renderEngine
gzdbg << "Engine '" << _renderEngine
<< "' is not supported" << std::endl;
return;
}
Expand Down Expand Up @@ -849,7 +849,7 @@ void GpuLidarSensorTest::Topic(const std::string &_renderEngine)
auto engine = gz::rendering::engine(_renderEngine);
if (!engine)
{
igndbg << "Engine '" << _renderEngine
gzdbg << "Engine '" << _renderEngine
<< "' is not supported" << std::endl;
return;
}
Expand Down
4 changes: 2 additions & 2 deletions test/integration/rgbd_camera.cc
Original file line number Diff line number Diff line change
Expand Up @@ -205,7 +205,7 @@ void RgbdCameraSensorTest::ImagesWithBuiltinSDF(
if ((_renderEngine.compare("ogre") != 0) &&
(_renderEngine.compare("ogre2") != 0))
{
igndbg << "Engine '" << _renderEngine
gzdbg << "Engine '" << _renderEngine
<< "' doesn't support rgbd cameras" << std::endl;
return;
}
Expand All @@ -214,7 +214,7 @@ void RgbdCameraSensorTest::ImagesWithBuiltinSDF(
auto *engine = gz::rendering::engine(_renderEngine);
if (!engine)
{
igndbg << "Engine '" << _renderEngine
gzdbg << "Engine '" << _renderEngine
<< "' is not supported" << std::endl;
return;
}
Expand Down
4 changes: 2 additions & 2 deletions test/integration/segmentation_camera.cc
Original file line number Diff line number Diff line change
Expand Up @@ -198,15 +198,15 @@ void SegmentationCameraSensorTest::ImagesWithBuiltinSDF(
// If ogre2 is not the engine, don't run the test
if (_renderEngine.compare("ogre2") != 0)
{
igndbg << "Engine '" << _renderEngine
gzdbg << "Engine '" << _renderEngine
<< "' doesn't support segmentation cameras" << std::endl;
return;
}
// Setup ign-rendering with an empty scene
auto *engine = gz::rendering::engine(_renderEngine);
if (!engine)
{
igndbg << "Engine '" << _renderEngine
gzdbg << "Engine '" << _renderEngine
<< "' is not supported" << std::endl;
return;
}
Expand Down
Loading

0 comments on commit 4faf38c

Please sign in to comment.