Loading...
Searching...
No Matches
Public Member Functions | Static Public Member Functions | List of all members
sdf::SDF_VERSION_NAMESPACE::Camera Class Reference

Information about a monocular camera sensor. More...

#include <Camera.hh>

Public Member Functions

 Camera ()
 Constructor.
 
uint32_t AntiAliasingValue () const
 Get the anti-aliasing value.
 
const std::string & BoundingBoxType () const
 Get the boundingbox type.
 
std::string CameraInfoTopic () const
 Get the camera info topic.
 
double DepthFarClip () const
 Get the far clip distance for the depth camera.
 
double DepthNearClip () const
 Get the near clip distance for the depth camera.
 
const gz::math::Vector2d & DistortionCenter () const
 Get the distortion center or principal point.
 
double DistortionK1 () const
 Get the radial distortion coefficient k1.
 
double DistortionK2 () const
 Get the radial distortion coefficient k2.
 
double DistortionK3 () const
 Get the radial distortion coefficient k3.
 
double DistortionP1 () const
 Get the tangential distortion coefficient p1.
 
double DistortionP2 () const
 Get the tangential distortion coefficient p2.
 
sdf::ElementPtr Element () const
 Get a pointer to the SDF element that was used during load.
 
double FarClip () const
 Get the far clip distance.
 
const std::string GZ_DEPRECATED (15) OpticalFrameId() const
 Get the name of the coordinate frame relative to which this object's camera_info message header is expressed.
 
bool HasBoundingBoxType () const
 Get whether the boundingbox type was set.
 
bool HasDepthCamera () const
 Get whether the depth camera was set.
 
bool HasDepthFarClip () const
 Get whether the depth camera far clip distance was set.
 
bool HasDepthNearClip () const
 Get whether the depth camera near clip distance was set.
 
bool HasLensIntrinsics () const
 Get whether or not the camera has instrinsics values set.
 
bool HasLensProjection () const
 Get whether or not the camera has projection values set.
 
bool HasSegmentationType () const
 Get whether the segmentation type was set.
 
gz::math::Angle HorizontalFov () const
 Get the horizontal field of view in radians.
 
uint32_t ImageHeight () const
 Get the image height in pixels.
 
const NoiseImageNoise () const
 Get the image noise values.
 
uint32_t ImageWidth () const
 Get the image width in pixels.
 
double LensC1 () const
 Get lens custom function linear scaling constant.
 
double LensC2 () const
 Get lens custom function angular scaling constant.
 
double LensC3 () const
 Get lens custom function angle offset constant.
 
gz::math::Angle LensCutoffAngle () const
 Get lens cutoff angle.
 
int LensEnvironmentTextureSize () const
 Get environment texture size.
 
double LensFocalLength () const
 Get lens custom function focal length.
 
const std::string & LensFunction () const
 Get lens custom function.
 
double LensIntrinsicsCx () const
 Get the lens intrinsic matrix X principal point in pixels.
 
double LensIntrinsicsCy () const
 Get the lens intrinsic matrix Y principal point in pixels.
 
double LensIntrinsicsFx () const
 Get the lens intrinsic matrix X focal length in pixels.
 
double LensIntrinsicsFy () const
 Get the lens intrinsic matrix Y focal length in pixels.
 
double LensIntrinsicsSkew () const
 Get the lens XY axis skew.
 
double LensProjectionCx () const
 Get the lens projection matrix X principal point in pixels.
 
double LensProjectionCy () const
 Get the lens projection matrix Y principal point in pixels.
 
double LensProjectionFx () const
 Get the lens projection matrix X focal length in pixels.
 
double LensProjectionFy () const
 Get the lens projection matrix Y focal length in pixels.
 
double LensProjectionTx () const
 Get the lens projection matrix X translation in pixels.
 
double LensProjectionTy () const
 Get the lens projection matrix Y translation in pixels.
 
bool LensScaleToHfov () const
 Get lens scale to horizontal field of field.
 
std::string LensType () const
 Set the name of the coordinate frame relative to which this object's camera_info is expressed.
 
Errors Load (ElementPtr _sdf)
 Load the camera sensor based on an element pointer.
 
std::string Name () const
 Get the name of the camera.
 
double NearClip () const
 Get the near clip distance.
 
bool operator!= (const Camera &_alt) const
 Return true this Camera object does not contain the same values as the passed in parameter.
 
bool operator== (const Camera &_alt) const
 Return true if both Camera objects contain the same values.
 
PixelFormatType PixelFormat () const
 Get the pixel format.
 
std::string PixelFormatStr () const
 Get the pixel format as a string.
 
const std::string & PoseRelativeTo () const
 Get the name of the coordinate frame relative to which this object's pose is expressed.
 
const gz::math::Pose3d & RawPose () const
 Get the pose of the camer.
 
bool SaveFrames () const
 Get whether frames should be saved.
 
const std::string & SaveFramesPath () const
 Get the path in which to save frames.
 
const std::string & SegmentationType () const
 Get the segmentation type.
 
void SetAntiAliasingValue (uint32_t _antiAliasingValue)
 Set the anti-aliasing value.
 
void SetBoundingBoxType (const std::string &_type)
 Set the boundingbox type.
 
void SetCameraInfoTopic (const std::string &_cameraInfoTopic)
 Set the camera info topic.
 
void SetDepthFarClip (double _far)
 Set the far clip distance for the depth camera.
 
void SetDepthNearClip (double _near)
 Set the near clip distance for the depth camera.
 
void SetDistortionCenter (const gz::math::Vector2d &_center)
 Set the distortion center or principal point.
 
void SetDistortionK1 (double _k1)
 Set the radial distortion coefficient k1.
 
void SetDistortionK2 (double _k2)
 Set the radial distortion coefficient k2.
 
void SetDistortionK3 (double _k3)
 Set the radial distortion coefficient k3.
 
void SetDistortionP1 (double _p1)
 Set the tangential distortion coefficient p1.
 
void SetDistortionP2 (double _p2)
 Set the tangential distortion coefficient p2.
 
void SetFarClip (double _far)
 Set the far clip distance.
 
void SetHasBoundingBoxType (bool _type)
 Set whether the boundingbox type has been specified.
 
void SetHasDepthCamera (bool _camera)
 Set whether the depth camera has been specified.
 
void SetHasDepthFarClip (bool _far)
 Set whether the depth camera far clip distance has been specified.
 
void SetHasDepthNearClip (bool _near)
 Set whether the depth camera near clip distance has been specified.
 
void SetHasSegmentationType (bool _type)
 Set whether the segmentation type has been specified.
 
void SetHorizontalFov (const gz::math::Angle &_hfov)
 Set the horizontal field of view in radians.
 
void SetImageHeight (uint32_t _height)
 Set the image height in pixels.
 
void SetImageNoise (const Noise &_noise)
 Set the noise values related to the image.
 
void SetImageWidth (uint32_t _width)
 Set the image width in pixels.
 
void SetLensC1 (double _c1)
 Set lens custom function linear scaling constant.
 
void SetLensC2 (double _c2)
 Set lens custom function angular scaling constant.
 
void SetLensC3 (double _c3)
 Set lens custom function angle offset constant.
 
void SetLensCutoffAngle (const gz::math::Angle &_angle)
 Set lens cutoff angle.
 
void SetLensEnvironmentTextureSize (int _size)
 Set environment texture size.
 
void SetLensFocalLength (double _f)
 Set lens custom function focal length.
 
void SetLensFunction (const std::string &_fun)
 Set lens custom function.
 
void SetLensIntrinsicsCx (double _cx)
 Set the lens intrinsic matrix X principal point in pixels.
 
void SetLensIntrinsicsCy (double _cy)
 Set the lens intrinsic matrix Y principal point in pixels.
 
void SetLensIntrinsicsFx (double _fx)
 Set the lens intrinsic matrix X focal length in pixels.
 
void SetLensIntrinsicsFy (double _fy)
 Set the lens intrinsic matrix Y focal length in pixels.
 
void SetLensIntrinsicsSkew (double _s)
 Set the lens XY axis skew.
 
void SetLensProjectionCx (double _cx_p)
 Set the lens projection matrix X principal point in pixels.
 
void SetLensProjectionCy (double _cy_p)
 Set the lens projection matrix Y principal point in pixels.
 
void SetLensProjectionFx (double _fx_p)
 Set the lens projection matrix X focal length in pixels.
 
void SetLensProjectionFy (double _fy_p)
 Set the lens projection matrix Y focal length in pixels.
 
void SetLensProjectionTx (double _tx)
 Set the lens projection matrix X translation in pixels.
 
void SetLensProjectionTy (double _ty)
 Set the lens projection matrix Y translation in pixels.
 
void SetLensScaleToHfov (bool _scale)
 Set lens scale to horizontal field of field.
 
void SetLensType (const std::string &_type)
 Set the lens type.
 
void SetName (const std::string &_name)
 Set the name of the camera.
 
void SetNearClip (double _near)
 Set the near clip distance.
 
void SetPixelFormat (PixelFormatType _format)
 Set the pixel format type.
 
void SetPixelFormatStr (const std::string &_fmt)
 Set the pixel format from a string.
 
void SetPoseRelativeTo (const std::string &_frame)
 Set the name of the coordinate frame relative to which this object's pose is expressed.
 
void SetRawPose (const gz::math::Pose3d &_pose)
 Set the pose of the camera.
 
void SetSaveFrames (bool _save)
 Set whether frames should be saved.
 
void SetSaveFramesPath (const std::string &_path)
 Set the path in which to save frames.
 
void SetSegmentationType (const std::string &_type)
 Set the segmentation type.
 
void SetTriggered (bool _triggered)
 Set whether the camera should be triggered by a topic.
 
void SetTriggerTopic (const std::string &_triggerTopic)
 Set the topic that will trigger the camera.
 
void SetVisibilityMask (uint32_t _mask)
 Set the visibility mask of a camera.
 
sdf::ElementPtr ToElement () const
 Create and return an SDF element filled with data from this camera.
 
bool Triggered () const
 Get whether the camera is triggered by a topic.
 
std::string TriggerTopic () const
 Get the topic that will trigger the camera.
 
uint32_t VisibilityMask () const
 Get the visibility mask of a camera.
 

Static Public Member Functions

static PixelFormatType ConvertPixelFormat (const std::string &_format)
 Convert a string to a PixelFormatType.
 
static std::string ConvertPixelFormat (PixelFormatType _type)
 Convert a PixelFormatType to a string.
 

Detailed Description

Information about a monocular camera sensor.

Constructor & Destructor Documentation

◆ Camera()

sdf::SDF_VERSION_NAMESPACE::Camera::Camera ( )

Constructor.

Member Function Documentation

◆ AntiAliasingValue()

uint32_t sdf::SDF_VERSION_NAMESPACE::Camera::AntiAliasingValue ( ) const

Get the anti-aliasing value.

Returns
The anti-aliasing value.

◆ BoundingBoxType()

const std::string & sdf::SDF_VERSION_NAMESPACE::Camera::BoundingBoxType ( ) const

Get the boundingbox type.

Returns
The boundingbox type.

◆ CameraInfoTopic()

std::string sdf::SDF_VERSION_NAMESPACE::Camera::CameraInfoTopic ( ) const

Get the camera info topic.

Returns
Topic for the camera info

◆ ConvertPixelFormat() [1/2]

static PixelFormatType sdf::SDF_VERSION_NAMESPACE::Camera::ConvertPixelFormat ( const std::string &  _format)
static

Convert a string to a PixelFormatType.

Parameters
[in]_formatString equivalent of a pixel format type to convert.
Returns
The matching PixelFormatType.

◆ ConvertPixelFormat() [2/2]

static std::string sdf::SDF_VERSION_NAMESPACE::Camera::ConvertPixelFormat ( PixelFormatType  _type)
static

Convert a PixelFormatType to a string.

Parameters
[in]_typePixel format type to convert.
Returns
String equivalent of _type.

◆ DepthFarClip()

double sdf::SDF_VERSION_NAMESPACE::Camera::DepthFarClip ( ) const

Get the far clip distance for the depth camera.

Returns
The far clip depth distance.

◆ DepthNearClip()

double sdf::SDF_VERSION_NAMESPACE::Camera::DepthNearClip ( ) const

Get the near clip distance for the depth camera.

Returns
The near clip depth distance.

◆ DistortionCenter()

const gz::math::Vector2d & sdf::SDF_VERSION_NAMESPACE::Camera::DistortionCenter ( ) const

Get the distortion center or principal point.

Returns
Distortion center or principal point.

◆ DistortionK1()

double sdf::SDF_VERSION_NAMESPACE::Camera::DistortionK1 ( ) const

Get the radial distortion coefficient k1.

Returns
_k1 The k1 radial distortion.

◆ DistortionK2()

double sdf::SDF_VERSION_NAMESPACE::Camera::DistortionK2 ( ) const

Get the radial distortion coefficient k2.

Returns
_k2 The k2 radial distortion.

◆ DistortionK3()

double sdf::SDF_VERSION_NAMESPACE::Camera::DistortionK3 ( ) const

Get the radial distortion coefficient k3.

Returns
_k3 The k3 radial distortion.

◆ DistortionP1()

double sdf::SDF_VERSION_NAMESPACE::Camera::DistortionP1 ( ) const

Get the tangential distortion coefficient p1.

Returns
_p1 The p1 tangential distortion.

◆ DistortionP2()

double sdf::SDF_VERSION_NAMESPACE::Camera::DistortionP2 ( ) const

Get the tangential distortion coefficient p2.

Returns
The p2 tangential distortion.

◆ Element()

sdf::ElementPtr sdf::SDF_VERSION_NAMESPACE::Camera::Element ( ) const

Get a pointer to the SDF element that was used during load.

Returns
SDF element pointer. The value will be nullptr if Load has not been called.

◆ FarClip()

double sdf::SDF_VERSION_NAMESPACE::Camera::FarClip ( ) const

Get the far clip distance.

Returns
The far clip distance.

◆ GZ_DEPRECATED()

const std::string sdf::SDF_VERSION_NAMESPACE::Camera::GZ_DEPRECATED ( 15  ) const

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.

Returns
The name of the frame this camera uses in its camera_info topic.

◆ HasBoundingBoxType()

bool sdf::SDF_VERSION_NAMESPACE::Camera::HasBoundingBoxType ( ) const

Get whether the boundingbox type was set.

Returns
True if the boundingbox type was set.

◆ HasDepthCamera()

bool sdf::SDF_VERSION_NAMESPACE::Camera::HasDepthCamera ( ) const

Get whether the depth camera was set.

Returns
True if the depth camera was set.

◆ HasDepthFarClip()

bool sdf::SDF_VERSION_NAMESPACE::Camera::HasDepthFarClip ( ) const

Get whether the depth camera far clip distance was set.

Returns
True if the depth camera far clip distance was set.

◆ HasDepthNearClip()

bool sdf::SDF_VERSION_NAMESPACE::Camera::HasDepthNearClip ( ) const

Get whether the depth camera near clip distance was set.

Returns
True if the depth camera near clip distance was set.

◆ HasLensIntrinsics()

bool sdf::SDF_VERSION_NAMESPACE::Camera::HasLensIntrinsics ( ) const

Get whether or not the camera has instrinsics values set.

Returns
True if the camera has instrinsics values set, false otherwise

◆ HasLensProjection()

bool sdf::SDF_VERSION_NAMESPACE::Camera::HasLensProjection ( ) const

Get whether or not the camera has projection values set.

Returns
True if the camera has projection values set, false otherwise

◆ HasSegmentationType()

bool sdf::SDF_VERSION_NAMESPACE::Camera::HasSegmentationType ( ) const

Get whether the segmentation type was set.

Returns
True if the segmentation type was set.

◆ HorizontalFov()

gz::math::Angle sdf::SDF_VERSION_NAMESPACE::Camera::HorizontalFov ( ) const

Get the horizontal field of view in radians.

Returns
The horizontal field of view in radians.

◆ ImageHeight()

uint32_t sdf::SDF_VERSION_NAMESPACE::Camera::ImageHeight ( ) const

Get the image height in pixels.

Returns
The image height in pixels.

◆ ImageNoise()

const Noise & sdf::SDF_VERSION_NAMESPACE::Camera::ImageNoise ( ) const

Get the image noise values.

Returns
Noise values for the image.

◆ ImageWidth()

uint32_t sdf::SDF_VERSION_NAMESPACE::Camera::ImageWidth ( ) const

Get the image width in pixels.

Returns
The image width in pixels.

◆ LensC1()

double sdf::SDF_VERSION_NAMESPACE::Camera::LensC1 ( ) const

Get lens custom function linear scaling constant.

Returns
The lens custom function linear scaling constant.

◆ LensC2()

double sdf::SDF_VERSION_NAMESPACE::Camera::LensC2 ( ) const

Get lens custom function angular scaling constant.

Returns
The lens custom function angular scaling constant.

◆ LensC3()

double sdf::SDF_VERSION_NAMESPACE::Camera::LensC3 ( ) const

Get lens custom function angle offset constant.

Returns
The lens custom function angle offset constant.

◆ LensCutoffAngle()

gz::math::Angle sdf::SDF_VERSION_NAMESPACE::Camera::LensCutoffAngle ( ) const

Get lens cutoff angle.

Everything outside of the specified angle will be hidden.

Returns
The lens cutoff angle.

◆ LensEnvironmentTextureSize()

int sdf::SDF_VERSION_NAMESPACE::Camera::LensEnvironmentTextureSize ( ) const

Get environment texture size.

This is the resolution of the environment cube map used to draw the world.

Returns
The lens environment texture size.

◆ LensFocalLength()

double sdf::SDF_VERSION_NAMESPACE::Camera::LensFocalLength ( ) const

Get lens custom function focal length.

Returns
The lens custom function focal length.

◆ LensFunction()

const std::string & sdf::SDF_VERSION_NAMESPACE::Camera::LensFunction ( ) const

Get lens custom function.

Possible values are 'sin', 'tan', and 'id'.

Returns
The lens custom function.

◆ LensIntrinsicsCx()

double sdf::SDF_VERSION_NAMESPACE::Camera::LensIntrinsicsCx ( ) const

Get the lens intrinsic matrix X principal point in pixels.

Returns
The lens intrinsic matrix X principal point in pixels.

◆ LensIntrinsicsCy()

double sdf::SDF_VERSION_NAMESPACE::Camera::LensIntrinsicsCy ( ) const

Get the lens intrinsic matrix Y principal point in pixels.

Returns
The lens intrinsic matrix Y principal point in pixels.

◆ LensIntrinsicsFx()

double sdf::SDF_VERSION_NAMESPACE::Camera::LensIntrinsicsFx ( ) const

Get the lens intrinsic matrix X focal length in pixels.

Returns
The lens X focal length in pixels for the intrinsic matrix.

◆ LensIntrinsicsFy()

double sdf::SDF_VERSION_NAMESPACE::Camera::LensIntrinsicsFy ( ) const

Get the lens intrinsic matrix Y focal length in pixels.

Returns
The lens intrinsic matrix Y focal length in pixels.

◆ LensIntrinsicsSkew()

double sdf::SDF_VERSION_NAMESPACE::Camera::LensIntrinsicsSkew ( ) const

Get the lens XY axis skew.

Returns
The lens XY axis skew.

◆ LensProjectionCx()

double sdf::SDF_VERSION_NAMESPACE::Camera::LensProjectionCx ( ) const

Get the lens projection matrix X principal point in pixels.

Returns
The lens projection matrix X principal point in pixels.

◆ LensProjectionCy()

double sdf::SDF_VERSION_NAMESPACE::Camera::LensProjectionCy ( ) const

Get the lens projection matrix Y principal point in pixels.

Returns
The lens projection matrix Y principal point in pixels.

◆ LensProjectionFx()

double sdf::SDF_VERSION_NAMESPACE::Camera::LensProjectionFx ( ) const

Get the lens projection matrix X focal length in pixels.

Returns
The lens projection matrix X focal length in pixels.

◆ LensProjectionFy()

double sdf::SDF_VERSION_NAMESPACE::Camera::LensProjectionFy ( ) const

Get the lens projection matrix Y focal length in pixels.

Returns
The lens projection matrix Y focal length in pixels.

◆ LensProjectionTx()

double sdf::SDF_VERSION_NAMESPACE::Camera::LensProjectionTx ( ) const

Get the lens projection matrix X translation in pixels.

Returns
The lens projection matrix X translation in pixels.

◆ LensProjectionTy()

double sdf::SDF_VERSION_NAMESPACE::Camera::LensProjectionTy ( ) const

Get the lens projection matrix Y translation in pixels.

Returns
The lens projection matrix Y translation in pixels.

◆ LensScaleToHfov()

bool sdf::SDF_VERSION_NAMESPACE::Camera::LensScaleToHfov ( ) const

Get lens scale to horizontal field of field.

Returns
True if the image should be scaled to fit horizontal FOV, otherwise it will be shown according to projection type parameters.

◆ LensType()

std::string sdf::SDF_VERSION_NAMESPACE::Camera::LensType ( ) const

Set the name of the coordinate frame relative to which this object's camera_info is expressed.

Parameters
[in]_frameThe frame this camera uses in its camera_info topic.

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) projection, it is recommended to specify a horizontal_fov of less than or equal to 90 degrees

Returns
The lens type.

◆ Load()

Errors sdf::SDF_VERSION_NAMESPACE::Camera::Load ( ElementPtr  _sdf)

Load the camera sensor based on an element pointer.

This is not the usual entry point. Typical usage of the SDF DOM is through the Root object.

Parameters
[in]_sdfThe SDF Element pointer
Returns
Errors, which is a vector of Error objects. Each Error includes an error code and message. An empty vector indicates no error.

◆ Name()

std::string sdf::SDF_VERSION_NAMESPACE::Camera::Name ( ) const

Get the name of the camera.

Returns
Name of the sensor.

◆ NearClip()

double sdf::SDF_VERSION_NAMESPACE::Camera::NearClip ( ) const

Get the near clip distance.

Returns
The near clip distance.

◆ operator!=()

bool sdf::SDF_VERSION_NAMESPACE::Camera::operator!= ( const Camera _alt) const

Return true this Camera object does not contain the same values as the passed in parameter.

Parameters
[_in]_alt Camera value to compare. \returen True if 'this' != _alt.

◆ operator==()

bool sdf::SDF_VERSION_NAMESPACE::Camera::operator== ( const Camera _alt) const

Return true if both Camera objects contain the same values.

Parameters
[_in]_alt Camera value to compare. \returen True if 'this' == _alt.

◆ PixelFormat()

PixelFormatType sdf::SDF_VERSION_NAMESPACE::Camera::PixelFormat ( ) const

Get the pixel format.

This value is set from the <format> element that is the child of <image>.

Returns
The pixel format.

◆ PixelFormatStr()

std::string sdf::SDF_VERSION_NAMESPACE::Camera::PixelFormatStr ( ) const

Get the pixel format as a string.

Returns
The pixel format string.

◆ PoseRelativeTo()

const std::string & sdf::SDF_VERSION_NAMESPACE::Camera::PoseRelativeTo ( ) const

Get the name of the coordinate frame relative to which this object's pose is expressed.

An empty value indicates that the frame is relative to the parent link.

Returns
The name of the pose relative-to frame.

◆ RawPose()

const gz::math::Pose3d & sdf::SDF_VERSION_NAMESPACE::Camera::RawPose ( ) const

Get the pose of the camer.

This is the pose of the camera as specified in SDF (<camera> <pose> ... </pose></camera>).

Returns
The pose of the link.

◆ SaveFrames()

bool sdf::SDF_VERSION_NAMESPACE::Camera::SaveFrames ( ) const

Get whether frames should be saved.

Returns
True if image frames should be saved.

◆ SaveFramesPath()

const std::string & sdf::SDF_VERSION_NAMESPACE::Camera::SaveFramesPath ( ) const

Get the path in which to save frames.

Returns
Path to save frames.

◆ SegmentationType()

const std::string & sdf::SDF_VERSION_NAMESPACE::Camera::SegmentationType ( ) const

Get the segmentation type.

Returns
The segmentation type.

◆ SetAntiAliasingValue()

void sdf::SDF_VERSION_NAMESPACE::Camera::SetAntiAliasingValue ( uint32_t  _antiAliasingValue)

Set the anti-aliasing value.

Parameters
[in]_antiAliasingValueThe anti-aliasing value.

◆ SetBoundingBoxType()

void sdf::SDF_VERSION_NAMESPACE::Camera::SetBoundingBoxType ( const std::string &  _type)

Set the boundingbox type.

Parameters
[in]_typeThe boundingbox type.

◆ SetCameraInfoTopic()

void sdf::SDF_VERSION_NAMESPACE::Camera::SetCameraInfoTopic ( const std::string &  _cameraInfoTopic)

Set the camera info topic.

Parameters
[in]_cameraInfoTopicTopic for the camera info.

◆ SetDepthFarClip()

void sdf::SDF_VERSION_NAMESPACE::Camera::SetDepthFarClip ( double  _far)

Set the far clip distance for the depth camera.

Parameters
[in]_farThe far clip depth distance.

◆ SetDepthNearClip()

void sdf::SDF_VERSION_NAMESPACE::Camera::SetDepthNearClip ( double  _near)

Set the near clip distance for the depth camera.

Parameters
[in]_nearThe near clip depth distance.

◆ SetDistortionCenter()

void sdf::SDF_VERSION_NAMESPACE::Camera::SetDistortionCenter ( const gz::math::Vector2d &  _center)

Set the distortion center or principal point.

Parameters
[in]_centerDistortion center or principal point.

◆ SetDistortionK1()

void sdf::SDF_VERSION_NAMESPACE::Camera::SetDistortionK1 ( double  _k1)

Set the radial distortion coefficient k1.

Parameters
[in]_k1The k1 radial distortion.

◆ SetDistortionK2()

void sdf::SDF_VERSION_NAMESPACE::Camera::SetDistortionK2 ( double  _k2)

Set the radial distortion coefficient k2.

Parameters
[in]_k2The k2 radial distortion.

◆ SetDistortionK3()

void sdf::SDF_VERSION_NAMESPACE::Camera::SetDistortionK3 ( double  _k3)

Set the radial distortion coefficient k3.

Parameters
[in]_k3The k3 radial distortion.

◆ SetDistortionP1()

void sdf::SDF_VERSION_NAMESPACE::Camera::SetDistortionP1 ( double  _p1)

Set the tangential distortion coefficient p1.

Parameters
[in]_p1The p1 tangential distortion.

◆ SetDistortionP2()

void sdf::SDF_VERSION_NAMESPACE::Camera::SetDistortionP2 ( double  _p2)

Set the tangential distortion coefficient p2.

Returns
The p2 tangential distortion.

◆ SetFarClip()

void sdf::SDF_VERSION_NAMESPACE::Camera::SetFarClip ( double  _far)

Set the far clip distance.

Parameters
[in]_farThe far clip distance.

◆ SetHasBoundingBoxType()

void sdf::SDF_VERSION_NAMESPACE::Camera::SetHasBoundingBoxType ( bool  _type)

Set whether the boundingbox type has been specified.

Parameters
[in]_typeTrue if the boundingbox type has been set in the sdf.

◆ SetHasDepthCamera()

void sdf::SDF_VERSION_NAMESPACE::Camera::SetHasDepthCamera ( bool  _camera)

Set whether the depth camera has been specified.

Parameters
[in]_cameraTrue if the depth camera has been set in the sdf.

◆ SetHasDepthFarClip()

void sdf::SDF_VERSION_NAMESPACE::Camera::SetHasDepthFarClip ( bool  _far)

Set whether the depth camera far clip distance has been specified.

Parameters
[in]_cameraTrue if the depth camera far clip distance has been set in the sdf.

◆ SetHasDepthNearClip()

void sdf::SDF_VERSION_NAMESPACE::Camera::SetHasDepthNearClip ( bool  _near)

Set whether the depth camera near clip distance has been specified.

Parameters
[in]_cameraTrue if the depth camera near clip distance has been set in the sdf.

◆ SetHasSegmentationType()

void sdf::SDF_VERSION_NAMESPACE::Camera::SetHasSegmentationType ( bool  _type)

Set whether the segmentation type has been specified.

Parameters
[in]_typeTrue if the segmentation type has been set in the sdf.

◆ SetHorizontalFov()

void sdf::SDF_VERSION_NAMESPACE::Camera::SetHorizontalFov ( const gz::math::Angle &  _hfov)

Set the horizontal field of view in radians.

Parameters
[in]_hfovThe horizontal field of view in radians.

◆ SetImageHeight()

void sdf::SDF_VERSION_NAMESPACE::Camera::SetImageHeight ( uint32_t  _height)

Set the image height in pixels.

Parameters
[in]_heightThe image height in pixels.

◆ SetImageNoise()

void sdf::SDF_VERSION_NAMESPACE::Camera::SetImageNoise ( const Noise _noise)

Set the noise values related to the image.

Parameters
[in]_noiseNoise values for the image.

◆ SetImageWidth()

void sdf::SDF_VERSION_NAMESPACE::Camera::SetImageWidth ( uint32_t  _width)

Set the image width in pixels.

Parameters
[in]_widthThe image width in pixels.

◆ SetLensC1()

void sdf::SDF_VERSION_NAMESPACE::Camera::SetLensC1 ( double  _c1)

Set lens custom function linear scaling constant.

Parameters
[in]_c1The lens custom function linear scaling constant.

◆ SetLensC2()

void sdf::SDF_VERSION_NAMESPACE::Camera::SetLensC2 ( double  _c2)

Set lens custom function angular scaling constant.

Parameters
[in]_c2The lens custom function angular scaling constant.

◆ SetLensC3()

void sdf::SDF_VERSION_NAMESPACE::Camera::SetLensC3 ( double  _c3)

Set lens custom function angle offset constant.

Parameters
[in]_c3The lens custom function angle offset constant.

◆ SetLensCutoffAngle()

void sdf::SDF_VERSION_NAMESPACE::Camera::SetLensCutoffAngle ( const gz::math::Angle &  _angle)

Set lens cutoff angle.

Everything outside of the specified angle will be hidden.

Parameters
[in]_angleThe lens cutoff angle.

◆ SetLensEnvironmentTextureSize()

void sdf::SDF_VERSION_NAMESPACE::Camera::SetLensEnvironmentTextureSize ( int  _size)

Set environment texture size.

This is the resolution of the environment cube map used to draw the world.

Parameters
[in]_sizeThe lens environment texture size.

◆ SetLensFocalLength()

void sdf::SDF_VERSION_NAMESPACE::Camera::SetLensFocalLength ( double  _f)

Set lens custom function focal length.

Parameters
[in]_fThe lens custom function focal length.

◆ SetLensFunction()

void sdf::SDF_VERSION_NAMESPACE::Camera::SetLensFunction ( const std::string &  _fun)

Set lens custom function.

Parameters
[in]_funThe lens custom function. Possible values are 'sin', 'tan', and 'id'.

◆ SetLensIntrinsicsCx()

void sdf::SDF_VERSION_NAMESPACE::Camera::SetLensIntrinsicsCx ( double  _cx)

Set the lens intrinsic matrix X principal point in pixels.

Parameters
[in]_cxThe lens intrinsic matrix X principal point in pixels.

◆ SetLensIntrinsicsCy()

void sdf::SDF_VERSION_NAMESPACE::Camera::SetLensIntrinsicsCy ( double  _cy)

Set the lens intrinsic matrix Y principal point in pixels.

Parameters
[in]_cyThe lens intrinsic matrix Y principal point in pixels.

◆ SetLensIntrinsicsFx()

void sdf::SDF_VERSION_NAMESPACE::Camera::SetLensIntrinsicsFx ( double  _fx)

Set the lens intrinsic matrix X focal length in pixels.

Parameters
[in]_fxThe intrinsic matrix lens X focal length in pixels.

◆ SetLensIntrinsicsFy()

void sdf::SDF_VERSION_NAMESPACE::Camera::SetLensIntrinsicsFy ( double  _fy)

Set the lens intrinsic matrix Y focal length in pixels.

Parameters
[in]_fyThe lens intrinsic matrix Y focal length in pixels.

◆ SetLensIntrinsicsSkew()

void sdf::SDF_VERSION_NAMESPACE::Camera::SetLensIntrinsicsSkew ( double  _s)

Set the lens XY axis skew.

Parameters
[in]_sThe lens XY axis skew.

◆ SetLensProjectionCx()

void sdf::SDF_VERSION_NAMESPACE::Camera::SetLensProjectionCx ( double  _cx_p)

Set the lens projection matrix X principal point in pixels.

Parameters
[in]_cx_pThe lens projection matrix X principal point in pixels.

◆ SetLensProjectionCy()

void sdf::SDF_VERSION_NAMESPACE::Camera::SetLensProjectionCy ( double  _cy_p)

Set the lens projection matrix Y principal point in pixels.

Parameters
[in]_cy_pThe lens projection matrix Y principal point in pixels.

◆ SetLensProjectionFx()

void sdf::SDF_VERSION_NAMESPACE::Camera::SetLensProjectionFx ( double  _fx_p)

Set the lens projection matrix X focal length in pixels.

Parameters
[in]_fx_pThe lens projection matrix X focal length in pixels.

◆ SetLensProjectionFy()

void sdf::SDF_VERSION_NAMESPACE::Camera::SetLensProjectionFy ( double  _fy_p)

Set the lens projection matrix Y focal length in pixels.

Parameters
[in]_fy_pThe lens projection matrix Y focal length in pixels.

◆ SetLensProjectionTx()

void sdf::SDF_VERSION_NAMESPACE::Camera::SetLensProjectionTx ( double  _tx)

Set the lens projection matrix X translation in pixels.

Parameters
[in]_txThe lens projection matrix X translation in pixels.

◆ SetLensProjectionTy()

void sdf::SDF_VERSION_NAMESPACE::Camera::SetLensProjectionTy ( double  _ty)

Set the lens projection matrix Y translation in pixels.

Parameters
[in]_tyThe lens projection matrix Y translation in pixels.

◆ SetLensScaleToHfov()

void sdf::SDF_VERSION_NAMESPACE::Camera::SetLensScaleToHfov ( bool  _scale)

Set lens scale to horizontal field of field.

Parameters
[in]_scaleTrue if the image should be scaled to fit horizontal FOV, otherwise it will be shown according to projection type parameters.

◆ SetLensType()

void sdf::SDF_VERSION_NAMESPACE::Camera::SetLensType ( const std::string &  _type)

Set the lens type.

Supported values are gnomonical, stereographic, equidistant, equisolid_angle, orthographic, custom.

Parameters
[in]_typeThe lens type.

◆ SetName()

void sdf::SDF_VERSION_NAMESPACE::Camera::SetName ( const std::string &  _name)

Set the name of the camera.

Parameters
[in]_nameName of the sensor.

◆ SetNearClip()

void sdf::SDF_VERSION_NAMESPACE::Camera::SetNearClip ( double  _near)

Set the near clip distance.

Parameters
[in]_nearThe near clip distance.

◆ SetPixelFormat()

void sdf::SDF_VERSION_NAMESPACE::Camera::SetPixelFormat ( PixelFormatType  _format)

Set the pixel format type.

Parameters
[in]_formatThe image format.

◆ SetPixelFormatStr()

void sdf::SDF_VERSION_NAMESPACE::Camera::SetPixelFormatStr ( const std::string &  _fmt)

Set the pixel format from a string.

Parameters
[in]_fmtThe pixel format string.

◆ SetPoseRelativeTo()

void sdf::SDF_VERSION_NAMESPACE::Camera::SetPoseRelativeTo ( const std::string &  _frame)

Set the name of the coordinate frame relative to which this object's pose is expressed.

An empty value indicates that the frame is relative to the parent link.

Parameters
[in]_frameThe name of the pose relative-to frame.

◆ SetRawPose()

void sdf::SDF_VERSION_NAMESPACE::Camera::SetRawPose ( const gz::math::Pose3d &  _pose)

Set the pose of the camera.

See also
const gz::math::Pose3d &RawPose() const
Parameters
[in]_poseThe new camera pose.

◆ SetSaveFrames()

void sdf::SDF_VERSION_NAMESPACE::Camera::SetSaveFrames ( bool  _save)

Set whether frames should be saved.

Parameters
[in]_saveTrue if image frames should be saved.

◆ SetSaveFramesPath()

void sdf::SDF_VERSION_NAMESPACE::Camera::SetSaveFramesPath ( const std::string &  _path)

Set the path in which to save frames.

Parameters
[in]_pathPath to save frames.

◆ SetSegmentationType()

void sdf::SDF_VERSION_NAMESPACE::Camera::SetSegmentationType ( const std::string &  _type)

Set the segmentation type.

Parameters
[in]_typeThe segmentation type.

◆ SetTriggered()

void sdf::SDF_VERSION_NAMESPACE::Camera::SetTriggered ( bool  _triggered)

Set whether the camera should be triggered by a topic.

Parameters
[in]_triggeredTrue if the camera should be triggered by a topic.

◆ SetTriggerTopic()

void sdf::SDF_VERSION_NAMESPACE::Camera::SetTriggerTopic ( const std::string &  _triggerTopic)

Set the topic that will trigger the camera.

Parameters
[in]_triggerTopicTopic for the camera trigger.

◆ SetVisibilityMask()

void sdf::SDF_VERSION_NAMESPACE::Camera::SetVisibilityMask ( uint32_t  _mask)

Set the visibility mask of a camera.

Parameters
[in]_maskvisibility mask

◆ ToElement()

sdf::ElementPtr sdf::SDF_VERSION_NAMESPACE::Camera::ToElement ( ) const

Create and return an SDF element filled with data from this camera.

Note that parameter passing functionality is not captured with this function.

Returns
SDF element pointer with updated camera values.

◆ Triggered()

bool sdf::SDF_VERSION_NAMESPACE::Camera::Triggered ( ) const

Get whether the camera is triggered by a topic.

Returns
True if the camera is triggered by a topic.

◆ TriggerTopic()

std::string sdf::SDF_VERSION_NAMESPACE::Camera::TriggerTopic ( ) const

Get the topic that will trigger the camera.

Returns
Topic for the camera trigger.

◆ VisibilityMask()

uint32_t sdf::SDF_VERSION_NAMESPACE::Camera::VisibilityMask ( ) const

Get the visibility mask of a camera.

Returns
visibility mask

The documentation for this class was generated from the following file: