29 #include <gazebo/sensors/Sensor.hh>
30 #include <gazebo/sensors/CameraSensor.hh>
31 #include <gazebo/sensors/SensorTypes.hh>
33 #ifdef ENABLE_PROFILER
34 #include <ignition/common/Profiler.hh>
40 GZ_REGISTER_SENSOR_PLUGIN(GazeboRosCamera)
61 <<
"Load the Gazebo system plugin 'libgazebo_ros_api_plugin.so' in the gazebo_ros package)");
65 CameraPlugin::Load(_parent, _sdf);
68 this->
width_ = this->width;
70 this->
depth_ = this->depth;
80 unsigned int _width,
unsigned int _height,
unsigned int _depth,
81 const std::string &_format)
83 #ifdef ENABLE_PROFILER
84 IGN_PROFILE(
"GazeboRosCamera::OnNewFrame");
87 # if GAZEBO_MAJOR_VERSION >= 7
88 common::Time sensor_update_time = this->
parentSensor_->LastMeasurementTime();
90 common::Time sensor_update_time = this->
parentSensor_->GetLastMeasurementTime();
93 if (!this->parentSensor->IsActive())
97 this->parentSensor->SetActive(
true);
105 ROS_WARN_NAMED(
"camera",
"Negative sensor update time difference detected.");
106 this->last_update_time_ = sensor_update_time;
116 if (sensor_update_time - this->last_update_time_ >= this->
update_period_)
118 #ifdef ENABLE_PROFILER
119 IGN_PROFILE_BEGIN(
"PutCameraData");
122 #ifdef ENABLE_PROFILER
124 IGN_PROFILE_BEGIN(
"PublishCameraInfo");
127 #ifdef ENABLE_PROFILER
130 this->last_update_time_ = sensor_update_time;