All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Macros Groups Pages
Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
gazebo::sensors::Sensor Class Reference

Base class for sensors. More...

#include <sensors/sensors.hh>

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

Public Member Functions

 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...
 
virtual void Fini ()
 Finalize the sensor. 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...
 
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...
 
virtual std::string GetTopic () const
 Returns the topic name as set in SDF. 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 void Init ()
 Initialize the sensor. 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 void Load (const std::string &_worldName)
 Load the sensor with default parameters. More...
 
void ResetLastUpdateTime ()
 Reset the lastUpdateTime to zero. More...
 
virtual void SetActive (bool _value)
 Set whether the sensor is active or not. More...
 
virtual void SetParent (const std::string &_name) GAZEBO_DEPRECATED(2.0)
 Set the parent of the sensor. 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...
 

Protected Member Functions

virtual void UpdateImpl (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...
 
boost::mutex mutexLastUpdateTime
 Mutex to protect resetting lastUpdateTime. More...
 
transport::NodePtr node
 Node for communication. 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...
 
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...
 

Detailed Description

Base class for sensors.

Constructor & Destructor Documentation

gazebo::sensors::Sensor::Sensor ( SensorCategory  _cat)
explicit

Constructor.

Parameters
[in]_class
virtual gazebo::sensors::Sensor::~Sensor ( )
virtual

Destructor.

Member Function Documentation

template<typename T >
event::ConnectionPtr gazebo::sensors::Sensor::ConnectUpdated ( _subscriber)
inline

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

References gazebo::event::EventT< T >::Connect().

void gazebo::sensors::Sensor::DisconnectUpdated ( event::ConnectionPtr _c)
inline

Disconnect from a the updated signal.

Parameters
[in]_cThe connection to disconnect
See Also
Sensor::ConnectUpdated

References gazebo::event::EventT< T >::Disconnect().

void gazebo::sensors::Sensor::FillMsg ( msgs::Sensor &  _msg)

fills a msgs::Sensor message.

Parameters
[out]_msgMessage to fill.
virtual void gazebo::sensors::Sensor::Fini ( )
virtual
SensorCategory gazebo::sensors::Sensor::GetCategory ( ) const

Get the category of the sensor.

Returns
The category of the sensor.
See Also
SensorCategory
uint32_t gazebo::sensors::Sensor::GetId ( ) const

Get the sensor's ID.

Returns
The sensor's ID.
common::Time gazebo::sensors::Sensor::GetLastMeasurementTime ( )

Return last measurement time.

Returns
Time of last measurement.
common::Time gazebo::sensors::Sensor::GetLastUpdateTime ( )

Return last update time.

Returns
Time of last update.
std::string gazebo::sensors::Sensor::GetName ( ) const

Get name.

Returns
Name of sensor.
uint32_t gazebo::sensors::Sensor::GetParentId ( ) const

Get the sensor's parent's ID.

Returns
The sensor's parent's ID.
std::string gazebo::sensors::Sensor::GetParentName ( ) const

Returns the name of the sensor parent.

The parent name is set by Sensor::SetParent.

Returns
Name of Parent.
virtual math::Pose gazebo::sensors::Sensor::GetPose ( ) const
virtual

Get the current pose.

Returns
Current pose of the sensor.
std::string gazebo::sensors::Sensor::GetScopedName ( ) const

Get fully scoped name of the sensor.

Returns
world_name::parent_name::sensor_name.
virtual std::string gazebo::sensors::Sensor::GetTopic ( ) const
virtual
std::string gazebo::sensors::Sensor::GetType ( ) const

Get sensor type.

Returns
Type of sensor.
double gazebo::sensors::Sensor::GetUpdateRate ( )

Get the update rate of the sensor.

Returns
_hz update rate of sensor. Returns 0 if unthrottled.
bool gazebo::sensors::Sensor::GetVisualize ( ) 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.
std::string gazebo::sensors::Sensor::GetWorldName ( ) const

Returns the name of the world the sensor is in.

Returns
Name of the world.
virtual void gazebo::sensors::Sensor::Init ( )
virtual
virtual bool gazebo::sensors::Sensor::IsActive ( )
virtual
virtual void gazebo::sensors::Sensor::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 gazebo::sensors::ContactSensor, gazebo::sensors::RFIDSensor, gazebo::sensors::CameraSensor, and gazebo::sensors::ImuSensor.

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

Reset the lastUpdateTime to zero.

virtual void gazebo::sensors::Sensor::SetActive ( bool  _value)
virtual

Set whether the sensor is active or not.

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

Reimplemented in gazebo::sensors::DepthCameraSensor.

virtual void gazebo::sensors::Sensor::SetParent ( const std::string &  _name)
virtual

Set the parent of the sensor.

Parameters
[in]_nameName of the parent.
void gazebo::sensors::Sensor::SetParent ( const std::string &  _name,
uint32_t  _id 
)

Set the sensor's parent.

Parameters
[in]_nameThe sensor's parent's name.
[in]_idThe sensor's parent's ID.
void gazebo::sensors::Sensor::SetUpdateRate ( double  _hz)

Set the update rate of the sensor.

Parameters
[in]_hzupdate rate of sensor.
void gazebo::sensors::Sensor::Update ( bool  _force)

Update the sensor.

Parameters
[in]_forceTrue to force update, false otherwise.
virtual void gazebo::sensors::Sensor::UpdateImpl ( 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

Reimplemented in gazebo::sensors::MultiCameraSensor, gazebo::sensors::ForceTorqueSensor, gazebo::sensors::GpuRaySensor, gazebo::sensors::CameraSensor, gazebo::sensors::ContactSensor, gazebo::sensors::RFIDSensor, gazebo::sensors::RaySensor, gazebo::sensors::DepthCameraSensor, gazebo::sensors::RFIDTag, gazebo::sensors::GpsSensor, gazebo::sensors::SonarSensor, gazebo::sensors::WirelessTransmitter, and gazebo::sensors::ImuSensor.

Member Data Documentation

bool gazebo::sensors::Sensor::active
protected

True if sensor generation is active.

std::vector<event::ConnectionPtr> gazebo::sensors::Sensor::connections
protected

All event connections.

common::Time gazebo::sensors::Sensor::lastMeasurementTime
protected

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

common::Time gazebo::sensors::Sensor::lastUpdateTime
protected

Time of the last update.

boost::mutex gazebo::sensors::Sensor::mutexLastUpdateTime
protected

Mutex to protect resetting lastUpdateTime.

transport::NodePtr gazebo::sensors::Sensor::node
protected

Node for communication.

uint32_t gazebo::sensors::Sensor::parentId
protected

The sensor's parent ID.

std::string gazebo::sensors::Sensor::parentName
protected

Name of the parent.

std::vector<SensorPluginPtr> gazebo::sensors::Sensor::plugins
protected

All the plugins for the sensor.

math::Pose gazebo::sensors::Sensor::pose
protected

Pose of the sensor.

transport::SubscriberPtr gazebo::sensors::Sensor::poseSub
protected

Subscribe to pose updates.

gazebo::rendering::ScenePtr gazebo::sensors::Sensor::scene
protected

Pointer to the Scene.

sdf::ElementPtr gazebo::sensors::Sensor::sdf
protected

Pointer the the SDF element for the sensor.

common::Time gazebo::sensors::Sensor::updatePeriod
protected

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

gazebo::physics::WorldPtr gazebo::sensors::Sensor::world
protected

Pointer to the world.


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