gazebo_ros_projector.h
Go to the documentation of this file.
00001 /*
00002  * Desc: A dynamic controller plugin that controls texture projection.
00003  * Author: Jared Duke
00004  * Date: 17 June 2010
00005  * SVN: $Id$
00006  */
00007 #ifndef GAZEBO_ROS_PROJECTOR_HH
00008 #define GAZEBO_ROS_PROJECTOR_HH
00009 
00010 // Custom Callback Queue
00011 #include <ros/callback_queue.h>
00012 #include <ros/subscribe_options.h>
00013 
00014 #include <ros/ros.h>
00015 #include <boost/thread/mutex.hpp>
00016 
00017 #include <gazebo/physics/physics.hh>
00018 #include <gazebo/transport/TransportTypes.hh>
00019 #include <gazebo/transport/Node.hh>
00020 #include <gazebo/common/Time.hh>
00021 #include <gazebo/common/Plugin.hh>
00022 #include <gazebo/common/Events.hh>
00023 #include <gazebo/rendering/RenderTypes.hh>
00024 
00025 #include <std_msgs/String.h>
00026 #include <std_msgs/Int32.h>
00027 
00028 #include <OgrePrerequisites.h>
00029 #include <OgreTexture.h>
00030 #include <OgreFrameListener.h>
00031 
00032 namespace Ogre
00033 {
00034   class PlaneBoundedVolumeListSceneQuery;
00035   class Frustum;
00036   class Pass;
00037   class SceneNode;
00038 }
00039 
00040 namespace gazebo
00041 {
00042 
00045 
00075 class GazeboRosProjector : public ModelPlugin
00076 {
00079   public: GazeboRosProjector();
00080 
00082   public: virtual ~GazeboRosProjector();
00083 
00086   protected: virtual void Load( physics::ModelPtr _parent, sdf::ElementPtr _sdf );
00087 
00089   private: physics::WorldPtr world_;
00090 
00092   private: void LoadImage(const std_msgs::String::ConstPtr& imageMsg);
00093 
00095   private: void ToggleProjector(const std_msgs::Int32::ConstPtr& projectorMsg);  
00096 
00098   private: ros::NodeHandle* rosnode_;
00099   private: ros::Subscriber imageSubscriber_;
00100   private: ros::Subscriber projectorSubscriber_;  
00101 
00103   private: std::string texture_topic_name_;
00104 
00106   private: std::string projector_topic_name_;
00107 
00109   private: std::string robot_namespace_;
00110 
00111   // Custom Callback Queue
00112   private: ros::CallbackQueue queue_;
00113   private: void QueueThread();
00114   private: boost::thread callback_queue_thread_;
00115 
00116   private: event::ConnectionPtr add_model_event_;
00117 
00118   private: transport::NodePtr node_; 
00119   private: transport::PublisherPtr projector_pub_; 
00120 };
00121 
00123 
00124 
00125 }
00126 #endif
00127 


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