Skip to content

Commit 4300c17

Browse files
Expose optical frame in CameraSensor so it can be set in DepthCameraSensor (#362)
Signed-off-by: Levi Armstrong <[email protected]>
1 parent 44c67b0 commit 4300c17

File tree

3 files changed

+25
-11
lines changed

3 files changed

+25
-11
lines changed

include/gz/sensors/CameraSensor.hh

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -146,6 +146,10 @@ namespace gz
146146
/// \todo(iche033) Make this function virtual on Harmonic
147147
public: bool HasInfoConnections() const;
148148

149+
/// \brief Get the camera optical frame
150+
/// \return The camera optical frame
151+
public: const std::string& OpticalFrameId() const;
152+
149153
/// \brief Advertise camera info topic.
150154
/// \return True if successful.
151155
protected: bool AdvertiseInfo();

src/CameraSensor.cc

Lines changed: 6 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -921,6 +921,12 @@ bool CameraSensor::HasInfoConnections() const
921921
return this->dataPtr->infoPub && this->dataPtr->infoPub.HasConnections();
922922
}
923923

924+
//////////////////////////////////////////////////
925+
const std::string& CameraSensor::OpticalFrameId() const
926+
{
927+
return this->dataPtr->opticalFrameId;
928+
}
929+
924930
//////////////////////////////////////////////////
925931
math::Matrix4d CameraSensorPrivate::BuildProjectionMatrix(
926932
double _imageWidth, double _imageHeight,

src/DepthCameraSensor.cc

Lines changed: 15 additions & 11 deletions
Original file line numberDiff line numberDiff line change
@@ -299,15 +299,6 @@ bool DepthCameraSensor::Load(const sdf::Sensor &_sdf)
299299
gzdbg << "Points for [" << this->Name() << "] advertised on ["
300300
<< this->Topic() << "/points]" << std::endl;
301301

302-
// Initialize the point message.
303-
// \todo(anyone) The true value in the following function call forces
304-
// the xyz and rgb fields to be aligned to memory boundaries. This is need
305-
// by ROS1: https://github.com/ros/common_msgs/pull/77. Ideally, memory
306-
// alignment should be configured.
307-
msgs::InitPointCloudPacked(this->dataPtr->pointMsg, this->FrameId(), true,
308-
{{"xyz", msgs::PointCloudPacked::Field::FLOAT32},
309-
{"rgb", msgs::PointCloudPacked::Field::FLOAT32}});
310-
311302
if (this->Scene())
312303
{
313304
this->CreateCamera();
@@ -422,6 +413,18 @@ bool DepthCameraSensor::CreateCamera()
422413
std::placeholders::_1, std::placeholders::_2, std::placeholders::_3,
423414
std::placeholders::_4, std::placeholders::_5));
424415

416+
// Initialize the point message.
417+
// \todo(anyone) The true value in the following function call forces
418+
// the xyz and rgb fields to be aligned to memory boundaries. This is need
419+
// by ROS1: https://github.com/ros/common_msgs/pull/77. Ideally, memory
420+
// alignment should be configured.
421+
msgs::InitPointCloudPacked(
422+
this->dataPtr->pointMsg,
423+
this->OpticalFrameId(),
424+
true,
425+
{{"xyz", msgs::PointCloudPacked::Field::FLOAT32},
426+
{"rgb", msgs::PointCloudPacked::Field::FLOAT32}});
427+
425428
// Set the values of the point message based on the camera information.
426429
this->dataPtr->pointMsg.set_width(this->ImageWidth());
427430
this->dataPtr->pointMsg.set_height(this->ImageHeight());
@@ -549,9 +552,10 @@ bool DepthCameraSensor::Update(
549552
rendering::PF_FLOAT32_R));
550553
msg.set_pixel_format_type(msgsFormat);
551554
*msg.mutable_header()->mutable_stamp() = msgs::Convert(_now);
552-
auto frame = msg.mutable_header()->add_data();
555+
556+
auto* frame = msg.mutable_header()->add_data();
553557
frame->set_key("frame_id");
554-
frame->add_value(this->FrameId());
558+
frame->add_value(this->OpticalFrameId());
555559

556560
std::lock_guard<std::mutex> lock(this->dataPtr->mutex);
557561
msg.set_data(this->dataPtr->depthBuffer,

0 commit comments

Comments
 (0)