Gazebo Sensors

API Reference

7.3.0

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...
 
gz::common::ConnectionPtr ConnectImageCallback (std::function< void(const gz::msgs::Image &)> _callback)
 Set a callback to be called when image frame data is generated. More...
 
virtual bool HasConnections () const override
 Check if there are any subscribers. More...
 
bool HasImageConnections () const
 Check if there are any image subscribers. More...
 
bool HasInfoConnections () const
 Check if there are any info subscribers. 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...
 
const std::stringOpticalFrameId () const
 Get the camera optical frame. More...
 
virtual 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 (gz::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...
 
virtual bool Update (const std::chrono::steady_clock::duration &_now)=0
 Force the sensor to generate data. More...
 
bool Update (const std::chrono::steady_clock::duration &_now, const bool _force)
 Update the sensor. 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 (gz::msgs::Header *_msg, const std::string &_seqKey="default")
 Add a sequence number to a gz::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...
 
std::string FrameId () const
 FrameId. More...
 
SensorId Id () const
 Get the sensor's ID. More...
 
bool IsActive () const
 Get whether the sensor is enabled or not. 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...
 
gz::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 SetActive (bool _active)
 Enable or disable the sensor. Disabled sensors will not generate or publish data unless Update is called with the '_force' argument set to true. More...
 
void SetEnableMetrics (bool _enableMetrics)
 Set flag to enable publishing performance metrics. More...
 
void SetFrameId (const std::string &_frameId)
 Set Frame ID of the sensor. More...
 
void SetNextDataUpdateTime (const std::chrono::steady_clock::duration &_time)
 Manually set the next time the sensor will generate data Useful for accomodating jumps backwards in time as well as specifying updates for non-uniformly updating sensors. More...
 
virtual void SetParent (const std::string &_parent)
 Set the parent of the sensor. More...
 
void SetPose (const gz::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. \detail 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 a Gazebo Rendering scene. The scene must be created in advance and given to Manager::Init(). It offers both a gz-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()

gz::common::ConnectionPtr ConnectImageCallback ( std::function< void(const gz::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.

◆ HasConnections()

virtual bool HasConnections ( ) const
overridevirtual

Check if there are any subscribers.

Returns
True if there are subscribers, false otherwise

Reimplemented from Sensor.

Reimplemented in ThermalCameraSensor, DepthCameraSensor, WideAngleCameraSensor, SegmentationCameraSensor, BoundingBoxCameraSensor, and RgbdCameraSensor.

◆ HasImageConnections()

bool HasImageConnections ( ) const

Check if there are any image subscribers.

Returns
True if there are image subscribers, false otherwise
Todo:
(iche033) Make this function virtual on Harmonic

◆ HasInfoConnections()

bool HasInfoConnections ( ) const

Check if there are any info subscribers.

Returns
True if there are info subscribers, false otherwise
Todo:
(iche033) Make this function virtual on Harmonic

◆ ImageHeight()

virtual unsigned int ImageHeight ( ) const
virtual

◆ ImageWidth()

virtual unsigned int ImageWidth ( ) const
virtual

◆ 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, WideAngleCameraSensor, SegmentationCameraSensor, RgbdCameraSensor, and BoundingBoxCameraSensor.

◆ 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, WideAngleCameraSensor, SegmentationCameraSensor, RgbdCameraSensor, and BoundingBoxCameraSensor.

◆ 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, WideAngleCameraSensor, SegmentationCameraSensor, RgbdCameraSensor, and BoundingBoxCameraSensor.

◆ OpticalFrameId()

const std::string& OpticalFrameId ( ) const

Get the camera optical frame.

Returns
The camera optical frame

◆ 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()

virtual rendering::CameraPtr RenderingCamera ( ) const
virtual

Get pointer to rendering camera object.

Returns
Camera in Gazebo Rendering.

Reimplemented in WideAngleCameraSensor.

◆ 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 ( gz::rendering::ScenePtr  _scene)
overridevirtual

Set the rendering scene.

Parameters
[in]_scenePointer to the scene

Reimplemented in DepthCameraSensor, ThermalCameraSensor, WideAngleCameraSensor, SegmentationCameraSensor, and RgbdCameraSensor.

◆ Update() [1/3]

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, WideAngleCameraSensor, SegmentationCameraSensor, RgbdCameraSensor, and BoundingBoxCameraSensor.

◆ Update() [2/3]

virtual bool Update

Force the sensor to generate data.

This method must be overridden by sensors. Subclasses should not not make a decision about whether or not they need to update. The Sensor class will make sure Update() is called at the correct time.

If a subclass wants to have a variable update rate it should call SetUpdateRate().

A subclass should return false if there was an error while updating

Parameters
[in]_nowThe current time
Returns
true if the update was successfull
See also
SetUpdateRate()

◆ Update() [3/3]

bool Update

Update the sensor.

This is called by the manager, and is responsible for determining if this sensor needs to generate data at this time. If so, the subclasses' Update() method will be called.

Parameters
[in]_nowThe current time
[in]_forceForce the update to happen even if it's not time
Returns
True if the update was triggered (_force was true or _now >= next_update_time) and the sensor's bool Sensor::Update(std::chrono::steady_clock::time_point) function returned true. False otherwise.
Remarks
If forced the NextUpdateTime() will be unchanged.

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