diff --git a/examples/custom_sensor/Odometer.cc b/examples/custom_sensor/Odometer.cc index 43e328ca..cd493cf3 100644 --- a/examples/custom_sensor/Odometer.cc +++ b/examples/custom_sensor/Odometer.cc @@ -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; } @@ -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; } diff --git a/src/AirPressureSensor.cc b/src/AirPressureSensor.cc index 4b85fe05..0399a743 100644 --- a/src/AirPressureSensor.cc +++ b/src/AirPressureSensor.cc @@ -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 diff --git a/src/AltimeterSensor.cc b/src/AltimeterSensor.cc index b3e2022b..72717c7d 100644 --- a/src/AltimeterSensor.cc +++ b/src/AltimeterSensor.cc @@ -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 diff --git a/src/CameraSensor.cc b/src/CameraSensor.cc index 0b2f676e..c597e770 100644 --- a/src/CameraSensor.cc +++ b/src/CameraSensor.cc @@ -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()) @@ -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; } @@ -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; } @@ -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; } @@ -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; } diff --git a/src/DepthCameraSensor.cc b/src/DepthCameraSensor.cc index c3a019ab..9700bb61 100644 --- a/src/DepthCameraSensor.cc +++ b/src/DepthCameraSensor.cc @@ -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()) @@ -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. diff --git a/src/GpuLidarSensor.cc b/src/GpuLidarSensor.cc index fc7b1805..3adfe423 100644 --- a/src/GpuLidarSensor.cc +++ b/src/GpuLidarSensor.cc @@ -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; diff --git a/src/ImuSensor.cc b/src/ImuSensor.cc index d88b770c..2653dc63 100644 --- a/src/ImuSensor.cc +++ b/src/ImuSensor.cc @@ -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 noises = { diff --git a/src/Lidar.cc b/src/Lidar.cc index cab5277c..c237b5b1 100644 --- a/src/Lidar.cc +++ b/src/Lidar.cc @@ -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 @@ -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) diff --git a/src/LogicalCameraSensor.cc b/src/LogicalCameraSensor.cc index fda80160..2608d936 100644 --- a/src/LogicalCameraSensor.cc +++ b/src/LogicalCameraSensor.cc @@ -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; diff --git a/src/MagnetometerSensor.cc b/src/MagnetometerSensor.cc index fe6d5c14..2f1e5a92 100644 --- a/src/MagnetometerSensor.cc +++ b/src/MagnetometerSensor.cc @@ -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 diff --git a/src/RgbdCameraSensor.cc b/src/RgbdCameraSensor.cc index 33dd0e1c..6b758e0d 100644 --- a/src/RgbdCameraSensor.cc +++ b/src/RgbdCameraSensor.cc @@ -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 @@ -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 @@ -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")) diff --git a/src/SegmentationCameraSensor.cc b/src/SegmentationCameraSensor.cc index 291806ad..276d388a 100644 --- a/src/SegmentationCameraSensor.cc +++ b/src/SegmentationCameraSensor.cc @@ -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 @@ -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"; @@ -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; } diff --git a/src/Sensor.cc b/src/Sensor.cc index f47f8591..480e3b3b 100644 --- a/src/Sensor.cc +++ b/src/Sensor.cc @@ -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; diff --git a/src/ThermalCameraSensor.cc b/src/ThermalCameraSensor.cc index d6626da1..155f2ed0 100644 --- a/src/ThermalCameraSensor.cc +++ b/src/ThermalCameraSensor.cc @@ -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()) diff --git a/src/WideAngleCameraSensor.cc b/src/WideAngleCameraSensor.cc index fa7c5b7a..c5c4c45d 100644 --- a/src/WideAngleCameraSensor.cc +++ b/src/WideAngleCameraSensor.cc @@ -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()) @@ -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; } @@ -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; } diff --git a/test/integration/camera.cc b/test/integration/camera.cc index a561b02b..98483438 100644 --- a/test/integration/camera.cc +++ b/test/integration/camera.cc @@ -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; } @@ -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; } diff --git a/test/integration/depth_camera.cc b/test/integration/depth_camera.cc index ae6ae405..ae4d0cbd 100644 --- a/test/integration/depth_camera.cc +++ b/test/integration/depth_camera.cc @@ -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; } @@ -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; } diff --git a/test/integration/distortion_camera.cc b/test/integration/distortion_camera.cc index d82e43e1..6e6b0b22 100644 --- a/test/integration/distortion_camera.cc +++ b/test/integration/distortion_camera.cc @@ -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; } @@ -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; } diff --git a/test/integration/gpu_lidar_sensor.cc b/test/integration/gpu_lidar_sensor.cc index 59bf2069..0d28d427 100644 --- a/test/integration/gpu_lidar_sensor.cc +++ b/test/integration/gpu_lidar_sensor.cc @@ -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; } @@ -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; } @@ -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; } @@ -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; } @@ -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; } @@ -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; } diff --git a/test/integration/rgbd_camera.cc b/test/integration/rgbd_camera.cc index 475fe3c9..f9632c60 100644 --- a/test/integration/rgbd_camera.cc +++ b/test/integration/rgbd_camera.cc @@ -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; } @@ -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; } diff --git a/test/integration/segmentation_camera.cc b/test/integration/segmentation_camera.cc index 43eaa036..99145d23 100644 --- a/test/integration/segmentation_camera.cc +++ b/test/integration/segmentation_camera.cc @@ -198,7 +198,7 @@ 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; } @@ -206,7 +206,7 @@ void SegmentationCameraSensorTest::ImagesWithBuiltinSDF( auto *engine = gz::rendering::engine(_renderEngine); if (!engine) { - igndbg << "Engine '" << _renderEngine + gzdbg << "Engine '" << _renderEngine << "' is not supported" << std::endl; return; } diff --git a/test/integration/thermal_camera.cc b/test/integration/thermal_camera.cc index 5f0ef607..a39ce960 100644 --- a/test/integration/thermal_camera.cc +++ b/test/integration/thermal_camera.cc @@ -138,7 +138,7 @@ void ThermalCameraSensorTest::ImagesWithBuiltinSDF( if ((_renderEngine.compare("ogre") != 0) && (_renderEngine.compare("ogre2") != 0)) { - igndbg << "Engine '" << _renderEngine + gzdbg << "Engine '" << _renderEngine << "' doesn't support thermal cameras" << std::endl; return; } @@ -147,7 +147,7 @@ void ThermalCameraSensorTest::ImagesWithBuiltinSDF( auto *engine = gz::rendering::engine(_renderEngine); if (!engine) { - igndbg << "Engine '" << _renderEngine + gzdbg << "Engine '" << _renderEngine << "' is not supported" << std::endl; return; } @@ -400,7 +400,7 @@ void ThermalCameraSensorTest::Images8BitWithBuiltinSDF( // 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 8 bit thermal cameras" << std::endl; return; } @@ -409,7 +409,7 @@ void ThermalCameraSensorTest::Images8BitWithBuiltinSDF( auto *engine = gz::rendering::engine(_renderEngine); if (!engine) { - igndbg << "Engine '" << _renderEngine + gzdbg << "Engine '" << _renderEngine << "' is not supported" << std::endl; return; } diff --git a/test/integration/triggered_camera.cc b/test/integration/triggered_camera.cc index 305f7df7..72fdae7c 100644 --- a/test/integration/triggered_camera.cc +++ b/test/integration/triggered_camera.cc @@ -82,7 +82,7 @@ void TriggeredCameraTest::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; } diff --git a/test/integration/wide_angle_camera.cc b/test/integration/wide_angle_camera.cc index 21750473..93b88660 100644 --- a/test/integration/wide_angle_camera.cc +++ b/test/integration/wide_angle_camera.cc @@ -118,7 +118,7 @@ void WideAngleCameraSensorTest::ImagesWithBuiltinSDF( auto *engine = gz::rendering::engine(_renderEngine); if (!engine) { - igndbg << "Engine '" << _renderEngine + gzdbg << "Engine '" << _renderEngine << "' is not supported" << std::endl; return; }