gazebo_ros_prosilica.h
Go to the documentation of this file.
1 /*
2  * Copyright 2012 Open Source Robotics Foundation
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9  *
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  *
16 */
17 
18 #ifndef GAZEBO_ROS_PROSILICA_CAMERA_HH
19 #define GAZEBO_ROS_PROSILICA_CAMERA_HH
20 
21 #include <boost/thread/mutex.hpp>
22 
23 // library for processing camera data for gazebo / ros conversions
25 #include <gazebo/plugins/CameraPlugin.hh>
26 
27 // ros
28 #include <ros/callback_queue.h>
29 
30 // image components
31 #include <cv_bridge/cv_bridge.h>
32 // used by polled_camera
33 #include <sensor_msgs/RegionOfInterest.h>
34 
35 // prosilica components
36 // Stuff in image_common
38 #include <polled_camera/publication_server.h> // do: sudo apt-get install ros-hydro-polled-camera
39 #include <polled_camera/GetPolledImage.h>
40 
41 namespace gazebo
42 {
43 
44 class GazeboRosProsilica : public CameraPlugin, GazeboRosCameraUtils
45 {
48  public: GazeboRosProsilica();
49 
51  public: virtual ~GazeboRosProsilica();
52 
55  public: void Load(sensors::SensorPtr _parent, sdf::ElementPtr _sdf);
56 
58  private: static void mouse_cb(int event, int x, int y, int flags, void* param) { };
59 
61  private: polled_camera::PublicationServer poll_srv_; // Handles requests in polled mode
62 
63  private: std::string mode_;
64 
65  private: std::string mode_param_name;
66 /*
68  private: bool camInfoService(prosilica_camera::CameraInfo::Request &req,
69  prosilica_camera::CameraInfo::Response &res);
70  private: bool triggeredGrab(prosilica_camera::PolledImage::Request &req,
71  prosilica_camera::PolledImage::Response &res);
72 */
73 
74  private: void pollCallback(polled_camera::GetPolledImage::Request& req,
75  polled_camera::GetPolledImage::Response& rsp,
76  sensor_msgs::Image& image, sensor_msgs::CameraInfo& info);
77 
80  private: sensor_msgs::Image *roiImageMsg;
81  private: sensor_msgs::CameraInfo *roiCameraInfoMsg;
82 
84  private: std::string pollServiceName;
85 
86  private: void Advertise();
87  private: event::ConnectionPtr load_connection_;
88 
89  // subscribe to world stats
90  //private: transport::NodePtr node;
91  //private: transport::SubscriberPtr statsSub;
92  //private: common::Time simTime;
93  //public: void OnStats( const boost::shared_ptr<msgs::WorldStatistics const> &_msg);
94 
96  protected: virtual void OnNewImageFrame(const unsigned char *_image,
97  unsigned int _width, unsigned int _height,
98  unsigned int _depth, const std::string &_format);
99 
100 };
101 
102 }
103 #endif
104 
static void mouse_cb(int event, int x, int y, int flags, void *param)
does nothing for now
polled_camera::PublicationServer poll_srv_
image_transport
sensor_msgs::CameraInfo * roiCameraInfoMsg
event::ConnectionPtr load_connection_
sensor_msgs::Image * roiImageMsg
ros message
virtual ~GazeboRosProsilica()
Destructor.
void pollCallback(polled_camera::GetPolledImage::Request &req, polled_camera::GetPolledImage::Response &rsp, sensor_msgs::Image &image, sensor_msgs::CameraInfo &info)
virtual void OnNewImageFrame(const unsigned char *_image, unsigned int _width, unsigned int _height, unsigned int _depth, const std::string &_format)
Update the controller.
void Load(sensors::SensorPtr _parent, sdf::ElementPtr _sdf)
Load the controller.
std::string pollServiceName
ROS image topic name.


gazebo_plugins
Author(s): John Hsu
autogenerated on Tue Mar 26 2019 02:31:27