Sensor class for receiving wireless signals. More...
#include <sensors/sensors.hh>
Public Member Functions | |
WirelessReceiver () | |
Constructor. More... | |
virtual | ~WirelessReceiver () |
Constructor. More... | |
virtual void | Fini () |
Finalize the sensor. More... | |
double | GetMaxFreqFiltered () const |
Returns the maximum frequency filtered (MHz). More... | |
double | GetMinFreqFiltered () const |
Returns the minimum frequency filtered (MHz). More... | |
double | GetSensitivity () const |
Returns the receiver sensitivity (dBm). More... | |
virtual void | Init () |
Initialize the sensor. More... | |
virtual void | Load (const std::string &_worldName) |
Load the sensor with default parameters. More... | |
Public Member Functions inherited from gazebo::sensors::WirelessTransceiver | |
WirelessTransceiver () | |
Constructor. More... | |
~WirelessTransceiver () | |
Constructor. 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 |
Get the sensor's noise model. 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 |
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... | |
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... | |
Additional Inherited Members | |
Protected Member Functions inherited from gazebo::sensors::Sensor | |
bool | NeedsUpdate () |
Return true if the sensor needs to be updated. More... | |
Protected Attributes inherited from gazebo::sensors::WirelessTransceiver | |
double | gain |
Antenna's gain of the receiver (dBi). More... | |
boost::weak_ptr< physics::Link > | parentEntity |
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... | |
math::Pose | referencePose |
Sensor reference pose. More... | |
Protected Attributes inherited from gazebo::sensors::Sensor | |
bool | active |
True if sensor generation is active. More... | |
std::vector< event::ConnectionPtr > | connections |
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::vector< NoisePtr > | noises |
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< SensorPluginPtr > | plugins |
All the plugins for the sensor. More... | |
math::Pose | 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... | |
Sensor class for receiving wireless signals.
gazebo::sensors::WirelessReceiver::WirelessReceiver | ( | ) |
Constructor.
|
virtual |
Constructor.
|
virtual |
Finalize the sensor.
Reimplemented from gazebo::sensors::WirelessTransceiver.
double gazebo::sensors::WirelessReceiver::GetMaxFreqFiltered | ( | ) | const |
Returns the maximum frequency filtered (MHz).
double gazebo::sensors::WirelessReceiver::GetMinFreqFiltered | ( | ) | const |
Returns the minimum frequency filtered (MHz).
double gazebo::sensors::WirelessReceiver::GetSensitivity | ( | ) | const |
Returns the receiver sensitivity (dBm).
|
virtual |
Initialize the sensor.
Reimplemented from gazebo::sensors::WirelessTransceiver.
|
virtual |
Load the sensor with default parameters.
[in] | _worldName | Name of world to load from. |
Reimplemented from gazebo::sensors::WirelessTransceiver.