Sensor Class Reference

Base class for sensors. More...

#include <sensors/sensors.hh>

Inherits enable_shared_from_this< Sensor >.

Inherited by AltimeterSensor, CameraSensor, ContactSensor, ForceTorqueSensor, GpsSensor, GpuRaySensor, ImuSensor, LogicalCameraSensor, MagnetometerSensor, MultiCameraSensor, RaySensor, RFIDSensor, RFIDTag, SonarSensor, and WirelessTransceiver.

Public Member Functions

 Sensor (SensorCategory _cat)
 Constructor. More...
 
virtual ~Sensor ()
 Destructor. More...
 
SensorCategory Category () const
 Get the category of the sensor. More...
 
event::ConnectionPtr ConnectUpdated (std::function< void()> _subscriber)
 Connect a signal that is triggered when the sensor is updated. More...
 
void FillMsg (msgs::Sensor &_msg)
 fills a msgs::Sensor message. More...
 
virtual void Fini ()
 Finalize the sensor. More...
 
uint32_t Id () const
 Get the sensor's ID. More...
 
virtual void Init ()
 Initialize the sensor. More...
 
virtual bool IsActive () const
 Returns true if sensor generation is active. More...
 
common::Time LastMeasurementTime () const
 Return last measurement time. More...
 
common::Time LastUpdateTime () const
 Return last update time. More...
 
virtual void Load (const std::string &_worldName, sdf::ElementPtr _sdf)
 Load the sensor with SDF parameters. More...
 
virtual void Load (const std::string &_worldName)
 Load the sensor with default parameters. More...
 
std::string Name () const
 Get name. More...
 
virtual double NextRequiredTimestamp () const
 Get the next timestamp that will be used by the sensor. More...
 
NoisePtr Noise (const SensorNoiseType _type) const
 Get the sensor's noise model for a specified noise type. More...
 
uint32_t ParentId () const
 Get the sensor's parent's ID. More...
 
std::string ParentName () const
 Returns the name of the sensor parent. More...
 
virtual ignition::math::Pose3d Pose () const
 Get the current pose. More...
 
virtual void ResetLastUpdateTime ()
 Reset the lastUpdateTime to zero. More...
 
std::string ScopedName () const
 Get fully scoped name of the sensor. More...
 
virtual void SetActive (const bool _value)
 Set whether the sensor is active or not. More...
 
void SetParent (const std::string &_name, const uint32_t _id)
 Set the sensor's parent. More...
 
virtual void SetPose (const ignition::math::Pose3d &_pose)
 Set the current pose. More...
 
void SetUpdateRate (const double _hz)
 Set the update rate of the sensor. More...
 
virtual std::string Topic () const
 Returns the topic name as set in SDF. More...
 
std::string Type () const
 Get sensor type. More...
 
virtual void Update (const bool _force)
 Update the sensor. More...
 
double UpdateRate () const
 Get the update rate of the sensor. More...
 
bool Visualize () const
 Return true if user requests the sensor to be visualized via tag: <visualize>true</visualize> in SDF. More...
 
std::string WorldName () const
 Returns the name of the world the sensor is in. More...
 

Protected Member Functions

virtual bool NeedsUpdate ()
 Return true if the sensor needs to be updated. More...
 
virtual bool UpdateImpl (const bool)
 This gets overwritten by derived sensor types. More...
 

Protected Attributes

bool active
 True if sensor generation is active. More...
 
std::vector< event::ConnectionPtrconnections
 All event connections. More...
 
common::Time lastMeasurementTime
 Stores last time that a sensor measurement was generated; this value must be updated within each sensor's UpdateImpl. More...
 
common::Time lastUpdateTime
 Time of the last update. More...
 
transport::NodePtr node
 Node for communication. More...
 
ignition::transport::Node nodeIgn
 Ignition transport node. More...
 
std::map< SensorNoiseType, NoisePtrnoises
 Noise added to sensor data. More...
 
uint32_t parentId
 The sensor's parent ID. More...
 
std::string parentName
 Name of the parent. More...
 
std::vector< SensorPluginPtrplugins
 All the plugins for the sensor. More...
 
ignition::math::Pose3d pose
 Pose of the sensor. More...
 
gazebo::rendering::ScenePtr scene
 Pointer to the Scene. More...
 
sdf::ElementPtr sdf
 Pointer the the SDF element for the sensor. More...
 
event::EventT< void()> updated
 Event triggered when a sensor is updated. More...
 
common::Time updatePeriod
 Desired time between updates, set indirectly by Sensor::SetUpdateRate. More...
 
gazebo::physics::WorldPtr world
 Pointer to the world. More...
 

Detailed Description

Base class for sensors.

Constructor & Destructor Documentation

◆ Sensor()

Sensor ( SensorCategory  _cat)
explicit

Constructor.

Parameters
[in]_catCategory of the sensor

◆ ~Sensor()

virtual ~Sensor ( )
virtual

Destructor.

Member Function Documentation

◆ Category()

SensorCategory Category ( ) const

Get the category of the sensor.

Returns
The category of the sensor.
See also
SensorCategory

◆ ConnectUpdated()

event::ConnectionPtr ConnectUpdated ( std::function< void()>  _subscriber)

Connect a signal that is triggered when the sensor is updated.

Parameters
[in]_subscriberCallback that receives the signal.
Returns
A pointer to the connection. This must be kept in scope.
See also
Sensor::DisconnectUpdated

◆ FillMsg()

void FillMsg ( msgs::Sensor &  _msg)

fills a msgs::Sensor message.

Parameters
[out]_msgMessage to fill.

◆ Fini()

◆ Id()

uint32_t Id ( ) const

Get the sensor's ID.

Returns
The sensor's ID.

◆ Init()

◆ IsActive()

virtual bool IsActive ( ) const
virtual

Returns true if sensor generation is active.

Returns
True if active, false if not.

Reimplemented in GpuRaySensor, RaySensor, ContactSensor, CameraSensor, ImuSensor, MultiCameraSensor, LogicalCameraSensor, SonarSensor, and ForceTorqueSensor.

◆ LastMeasurementTime()

common::Time LastMeasurementTime ( ) const

Return last measurement time.

Returns
Time of last measurement.

◆ LastUpdateTime()

common::Time LastUpdateTime ( ) const

Return last update time.

Returns
Time of last update.

◆ Load() [1/2]

virtual void Load ( const std::string &  _worldName,
sdf::ElementPtr  _sdf 
)
virtual

Load the sensor with SDF parameters.

Parameters
[in]_sdfSDF Sensor parameters.
[in]_worldNameName of world to load from.

Reimplemented in GpuRaySensor, ContactSensor, CameraSensor, ForceTorqueSensor, AltimeterSensor, GpsSensor, LogicalCameraSensor, RFIDSensor, ImuSensor, MagnetometerSensor, and RFIDTag.

◆ Load() [2/2]

virtual void Load ( const std::string &  _worldName)
virtual

◆ Name()

std::string Name ( ) const

Get name.

Returns
Name of sensor.

◆ NeedsUpdate()

virtual bool NeedsUpdate ( )
protectedvirtual

Return true if the sensor needs to be updated.

Returns
True when sensor should be updated.

Reimplemented in GpuRaySensor, and CameraSensor.

Referenced by Sensor::UpdateImpl().

◆ NextRequiredTimestamp()

virtual double NextRequiredTimestamp ( ) const
virtual

Get the next timestamp that will be used by the sensor.

Returns
the timestamp

Reimplemented in GpuRaySensor, and CameraSensor.

◆ Noise()

NoisePtr Noise ( const SensorNoiseType  _type) const

Get the sensor's noise model for a specified noise type.

Parameters
[in]_typeIndex of the noise type. Refer to SensorNoiseType enumeration for possible indices
Returns
The sensor's noise model for the given noise type

◆ ParentId()

uint32_t ParentId ( ) const

Get the sensor's parent's ID.

Returns
The sensor's parent's ID.

◆ ParentName()

std::string ParentName ( ) const

Returns the name of the sensor parent.

The parent name is set by Sensor::SetParent.

Returns
Name of Parent.

◆ Pose()

virtual ignition::math::Pose3d Pose ( ) const
virtual

Get the current pose.

Returns
Current pose of the sensor.
See also
SetPose()

◆ ResetLastUpdateTime()

virtual void ResetLastUpdateTime ( )
virtual

Reset the lastUpdateTime to zero.

Reimplemented in GpuRaySensor, and CameraSensor.

◆ ScopedName()

std::string ScopedName ( ) const

Get fully scoped name of the sensor.

Returns
world_name::model_name::link_name::sensor_name.

◆ SetActive()

virtual void SetActive ( const bool  _value)
virtual

Set whether the sensor is active or not.

Parameters
[in]_valueTrue if active, false if not.

Reimplemented in GpuRaySensor, and CameraSensor.

◆ SetParent()

void SetParent ( const std::string &  _name,
const uint32_t  _id 
)

Set the sensor's parent.

Parameters
[in]_nameThe sensor's parent's name.
[in]_idThe sensor's parent's ID.

◆ SetPose()

virtual void SetPose ( const ignition::math::Pose3d &  _pose)
virtual

Set the current pose.

Parameters
[in]_poseNew pose of the sensor.
See also
Pose()

◆ SetUpdateRate()

void SetUpdateRate ( const double  _hz)

Set the update rate of the sensor.

Parameters
[in]_hzupdate rate of sensor.

◆ Topic()

virtual std::string Topic ( ) const
virtual

Returns the topic name as set in SDF.

Returns
Topic name.

Reimplemented in GpuRaySensor, CameraSensor, RaySensor, ForceTorqueSensor, LogicalCameraSensor, MultiCameraSensor, SonarSensor, and WirelessTransceiver.

◆ Type()

std::string Type ( ) const

Get sensor type.

Returns
Type of sensor.

◆ Update()

virtual void Update ( const bool  _force)
virtual

Update the sensor.

Parameters
[in]_forceTrue to force update, false otherwise.

Reimplemented in GpuRaySensor, and CameraSensor.

◆ UpdateImpl()

virtual bool UpdateImpl ( const bool  )
inlineprotectedvirtual

This gets overwritten by derived sensor types.

This function is called during Sensor::Update. And in turn, Sensor::Update is called by SensorManager::Update

Parameters
[in]_forceTrue if update is forced, false if not
Returns
True if the sensor was updated.

Reimplemented in CameraSensor, MultiCameraSensor, SonarSensor, LogicalCameraSensor, GpuRaySensor, ForceTorqueSensor, WirelessReceiver, ContactSensor, DepthCameraSensor, RaySensor, AltimeterSensor, RFIDSensor, MagnetometerSensor, WideAngleCameraSensor, GpsSensor, ImuSensor, RFIDTag, and WirelessTransmitter.

References Sensor::NeedsUpdate().

◆ UpdateRate()

double UpdateRate ( ) const

Get the update rate of the sensor.

Returns
_hz update rate of sensor. Returns 0 if unthrottled.

◆ Visualize()

bool Visualize ( ) const

Return true if user requests the sensor to be visualized via tag: <visualize>true</visualize> in SDF.

Returns
True if visualized, false if not.

◆ WorldName()

std::string WorldName ( ) const

Returns the name of the world the sensor is in.

Returns
Name of the world.

Member Data Documentation

◆ active

bool active
protected

True if sensor generation is active.

◆ connections

std::vector<event::ConnectionPtr> connections
protected

All event connections.

◆ lastMeasurementTime

common::Time lastMeasurementTime
protected

Stores last time that a sensor measurement was generated; this value must be updated within each sensor's UpdateImpl.

◆ lastUpdateTime

common::Time lastUpdateTime
protected

Time of the last update.

◆ node

transport::NodePtr node
protected

Node for communication.

◆ nodeIgn

ignition::transport::Node nodeIgn
protected

Ignition transport node.

◆ noises

std::map<SensorNoiseType, NoisePtr> noises
protected

Noise added to sensor data.

◆ parentId

uint32_t parentId
protected

The sensor's parent ID.

◆ parentName

std::string parentName
protected

Name of the parent.

◆ plugins

std::vector<SensorPluginPtr> plugins
protected

All the plugins for the sensor.

◆ pose

ignition::math::Pose3d pose
protected

Pose of the sensor.

◆ scene

gazebo::rendering::ScenePtr scene
protected

Pointer to the Scene.

◆ sdf

sdf::ElementPtr sdf
protected

Pointer the the SDF element for the sensor.

◆ updated

event::EventT<void()> updated
protected

Event triggered when a sensor is updated.

◆ updatePeriod

common::Time updatePeriod
protected

Desired time between updates, set indirectly by Sensor::SetUpdateRate.

◆ world

gazebo::physics::WorldPtr world
protected

Pointer to the world.


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