55 #include <gazebo/sensors/Sensor.hh> 56 #include <gazebo/sensors/SensorTypes.hh> 60 #include <gazebo/gazebo_config.h> 82 Base::Load(_parent, _sdf);
84 this->parentSensor_ = this->parentSensor;
85 this->width_ = this->width;
86 this->height_ = this->height;
87 this->depth_ = this->depth;
88 this->format_ = this->format;
91 *this->image_connect_count_ = 0;
94 *this->was_active_ =
false;
96 LoadImpl(_parent, _sdf);
102 template <
class Base>
104 unsigned int _width,
unsigned int _height,
unsigned int _depth,
105 const std::string &_format)
107 if (!this->initialized_ || this->height_ <=0 || this->width_ <=0)
110 #if (GAZEBO_MAJOR_VERSION > 6) 111 this->sensor_update_time_ = this->parentSensor_->LastUpdateTime();
113 this->sensor_update_time_ = this->parentSensor_->GetLastUpdateTime();
116 if (!this->parentSensor->IsActive())
118 if ((*this->image_connect_count_) > 0)
120 this->parentSensor->SetActive(
true);
124 if ((*this->image_connect_count_) > 0)
126 #if (GAZEBO_MAJOR_VERSION >= 8) 127 common::Time cur_time = this->world_->SimTime();
129 common::Time cur_time = this->world_->GetSimTime();
131 if (cur_time - this->last_update_time_ >= this->update_period_)
133 this->PutCameraData(_image);
134 this->PublishCameraInfo();
135 this->last_update_time_ = cur_time;
141 template <
class Base>
143 unsigned int _width,
unsigned int _height,
unsigned int _depth,
144 const std::string &_format)
146 OnNewFrame(_image, _width, _height, _depth, _format);
151 template <
class Base>
154 this->sensor_update_time_ = last_update_time;
155 this->PutCameraData(_src);
158 template <
class Base>
161 if (!this->initialized_ || this->height_ <=0 || this->width_ <=0)
167 this->image_msg_.header.frame_id = this->frame_name_;
168 this->image_msg_.header.stamp.sec = this->sensor_update_time_.sec;
169 this->image_msg_.header.stamp.nsec = this->sensor_update_time_.nsec;
172 if ((*this->image_connect_count_) > 0)
174 this->image_msg_.width = this->width_;
175 this->image_msg_.height = this->height_;
177 this->image_msg_.step = this->image_msg_.width;
179 size_t size = this->width_ * this->height_;
181 std::vector<uint8_t>&
data (this->image_msg_.data);
184 size_t img_index = 0;
186 for (
size_t i = 0; i < size; ++i){
187 if ((_src[img_index] >254) && (_src[img_index+1] < 1) && (_src[img_index+2] < 1)){
192 data[i]= (_src[img_index] + _src[img_index+1] + _src[img_index+2]) /8 ;
198 this->image_pub_.publish(this->image_msg_);
201 this->lock_.unlock();
GazeboRosThermalCamera_()
Constructor.
void Load(sensors::SensorPtr _parent, sdf::ElementPtr _sdf, const std::string &_camera_name_suffix="")
void PutCameraData(const unsigned char *_src)
Put camera data to the ROS topic.
void Load(sensors::SensorPtr _parent, sdf::ElementPtr _sdf)
Load the plugin.
virtual void OnNewImageFrame(const unsigned char *_image, unsigned int _width, unsigned int _height, unsigned int _depth, const std::string &_format)
Update the controller.
~GazeboRosThermalCamera_()
Destructor.
virtual void OnNewFrame(const unsigned char *_image, unsigned int _width, unsigned int _height, unsigned int _depth, const std::string &_format)
Update the controller.