Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025 #include "gazebo_plugins/gazebo_ros_camera.h"
00026
00027 #include <string>
00028
00029 #include <gazebo/sensors/Sensor.hh>
00030 #include <gazebo/sensors/CameraSensor.hh>
00031 #include <gazebo/sensors/SensorTypes.hh>
00032
00033 namespace gazebo
00034 {
00035
00036 GZ_REGISTER_SENSOR_PLUGIN(GazeboRosCamera)
00037
00038
00039
00040 GazeboRosCamera::GazeboRosCamera()
00041 {
00042 }
00043
00045
00046 GazeboRosCamera::~GazeboRosCamera()
00047 {
00048 ROS_DEBUG_STREAM_NAMED("camera","Unloaded");
00049 }
00050
00051 void GazeboRosCamera::Load(sensors::SensorPtr _parent, sdf::ElementPtr _sdf)
00052 {
00053
00054 if (!ros::isInitialized())
00055 {
00056 ROS_FATAL_STREAM("A ROS node for Gazebo has not been initialized, unable to load plugin. "
00057 << "Load the Gazebo system plugin 'libgazebo_ros_api_plugin.so' in the gazebo_ros package)");
00058 return;
00059 }
00060
00061 CameraPlugin::Load(_parent, _sdf);
00062
00063 this->parentSensor_ = this->parentSensor;
00064 this->width_ = this->width;
00065 this->height_ = this->height;
00066 this->depth_ = this->depth;
00067 this->format_ = this->format;
00068 this->camera_ = this->camera;
00069
00070 GazeboRosCameraUtils::Load(_parent, _sdf);
00071 }
00072
00074
00075 void GazeboRosCamera::OnNewFrame(const unsigned char *_image,
00076 unsigned int _width, unsigned int _height, unsigned int _depth,
00077 const std::string &_format)
00078 {
00079 # if GAZEBO_MAJOR_VERSION >= 7
00080 common::Time sensor_update_time = this->parentSensor_->LastMeasurementTime();
00081 # else
00082 common::Time sensor_update_time = this->parentSensor_->GetLastMeasurementTime();
00083 # endif
00084
00085 if (!this->parentSensor->IsActive())
00086 {
00087 if ((*this->image_connect_count_) > 0)
00088
00089 this->parentSensor->SetActive(true);
00090 }
00091 else
00092 {
00093 if ((*this->image_connect_count_) > 0)
00094 {
00095
00096
00097
00098
00099
00100
00101
00102 if (sensor_update_time - this->last_update_time_ >= this->update_period_)
00103 {
00104 this->PutCameraData(_image, sensor_update_time);
00105 this->PublishCameraInfo(sensor_update_time);
00106 this->last_update_time_ = sensor_update_time;
00107 }
00108 }
00109 }
00110 }
00111 }