#include <DepthCameraPlugin.hh>
|
| DepthCameraPlugin () |
| Constructor. More...
|
|
virtual | ~DepthCameraPlugin () |
| Destructor. More...
|
|
void | Load (sensors::SensorPtr _sensor, sdf::ElementPtr _sdf) |
| Load function. More...
|
|
virtual void | OnNewDepthFrame (const float *_image, unsigned int _width, unsigned int _height, unsigned int _depth, const std::string &_format) |
|
virtual void | OnNewImageFrame (const unsigned char *_image, unsigned int _width, unsigned int _height, unsigned int _depth, const std::string &_format) |
|
virtual void | OnNewRGBPointCloud (const float *_pcd, unsigned int _width, unsigned int _height, unsigned int _depth, const std::string &_format) |
| Update the controller. More...
|
|
| SensorPlugin () |
| Constructor. More...
|
|
virtual | ~SensorPlugin () |
| Destructor. More...
|
|
virtual void | Init () |
| Override this method for custom plugin initialization behavior. More...
|
|
virtual void | Reset () |
| Override this method for custom plugin reset behavior. More...
|
|
| PluginT () |
| Constructor. More...
|
|
virtual | ~PluginT () |
| Destructor. More...
|
|
std::string | GetFilename () const |
| Get the name of the handler. More...
|
|
std::string | GetHandle () const |
| Get the short name of the handler. More...
|
|
PluginType | GetType () const |
| Returns the type of the plugin. More...
|
|
|
typedef boost::shared_ptr
< SensorPlugin > | TPtr |
| plugin pointer type definition More...
|
|
static TPtr | Create (const std::string &_filename, const std::string &_name) |
| a class method that creates a plugin from a file name. More...
|
|
gazebo::DepthCameraPlugin::DepthCameraPlugin |
( |
| ) |
|
virtual gazebo::DepthCameraPlugin::~DepthCameraPlugin |
( |
| ) |
|
|
virtual |
Load function.
Called when a Plugin is first created, and after the World has been loaded. This function should not be blocking.
- Parameters
-
[in] | _sensor | Pointer the Sensor. |
[in] | _sdf | Pointer the the SDF element of the plugin. |
Implements gazebo::SensorPlugin.
virtual void gazebo::DepthCameraPlugin::OnNewDepthFrame |
( |
const float * |
_image, |
|
|
unsigned int |
_width, |
|
|
unsigned int |
_height, |
|
|
unsigned int |
_depth, |
|
|
const std::string & |
_format |
|
) |
| |
|
virtual |
virtual void gazebo::DepthCameraPlugin::OnNewImageFrame |
( |
const unsigned char * |
_image, |
|
|
unsigned int |
_width, |
|
|
unsigned int |
_height, |
|
|
unsigned int |
_depth, |
|
|
const std::string & |
_format |
|
) |
| |
|
virtual |
virtual void gazebo::DepthCameraPlugin::OnNewRGBPointCloud |
( |
const float * |
_pcd, |
|
|
unsigned int |
_width, |
|
|
unsigned int |
_height, |
|
|
unsigned int |
_depth, |
|
|
const std::string & |
_format |
|
) |
| |
|
virtual |
unsigned int gazebo::DepthCameraPlugin::depth |
|
protected |
std::string gazebo::DepthCameraPlugin::format |
|
protected |
unsigned int gazebo::DepthCameraPlugin::height |
|
protected |
unsigned int gazebo::DepthCameraPlugin::width |
|
protected |
The documentation for this class was generated from the following file: