#include <gazebo_ros_multicamera.h>
Public Member Functions | |
GazeboRosMultiCamera () | |
Constructor. | |
void | Load (sensors::SensorPtr _parent, sdf::ElementPtr _sdf) |
Load the plugin. | |
~GazeboRosMultiCamera () | |
Destructor. | |
Public Attributes | |
std::vector < GazeboRosCameraUtils * > | utils |
Protected Member Functions | |
void | OnNewFrame (const unsigned char *_image, GazeboRosCameraUtils *util) |
virtual void | OnNewFrameLeft (const unsigned char *_image, unsigned int _width, unsigned int _height, unsigned int _depth, const std::string &_format) |
Update the controller FIXME: switch to function vectors. | |
virtual void | OnNewFrameRight (const unsigned char *_image, unsigned int _width, unsigned int _height, unsigned int _depth, const std::string &_format) |
Private Attributes | |
boost::shared_ptr< int > | image_connect_count_ |
boost::shared_ptr< boost::mutex > | image_connect_count_lock_ |
boost::shared_ptr< bool > | was_active_ |
Definition at line 30 of file gazebo_ros_multicamera.h.
Constructor.
parent | The parent entity, must be a Model or a Sensor |
Definition at line 38 of file gazebo_ros_multicamera.cpp.
Destructor.
Definition at line 44 of file gazebo_ros_multicamera.cpp.
void gazebo::GazeboRosMultiCamera::Load | ( | sensors::SensorPtr | _parent, |
sdf::ElementPtr | _sdf | ||
) | [virtual] |
Load the plugin.
take | in SDF root element |
Reimplemented from gazebo::MultiCameraPlugin.
Definition at line 48 of file gazebo_ros_multicamera.cpp.
void gazebo::GazeboRosMultiCamera::OnNewFrame | ( | const unsigned char * | _image, |
GazeboRosCameraUtils * | util | ||
) | [protected] |
Definition at line 106 of file gazebo_ros_multicamera.cpp.
void gazebo::GazeboRosMultiCamera::OnNewFrameLeft | ( | const unsigned char * | _image, |
unsigned int | _width, | ||
unsigned int | _height, | ||
unsigned int | _depth, | ||
const std::string & | _format | ||
) | [protected, virtual] |
Update the controller FIXME: switch to function vectors.
Reimplemented from gazebo::MultiCameraPlugin.
Definition at line 127 of file gazebo_ros_multicamera.cpp.
void gazebo::GazeboRosMultiCamera::OnNewFrameRight | ( | const unsigned char * | _image, |
unsigned int | _width, | ||
unsigned int | _height, | ||
unsigned int | _depth, | ||
const std::string & | _format | ||
) | [protected, virtual] |
Reimplemented from gazebo::MultiCameraPlugin.
Definition at line 136 of file gazebo_ros_multicamera.cpp.
boost::shared_ptr<int> gazebo::GazeboRosMultiCamera::image_connect_count_ [private] |
Bookkeeping flags that will be passed into the underlying GazeboRosCameraUtils objects to let them share state about the parent sensor.
Definition at line 59 of file gazebo_ros_multicamera.h.
boost::shared_ptr<boost::mutex> gazebo::GazeboRosMultiCamera::image_connect_count_lock_ [private] |
Definition at line 60 of file gazebo_ros_multicamera.h.
std::vector<GazeboRosCameraUtils*> gazebo::GazeboRosMultiCamera::utils |
Definition at line 43 of file gazebo_ros_multicamera.h.
boost::shared_ptr<bool> gazebo::GazeboRosMultiCamera::was_active_ [private] |
Definition at line 61 of file gazebo_ros_multicamera.h.