$search
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<Vector3> *xyzP; 00126 private: ParamT<Quatern> *rpyP; 00127 private: ParamT<std::string> *textureNameP; 00128 private: ParamT<std::string> *filterTextureNameP; 00129 private: ParamT<double> *fovP; 00130 private: ParamT<double> *nearClipDistP; 00131 private: ParamT<double> *farClipDistP; 00132 00134 private: std::string textureTopicName; 00135 00137 private: std::string projectorTopicName; 00138 00139 // \brief Projector parameters 00140 private: std::string bodyName; 00141 private: std::string textureName; 00142 private: std::string filterTextureName; 00143 private: double fov; 00144 private: double nearClipDist; 00145 private: double farClipDist; 00146 private: Vector3 xyz; 00147 private: Quatern rpy; 00148 00150 private: ParamT<std::string> *robotNamespaceP; 00151 private: std::string robotNamespace; 00152 00153 // Custom Callback Queue 00154 private: ros::CallbackQueue queue_; 00155 private: void QueueThread(); 00156 private: boost::thread callback_queue_thread_; 00157 00158 private: std::string projectorNodeName; 00159 private: std::string projectorFilterNodeName; 00160 00161 private: 00162 class Projector : public Ogre::FrameListener 00163 { 00164 00165 public: Projector(); 00166 public: virtual ~Projector(); 00167 00168 public: void init( Ogre::SceneNode *sceneNodePtr = NULL, 00169 Ogre::String textureName = "stereo_projection_pattern_alpha.png", 00170 Ogre::String filterTextureName = "stereo_projection_pattern_filter.png", 00171 double nearDist = .5, 00172 double farDist = 10, 00173 double fov = 0.785398163, 00174 std::string projectorNodeName = "projectorNodeName", 00175 std::string projectorFilterNodeName = "projectorFilterNodeName"); 00176 00177 public: virtual bool frameStarted(const Ogre::FrameEvent &evt); 00178 public: virtual bool frameEnded(const Ogre::FrameEvent &evt); 00179 public: virtual bool frameRenderingQueued(const Ogre::FrameEvent &evt); 00180 00181 public: void setEnabled( bool enabled ); 00182 public: void setUsingShaders( bool usingShaders ); 00183 public: void setSceneNode(); 00184 public: void setTextureName( const Ogre::String& textureName ); 00185 public: void setFilterTextureName( const Ogre::String& textureName ); 00186 public: void setFrustumClipDistance( double nearDist, double farDist ); 00187 public: void setFrustumFOV( double fovInRadians ); 00188 public: void setPose( Vector3 xyz, Quatern rpy ); 00189 00190 private: void addProjectorPassToVisibleMaterials(); 00191 private: void addProjectorPassToAllMaterials(); 00192 private: void addProjectorPassToMaterials(std::list<std::string>& matList); 00193 private: void addProjectorPassToMaterial(std::string matName); 00194 private: void removeProjectorPassFromMaterials(); 00195 private: void removeProjectorPassFromMaterial(std::string matName); 00196 00197 private: Ogre::SceneManager* getSceneMgrP(); 00198 private: Ogre::SceneNode* parentSceneNode; 00199 00200 private: bool isEnabled; 00201 private: bool isInit; 00202 private: bool isUsingShaders; 00203 00204 private: Ogre::Frustum *projectorFrustum; 00205 private: Ogre::Frustum *projectorFilterFrustum; 00206 private: Ogre::PlaneBoundedVolumeListSceneQuery *projectorQuery; 00207 private: Ogre::SceneNode *projectorNode; 00208 private: Ogre::SceneNode *projectorFilterNode; 00209 00210 private: Ogre::String projectedTextureName; 00211 private: Ogre::String projectedFilterTextureName; 00212 00213 private: std::map<std::string,Ogre::Pass*> projectorTargets; 00214 00215 private: std::string projectorNodeName; 00216 private: std::string projectorFilterNodeName; 00217 }; 00218 00219 private: Projector projector_; 00220 00221 }; 00222 00224 00225 00226 } 00227 #endif 00228