WirelessReceiver Class Reference

Sensor class for receiving wireless signals. More...

#include <sensors/sensors.hh>

Inherits WirelessTransceiver.

Public Member Functions

 WirelessReceiver ()
 Constructor. More...
 
virtual ~WirelessReceiver ()
 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 DisconnectUpdated (event::ConnectionPtr &_c)
 Disconnect from a the updated signal. More...
 
void FillMsg (msgs::Sensor &_msg)
 fills a msgs::Sensor message. More...
 
virtual void Fini ()
 Finalize the sensor. More...
 
double Gain () const
 Returns the antenna's gain of the receiver (dBi). More...
 
SensorCategory GetCategory () const GAZEBO_DEPRECATED(7.0)
 Get the category of the sensor. More...
 
double GetGain () const GAZEBO_DEPRECATED(7.0)
 Returns the antenna's gain of the receiver (dBi). More...
 
uint32_t GetId () const GAZEBO_DEPRECATED(7.0)
 Get the sensor's ID. More...
 
common::Time GetLastMeasurementTime () GAZEBO_DEPRECATED(7.0)
 Return last measurement time. More...
 
common::Time GetLastUpdateTime () GAZEBO_DEPRECATED(7.0)
 Return last update time. More...
 
double GetMaxFreqFiltered () const GAZEBO_DEPRECATED(7.0)
 Returns the maximum frequency filtered (MHz). More...
 
double GetMinFreqFiltered () const GAZEBO_DEPRECATED(7.0)
 Returns the minimum frequency filtered (MHz). More...
 
std::string GetName () const GAZEBO_DEPRECATED(7.0)
 Get name. More...
 
NoisePtr GetNoise (const SensorNoiseType _type) const GAZEBO_DEPRECATED(7.0)
 Get the sensor's noise model for a specified noise type. More...
 
uint32_t GetParentId () const GAZEBO_DEPRECATED(7.0)
 Get the sensor's parent's ID. More...
 
std::string GetParentName () const GAZEBO_DEPRECATED(7.0)
 Returns the name of the sensor parent. More...
 
double GetPower () const GAZEBO_DEPRECATED(7.0)
 Returns the receiver power (dBm). More...
 
std::string GetScopedName () const GAZEBO_DEPRECATED(7.0)
 Get fully scoped name of the sensor. More...
 
double GetSensitivity () const GAZEBO_DEPRECATED(7.0)
 Returns the receiver sensitivity (dBm). More...
 
virtual std::string GetTopic () const GAZEBO_DEPRECATED(7.0)
 Returns the topic name as set in SDF. More...
 
std::string GetType () const GAZEBO_DEPRECATED(7.0)
 Get sensor type. More...
 
double GetUpdateRate () GAZEBO_DEPRECATED(7.0)
 Get the update rate of the sensor. More...
 
bool GetVisualize () const GAZEBO_DEPRECATED(7.0)
 Return true if user requests the sensor to be visualized via tag: <visualize>true</visualize> in SDF. More...
 
std::string GetWorldName () const GAZEBO_DEPRECATED(7.0)
 Returns the name of the world the sensor is in. 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)
 Load the sensor with default parameters. More...
 
virtual void Load (const std::string &_worldName, sdf::ElementPtr _sdf)
 Load the sensor with SDF parameters. More...
 
double MaxFreqFiltered () const
 Returns the maximum frequency filtered (MHz). More...
 
double MinFreqFiltered () const
 Returns the minimum frequency filtered (MHz). More...
 
std::string Name () const
 Get name. 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...
 
double Power () const
 Returns the receiver power (dBm). More...
 
void ResetLastUpdateTime ()
 Reset the lastUpdateTime to zero. More...
 
std::string ScopedName () const
 Get fully scoped name of the sensor. More...
 
double Sensitivity () const
 Returns the receiver sensitivity (dBm). 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...
 
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

bool NeedsUpdate ()
 Return true if the sensor needs to be updated. More...
 
virtual bool UpdateImpl (const bool _force)
 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...
 
double gain = 2.5
 Antenna's gain of the receiver (dBi). 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...
 
std::map< SensorNoiseType,
NoisePtr
noises
 Noise added to sensor data. More...
 
boost::weak_ptr< physics::LinkparentEntity
 Parent entity which the sensor is attached to. 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...
 
double power = 14.5
 Receiver's power (dBm). More...
 
transport::PublisherPtr pub
 Publisher to publish propagation model data. More...
 
ignition::math::Pose3d referencePose
 Sensor reference pose. More...
 
gazebo::rendering::ScenePtr scene
 Pointer to the Scene. More...
 
sdf::ElementPtr sdf
 Pointer the the SDF element for the sensor. 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

Sensor class for receiving wireless signals.

Constructor & Destructor Documentation

Constructor.

virtual ~WirelessReceiver ( )
virtual

Destructor.

Member Function Documentation

SensorCategory Category ( ) const
inherited

Get the category of the sensor.

Returns
The category of the sensor.
See Also
SensorCategory
event::ConnectionPtr ConnectUpdated ( std::function< void()>  _subscriber)
inherited

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
void DisconnectUpdated ( event::ConnectionPtr _c)
inherited

Disconnect from a the updated signal.

Parameters
[in]_cThe connection to disconnect
See Also
Sensor::ConnectUpdated
void FillMsg ( msgs::Sensor &  _msg)
inherited

fills a msgs::Sensor message.

Parameters
[out]_msgMessage to fill.
virtual void Fini ( )
virtual

Finalize the sensor.

Reimplemented from WirelessTransceiver.

double Gain ( ) const
inherited

Returns the antenna's gain of the receiver (dBi).

Returns
Antenna's gain of the receiver (dBi).
SensorCategory GetCategory ( ) const
inherited

Get the category of the sensor.

Returns
The category of the sensor.
See Also
SensorCategory
Deprecated:
See Category() function.
double GetGain ( ) const
inherited

Returns the antenna's gain of the receiver (dBi).

Returns
Antenna's gain of the receiver (dBi).
Deprecated:
See Gain()
uint32_t GetId ( ) const
inherited

Get the sensor's ID.

Returns
The sensor's ID.
Deprecated:
See Id() function
common::Time GetLastMeasurementTime ( )
inherited

Return last measurement time.

Returns
Time of last measurement.
Deprecated:
See LastMeasurementTime() function.
common::Time GetLastUpdateTime ( )
inherited

Return last update time.

Returns
Time of last update.
Deprecated:
See LastUpdateTime() function
double GetMaxFreqFiltered ( ) const

Returns the maximum frequency filtered (MHz).

Returns
Reception frequency (MHz).
Deprecated:
See MaxFreqFiltered()
double GetMinFreqFiltered ( ) const

Returns the minimum frequency filtered (MHz).

Returns
Reception frequency (MHz).
Deprecated:
See MinFreqFiltered()
std::string GetName ( ) const
inherited

Get name.

Returns
Name of sensor.
Deprecated:
See Name() function.
NoisePtr GetNoise ( const SensorNoiseType  _type) const
inherited

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
Deprecated:
See Noise(const SensorNoiseType _type) function
uint32_t GetParentId ( ) const
inherited

Get the sensor's parent's ID.

Returns
The sensor's parent's ID.
Deprecated:
See ParentId() function
std::string GetParentName ( ) const
inherited

Returns the name of the sensor parent.

The parent name is set by Sensor::SetParent.

Returns
Name of Parent.
Deprecated:
See ParentName() function.
double GetPower ( ) const
inherited

Returns the receiver power (dBm).

Returns
Receiver power (dBm).
Deprecated:
See Power()
std::string GetScopedName ( ) const
inherited

Get fully scoped name of the sensor.

Returns
world_name::model_name::link_name::sensor_name.
Deprecated:
See ScopedName() function
double GetSensitivity ( ) const

Returns the receiver sensitivity (dBm).

Returns
Receiver sensitivity (dBm).
Deprecated:
See Sensitivity()
virtual std::string GetTopic ( ) const
virtualinherited

Returns the topic name as set in SDF.

Returns
Topic name.
Deprecated:
See Topic() function.

Reimplemented in AltimeterSensor, LogicalCameraSensor, and MagnetometerSensor.

std::string GetType ( ) const
inherited

Get sensor type.

Returns
Type of sensor.
Deprecated:
See Type() function.
double GetUpdateRate ( )
inherited

Get the update rate of the sensor.

Returns
_hz update rate of sensor. Returns 0 if unthrottled.
Deprecated:
See UpdateRate() function
bool GetVisualize ( ) const
inherited

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

Returns
True if visualized, false if not.
Deprecated:
See Visualize() function
std::string GetWorldName ( ) const
inherited

Returns the name of the world the sensor is in.

Returns
Name of the world.
Deprecated:
See WorldName() function.
uint32_t Id ( ) const
inherited

Get the sensor's ID.

Returns
The sensor's ID.
virtual void Init ( )
virtual

Initialize the sensor.

Reimplemented from WirelessTransceiver.

virtual bool IsActive ( ) const
virtualinherited

Returns true if sensor generation is active.

Returns
True if active, false if not.

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

common::Time LastMeasurementTime ( ) const
inherited

Return last measurement time.

Returns
Time of last measurement.
Deprecated:
See LastMeasurementTime() function.
common::Time LastUpdateTime ( ) const
inherited

Return last update time.

Returns
Time of last update.
virtual void Load ( const std::string &  _worldName)
virtual

Load the sensor with default parameters.

Parameters
[in]_worldNameName of world to load from.

Reimplemented from WirelessTransceiver.

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

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, MagnetometerSensor, ImuSensor, and RFIDTag.

double MaxFreqFiltered ( ) const

Returns the maximum frequency filtered (MHz).

Returns
Reception frequency (MHz).
double MinFreqFiltered ( ) const

Returns the minimum frequency filtered (MHz).

Returns
Reception frequency (MHz).
std::string Name ( ) const
inherited

Get name.

Returns
Name of sensor.
bool NeedsUpdate ( )
protectedinherited

Return true if the sensor needs to be updated.

Returns
True when sensor should be updated.
NoisePtr Noise ( const SensorNoiseType  _type) const
inherited

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
uint32_t ParentId ( ) const
inherited

Get the sensor's parent's ID.

Returns
The sensor's parent's ID.
std::string ParentName ( ) const
inherited

Returns the name of the sensor parent.

The parent name is set by Sensor::SetParent.

Returns
Name of Parent.
virtual ignition::math::Pose3d Pose ( ) const
virtualinherited

Get the current pose.

Returns
Current pose of the sensor.
See Also
SetPose()
double Power ( ) const
inherited

Returns the receiver power (dBm).

Returns
Receiver power (dBm).
void ResetLastUpdateTime ( )
inherited

Reset the lastUpdateTime to zero.

std::string ScopedName ( ) const
inherited

Get fully scoped name of the sensor.

Returns
world_name::model_name::link_name::sensor_name.
double Sensitivity ( ) const

Returns the receiver sensitivity (dBm).

Returns
Receiver sensitivity (dBm).
virtual void SetActive ( const bool  _value)
virtualinherited

Set whether the sensor is active or not.

Parameters
[in]_valueTrue if active, false if not.
void SetParent ( const std::string &  _name,
const uint32_t  _id 
)
inherited

Set the sensor's parent.

Parameters
[in]_nameThe sensor's parent's name.
[in]_idThe sensor's parent's ID.
virtual void SetPose ( const ignition::math::Pose3d &  _pose)
virtualinherited

Set the current pose.

Parameters
[in]_poseNew pose of the sensor.
See Also
Pose()
void SetUpdateRate ( const double  _hz)
inherited

Set the update rate of the sensor.

Parameters
[in]_hzupdate rate of sensor.
virtual std::string Topic ( ) const
virtualinherited

Returns the topic name as set in SDF.

Returns
Topic name.

Reimplemented from Sensor.

std::string Type ( ) const
inherited

Get sensor type.

Returns
Type of sensor.
void Update ( const bool  _force)
inherited

Update the sensor.

Parameters
[in]_forceTrue to force update, false otherwise.
virtual bool UpdateImpl ( const bool  )
protectedvirtual

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 from Sensor.

double UpdateRate ( ) const
inherited

Get the update rate of the sensor.

Returns
_hz update rate of sensor. Returns 0 if unthrottled.
bool Visualize ( ) const
inherited

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

Returns
True if visualized, false if not.
std::string WorldName ( ) const
inherited

Returns the name of the world the sensor is in.

Returns
Name of the world.

Member Data Documentation

bool active
protectedinherited

True if sensor generation is active.

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

All event connections.

double gain = 2.5
protectedinherited

Antenna's gain of the receiver (dBi).

common::Time lastMeasurementTime
protectedinherited

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

common::Time lastUpdateTime
protectedinherited

Time of the last update.

transport::NodePtr node
protectedinherited

Node for communication.

std::map<SensorNoiseType, NoisePtr> noises
protectedinherited

Noise added to sensor data.

boost::weak_ptr<physics::Link> parentEntity
protectedinherited

Parent entity which the sensor is attached to.

uint32_t parentId
protectedinherited

The sensor's parent ID.

std::string parentName
protectedinherited

Name of the parent.

std::vector<SensorPluginPtr> plugins
protectedinherited

All the plugins for the sensor.

ignition::math::Pose3d pose
protectedinherited

Pose of the sensor.

double power = 14.5
protectedinherited

Receiver's power (dBm).

transport::PublisherPtr pub
protectedinherited

Publisher to publish propagation model data.

ignition::math::Pose3d referencePose
protectedinherited

Sensor reference pose.

gazebo::rendering::ScenePtr scene
protectedinherited

Pointer to the Scene.

sdf::ElementPtr sdf
protectedinherited

Pointer the the SDF element for the sensor.

common::Time updatePeriod
protectedinherited

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

gazebo::physics::WorldPtr world
protectedinherited

Pointer to the world.


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