17 #include <gazebo/sensors/DepthCameraSensor.hh> 18 #include <gazebo/sensors/CameraSensor.hh> 31 MultiCameraPlugin::~MultiCameraPlugin()
42 gzerr <<
"Invalid sensor pointer.\n";
46 dynamic_pointer_cast<sensors::MultiCameraSensor>(_sensor);
50 gzerr <<
"MultiCameraPlugin requires a CameraSensor.\n";
51 if (dynamic_pointer_cast<sensors::DepthCameraSensor>(_sensor))
52 gzmsg <<
"It is a depth camera sensor\n";
53 if (dynamic_pointer_cast<sensors::CameraSensor>(_sensor))
54 gzmsg <<
"It is a camera sensor\n";
59 gzerr <<
"MultiCameraPlugin not attached to a camera sensor\n";
63 for (
unsigned int i = 0; i < this->
parentSensor->CameraCount(); ++i)
68 this->
width.push_back(this->
camera[i]->ImageWidth());
70 this->
depth.push_back(this->
camera[i]->ImageDepth());
73 std::string cameraName = this->
parentSensor->Camera(i)->Name();
77 if (cameraName.find(
"left") != std::string::npos)
81 this, _1, _2, _3, _4, _5)));
83 else if (cameraName.find(
"right") != std::string::npos)
87 this, _1, _2, _3, _4, _5)));
std::vector< rendering::CameraPtr > camera
virtual void OnNewFrameLeft(const unsigned char *_image, unsigned int _width, unsigned int _height, unsigned int _depth, const std::string &_format)
std::vector< unsigned int > width
sensors::MultiCameraSensorPtr parentSensor
virtual void Load(sensors::SensorPtr _sensor, sdf::ElementPtr _sdf)
std::vector< unsigned int > depth
std::vector< unsigned int > height
#define GAZEBO_SENSORS_USING_DYNAMIC_POINTER_CAST
std::vector< std::string > format
std::vector< event::ConnectionPtr > newFrameConnection
virtual void OnNewFrameRight(const unsigned char *_image, unsigned int _width, unsigned int _height, unsigned int _depth, const std::string &_format)