Transmitter to send wireless signals. More...
#include <sensors/sensors.hh>
Inherits WirelessTransceiver.
| Public Member Functions | |
| WirelessTransmitter () | |
| Constructor.  More... | |
| virtual | ~WirelessTransmitter () | 
| 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... | |
| std::string | ESSID () const | 
| Returns the Service Set Identifier (network name).  More... | |
| void | FillMsg (msgs::Sensor &_msg) | 
| fills a msgs::Sensor message.  More... | |
| virtual void | Fini () | 
| Finalize the sensor.  More... | |
| double | Freq () const | 
| Returns reception frequency (MHz).  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... | |
| std::string | GetESSID () const GAZEBO_DEPRECATED(7.0) | 
| Returns the Service Set Identifier (network name).  More... | |
| double | GetFreq () const GAZEBO_DEPRECATED(7.0) | 
| Returns reception frequency (MHz).  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... | |
| 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... | |
| 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 | ModelStdDev () const | 
| Get the std dev of the Gaussian random variable used in the propagation model.  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... | |
| 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... | |
| double | SignalStrength (const ignition::math::Pose3d &_receiver, const double _rxGain) | 
| Returns the signal strength in a given world's point (dBm).  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::ConnectionPtr > | connections | 
| 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::Link > | parentEntity | 
| 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< SensorPluginPtr > | plugins | 
| 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... | |
Transmitter to send wireless signals.
Constructor.
| 
 | virtual | 
Destructor.
| 
 | inherited | 
| 
 | inherited | 
Connect a signal that is triggered when the sensor is updated.
| [in] | _subscriber | Callback that receives the signal. | 
| 
 | inherited | 
Disconnect from a the updated signal.
| [in] | _c | The connection to disconnect | 
| std::string ESSID | ( | ) | const | 
Returns the Service Set Identifier (network name).
| 
 | inherited | 
fills a msgs::Sensor message.
| [out] | _msg | Message to fill. | 
| 
 | virtualinherited | 
| double Freq | ( | ) | const | 
Returns reception frequency (MHz).
| 
 | inherited | 
Returns the antenna's gain of the receiver (dBi).
| 
 | inherited | 
Get the category of the sensor.
| std::string GetESSID | ( | ) | const | 
Returns the Service Set Identifier (network name).
| double GetFreq | ( | ) | const | 
| 
 | inherited | 
Returns the antenna's gain of the receiver (dBi).
| 
 | inherited | 
| 
 | inherited | 
Return last measurement time.
| 
 | inherited | 
| 
 | inherited | 
| 
 | inherited | 
Get the sensor's noise model for a specified noise type.
| [in] | _type | Index of the noise type. Refer to SensorNoiseType enumeration for possible indices | 
| 
 | inherited | 
| 
 | inherited | 
Returns the name of the sensor parent.
The parent name is set by Sensor::SetParent.
| 
 | inherited | 
| 
 | inherited | 
Get fully scoped name of the sensor.
| 
 | virtualinherited | 
Returns the topic name as set in SDF.
Reimplemented in AltimeterSensor, LogicalCameraSensor, and MagnetometerSensor.
| 
 | inherited | 
| 
 | inherited | 
Get the update rate of the sensor.
| 
 | inherited | 
Return true if user requests the sensor to be visualized via tag: <visualize>true</visualize> in SDF.
| 
 | inherited | 
Returns the name of the world the sensor is in.
| 
 | inherited | 
Get the sensor's ID.
| 
 | virtual | 
Initialize the sensor.
Reimplemented from WirelessTransceiver.
| 
 | virtualinherited | 
Returns true if sensor generation is active.
Reimplemented in GpuRaySensor, RaySensor, ContactSensor, MultiCameraSensor, CameraSensor, SonarSensor, LogicalCameraSensor, ImuSensor, and ForceTorqueSensor.
| 
 | inherited | 
Return last measurement time.
| 
 | inherited | 
Return last update time.
| 
 | virtual | 
Load the sensor with default parameters.
| [in] | _worldName | Name of world to load from. | 
Reimplemented from WirelessTransceiver.
| 
 | virtualinherited | 
Load the sensor with SDF parameters.
| [in] | _sdf | SDF Sensor parameters. | 
| [in] | _worldName | Name of world to load from. | 
Reimplemented in GpuRaySensor, ContactSensor, CameraSensor, ForceTorqueSensor, AltimeterSensor, GpsSensor, LogicalCameraSensor, RFIDSensor, MagnetometerSensor, ImuSensor, and RFIDTag.
| double ModelStdDev | ( | ) | const | 
Get the std dev of the Gaussian random variable used in the propagation model.
| 
 | inherited | 
Get name.
| 
 | protectedinherited | 
Return true if the sensor needs to be updated.
| 
 | inherited | 
Get the sensor's noise model for a specified noise type.
| [in] | _type | Index of the noise type. Refer to SensorNoiseType enumeration for possible indices | 
| 
 | inherited | 
Get the sensor's parent's ID.
| 
 | inherited | 
Returns the name of the sensor parent.
The parent name is set by Sensor::SetParent.
| 
 | virtualinherited | 
| 
 | inherited | 
Returns the receiver power (dBm).
| 
 | inherited | 
Reset the lastUpdateTime to zero.
| 
 | inherited | 
Get fully scoped name of the sensor.
| 
 | virtualinherited | 
Set whether the sensor is active or not.
| [in] | _value | True if active, false if not. | 
| 
 | inherited | 
Set the sensor's parent.
| [in] | _name | The sensor's parent's name. | 
| [in] | _id | The sensor's parent's ID. | 
| 
 | virtualinherited | 
| 
 | inherited | 
Set the update rate of the sensor.
| [in] | _hz | update rate of sensor. | 
| double SignalStrength | ( | const ignition::math::Pose3d & | _receiver, | 
| const double | _rxGain | ||
| ) | 
Returns the signal strength in a given world's point (dBm).
| [in] | _receiver | Pose of the receiver | 
| [in] | _rxGain | Receiver gain value | 
| 
 | virtualinherited | 
| 
 | inherited | 
Get sensor type.
| 
 | inherited | 
Update the sensor.
| [in] | _force | True to force update, false otherwise. | 
| 
 | 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
| [in] | _force | True if update is forced, false if not | 
Reimplemented from Sensor.
| 
 | inherited | 
Get the update rate of the sensor.
| 
 | inherited | 
Return true if user requests the sensor to be visualized via tag: <visualize>true</visualize> in SDF.
| 
 | inherited | 
Returns the name of the world the sensor is in.
| 
 | protectedinherited | 
True if sensor generation is active.
| 
 | protectedinherited | 
All event connections.
| 
 | protectedinherited | 
Antenna's gain of the receiver (dBi).
| 
 | protectedinherited | 
Stores last time that a sensor measurement was generated; this value must be updated within each sensor's UpdateImpl.
| 
 | protectedinherited | 
Time of the last update.
| 
 | protectedinherited | 
Node for communication.
| 
 | protectedinherited | 
Noise added to sensor data.
| 
 | protectedinherited | 
Parent entity which the sensor is attached to.
| 
 | protectedinherited | 
The sensor's parent ID.
| 
 | protectedinherited | 
Name of the parent.
| 
 | protectedinherited | 
All the plugins for the sensor.
| 
 | protectedinherited | 
Pose of the sensor.
| 
 | protectedinherited | 
Receiver's power (dBm).
| 
 | protectedinherited | 
Publisher to publish propagation model data.
| 
 | protectedinherited | 
Sensor reference pose.
| 
 | protectedinherited | 
Pointer to the Scene.
| 
 | protectedinherited | 
Pointer the the SDF element for the sensor.
| 
 | protectedinherited | 
Desired time between updates, set indirectly by Sensor::SetUpdateRate.
| 
 | protectedinherited | 
Pointer to the world.