From 32576a84b994efa48a9860665233f82da8be979d Mon Sep 17 00:00:00 2001 From: Kvk Praneeth <55596533+kvkpraneeth@users.noreply.github.com> Date: Thu, 8 Jun 2023 13:31:19 +0530 Subject: [PATCH 1/3] Fix frame_id for depth camera point cloud (#350) Signed-off-by: kvkpraneeth --- src/DepthCameraSensor.cc | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/DepthCameraSensor.cc b/src/DepthCameraSensor.cc index d2c2c556..e295d0e5 100644 --- a/src/DepthCameraSensor.cc +++ b/src/DepthCameraSensor.cc @@ -304,7 +304,7 @@ bool DepthCameraSensor::Load(const sdf::Sensor &_sdf) // the xyz and rgb fields to be aligned to memory boundaries. This is need // by ROS1: https://github.com/ros/common_msgs/pull/77. Ideally, memory // alignment should be configured. - msgs::InitPointCloudPacked(this->dataPtr->pointMsg, this->Name(), true, + msgs::InitPointCloudPacked(this->dataPtr->pointMsg, this->FrameId(), true, {{"xyz", msgs::PointCloudPacked::Field::FLOAT32}, {"rgb", msgs::PointCloudPacked::Field::FLOAT32}}); From 28089ab93edf3b612f5a901a14f4f29e600b7e3b Mon Sep 17 00:00:00 2001 From: shameekganguly Date: Thu, 8 Jun 2023 10:24:41 -0700 Subject: [PATCH 2/3] Minor cleanup - lint, typos (#352) * Change remaining ignerr to gzerr * Add one missing header * Ensure parameter names match in function declaration and definition --------- Signed-off-by: Shameek Ganguly --- include/gz/sensors/DepthCameraSensor.hh | 4 ++-- src/CameraSensor.cc | 2 +- src/GpuLidarSensor.cc | 6 +++--- src/NavSatSensor.cc | 2 ++ src/SegmentationCameraSensor.cc | 4 ++-- src/Sensor.cc | 4 ++-- 6 files changed, 12 insertions(+), 10 deletions(-) diff --git a/include/gz/sensors/DepthCameraSensor.hh b/include/gz/sensors/DepthCameraSensor.hh index 3dc31767..77c6d85c 100644 --- a/include/gz/sensors/DepthCameraSensor.hh +++ b/include/gz/sensors/DepthCameraSensor.hh @@ -105,12 +105,12 @@ namespace gz const std::string &/*_format*/); /// \brief Point cloud data callback used to get the data from the sensor - /// \param[in] _data pointer to the data from the sensor + /// \param[in] _scan pointer to the data from the sensor /// \param[in] _width width of the point cloud image /// \param[in] _height height of the point cloud image /// \param[in] _channel bytes used for the point cloud data /// \param[in] _format string with the format - public: void OnNewRgbPointCloud(const float *_data, + public: void OnNewRgbPointCloud(const float *_scan, unsigned int _width, unsigned int _height, unsigned int /*_channels*/, const std::string &/*_format*/); diff --git a/src/CameraSensor.cc b/src/CameraSensor.cc index 977c7bdc..e8f99e76 100644 --- a/src/CameraSensor.cc +++ b/src/CameraSensor.cc @@ -671,7 +671,7 @@ bool CameraSensor::Update(const std::chrono::steady_clock::duration &_now) } catch(...) { - ignerr << "Exception thrown in an image callback.\n"; + gzerr << "Exception thrown in an image callback.\n"; } } diff --git a/src/GpuLidarSensor.cc b/src/GpuLidarSensor.cc index 941fce96..ff3e9aa1 100644 --- a/src/GpuLidarSensor.cc +++ b/src/GpuLidarSensor.cc @@ -239,7 +239,7 @@ bool GpuLidarSensor::CreateLidar() } ///////////////////////////////////////////////// -void GpuLidarSensor::OnNewLidarFrame(const float *_data, +void GpuLidarSensor::OnNewLidarFrame(const float *_scan, unsigned int _width, unsigned int _height, unsigned int _channels, const std::string &_format) { @@ -251,11 +251,11 @@ void GpuLidarSensor::OnNewLidarFrame(const float *_data, if (!this->laserBuffer) this->laserBuffer = new float[samples]; - memcpy(this->laserBuffer, _data, lidarBufferSize); + memcpy(this->laserBuffer, _scan, lidarBufferSize); if (this->dataPtr->lidarEvent.ConnectionCount() > 0) { - this->dataPtr->lidarEvent(_data, _width, _height, _channels, _format); + this->dataPtr->lidarEvent(_scan, _width, _height, _channels, _format); } } diff --git a/src/NavSatSensor.cc b/src/NavSatSensor.cc index fa105ebc..be6e1786 100644 --- a/src/NavSatSensor.cc +++ b/src/NavSatSensor.cc @@ -15,6 +15,8 @@ * */ +#include + #ifdef _WIN32 #pragma warning(push) #pragma warning(disable: 4005) diff --git a/src/SegmentationCameraSensor.cc b/src/SegmentationCameraSensor.cc index 04e5cb87..70fa38f8 100644 --- a/src/SegmentationCameraSensor.cc +++ b/src/SegmentationCameraSensor.cc @@ -406,12 +406,12 @@ rendering::SegmentationCameraPtr SegmentationCameraSensor::SegmentationCamera() ///////////////////////////////////////////////// void SegmentationCameraSensor::OnNewSegmentationFrame(const uint8_t * _data, - unsigned int _width, unsigned int _height, unsigned int _channles, + unsigned int _width, unsigned int _height, unsigned int _channels, const std::string &/*_format*/) { std::lock_guard lock(this->dataPtr->mutex); - unsigned int bufferSize = _width * _height * _channles; + unsigned int bufferSize = _width * _height * _channels; if (!this->dataPtr->segmentationColoredBuffer) this->dataPtr->segmentationColoredBuffer = new uint8_t[bufferSize]; diff --git a/src/Sensor.cc b/src/Sensor.cc index 242b02d3..ef6c10bd 100644 --- a/src/Sensor.cc +++ b/src/Sensor.cc @@ -345,8 +345,8 @@ void SensorPrivate::PublishMetrics(const std::chrono::duration &_now) } // Computes simulation update rate and real update rate. - double simUpdateRate; - double realUpdateRate; + double simUpdateRate = 0; + double realUpdateRate = 0; const auto clockNow = std::chrono::steady_clock::now(); // If lastUpdateTime == 0 means it wasn't initialized yet. if (this->lastUpdateTime.count() > 0) From 4f73c0a240b52b8f0eb99afa1f760cf2c491126e Mon Sep 17 00:00:00 2001 From: Silvio Traversaro Date: Sat, 10 Jun 2023 02:51:59 +0200 Subject: [PATCH 3/3] Support protobuf >= 22 (#351) Signed-off-by: Silvio Traversaro --- CMakeLists.txt | 2 -- 1 file changed, 2 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index b274d160..51817fc2 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -38,9 +38,7 @@ message(STATUS "\n\n-- ====== Finding Dependencies ======") #-------------------------------------- # Find Protobuf -set(REQ_PROTOBUF_VER 3) ign_find_package(IgnProtobuf - VERSION ${REQ_PROTOBUF_VER} REQUIRED PRETTY Protobuf)