Ignition Sensors

API Reference

6.0.1

Camera Sensor Class. More...

#include <CameraSensor.hh>

Public Member Functions

 CameraSensor ()
 constructor More...
 
virtual ~CameraSensor ()
 destructor More...
 
double Baseline () const
 Get baseline for stereo cameras. More...
 
ignition::common::ConnectionPtr ConnectImageCallback (std::function< void(const ignition::msgs::Image &)> _callback)
 Set a callback to be called when image frame data is generated. More...
 
virtual unsigned int ImageHeight () const
 Get image height. More...
 
virtual unsigned int ImageWidth () const
 Get image width. More...
 
std::string InfoTopic () const
 Topic where camera info is published. More...
 
virtual bool Init () override
 Initialize values in the sensor. More...
 
virtual bool Load (const sdf::Sensor &_sdf) override
 Load the sensor based on data from an sdf::Sensor object. More...
 
virtual bool Load (sdf::ElementPtr _sdf) override
 Load the sensor with SDF parameters. More...
 
rendering::CameraPtr RenderingCamera () const
 Get pointer to rendering camera object. More...
 
void SetBaseline (double _baseline)
 Set baseline for stereo cameras. This is used to populate the projection matrix in the camera info message. More...
 
virtual void SetScene (ignition::rendering::ScenePtr _scene) override
 Set the rendering scene. More...
 
virtual bool Update (const std::chrono::steady_clock::duration &_now) override
 Force the sensor to generate data. More...
 
- Public Member Functions inherited from RenderingSensor
virtual ~RenderingSensor ()
 destructor More...
 
bool ManualSceneUpdate () const
 Get whether the scene graph is updated manually. Defaults to false. More...
 
void Render ()
 Render update. This performs the actual render operation. More...
 
rendering::ScenePtr Scene () const
 Get the rendering scene. More...
 
void SetManualSceneUpdate (bool _manual)
 Set whether to update the scene graph manually. If set to true, it is expected that rendering::Scene::PreRender is called manually before calling Render() More...
 
virtual void SetScene (rendering::ScenePtr _scene)
 Set the rendering scene. More...
 
- Public Member Functions inherited from Sensor
virtual ~Sensor ()
 destructor More...
 
void AddSequence (ignition::msgs::Header *_msg, const std::string &_seqKey="default")
 Add a sequence number to an ignition::msgs::Header. This function can be called by a sensor that wants to add a sequence number to a sensor message in order to have improved accountability for generated sensor data. More...
 
bool EnableMetrics () const
 Get flag state for enabling performance metrics publication. More...
 
SensorId Id () const
 Get the sensor's ID. More...
 
std::string Name () const
 Get name. More...
 
std::chrono::steady_clock::duration NextDataUpdateTime () const
 Return the next time the sensor will generate data. More...
 
std::string Parent () const
 Get parent link of the sensor. More...
 
ignition::math::Pose3d Pose () const
 Get the current pose. More...
 
void PublishMetrics (const std::chrono::duration< double > &_now)
 Publishes information about the performance of the sensor. This method is called by Update(). More...
 
sdf::ElementPtr SDF () const
 Get the SDF used to load this sensor. More...
 
void SetEnableMetrics (bool _enableMetrics)
 Set flag to enable publishing performance metrics. More...
 
virtual void SetParent (const std::string &_parent)
 Set the parent of the sensor. More...
 
void SetPose (const ignition::math::Pose3d &_pose)
 Update the pose of the sensor. More...
 
bool SetTopic (const std::string &_topic)
 Set topic where sensor data is published. More...
 
void SetUpdateRate (const double _hz)
 Set the update rate of the sensor. An update rate of zero means that the sensor is updated every cycle. It's zero by default. Negative rates become zero. More...
 
std::string Topic () const
 Get topic where sensor data is published. More...
 
bool Update (const std::chrono::steady_clock::duration &_now, const bool _force)
 Update the sensor. More...
 
double UpdateRate () const
 Get the update rate of the sensor. More...
 

Protected Member Functions

bool AdvertiseInfo ()
 Advertise camera info topic. More...
 
bool AdvertiseInfo (const std::string &_topic)
 Advertise camera info topic. This version takes a string that allows one to override the camera_info topic. More...
 
void PopulateInfo (const sdf::Camera *_cameraSdf)
 Populate camera info message. More...
 
void PublishInfo (const std::chrono::steady_clock::duration &_now)
 Publish camera info message. More...
 
- Protected Member Functions inherited from RenderingSensor
 RenderingSensor ()
 constructor More...
 
void AddSensor (rendering::SensorPtr _sensor)
 Add a rendering::Sensor. Its render updates will be handled by this base class. More...
 
- Protected Member Functions inherited from Sensor
 Sensor ()
 constructor More...
 

Detailed Description

Camera Sensor Class.

This class creates images from an ignition rendering scene. The scene must be created in advance and given to Manager::Init(). It offers both an ignition-transport interface and a direct C++ API to access the image data. The API works by setting a callback to be called with image data.

Constructor & Destructor Documentation

◆ CameraSensor()

constructor

◆ ~CameraSensor()

virtual ~CameraSensor ( )
virtual

destructor

Member Function Documentation

◆ AdvertiseInfo() [1/2]

bool AdvertiseInfo ( )
protected

Advertise camera info topic.

Returns
True if successful.

◆ AdvertiseInfo() [2/2]

bool AdvertiseInfo ( const std::string _topic)
protected

Advertise camera info topic. This version takes a string that allows one to override the camera_info topic.

Parameters
[in]_topicThe topic on which camera info is to be published.
Returns
True if successful.

◆ Baseline()

double Baseline ( ) const

Get baseline for stereo cameras.

Returns
The distance from the 1st camera, in meters.

◆ ConnectImageCallback()

ignition::common::ConnectionPtr ConnectImageCallback ( std::function< void(const ignition::msgs::Image &)>  _callback)

Set a callback to be called when image frame data is generated.

Parameters
[in]_callbackThis callback will be called every time the camera produces image data. The Update function will be blocked while the callbacks are executed.
Remarks
Do not block inside of the callback.
Returns
A connection pointer that must remain in scope. When the connection pointer falls out of scope, the connection is broken.

◆ ImageHeight()

virtual unsigned int ImageHeight ( ) const
virtual

Get image height.

Returns
height of the image

Reimplemented in DepthCameraSensor, ThermalCameraSensor, SegmentationCameraSensor, and RgbdCameraSensor.

◆ ImageWidth()

virtual unsigned int ImageWidth ( ) const
virtual

Get image width.

Returns
width of the image

Reimplemented in DepthCameraSensor, ThermalCameraSensor, SegmentationCameraSensor, and RgbdCameraSensor.

◆ InfoTopic()

std::string InfoTopic ( ) const

Topic where camera info is published.

Returns
Camera info topic.

◆ Init()

virtual bool Init ( )
overridevirtual

Initialize values in the sensor.

Returns
True on success

Reimplemented from Sensor.

Reimplemented in DepthCameraSensor, ThermalCameraSensor, SegmentationCameraSensor, and RgbdCameraSensor.

◆ Load() [1/2]

virtual bool Load ( const sdf::Sensor &  _sdf)
overridevirtual

Load the sensor based on data from an sdf::Sensor object.

Parameters
[in]_sdfSDF Sensor parameters.
Returns
true if loading was successful

Reimplemented from Sensor.

Reimplemented in DepthCameraSensor, ThermalCameraSensor, SegmentationCameraSensor, and RgbdCameraSensor.

◆ Load() [2/2]

virtual bool Load ( sdf::ElementPtr  _sdf)
overridevirtual

Load the sensor with SDF parameters.

Parameters
[in]_sdfSDF Sensor parameters.
Returns
true if loading was successful

Reimplemented from Sensor.

Reimplemented in DepthCameraSensor, ThermalCameraSensor, SegmentationCameraSensor, and RgbdCameraSensor.

◆ PopulateInfo()

void PopulateInfo ( const sdf::Camera *  _cameraSdf)
protected

Populate camera info message.

Parameters
[in]_cameraSdfPointer to SDF object containing camera information.

◆ PublishInfo()

void PublishInfo ( const std::chrono::steady_clock::duration &  _now)
protected

Publish camera info message.

Parameters
[in]_nowThe current time

◆ RenderingCamera()

rendering::CameraPtr RenderingCamera ( ) const

Get pointer to rendering camera object.

Returns
Camera in Ignition Rendering.

◆ SetBaseline()

void SetBaseline ( double  _baseline)

Set baseline for stereo cameras. This is used to populate the projection matrix in the camera info message.

Parameters
[in]_baselineThe distance from the 1st camera, in meters.

◆ SetScene()

virtual void SetScene ( ignition::rendering::ScenePtr  _scene)
overridevirtual

Set the rendering scene.

Parameters
[in]_scenePointer to the scene

Reimplemented in DepthCameraSensor, ThermalCameraSensor, SegmentationCameraSensor, and RgbdCameraSensor.

◆ Update()

virtual bool Update ( const std::chrono::steady_clock::duration &  _now)
overridevirtual

Force the sensor to generate data.

Parameters
[in]_nowThe current time
Returns
true if the update was successfull

Implements Sensor.

Reimplemented in DepthCameraSensor, ThermalCameraSensor, SegmentationCameraSensor, and RgbdCameraSensor.


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