Skip to content

Commit 76532a6

Browse files
authored
Better GZ_PROFILE instrumentation for rendering sensors (#532)
Signed-off-by: Maksim Derbasov <ntfs.hard@gmail.com>
1 parent aa52001 commit 76532a6

File tree

12 files changed

+43
-28
lines changed

12 files changed

+43
-28
lines changed

examples/loop_sensor/main.cc

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -72,7 +72,7 @@ int main(int argc, char **argv)
7272
{
7373
auto sensor = link->SensorByIndex(s);
7474

75-
gz::sensors::Sensor *sensorPtr;
75+
gz::sensors::Sensor *sensorPtr{};
7676
if (sensor->Type() == sdf::SensorType::ALTIMETER)
7777
{
7878
sensorPtr = mgr.CreateSensor<gz::sensors::AltimeterSensor>(

include/gz/sensors/Manager.hh

Lines changed: 3 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -17,11 +17,10 @@
1717
#ifndef GZ_SENSORS_MANAGER_HH_
1818
#define GZ_SENSORS_MANAGER_HH_
1919

20+
#include <chrono>
2021
#include <memory>
21-
#include <string>
2222
#include <utility>
2323
#include <type_traits>
24-
#include <vector>
2524
#include <sdf/sdf.hh>
2625
#include <gz/utils/SuppressWarning.hh>
2726
#include <gz/common/Console.hh>
@@ -42,7 +41,7 @@ namespace gz
4241
/// \brief Loads and runs sensors
4342
///
4443
/// This class is responsible for loading and running sensors, and
45-
/// providing sensors with common environments to generat data from.
44+
/// providing sensors with common environments to generate data from.
4645
///
4746
/// The primary interface through which to load a sensor is LoadSensor().
4847
/// This takes an sdf element pointer that should be configured with
@@ -62,7 +61,7 @@ namespace gz
6261
/// \return True if successfully initialized, false if not
6362
public: bool Init();
6463

65-
/// \brief Create a sensor from an SDF ovject with a known sensor type.
64+
/// \brief Create a sensor from an SDF object with a known sensor type.
6665
/// \sa Sensor()
6766
/// \param[in] _sdf An SDF element or DOM object.
6867
/// \tparam SensorType Sensor type

src/BoundingBoxCameraSensor.cc

Lines changed: 2 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -393,10 +393,9 @@ rendering::BoundingBoxCameraPtr
393393
void BoundingBoxCameraSensor::OnNewBoundingBoxes(
394394
const std::vector<rendering::BoundingBox> &_boxes)
395395
{
396+
GZ_PROFILE("BoundingBoxCameraSensor::OnNewBoundingBoxes");
396397
std::lock_guard<std::mutex> lock(this->dataPtr->mutex);
397-
this->dataPtr->boundingBoxes.clear();
398-
for (const auto &box : _boxes)
399-
this->dataPtr->boundingBoxes.push_back(box);
398+
this->dataPtr->boundingBoxes = _boxes;
400399
}
401400

402401
//////////////////////////////////////////////////

src/CameraSensor.cc

Lines changed: 4 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -15,7 +15,6 @@
1515
*
1616
*/
1717

18-
#include <gz/msgs/boolean.pb.h>
1918
#include <gz/msgs/camera_info.pb.h>
2019
#include <gz/msgs/image.pb.h>
2120

@@ -428,8 +427,8 @@ bool CameraSensor::Update(const std::chrono::steady_clock::duration &_now)
428427
{
429428
if (this->dataPtr->generatingData)
430429
{
431-
gzdbg << "Disabling camera sensor: '" << this->Name() << "' data "
432-
<< "generation. " << std::endl;;
430+
gzdbg << "Disabling camera sensor: '" << this->Name()
431+
<< "' data generation. " << std::endl;
433432
this->dataPtr->generatingData = false;
434433
}
435434

@@ -439,8 +438,8 @@ bool CameraSensor::Update(const std::chrono::steady_clock::duration &_now)
439438
{
440439
if (!this->dataPtr->generatingData)
441440
{
442-
gzdbg << "Enabling camera sensor: '" << this->Name() << "' data "
443-
<< "generation." << std::endl;;
441+
gzdbg << "Enabling camera sensor: '" << this->Name()
442+
<< "' data generation." << std::endl;
444443
this->dataPtr->generatingData = true;
445444
}
446445
}

src/DepthCameraSensor.cc

Lines changed: 6 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -461,6 +461,7 @@ void DepthCameraSensor::OnNewDepthFrame(const float *_scan,
461461
unsigned int /*_channels*/,
462462
const std::string &_format)
463463
{
464+
GZ_PROFILE("DepthCameraSensor::OnNewDepthFrame");
464465
std::lock_guard<std::mutex> lock(this->dataPtr->mutex);
465466

466467
unsigned int depthSamples = _width * _height;
@@ -488,6 +489,7 @@ void DepthCameraSensor::OnNewRgbPointCloud(const float *_scan,
488489
unsigned int _channels,
489490
const std::string &/*_format*/)
490491
{
492+
GZ_PROFILE("DepthCameraSensor::OnNewRgbPointCloud");
491493
std::lock_guard<std::mutex> lock(this->dataPtr->mutex);
492494

493495
unsigned int pointCloudSamples = _width * _height;
@@ -595,10 +597,12 @@ bool DepthCameraSensor::Update(
595597
msg.set_data(this->dataPtr->depthBuffer,
596598
rendering::PixelUtil::MemorySize(rendering::PF_FLOAT32_R,
597599
width, height));
598-
599600
this->AddSequence(msg.mutable_header(), "default");
600-
this->dataPtr->pub.Publish(msg);
601601

602+
{
603+
GZ_PROFILE("DepthCameraSensor::Update Publish");
604+
this->dataPtr->pub.Publish(msg);
605+
}
602606

603607
if (this->dataPtr->imageEvent.ConnectionCount() > 0u)
604608
{

src/GpuLidarSensor.cc

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -236,6 +236,7 @@ void GpuLidarSensor::OnNewLidarFrame(const float *_scan,
236236
unsigned int _width, unsigned int _height, unsigned int _channels,
237237
const std::string &_format)
238238
{
239+
GZ_PROFILE("GpuLidarSensor::OnNewLidarFrame");
239240
std::lock_guard<std::mutex> lock(this->lidarMutex);
240241

241242
unsigned int samples = _width * _height * _channels;

src/ImuSensor_TEST.cc

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -508,7 +508,7 @@ TEST(ImuSensor_TEST, CustomRpyParentFrame)
508508
}
509509

510510
sdf::ElementPtr sensorWithLocalization(
511-
std::string _orientationLocalization)
511+
const std::string &_orientationLocalization)
512512
{
513513
std::ostringstream stream;
514514
stream

src/LogicalCameraSensor.cc

Lines changed: 6 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -194,7 +194,6 @@ bool LogicalCameraSensor::Update(
194194
frame_log->set_key("frame_id");
195195
frame_log->add_value(this->FrameId());
196196

197-
// publish
198197
this->dataPtr->msgLogic.set_near_clip(this->dataPtr->frustum.Near());
199198
this->dataPtr->msgLogic.set_far_clip(this->dataPtr->frustum.Far());
200199
this->dataPtr->msgLogic.set_horizontal_fov(
@@ -203,8 +202,12 @@ bool LogicalCameraSensor::Update(
203202
this->dataPtr->frustum.AspectRatio());
204203
this->AddSequence(this->dataPtr->msg.mutable_header());
205204

206-
this->dataPtr->pub.Publish(this->dataPtr->msg);
207-
this->dataPtr->pubLogic.Publish(this->dataPtr->msgLogic);
205+
// publish
206+
{
207+
GZ_PROFILE("LogicalCameraSensor::Update Publish");
208+
this->dataPtr->pub.Publish(this->dataPtr->msg);
209+
this->dataPtr->pubLogic.Publish(this->dataPtr->msgLogic);
210+
}
208211

209212
return true;
210213
}

src/RgbdCameraSensor.cc

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -431,6 +431,7 @@ void RgbdCameraSensorPrivate::OnNewDepthFrame(const float *_scan,
431431
unsigned int /*_channels*/,
432432
const std::string &/*_format*/)
433433
{
434+
GZ_PROFILE("RgbdCameraSensorPrivate::OnNewDepthFrame");
434435
std::lock_guard<std::mutex> lock(this->mutex);
435436

436437
unsigned int depthSamples = _width * _height;
@@ -448,6 +449,7 @@ void RgbdCameraSensorPrivate::OnNewRgbPointCloud(const float *_scan,
448449
unsigned int _channels,
449450
const std::string &/*_format*/)
450451
{
452+
GZ_PROFILE("RgbdCameraSensorPrivate::OnNewRgbPointCloud");
451453
std::lock_guard<std::mutex> lock(this->mutex);
452454

453455
unsigned int pointCloudSamples = _width * _height;
@@ -513,7 +515,7 @@ bool RgbdCameraSensor::Update(const std::chrono::steady_clock::duration &_now)
513515
// generate sensor data
514516
this->Render();
515517

516-
// create and publish the depthmessage
518+
// create and publish the depth message
517519
if (this->HasDepthConnections())
518520
{
519521
msgs::Image msg;

src/SegmentationCameraSensor.cc

Lines changed: 6 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -434,6 +434,7 @@ void SegmentationCameraSensor::OnNewSegmentationFrame(const uint8_t * _data,
434434
unsigned int _width, unsigned int _height, unsigned int _channels,
435435
const std::string &/*_format*/)
436436
{
437+
GZ_PROFILE("SegmentationCameraSensor::OnNewSegmentationFrame");
437438
std::lock_guard<std::mutex> lock(this->dataPtr->mutex);
438439

439440
unsigned int bufferSize = _width * _height * _channels;
@@ -539,8 +540,11 @@ bool SegmentationCameraSensor::Update(
539540
width, height));
540541

541542
// Publish
542-
this->dataPtr->coloredMapPublisher.Publish(this->dataPtr->coloredMapMsg);
543-
this->dataPtr->labelsMapPublisher.Publish(this->dataPtr->labelsMapMsg);
543+
{
544+
GZ_PROFILE("SegmentationCameraSensor::Update Publish");
545+
this->dataPtr->coloredMapPublisher.Publish(this->dataPtr->coloredMapMsg);
546+
this->dataPtr->labelsMapPublisher.Publish(this->dataPtr->labelsMapMsg);
547+
}
544548

545549
// Trigger callbacks.
546550
if (this->dataPtr->imageEvent.ConnectionCount() > 0u)

0 commit comments

Comments
 (0)