Skip to content

Commit 1bda368

Browse files
committed
CameraSensor: use Sensor::FrameId only
Remove all references to sdf::Camera::OpticalFrameId. Signed-off-by: Steve Peters <scpeters@openrobotics.org>
1 parent 71647e6 commit 1bda368

File tree

2 files changed

+5
-47
lines changed

2 files changed

+5
-47
lines changed

src/CameraSensor.cc

Lines changed: 3 additions & 24 deletions
Original file line numberDiff line numberDiff line change
@@ -118,9 +118,6 @@ class gz::sensors::CameraSensorPrivate
118118
/// \brief Camera information message.
119119
public: msgs::CameraInfo infoMsg;
120120

121-
/// \brief The frame this camera uses in its camera_info topic.
122-
public: std::string opticalFrameId{""};
123-
124121
/// \brief Topic for info message.
125122
public: std::string infoTopic{""};
126123

@@ -511,7 +508,7 @@ bool CameraSensor::Update(const std::chrono::steady_clock::duration &_now)
511508
*msg.mutable_header()->mutable_stamp() = msgs::Convert(_now);
512509
auto frame = msg.mutable_header()->add_data();
513510
frame->set_key("frame_id");
514-
frame->add_value(this->dataPtr->opticalFrameId);
511+
frame->add_value(this->FrameId());
515512
msg.set_data(data, this->dataPtr->camera->ImageMemorySize());
516513
}
517514

@@ -708,27 +705,9 @@ void CameraSensor::PopulateInfo(const sdf::Camera *_cameraSdf)
708705
this->dataPtr->infoMsg.add_rectification_matrix(0.0);
709706
this->dataPtr->infoMsg.add_rectification_matrix(1.0);
710707

711-
// Note: while Gazebo interprets the camera frame to be looking towards +X,
712-
// other tools, such as ROS, may interpret this frame as looking towards +Z.
713-
// To make this configurable the user has the option to set an optical frame.
714-
// If the user has set <optical_frame_id> in the cameraSdf use it,
715-
// otherwise fall back to the sensor frame.
716-
// \todo(iche033 sdf::Camera::OpticalFrameId is deprecated.
717-
// Remove this if statement when gz-sensors is updated to use sdformat16
718-
GZ_UTILS_WARN_IGNORE__DEPRECATED_DECLARATION
719-
if (_cameraSdf->OpticalFrameId().empty())
720-
{
721-
this->dataPtr->opticalFrameId = this->FrameId();
722-
}
723-
else
724-
{
725-
this->dataPtr->opticalFrameId = _cameraSdf->OpticalFrameId();
726-
}
727-
GZ_UTILS_WARN_RESUME__DEPRECATED_DECLARATION
728-
729708
auto infoFrame = this->dataPtr->infoMsg.mutable_header()->add_data();
730709
infoFrame->set_key("frame_id");
731-
infoFrame->add_value(this->dataPtr->opticalFrameId);
710+
infoFrame->add_value(this->FrameId());
732711

733712
this->dataPtr->infoMsg.set_width(width);
734713
this->dataPtr->infoMsg.set_height(height);
@@ -776,7 +755,7 @@ bool CameraSensor::HasInfoConnections() const
776755
//////////////////////////////////////////////////
777756
const std::string& CameraSensor::OpticalFrameId() const
778757
{
779-
return this->dataPtr->opticalFrameId;
758+
return this->FrameId();
780759
}
781760

782761
//////////////////////////////////////////////////

src/RgbdCameraSensor.cc

Lines changed: 2 additions & 23 deletions
Original file line numberDiff line numberDiff line change
@@ -105,9 +105,6 @@ class gz::sensors::RgbdCameraSensorPrivate
105105
/// point cloud.
106106
public: unsigned int channels = 4;
107107

108-
/// \brief Frame ID the camera_info message header is expressed.
109-
public: std::string opticalFrameId{""};
110-
111108
/// \brief Pointer to an image to be published
112109
public: gz::rendering::Image image;
113110

@@ -295,24 +292,6 @@ bool RgbdCameraSensor::CreateCameras()
295292
this->dataPtr->depthCamera->SetNearClipPlane(cameraSdf->NearClip());
296293
this->dataPtr->depthCamera->SetFarClipPlane(cameraSdf->FarClip());
297294

298-
// Note: while Gazebo interprets the camera frame to be looking towards +X,
299-
// other tools, such as ROS, may interpret this frame as looking towards +Z.
300-
// To make this configurable the user has the option to set an optical frame.
301-
// If the user has set <optical_frame_id> in the cameraSdf use it,
302-
// otherwise fall back to the sensor frame.
303-
// \todo(iche033 sdf::Camera::OpticalFrameId is deprecated.
304-
// Remove this if statement when gz-sensors is updated to use sdformat16
305-
GZ_UTILS_WARN_IGNORE__DEPRECATED_DECLARATION
306-
if (cameraSdf->OpticalFrameId().empty())
307-
{
308-
this->dataPtr->opticalFrameId = this->FrameId();
309-
}
310-
else
311-
{
312-
this->dataPtr->opticalFrameId = cameraSdf->OpticalFrameId();
313-
}
314-
GZ_UTILS_WARN_RESUME__DEPRECATED_DECLARATION
315-
316295
// Depth camera clip params are new and only override the camera clip
317296
// params if specified.
318297
if (cameraSdf->HasDepthCamera())
@@ -525,7 +504,7 @@ bool RgbdCameraSensor::Update(const std::chrono::steady_clock::duration &_now)
525504
*msg.mutable_header()->mutable_stamp() = msgs::Convert(_now);
526505
auto frame = msg.mutable_header()->add_data();
527506
frame->set_key("frame_id");
528-
frame->add_value(this->dataPtr->opticalFrameId);
507+
frame->add_value(this->FrameId());
529508

530509
std::lock_guard<std::mutex> lock(this->dataPtr->mutex);
531510

@@ -637,7 +616,7 @@ bool RgbdCameraSensor::Update(const std::chrono::steady_clock::duration &_now)
637616
*msg.mutable_header()->mutable_stamp() = msgs::Convert(_now);
638617
auto frame = msg.mutable_header()->add_data();
639618
frame->set_key("frame_id");
640-
frame->add_value(this->dataPtr->opticalFrameId);
619+
frame->add_value(this->FrameId());
641620
msg.set_data(data, rendering::PixelUtil::MemorySize(rendering::PF_R8G8B8,
642621
width, height));
643622

0 commit comments

Comments
 (0)