#include <gazebo_ros_camera.h>
Public Member Functions | |
GazeboRosCamera () | |
Constructor. | |
void | Load (sensors::SensorPtr _parent, sdf::ElementPtr _sdf) |
Load the plugin. | |
~GazeboRosCamera () | |
Destructor. | |
Protected Member Functions | |
virtual void | OnNewFrame (const unsigned char *_image, unsigned int _width, unsigned int _height, unsigned int _depth, const std::string &_format) |
Update the controller. |
Definition at line 34 of file gazebo_ros_camera.h.
Constructor.
parent | The parent entity, must be a Model or a Sensor |
Definition at line 40 of file gazebo_ros_camera.cpp.
Destructor.
Definition at line 46 of file gazebo_ros_camera.cpp.
void gazebo::GazeboRosCamera::Load | ( | sensors::SensorPtr | _parent, |
sdf::ElementPtr | _sdf | ||
) |
Load the plugin.
take | in SDF root element |
Definition at line 51 of file gazebo_ros_camera.cpp.
void gazebo::GazeboRosCamera::OnNewFrame | ( | const unsigned char * | _image, |
unsigned int | _width, | ||
unsigned int | _height, | ||
unsigned int | _depth, | ||
const std::string & | _format | ||
) | [protected, virtual] |
Update the controller.
Definition at line 75 of file gazebo_ros_camera.cpp.