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/Controller.hh> 00018 #include <gazebo/Param.hh> 00019 #include <gazebo/Body.hh> 00020 #include <gazebo/Model.hh> 00021 00022 #include <std_msgs/String.h> 00023 #include <std_msgs/Int32.h> 00024 00025 #include <OgrePrerequisites.h> 00026 #include <OgreTexture.h> 00027 #include <OgreFrameListener.h> 00028 00029 namespace Ogre 00030 { 00031 class PlaneBoundedVolumeListSceneQuery; 00032 class Frustum; 00033 class Pass; 00034 class SceneNode; 00035 } 00036 00037 namespace gazebo 00038 { 00039 00040 class Geom; 00041 00044 00074 class GazeboRosProjector : public Controller 00075 { 00078 public: GazeboRosProjector(Entity *parent); 00079 00081 public: virtual ~GazeboRosProjector(); 00082 00085 protected: virtual void LoadChild(XMLConfigNode *node); 00086 00088 protected: virtual void InitChild(); 00089 00091 protected: virtual void UpdateChild(); 00092 00094 protected: virtual void FiniChild(); 00095 00097 private: void LoadImage(const std_msgs::String::ConstPtr& imageMsg); 00098 00100 private: void ToggleProjector(const std_msgs::Int32::ConstPtr& projectorMsg); 00101 00103 private: Ogre::Root *getRootP(); 00104 00106 private: Model *myParent; 00107 //private: Entity *myParent; 00108 00110 private: Body *myBody; 00111 00113 private: ros::NodeHandle* rosnode_; 00114 private: ros::Subscriber imageSubscriber_; 00115 private: ros::Subscriber projectorSubscriber_; 00116 00118 private: boost::mutex lock; 00119 00122 private: ParamT<std::string> *textureTopicNameP; 00123 private: ParamT<std::string> *projectorTopicNameP; 00124 private: ParamT<std::string> *bodyNameP; 00125 private: ParamT<std::string> *textureNameP; 00126 private: ParamT<std::string> *filterTextureNameP; 00127 private: ParamT<double> *fovP; 00128 private: ParamT<double> *nearClipDistP; 00129 private: ParamT<double> *farClipDistP; 00130 00132 private: std::string textureTopicName; 00133 00135 private: std::string projectorTopicName; 00136 00137 // \brief Projector parameters 00138 private: std::string bodyName; 00139 private: std::string textureName; 00140 private: std::string filterTextureName; 00141 private: double fov; 00142 private: double nearClipDist; 00143 private: double farClipDist; 00144 00146 private: ParamT<std::string> *robotNamespaceP; 00147 private: std::string robotNamespace; 00148 00149 // Custom Callback Queue 00150 private: ros::CallbackQueue queue_; 00151 private: void QueueThread(); 00152 private: boost::thread callback_queue_thread_; 00153 00154 private: std::string filterNodeName; 00155 00156 private: 00157 class Projector : public Ogre::FrameListener 00158 { 00159 00160 public: Projector(); 00161 public: virtual ~Projector(); 00162 00163 public: void init( Ogre::SceneNode *sceneNodePtr = NULL, 00164 Ogre::String textureName = "stereo_projection_pattern_alpha.png", 00165 Ogre::String filterTextureName = "stereo_projection_pattern_filter.png", 00166 double nearDist = .5, 00167 double farDist = 10, 00168 double fov = 0.785398163, 00169 std::string filterNodeName = "FilterNode" ); 00170 00171 public: virtual bool frameStarted(const Ogre::FrameEvent &evt); 00172 public: virtual bool frameEnded(const Ogre::FrameEvent &evt); 00173 public: virtual bool frameRenderingQueued(const Ogre::FrameEvent &evt); 00174 00175 public: void setEnabled( bool enabled ); 00176 public: void setUsingShaders( bool usingShaders ); 00177 public: void setSceneNode( Ogre::SceneNode *sceneNodePtr ); 00178 public: void setTextureName( const Ogre::String& textureName ); 00179 public: void setFilterTextureName( const Ogre::String& textureName ); 00180 public: void setFrustumClipDistance( double nearDist, double farDist ); 00181 public: void setFrustumFOV( double fovInRadians ); 00182 00183 private: void addProjectorPassToVisibleMaterials(); 00184 private: void addProjectorPassToAllMaterials(); 00185 private: void addProjectorPassToMaterials(std::list<std::string>& matList); 00186 private: void addProjectorPassToMaterial(std::string matName); 00187 private: void removeProjectorPassFromMaterials(); 00188 private: void removeProjectorPassFromMaterial(std::string matName); 00189 00190 private: Ogre::SceneManager* getSceneMgrP(); 00191 00192 private: bool isEnabled; 00193 private: bool isInit; 00194 private: bool isUsingShaders; 00195 00196 private: Ogre::Frustum *projectorFrustum; 00197 private: Ogre::Frustum *projectorFilterFrustum; 00198 private: Ogre::PlaneBoundedVolumeListSceneQuery *projectorQuery; 00199 private: Ogre::SceneNode *projectorNode; 00200 private: Ogre::SceneNode *projectorFilterNode; 00201 00202 private: Ogre::String projectedTextureName; 00203 private: Ogre::String projectedFilterTextureName; 00204 00205 private: std::map<std::string,Ogre::Pass*> projectorTargets; 00206 00207 private: std::string filterNodeName; 00208 }; 00209 00210 private: Projector projector_; 00211 00212 }; 00213 00215 00216 00217 } 00218 #endif 00219