18 #ifndef GAZEBO_ROS_TRIGGERED_MULTICAMERA_HH 19 #define GAZEBO_ROS_TRIGGERED_MULTICAMERA_HH 41 public:
void Load(sensors::SensorPtr _parent, sdf::ElementPtr _sdf);
47 protected:
virtual void OnNewFrameLeft(
const unsigned char *_image,
48 unsigned int _width,
unsigned int _height,
49 unsigned int _depth,
const std::string &_format);
51 unsigned int _width,
unsigned int _height,
52 unsigned int _depth,
const std::string &_format);
void SetCameraEnabled(const bool _enabled)
std::vector< GazeboRosTriggeredCamera * > triggered_cameras
void Load(sensors::SensorPtr _parent, sdf::ElementPtr _sdf)
Load the plugin.
boost::shared_ptr< bool > was_active_
boost::shared_ptr< boost::mutex > image_connect_count_lock_
boost::shared_ptr< int > image_connect_count_
virtual void OnNewFrameRight(const unsigned char *_image, unsigned int _width, unsigned int _height, unsigned int _depth, const std::string &_format)
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.
GazeboRosTriggeredMultiCamera()
Constructor.
~GazeboRosTriggeredMultiCamera()
Destructor.
event::ConnectionPtr preRenderConnection_