gazebo_ros_prosilica.h
Go to the documentation of this file.
00001 /*
00002  * Copyright 2012 Open Source Robotics Foundation
00003  *
00004  * Licensed under the Apache License, Version 2.0 (the "License");
00005  * you may not use this file except in compliance with the License.
00006  * You may obtain a copy of the License at
00007  *
00008  *     http://www.apache.org/licenses/LICENSE-2.0
00009  *
00010  * Unless required by applicable law or agreed to in writing, software
00011  * distributed under the License is distributed on an "AS IS" BASIS,
00012  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
00013  * See the License for the specific language governing permissions and
00014  * limitations under the License.
00015  *
00016 */
00017 
00018 #ifndef GAZEBO_ROS_PROSILICA_CAMERA_HH
00019 #define GAZEBO_ROS_PROSILICA_CAMERA_HH
00020 
00021 #include <boost/thread/mutex.hpp>
00022 
00023 // library for processing camera data for gazebo / ros conversions
00024 #include <gazebo_plugins/gazebo_ros_camera_utils.h>
00025 #include <gazebo/plugins/CameraPlugin.hh>
00026 
00027 // ros
00028 #include <ros/callback_queue.h>
00029 
00030 // image components
00031 #include <cv_bridge/cv_bridge.h>
00032 // used by polled_camera
00033 #include <sensor_msgs/RegionOfInterest.h>
00034 
00035 // prosilica components
00036 // Stuff in image_common
00037 #include <image_transport/image_transport.h>
00038 #include <polled_camera/publication_server.h>  // do: sudo apt-get install ros-hydro-polled-camera
00039 #include <polled_camera/GetPolledImage.h>
00040 
00041 namespace gazebo
00042 {
00043 
00044 class GazeboRosProsilica : public CameraPlugin, GazeboRosCameraUtils
00045 {
00048   public: GazeboRosProsilica();
00049 
00051   public: virtual ~GazeboRosProsilica();
00052 
00055   public: void Load(sensors::SensorPtr _parent, sdf::ElementPtr _sdf);
00056 
00058   private: static void mouse_cb(int event, int x, int y, int flags, void* param) { };
00059 
00061   private: polled_camera::PublicationServer poll_srv_;      // Handles requests in polled mode
00062 
00063   private: std::string mode_;
00064 
00065   private: std::string mode_param_name;
00066 /*
00068   private: bool camInfoService(prosilica_camera::CameraInfo::Request &req,
00069                                prosilica_camera::CameraInfo::Response &res);
00070   private: bool triggeredGrab(prosilica_camera::PolledImage::Request &req,
00071                               prosilica_camera::PolledImage::Response &res);
00072 */
00073 
00074   private: void pollCallback(polled_camera::GetPolledImage::Request& req,
00075                              polled_camera::GetPolledImage::Response& rsp,
00076                              sensor_msgs::Image& image, sensor_msgs::CameraInfo& info);
00077 
00080   private: sensor_msgs::Image *roiImageMsg;
00081   private: sensor_msgs::CameraInfo *roiCameraInfoMsg;
00082 
00084   private: std::string pollServiceName;
00085 
00086   private: void Advertise();
00087   private: event::ConnectionPtr load_connection_;
00088 
00089   // subscribe to world stats
00090   //private: transport::NodePtr node;
00091   //private: transport::SubscriberPtr statsSub;
00092   //private: common::Time simTime;
00093   //public: void OnStats( const boost::shared_ptr<msgs::WorldStatistics const> &_msg);
00094 
00096   protected: virtual void OnNewImageFrame(const unsigned char *_image, 
00097                  unsigned int _width, unsigned int _height, 
00098                  unsigned int _depth, const std::string &_format);
00099 
00100 };
00101 
00102 }
00103 #endif
00104 


gazebo_plugins
Author(s): John Hsu
autogenerated on Thu Jun 6 2019 18:41:09