gazebo_ros_prosilica.h
Go to the documentation of this file.
00001 /*
00002  *  Gazebo - Outdoor Multi-Robot Simulator
00003  *  Copyright (C) 2003  
00004  *     Nate Koenig & Andrew Howard
00005  *
00006  *  This program is free software; you can redistribute it and/or modify
00007  *  it under the terms of the GNU General Public License as published by
00008  *  the Free Software Foundation; either version 2 of the License, or
00009  *  (at your option) any later version.
00010  *
00011  *  This program is distributed in the hope that it will be useful,
00012  *  but WITHOUT ANY WARRANTY; without even the implied warranty of
00013  *  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
00014  *  GNU General Public License for more details.
00015  *
00016  *  You should have received a copy of the GNU General Public License
00017  *  along with this program; if not, write to the Free Software
00018  *  Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA  02111-1307  USA
00019  *
00020  */
00021 /*
00022  * Desc: A dynamic controller plugin that publishes ROS image topic for generic camera sensor.
00023  * Author: John Hsu
00024  * Date: 24 Sept 2008
00025  * SVN: $Id$
00026  */
00027 #ifndef GAZEBO_ROS_PROSILICA_CAMERA_HH
00028 #define GAZEBO_ROS_PROSILICA_CAMERA_HH
00029 
00030 // library for processing camera data for gazebo / ros conversions
00031 #include <gazebo_plugins/gazebo_ros_camera_utils.h>
00032 #include "plugins/DepthCameraPlugin.hh"
00033 
00034 #include <ros/callback_queue.h>
00035 #include "boost/thread/mutex.hpp"
00036 
00037 // image components
00038 #include "cv_bridge/cv_bridge.h"
00039 // used by polled_camera
00040 #include "sensor_msgs/RegionOfInterest.h"
00041 
00042 // prosilica components
00043 // Stuff in image_common
00044 #include <image_transport/image_transport.h>
00045 #include <polled_camera/publication_server.h>
00046 #include <polled_camera/GetPolledImage.h>
00047 
00048 namespace gazebo
00049 {
00050 
00051 class GazeboRosProsilica : public DepthCameraPlugin, GazeboRosCameraUtils
00052 {
00055   public: GazeboRosProsilica();
00056 
00058   public: virtual ~GazeboRosProsilica();
00059 
00062   public: void Load(sensors::SensorPtr _parent, sdf::ElementPtr _sdf);
00063 
00065   private: static void mouse_cb(int event, int x, int y, int flags, void* param) { };
00066 
00068   private: polled_camera::PublicationServer poll_srv_;      // Handles requests in polled mode
00069 
00070   private: std::string mode_;
00071 
00072   private: std::string mode_param_name;
00073 /*
00075   private: bool camInfoService(prosilica_camera::CameraInfo::Request &req,
00076                                prosilica_camera::CameraInfo::Response &res);
00077   private: bool triggeredGrab(prosilica_camera::PolledImage::Request &req,
00078                               prosilica_camera::PolledImage::Response &res);
00079 */
00080 
00081   private: void pollCallback(polled_camera::GetPolledImage::Request& req,
00082                              polled_camera::GetPolledImage::Response& rsp,
00083                              sensor_msgs::Image& image, sensor_msgs::CameraInfo& info);
00084 
00087   private: sensor_msgs::Image *roiImageMsg;
00088   private: sensor_msgs::CameraInfo *roiCameraInfoMsg;
00089 
00091   private: std::string pollServiceName;
00092 
00093   // subscribe to world stats
00094   //private: transport::NodePtr node;
00095   //private: transport::SubscriberPtr statsSub;
00096   //private: common::Time simTime;
00097   //public: void OnStats( const boost::shared_ptr<msgs::WorldStatistics const> &_msg);
00098 
00100   protected: virtual void OnNewDepthFrame(const float *_image, 
00101                  unsigned int _width, unsigned int _height, 
00102                  unsigned int _depth, const std::string &_format) {};
00103 
00104 
00106   protected: virtual void OnNewImageFrame(const unsigned char *_image, 
00107                  unsigned int _width, unsigned int _height, 
00108                  unsigned int _depth, const std::string &_format);
00109 
00110 };
00111 
00112 }
00113 #endif
00114 


pr2_gazebo_plugins
Author(s): Sachin Chitta, Stu Glaser, John Hsu
autogenerated on Thu Apr 24 2014 15:47:43