Skip to content

Commit

Permalink
Expose optical frame in CameraSensor so it can be set in DepthCameraS…
Browse files Browse the repository at this point in the history
…ensor (#362)

Signed-off-by: Levi Armstrong <[email protected]>
  • Loading branch information
Levi-Armstrong authored Jul 25, 2023
1 parent 44c67b0 commit 4300c17
Show file tree
Hide file tree
Showing 3 changed files with 25 additions and 11 deletions.
4 changes: 4 additions & 0 deletions include/gz/sensors/CameraSensor.hh
Original file line number Diff line number Diff line change
Expand Up @@ -146,6 +146,10 @@ namespace gz
/// \todo(iche033) Make this function virtual on Harmonic
public: bool HasInfoConnections() const;

/// \brief Get the camera optical frame
/// \return The camera optical frame
public: const std::string& OpticalFrameId() const;

/// \brief Advertise camera info topic.
/// \return True if successful.
protected: bool AdvertiseInfo();
Expand Down
6 changes: 6 additions & 0 deletions src/CameraSensor.cc
Original file line number Diff line number Diff line change
Expand Up @@ -921,6 +921,12 @@ bool CameraSensor::HasInfoConnections() const
return this->dataPtr->infoPub && this->dataPtr->infoPub.HasConnections();
}

//////////////////////////////////////////////////
const std::string& CameraSensor::OpticalFrameId() const
{
return this->dataPtr->opticalFrameId;
}

//////////////////////////////////////////////////
math::Matrix4d CameraSensorPrivate::BuildProjectionMatrix(
double _imageWidth, double _imageHeight,
Expand Down
26 changes: 15 additions & 11 deletions src/DepthCameraSensor.cc
Original file line number Diff line number Diff line change
Expand Up @@ -299,15 +299,6 @@ bool DepthCameraSensor::Load(const sdf::Sensor &_sdf)
gzdbg << "Points for [" << this->Name() << "] advertised on ["
<< this->Topic() << "/points]" << std::endl;

// Initialize the point message.
// \todo(anyone) The true value in the following function call forces
// 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->FrameId(), true,
{{"xyz", msgs::PointCloudPacked::Field::FLOAT32},
{"rgb", msgs::PointCloudPacked::Field::FLOAT32}});

if (this->Scene())
{
this->CreateCamera();
Expand Down Expand Up @@ -422,6 +413,18 @@ bool DepthCameraSensor::CreateCamera()
std::placeholders::_1, std::placeholders::_2, std::placeholders::_3,
std::placeholders::_4, std::placeholders::_5));

// Initialize the point message.
// \todo(anyone) The true value in the following function call forces
// 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->OpticalFrameId(),
true,
{{"xyz", msgs::PointCloudPacked::Field::FLOAT32},
{"rgb", msgs::PointCloudPacked::Field::FLOAT32}});

// Set the values of the point message based on the camera information.
this->dataPtr->pointMsg.set_width(this->ImageWidth());
this->dataPtr->pointMsg.set_height(this->ImageHeight());
Expand Down Expand Up @@ -549,9 +552,10 @@ bool DepthCameraSensor::Update(
rendering::PF_FLOAT32_R));
msg.set_pixel_format_type(msgsFormat);
*msg.mutable_header()->mutable_stamp() = msgs::Convert(_now);
auto frame = msg.mutable_header()->add_data();

auto* frame = msg.mutable_header()->add_data();
frame->set_key("frame_id");
frame->add_value(this->FrameId());
frame->add_value(this->OpticalFrameId());

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

0 comments on commit 4300c17

Please sign in to comment.