gazebo_ros_video.h
Go to the documentation of this file.
00001 /*
00002  * Copyright 2013 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 /*
00019  * Desc: Video plugin for displaying ROS image topics on Ogre textures 
00020  * Author: Piyush Khandelwal
00021  * Date: 26 July 2013
00022  */
00023 
00024 #ifndef GAZEBO_ROS_VIDEO_H
00025 #define GAZEBO_ROS_VIDEO_H
00026 
00027 #include <boost/thread/mutex.hpp>
00028 #include <cv_bridge/cv_bridge.h>
00029 #include <image_transport/image_transport.h>
00030 #include <opencv2/opencv.hpp>
00031 #include <ros/advertise_options.h>
00032 #include <ros/callback_queue.h>
00033 #include <ros/ros.h>
00034 #include <sensor_msgs/Image.h>
00035 
00036 #include <gazebo/common/Events.hh>
00037 #include <gazebo/common/Plugin.hh>
00038 #include <gazebo/common/Time.hh>
00039 #include <gazebo/rendering/rendering.hh>
00040 #include <gazebo/transport/TransportTypes.hh>
00041 
00042 namespace gazebo 
00043 {
00044 
00045   class VideoVisual : public rendering::Visual 
00046   {
00047     public: 
00048       VideoVisual(
00049           const std::string &name, rendering::VisualPtr parent, 
00050           int height, int width);
00051       virtual ~VideoVisual();
00052       void render(const cv::Mat& image);
00053     private:
00054       Ogre::TexturePtr texture_;
00055       int height_;
00056       int width_;
00057   }; 
00058 
00059   class GazeboRosVideo : public VisualPlugin 
00060   {
00061     public: 
00062     
00063       GazeboRosVideo();
00064       virtual ~GazeboRosVideo();
00065 
00066       void Load(rendering::VisualPtr parent, sdf::ElementPtr sdf);
00067       void processImage(const sensor_msgs::ImageConstPtr &msg);
00068 
00069     protected:
00070 
00071       virtual void UpdateChild();
00072 
00073       // Pointer to the model
00074       rendering::VisualPtr model_;
00075       // Pointer to the update event connection
00076       event::ConnectionPtr update_connection_;
00077 
00078       boost::shared_ptr<VideoVisual> video_visual_;
00079 
00080       cv_bridge::CvImagePtr image_;
00081       boost::mutex m_image_;
00082       bool new_image_available_;
00083 
00084       // ROS Stuff
00085       boost::shared_ptr<ros::NodeHandle> rosnode_;
00086       ros::Subscriber camera_subscriber_;
00087       std::string robot_namespace_;
00088       std::string topic_name_;
00089 
00090       ros::CallbackQueue queue_;
00091       boost::thread callback_queue_thread_;
00092       void QueueThread();
00093 
00094   };
00095 
00096 }
00097 
00098 #endif
00099 


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