Go to the documentation of this file.
20 #include <gazebo/sensors/Sensor.hh>
21 #include <gazebo/sensors/MultiCameraSensor.hh>
22 #include <gazebo/sensors/SensorTypes.hh>
26 #ifdef ENABLE_PROFILER
27 #include <ignition/common/Profiler.hh>
33 GZ_REGISTER_SENSOR_PLUGIN(GazeboRosTriggeredMultiCamera)
55 ROS_FATAL_STREAM(
"A ROS node for Gazebo has not been initialized, unable to load plugin. "
56 <<
"Load the Gazebo system plugin 'libgazebo_ros_api_plugin.so' in the gazebo_ros package)");
66 for (
unsigned i = 0; i < this->
camera.size(); ++i)
79 if (this->
camera[i]->Name().find(
"left") != std::string::npos)
82 cam->
Load(_parent, _sdf,
"/left", 0.0);
84 else if (this->
camera[i]->Name().find(
"right") != std::string::npos)
86 double hackBaseline = 0.0;
87 if (_sdf->HasElement(
"hackBaseline"))
88 hackBaseline = _sdf->Get<
double>(
"hackBaseline");
89 cam->
Load(_parent, _sdf,
"/right", hackBaseline);
98 unsigned int _width,
unsigned int _height,
unsigned int _depth,
99 const std::string &_format)
101 #ifdef ENABLE_PROFILER
102 IGN_PROFILE(
"GazeboRosTriggeredMultiCamera::OnNewFrameLeft");
105 #ifdef ENABLE_PROFILER
106 IGN_PROFILE_BEGIN(
"OnNewFrame");
108 cam->
OnNewFrame(_image, _width, _height, _depth, _format);
109 #ifdef ENABLE_PROFILER
117 unsigned int _width,
unsigned int _height,
unsigned int _depth,
118 const std::string &_format)
120 #ifdef ENABLE_PROFILER
121 IGN_PROFILE(
"GazeboRosTriggeredMultiCamera::OnNewFrameRight");
124 #ifdef ENABLE_PROFILER
125 IGN_PROFILE_BEGIN(
"OnNewFrame");
127 cam->
OnNewFrame(_image, _width, _height, _depth, _format);
128 #ifdef ENABLE_PROFILER
virtual void Load(sensors::SensorPtr _sensor, sdf::ElementPtr _sdf)
virtual void OnNewFrame(const unsigned char *_image, unsigned int _width, unsigned int _height, unsigned int _depth, const std::string &_format)
Update the controller.
sensors::SensorPtr parentSensor_
boost::shared_ptr< bool > was_active_
#define ROS_FATAL_STREAM(args)
std::vector< unsigned int > width
std::vector< unsigned int > depth
virtual void OnNewFrameRight(const unsigned char *_image, unsigned int _width, unsigned int _height, unsigned int _depth, const std::string &_format)
void Load(sensors::SensorPtr _parent, sdf::ElementPtr _sdf)
Load the plugin.
sensors::MultiCameraSensorPtr parentSensor
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.
boost::shared_ptr< boost::mutex > image_connect_count_lock_
A mutex to lock access to image_connect_count_.
std::vector< rendering::CameraPtr > camera
ROSCPP_DECL bool isInitialized()
boost::shared_ptr< int > image_connect_count_
Keep track of number of image connections.
void Load(sensors::SensorPtr _parent, sdf::ElementPtr _sdf)
Load the plugin.
~GazeboRosTriggeredMultiCamera()
Destructor.
boost::shared_ptr< bool > was_active_
Keep track when we activate this camera through ros subscription, was it already active?...
std::vector< std::string > format
std::vector< GazeboRosTriggeredCamera * > triggered_cameras
std::vector< unsigned int > height
rendering::CameraPtr camera_
boost::shared_ptr< int > image_connect_count_
boost::shared_ptr< boost::mutex > image_connect_count_lock_
gazebo_plugins
Author(s): John Hsu
autogenerated on Thu Sep 5 2024 02:49:55