Go to the documentation of this file.
25 #include <gazebo/sensors/Sensor.hh>
26 #include <gazebo/sensors/MultiCameraSensor.hh>
27 #include <gazebo/sensors/SensorTypes.hh>
31 #ifdef ENABLE_PROFILER
32 #include <ignition/common/Profiler.hh>
38 GZ_REGISTER_SENSOR_PLUGIN(GazeboRosMultiCamera)
60 ROS_FATAL_STREAM_NAMED(
"multicamera",
"A ROS node for Gazebo has not been initialized, unable to load plugin. "
61 <<
"Load the Gazebo system plugin 'libgazebo_ros_api_plugin.so' in the gazebo_ros package)");
71 for (
unsigned i = 0; i < this->
camera.size(); ++i)
84 if (this->
camera[i]->Name().find(
"left") != std::string::npos)
87 util->
Load(_parent, _sdf,
"/left", 0.0);
89 else if (this->
camera[i]->Name().find(
"right") != std::string::npos)
91 double hackBaseline = 0.0;
92 if (_sdf->HasElement(
"hackBaseline"))
93 hackBaseline = _sdf->Get<
double>(
"hackBaseline");
94 util->
Load(_parent, _sdf,
"/right", hackBaseline);
96 this->
utils.push_back(util);
105 #ifdef ENABLE_PROFILER
106 IGN_PROFILE(
"GazeboRosMultiCamera::OnNewFrame");
108 # if GAZEBO_MAJOR_VERSION >= 7
109 common::Time sensor_update_time = util->
parentSensor_->LastMeasurementTime();
111 common::Time sensor_update_time = util->
parentSensor_->GetLastMeasurementTime();
118 #ifdef ENABLE_PROFILER
119 IGN_PROFILE_BEGIN(
"PutCameraData");
122 #ifdef ENABLE_PROFILER
124 IGN_PROFILE_BEGIN(
"PublishCameraInfo");
127 #ifdef ENABLE_PROFILER
137 unsigned int _width,
unsigned int _height,
unsigned int _depth,
138 const std::string &_format)
146 unsigned int _width,
unsigned int _height,
unsigned int _depth,
147 const std::string &_format)
virtual void Load(sensors::SensorPtr _sensor, sdf::ElementPtr _sdf)
void OnNewFrame(const unsigned char *_image, GazeboRosCameraUtils *util)
sensors::SensorPtr parentSensor_
boost::shared_ptr< boost::mutex > image_connect_count_lock_
boost::shared_ptr< int > image_connect_count_
void PutCameraData(const unsigned char *_src)
Put camera data to the ROS topic.
std::vector< unsigned int > width
std::vector< unsigned int > depth
common::Time last_update_time_
std::vector< GazeboRosCameraUtils * > utils
sensors::MultiCameraSensorPtr parentSensor
void PublishCameraInfo(ros::Publisher camera_info_publisher)
Publish CameraInfo to the ROS topic.
boost::shared_ptr< boost::mutex > image_connect_count_lock_
A mutex to lock access to image_connect_count_.
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< bool > was_active_
~GazeboRosMultiCamera()
Destructor.
#define ROS_FATAL_STREAM_NAMED(name, args)
std::vector< rendering::CameraPtr > camera
ROSCPP_DECL bool isInitialized()
boost::shared_ptr< int > image_connect_count_
Keep track of number of image connections.
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, const std::string &_camera_name_suffix="")
Load the plugin.
boost::shared_ptr< bool > was_active_
Keep track when we activate this camera through ros subscription, was it already active?...
void Load(sensors::SensorPtr _parent, sdf::ElementPtr _sdf)
Load the plugin.
std::vector< std::string > format
std::vector< unsigned int > height
rendering::CameraPtr camera_
gazebo_plugins
Author(s): John Hsu
autogenerated on Thu Sep 5 2024 02:49:55