gazebo_ros_thermal_camera.cpp
Go to the documentation of this file.
00001 //=================================================================================================
00002 // Copyright (c) 2012, Stefan Kohlbrecher, TU Darmstadt
00003 // All rights reserved.
00004 
00005 // Redistribution and use in source and binary forms, with or without
00006 // modification, are permitted provided that the following conditions are met:
00007 //     * Redistributions of source code must retain the above copyright
00008 //       notice, this list of conditions and the following disclaimer.
00009 //     * Redistributions in binary form must reproduce the above copyright
00010 //       notice, this list of conditions and the following disclaimer in the
00011 //       documentation and/or other materials provided with the distribution.
00012 //     * Neither the name of the Simulation, Systems Optimization and Robotics
00013 //       group, TU Darmstadt nor the names of its contributors may be used to
00014 //       endorse or promote products derived from this software without
00015 //       specific prior written permission.
00016 
00017 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
00018 // ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
00019 // WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
00020 // DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER BE LIABLE FOR ANY
00021 // DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
00022 // (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00023 // LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
00024 // ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
00025 // (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
00026 // SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00027 //=================================================================================================
00032 /*
00033  *  Gazebo - Outdoor Multi-Robot Simulator
00034  *  Copyright (C) 2003
00035  *     Nate Koenig & Andrew Howard
00036  *
00037  *  This program is free software; you can redistribute it and/or modify
00038  *  it under the terms of the GNU General Public License as published by
00039  *  the Free Software Foundation; either version 2 of the License, or
00040  *  (at your option) any later version.
00041  *
00042  *  This program is distributed in the hope that it will be useful,
00043  *  but WITHOUT ANY WARRANTY; without even the implied warranty of
00044  *  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
00045  *  GNU General Public License for more details.
00046  *
00047  *  You should have received a copy of the GNU General Public License
00048  *  along with this program; if not, write to the Free Software
00049  *  Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA  02111-1307  USA
00050  *
00051  */
00052 
00053 #include <hector_gazebo_thermal_camera/gazebo_ros_thermal_camera.h>
00054 
00055 #include <gazebo/sensors/Sensor.hh>
00056 #include <gazebo/sdf/interface/SDF.hh>
00057 #include <gazebo/sensors/SensorTypes.hh>
00058 
00059 #include <sensor_msgs/image_encodings.h>
00060 
00061 namespace gazebo
00062 {
00063 
00065 // Constructor
00066 template <class Base>
00067 GazeboRosThermalCamera_<Base>::GazeboRosThermalCamera_()
00068 {
00069 }
00070 
00072 // Destructor
00073 template <class Base>
00074 GazeboRosThermalCamera_<Base>::~GazeboRosThermalCamera_()
00075 {
00076 }
00077 
00078 template <class Base>
00079 void GazeboRosThermalCamera_<Base>::Load(sensors::SensorPtr _parent, sdf::ElementPtr _sdf)
00080 {
00081   Base::Load(_parent, _sdf);
00082   // copying from CameraPlugin into GazeboRosCameraUtils
00083   this->parentSensor_ = this->parentSensor;
00084   this->width_ = this->width;
00085   this->height_ = this->height;
00086   this->depth_ = this->depth;
00087   this->format_ = this->format;
00088   LoadImpl(_parent, _sdf);
00089   GazeboRosCameraUtils::Load(_parent, _sdf);
00090 
00091   this->type_ = sensor_msgs::image_encodings::MONO8;
00092   this->skip_ = 1;
00093 }
00094 
00096 // Update the controller
00097 template <class Base>
00098 void GazeboRosThermalCamera_<Base>::OnNewFrame(const unsigned char *_image,
00099     unsigned int _width, unsigned int _height, unsigned int _depth,
00100     const std::string &_format)
00101 {
00102   this->sensor_update_time_ = this->parentSensor_->GetLastUpdateTime();
00103 
00104   if (!this->parentSensor->IsActive())
00105   {
00106     if (this->image_connect_count_ > 0)
00107       // do this first so there's chance for sensor to run 1 frame after activate
00108       this->parentSensor->SetActive(true);
00109   }
00110   else
00111   {
00112     if (this->image_connect_count_ > 0)
00113     {
00114       common::Time cur_time = this->world_->GetSimTime();
00115       if (cur_time - this->last_update_time_ >= this->update_period_)
00116       {
00117         this->PutCameraData(_image);
00118         this->last_update_time_ = cur_time;
00119       }
00120     }
00121   }
00122 }
00123 
00124 template <class Base>
00125 void GazeboRosThermalCamera_<Base>::OnNewImageFrame(const unsigned char *_image,
00126     unsigned int _width, unsigned int _height, unsigned int _depth,
00127     const std::string &_format)
00128 {
00129   OnNewFrame(_image, _width, _height, _depth, _format);
00130 }
00131 
00133 // Put camera_ data to the interface
00134 template <class Base>
00135 void GazeboRosThermalCamera_<Base>::PutCameraData(const unsigned char *_src, common::Time &last_update_time)
00136 {
00137   this->sensor_update_time_ = last_update_time;
00138   this->PutCameraData(_src);
00139 }
00140 
00141 template <class Base>
00142 void GazeboRosThermalCamera_<Base>::PutCameraData(const unsigned char *_src)
00143 {
00144   this->lock_.lock();
00145 
00146   // copy data into image
00147   this->image_msg_.header.frame_id = this->frame_name_;
00148   this->image_msg_.header.stamp.sec = this->sensor_update_time_.sec;
00149   this->image_msg_.header.stamp.nsec = this->sensor_update_time_.nsec;
00150 
00152   if (this->image_connect_count_ > 0)
00153   {
00154     this->image_msg_.encoding = this->type_;
00155     this->image_msg_.width = this->width_;
00156     this->image_msg_.height = this->height_;
00157 
00158     size_t size = this->width_ * this->height_;
00159 
00160     std::vector<uint8_t>& data (this->image_msg_.data);
00161     data.resize(size);
00162 
00163     size_t img_index = 0;
00164 
00165     for (size_t i = 0; i < size; ++i){
00166       if (_src[img_index] >254 && _src[img_index+1] < 1 && _src[img_index+2 < 1]){
00167         //RGB [255,0,0] translates to white (white hot)
00168         data[i]= 255;
00169       }else{
00170         //Everything else is written to the MONO8 output image much darker
00171         data[i]= (_src[img_index] + _src[img_index+1] + _src[img_index+2]) /8 ;
00172       }
00173       img_index += 3;
00174     }
00175 
00176     // publish to ros
00177     this->image_pub_.publish(this->image_msg_);
00178   }
00179 
00180   this->lock_.unlock();
00181 }
00182 
00183 }
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Properties Friends


hector_gazebo_thermal_camera
Author(s): Stefan Kohlbrecher
autogenerated on Mon Jul 15 2013 16:55:58