Public Member Functions | Static Public Attributes | Protected Member Functions | Protected Attributes | List of all members
gazebo::sensors::WirelessTransmitter Class Reference

Transmitter to send wireless signals. More...

#include <sensors/sensors.hh>

Inheritance diagram for gazebo::sensors::WirelessTransmitter:
Inheritance graph
[legend]

Public Member Functions

 WirelessTransmitter ()
 Constructor. More...
 
virtual ~WirelessTransmitter ()
 Destructor. More...
 
std::string GetESSID () const
 Returns the Service Set Identifier (network name). More...
 
double GetFreq () const
 Returns reception frequency (MHz). More...
 
double GetSignalStrength (const math::Pose &_receiver, const double _rxGain) GAZEBO_DEPRECATED(6.0)
 Returns the signal strength in a given world's point (dBm). More...
 
virtual void Init ()
 Initialize the sensor. More...
 
virtual void Load (const std::string &_worldName)
 Load the sensor with default parameters. More...
 
double SignalStrength (const ignition::math::Pose3d &_receiver, const double _rxGain)
 Returns the signal strength in a given world's point (dBm). More...
 
- Public Member Functions inherited from gazebo::sensors::WirelessTransceiver
 WirelessTransceiver ()
 Constructor. More...
 
 ~WirelessTransceiver ()
 Constructor. More...
 
virtual void Fini ()
 Finalize the sensor. More...
 
double GetGain () const
 Returns the antenna's gain of the receiver (dBi). More...
 
double GetPower () const
 Returns the receiver power (dBm). More...
 
virtual std::string GetTopic () const
 Returns the topic name as set in SDF. More...
 
- Public Member Functions inherited from gazebo::sensors::Sensor
 Sensor (SensorCategory _cat)
 Constructor. More...
 
virtual ~Sensor ()
 Destructor. More...
 
template<typename T >
event::ConnectionPtr ConnectUpdated (T _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...
 
SensorCategory GetCategory () const
 Get the category of the sensor. More...
 
uint32_t GetId () const
 Get the sensor's ID. More...
 
common::Time GetLastMeasurementTime ()
 Return last measurement time. More...
 
common::Time GetLastUpdateTime ()
 Return last update time. More...
 
std::string GetName () const
 Get name. More...
 
NoisePtr GetNoise (unsigned int _index=0) const GAZEBO_DEPRECATED(6.0)
 Get the sensor's noise model. More...
 
NoisePtr GetNoise (const SensorNoiseType _type) const
 Get the sensor's noise model for a specified noise type. More...
 
uint32_t GetParentId () const
 Get the sensor's parent's ID. More...
 
std::string GetParentName () const
 Returns the name of the sensor parent. More...
 
virtual math::Pose GetPose () const GAZEBO_DEPRECATED(6.0)
 Get the current pose. More...
 
std::string GetScopedName () const
 Get fully scoped name of the sensor. More...
 
std::string GetType () const
 Get sensor type. More...
 
double GetUpdateRate ()
 Get the update rate of the sensor. More...
 
bool GetVisualize () const
 Return true if user requests the sensor to be visualized via tag: <visualize>true</visualize> in SDF. More...
 
std::string GetWorldName () const
 Returns the name of the world the sensor is in. More...
 
virtual bool IsActive ()
 Returns true if sensor generation is active. More...
 
virtual void Load (const std::string &_worldName, sdf::ElementPtr _sdf)
 Load the sensor with SDF parameters. More...
 
virtual ignition::math::Pose3d Pose () const
 Get the current pose. More...
 
void ResetLastUpdateTime ()
 Reset the lastUpdateTime to zero. More...
 
virtual void SetActive (bool _value)
 Set whether the sensor is active or not. More...
 
void SetParent (const std::string &_name, uint32_t _id)
 Set the sensor's parent. More...
 
void SetUpdateRate (double _hz)
 Set the update rate of the sensor. More...
 
void Update (bool _force)
 Update the sensor. More...
 

Static Public Attributes

static const double ModelStdDesv
 Std desv of the Gaussian random variable used in the propagation model. More...
 
static const double NEmpty
 Constant used in the propagation model when there are no obstacles between transmitter and receiver. More...
 
static const double NObstacle
 Constant used in the propagation model when there are obstacles between transmitter and receiver. More...
 

Protected Member Functions

virtual bool UpdateImpl (bool _force)
 This gets overwritten by derived sensor types. More...
 
- Protected Member Functions inherited from gazebo::sensors::Sensor
bool NeedsUpdate ()
 Return true if the sensor needs to be updated. More...
 

Protected Attributes

double freq
 Reception frequency (MHz). More...
 
- Protected Attributes inherited from gazebo::sensors::WirelessTransceiver
double gain
 Antenna's gain of the receiver (dBi). More...
 
boost::weak_ptr< physics::LinkparentEntity
 Parent entity which the sensor is attached to. More...
 
double power
 Receiver's power (dBm). More...
 
transport::PublisherPtr pub
 Publisher to publish propagation model data. More...
 
ignition::math::Pose3d referencePose
 Sensor reference pose. More...
 
- Protected Attributes inherited from gazebo::sensors::Sensor
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...
 
std::map< int, NoisePtrnoises
 Noise added to sensor data The key maps to a SensorNoiseType, and is kept as an int value for backward compatibilty with Gazebo 5&6. 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...
 
transport::SubscriberPtr poseSub
 Subscribe to pose updates. 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

Transmitter to send wireless signals.

Constructor & Destructor Documentation

gazebo::sensors::WirelessTransmitter::WirelessTransmitter ( )

Constructor.

virtual gazebo::sensors::WirelessTransmitter::~WirelessTransmitter ( )
virtual

Destructor.

Member Function Documentation

std::string gazebo::sensors::WirelessTransmitter::GetESSID ( ) const

Returns the Service Set Identifier (network name).

Returns
Service Set Identifier (network name).
double gazebo::sensors::WirelessTransmitter::GetFreq ( ) const

Returns reception frequency (MHz).

Returns
Reception frequency (MHz).
double gazebo::sensors::WirelessTransmitter::GetSignalStrength ( const math::Pose _receiver,
const double  _rxGain 
)

Returns the signal strength in a given world's point (dBm).

Parameters
[in]_receiverPose of the receiver
[in]_rxGainReceiver gain value
Returns
Signal strength in a world's point (dBm).
Deprecated:
See SignalStrength() function that accepts an ignition::math::Pose3d object.
virtual void gazebo::sensors::WirelessTransmitter::Init ( )
virtual

Initialize the sensor.

Reimplemented from gazebo::sensors::WirelessTransceiver.

virtual void gazebo::sensors::WirelessTransmitter::Load ( const std::string &  _worldName)
virtual

Load the sensor with default parameters.

Parameters
[in]_worldNameName of world to load from.

Reimplemented from gazebo::sensors::WirelessTransceiver.

double gazebo::sensors::WirelessTransmitter::SignalStrength ( const ignition::math::Pose3d &  _receiver,
const double  _rxGain 
)

Returns the signal strength in a given world's point (dBm).

Parameters
[in]_receiverPose of the receiver
[in]_rxGainReceiver gain value
Returns
Signal strength in a world's point (dBm).
virtual bool gazebo::sensors::WirelessTransmitter::UpdateImpl ( 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 gazebo::sensors::Sensor.

Member Data Documentation

double gazebo::sensors::WirelessTransmitter::freq
protected

Reception frequency (MHz).

const double gazebo::sensors::WirelessTransmitter::ModelStdDesv
static

Std desv of the Gaussian random variable used in the propagation model.

const double gazebo::sensors::WirelessTransmitter::NEmpty
static

Constant used in the propagation model when there are no obstacles between transmitter and receiver.

const double gazebo::sensors::WirelessTransmitter::NObstacle
static

Constant used in the propagation model when there are obstacles between transmitter and receiver.


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