Skip to content

Commit

Permalink
Merge branch 'gz-sensors7' into scpeters/merge_7_main
Browse files Browse the repository at this point in the history
  • Loading branch information
scpeters committed Jun 18, 2023
2 parents 68c1839 + a5a0c34 commit 2527ef1
Show file tree
Hide file tree
Showing 8 changed files with 15 additions and 15 deletions.
6 changes: 2 additions & 4 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -38,11 +38,9 @@ message(STATUS "\n\n-- ====== Finding Dependencies ======")

#--------------------------------------
# Find Protobuf
set(REQ_PROTOBUF_VER 3)
gz_find_package(GzProtobuf
VERSION ${REQ_PROTOBUF_VER}
REQUIRED
PRETTY Protobuf)
REQUIRED
PRETTY Protobuf)

#--------------------------------------
# Find gz-math
Expand Down
4 changes: 2 additions & 2 deletions include/gz/sensors/DepthCameraSensor.hh
Original file line number Diff line number Diff line change
Expand Up @@ -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*/);
Expand Down
2 changes: 1 addition & 1 deletion src/CameraSensor.cc
Original file line number Diff line number Diff line change
Expand Up @@ -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";

Check warning on line 674 in src/CameraSensor.cc

View check run for this annotation

Codecov / codecov/patch

src/CameraSensor.cc#L674

Added line #L674 was not covered by tests
}
}

Expand Down
2 changes: 1 addition & 1 deletion src/DepthCameraSensor.cc
Original file line number Diff line number Diff line change
Expand Up @@ -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}});

Expand Down
6 changes: 3 additions & 3 deletions src/GpuLidarSensor.cc
Original file line number Diff line number Diff line change
Expand Up @@ -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)
{
Expand All @@ -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);
}
}

Expand Down
2 changes: 2 additions & 0 deletions src/NavSatSensor.cc
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,8 @@
*
*/

#include <unordered_map>

#ifdef _WIN32
#pragma warning(push)
#pragma warning(disable: 4005)
Expand Down
4 changes: 2 additions & 2 deletions src/SegmentationCameraSensor.cc
Original file line number Diff line number Diff line change
Expand Up @@ -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<std::mutex> 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];
Expand Down
4 changes: 2 additions & 2 deletions src/Sensor.cc
Original file line number Diff line number Diff line change
Expand Up @@ -345,8 +345,8 @@ void SensorPrivate::PublishMetrics(const std::chrono::duration<double> &_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)
Expand Down

0 comments on commit 2527ef1

Please sign in to comment.