Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Add camera sensor frame_id variable #806

Closed
wants to merge 2 commits into from
Closed
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
14 changes: 14 additions & 0 deletions include/sdf/Camera.hh
Original file line number Diff line number Diff line change
Expand Up @@ -324,6 +324,20 @@ namespace sdf
/// \param[in] _frame The name of the pose relative-to frame.
public: void SetPoseRelativeTo(const std::string &_frame);

/// \brief Get the name of the coordinate frame relative to which this
/// object's camera_info message header is expressed.
/// Note: while Gazebo interprets the camera frame to be looking towards +X,
/// other tools, such as ROS interprets this frame as looking towards +Z.
/// The Camera sensor assumes that the color and depth images are captured at
/// the same frame_id.
/// \return The name of the frame this camera uses in its camera_info topic.
public: const std::string OpticalFrameId() const;

/// \brief Set the name of the coordinate frame relative to which this
/// object's camera_info is expressed.
/// \param[in] _frame The frame this camera uses in its camera_info topic.
public: void SetOpticalFrameId(const std::string &_frame);

/// \brief Get the lens type. This is the type of the lens mapping.
/// Supported values are gnomonical, stereographic, equidistant,
/// equisolid_angle, orthographic, custom. For gnomonical (perspective)
Expand Down
23 changes: 22 additions & 1 deletion src/Camera.cc
Original file line number Diff line number Diff line change
Expand Up @@ -133,6 +133,9 @@ class sdf::Camera::Implementation
/// \brief Frame of the pose.
public: std::string poseRelativeTo = "";

/// \brief Frame ID the camera_info message header is expressed.
public: std::string opticalFrameId = "";

/// \brief Lens type.
public: std::string lensType{"stereographic"};

Expand Down Expand Up @@ -329,6 +332,11 @@ Errors Camera::Load(ElementPtr _sdf)
// Load the pose. Ignore the return value since the pose is optional.
loadPose(_sdf, this->dataPtr->pose, this->dataPtr->poseRelativeTo);

if (_sdf->HasElement("optical_frame_id"))
{
this->dataPtr->opticalFrameId = _sdf->Get<std::string>("optical_frame_id", "").first;
}

// Load the lens values.
if (_sdf->HasElement("lens"))
{
Expand Down Expand Up @@ -635,7 +643,8 @@ bool Camera::operator==(const Camera &_cam) const
this->SaveFrames() == _cam.SaveFrames() &&
this->SaveFramesPath() == _cam.SaveFramesPath() &&
this->ImageNoise() == _cam.ImageNoise() &&
this->VisibilityMask() == _cam.VisibilityMask();
this->VisibilityMask() == _cam.VisibilityMask() &&
this->OpticalFrameId() == _cam.OpticalFrameId();
}

//////////////////////////////////////////////////
Expand Down Expand Up @@ -752,6 +761,18 @@ void Camera::SetPoseRelativeTo(const std::string &_frame)
this->dataPtr->poseRelativeTo = _frame;
}

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

/////////////////////////////////////////////////
void Camera::SetOpticalFrameId(const std::string &_frame)
{
this->dataPtr->opticalFrameId = _frame;
}

/////////////////////////////////////////////////
std::string Camera::LensType() const
{
Expand Down