23 #include <gazebo/sensors/Sensor.hh>
24 #include <gazebo/sensors/CameraSensor.hh>
25 #include <gazebo/sensors/SensorTypes.hh>
27 #ifdef ENABLE_PROFILER
28 #include <ignition/common/Profiler.hh>
35 GZ_REGISTER_SENSOR_PLUGIN(GazeboRosTriggeredCamera)
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)");
60 CameraPlugin::Load(_parent, _sdf);
63 this->
width_ = this->width;
65 this->
depth_ = this->depth;
73 event::Events::ConnectPreRender(
79 const std::string &_camera_name_suffix,
80 double _hack_baseline)
86 event::Events::ConnectPreRender(
93 unsigned int _width,
unsigned int _height,
unsigned int _depth,
94 const std::string &_format)
96 #ifdef ENABLE_PROFILER
97 IGN_PROFILE(
"GazeboRosTriggeredCamera::OnNewFrame");
103 #ifdef ENABLE_PROFILER
104 IGN_PROFILE_BEGIN(
"PutCameraData");
107 #ifdef ENABLE_PROFILER
109 IGN_PROFILE_BEGIN(
"PublishCameraInfo");
112 #ifdef ENABLE_PROFILER
116 #ifdef ENABLE_PROFILER
117 IGN_PROFILE_BEGIN(
"SetCameraEnabled");
120 #ifdef ENABLE_PROFILER
123 std::lock_guard<std::mutex> lock(this->
mutex);
129 std::lock_guard<std::mutex> lock(this->
mutex);
142 std::lock_guard<std::mutex> lock(this->
mutex);
152 this->
parentSensor_->SetUpdateRate(_enabled ? 0.0 : DBL_MIN);