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

#include <sensors/sensors.hh>

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

Public Member Functions

 DepthCameraSensor ()
 Constructor.
 
virtual ~DepthCameraSensor ()
 Destructor.
 
rendering::DepthCameraPtr GetDepthCamera () const
 Returns a pointer to the rendering::DepthCamera.
 
bool SaveFrame (const std::string &_filename)
 Saves an image frame of depth camera sensor to file.
 
virtual void SetActive (bool _value)
 Set whether the sensor is active or not.
 
virtual void SetParent (const std::string &_name)
 Set the parent of the sensor.
 
- Public Member Functions inherited from gazebo::sensors::Sensor
 Sensor ()
 Constructor.
 
virtual ~Sensor ()
 Destructor.
 
void FillMsg (msgs::Sensor &_msg)
 fills a msgs::Sensor message.
 
common::Time GetLastMeasurementTime ()
 Return last measurement time.
 
common::Time GetLastUpdateTime ()
 Return last update time.
 
std::string GetName () const
 Get name.
 
std::string GetParentName () const
 Returns the name of the sensor parent.
 
virtual math::Pose GetPose () const
 Get the current pose.
 
std::string GetScopedName () const
 Get fully scoped name of the sensor.
 
virtual std::string GetTopic () const
 Returns the topic name as set in SDF.
 
std::string GetType () const
 Get sensor type.
 
bool GetVisualize () const
 Return true if user requests the sensor to be visualized via tag: <visualize>true</visualize> in SDF.
 
std::string GetWorldName () const
 Returns the name of the world the sensor is in.
 
bool IsActive ()
 Returns true if sensor generation is active.
 
virtual void Load (const std::string &_worldName, sdf::ElementPtr _sdf)
 Load the sensor with SDF parameters.
 
void SetUpdateRate (double _hz)
 Set the update rate of the sensor.
 
void Update (bool _force)
 Update the sensor.
 

Protected Member Functions

virtual void Fini ()
 Finalize the camera.
 
virtual void Init ()
 Initialize the camera.
 
virtual void Load (const std::string &_worldName, sdf::ElementPtr &_sdf)
 Load the sensor with SDF parameters.
 
virtual void Load (const std::string &_worldName)
 Load the sensor with default parameters.
 
virtual void UpdateImpl (bool _force)
 Update the sensor information.
 

Additional Inherited Members

- Protected Attributes inherited from gazebo::sensors::Sensor
bool active
 True if sensor generation is active.
 
std::vector< event::ConnectionPtrconnections
 All event connections.
 
common::Time lastMeasurementTime
 Stores last time that a sensor measurement was generated; this value must be updated within each sensor's UpdateImpl.
 
common::Time lastUpdateTime
 Time of the last update.
 
transport::NodePtr node
 Node for communication.
 
std::string parentName
 Name of the parent.
 
std::vector< SensorPluginPtrplugins
 All the plugins for the sensor.
 
math::Pose pose
 Pose of the sensor.
 
transport::SubscriberPtr poseSub
 Subscribe to pose updates.
 
sdf::ElementPtr sdf
 Pointer the the SDF element for the sensor.
 
common::Time updatePeriod
 Desired time between updates, set indirectly by Sensor::SetUpdateRate.
 
gazebo::physics::WorldPtr world
 Pointer to the world.
 

Constructor & Destructor Documentation

gazebo::sensors::DepthCameraSensor::DepthCameraSensor ( )

Constructor.

virtual gazebo::sensors::DepthCameraSensor::~DepthCameraSensor ( )
virtual

Destructor.

Member Function Documentation

virtual void gazebo::sensors::DepthCameraSensor::Fini ( )
protectedvirtual

Finalize the camera.

Reimplemented from gazebo::sensors::Sensor.

rendering::DepthCameraPtr gazebo::sensors::DepthCameraSensor::GetDepthCamera ( ) const
inline

Returns a pointer to the rendering::DepthCamera.

Returns
Depth Camera pointer
virtual void gazebo::sensors::DepthCameraSensor::Init ( )
protectedvirtual

Initialize the camera.

Reimplemented from gazebo::sensors::Sensor.

virtual void gazebo::sensors::DepthCameraSensor::Load ( const std::string &  _worldName,
sdf::ElementPtr _sdf 
)
protectedvirtual

Load the sensor with SDF parameters.

Parameters
[in]_sdfSDF Sensor parameters
[in]_worldNameName of world to load from
virtual void gazebo::sensors::DepthCameraSensor::Load ( const std::string &  _worldName)
protectedvirtual

Load the sensor with default parameters.

Parameters
[in]_worldNameName of world to load from

Reimplemented from gazebo::sensors::Sensor.

bool gazebo::sensors::DepthCameraSensor::SaveFrame ( const std::string &  _filename)

Saves an image frame of depth camera sensor to file.

Parameters
[in]Nameof file to save as
Returns
True if saved, false if not
virtual void gazebo::sensors::DepthCameraSensor::SetActive ( bool  _value)
virtual

Set whether the sensor is active or not.

Parameters
[in]_valueTrue if active, false if not

Reimplemented from gazebo::sensors::Sensor.

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

Set the parent of the sensor.

Parameters
[in]_nameName of parent

Reimplemented from gazebo::sensors::Sensor.

virtual void gazebo::sensors::DepthCameraSensor::UpdateImpl ( bool  _force)
protectedvirtual

Update the sensor information.

Parameters
[in]_forceTrue if update is forced, false if not

Reimplemented from gazebo::sensors::Sensor.


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