$search
00001 /****************************************************************************** 00002 * \file 00003 * 00004 * $Id:$ 00005 * 00006 * Copyright (C) Brno University of Technology 00007 * 00008 * This file is part of software developed by dcgm-robotics@FIT group. 00009 * 00010 * Author: Vit Stancl (stancl@fit.vutbr.cz) 00011 * Supervised by: Michal Spanel (spanel@fit.vutbr.cz) 00012 * Date: dd/mm/2011 00013 * 00014 * This file is free software: you can redistribute it and/or modify 00015 * it under the terms of the GNU Lesser General Public License as published by 00016 * the Free Software Foundation, either version 3 of the License, or 00017 * (at your option) any later version. 00018 * 00019 * This file is distributed in the hope that it will be useful, 00020 * but WITHOUT ANY WARRANTY; without even the implied warranty of 00021 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 00022 * GNU Lesser General Public License for more details. 00023 * 00024 * You should have received a copy of the GNU Lesser General Public License 00025 * along with this file. If not, see <http://www.gnu.org/licenses/>. 00026 */ 00027 #pragma once 00028 #ifndef BUT_PROJECTION_H 00029 #define BUT_PROJECTION_H 00030 00031 // ROS includes 00032 #include <message_filters/subscriber.h> 00033 00034 // Rviz includes 00035 #include <rviz/display.h> 00036 #include <rviz/view_controller.h> 00037 #include "rviz/properties/forwards.h" 00038 #include "rviz/properties/property.h" 00039 #include "rviz/properties/edit_enum_property.h" 00040 #include "rviz/properties/property_manager.h" 00041 //#include "rviz/image/ros_image_texture.h" 00042 #include "rviz/properties/forwards.h" 00043 #include <image_geometry/pinhole_camera_model.h> 00044 00045 // OGRE includes 00046 #include <OGRE/OgreSceneNode.h> 00047 #include <OgreManualObject.h> 00048 #include <OgreCamera.h> 00049 #include "OGRE/OgreMaterialManager.h" 00050 #include <OGRE/OgreTexture.h> 00051 00052 // Std includes 00053 #include <string> 00054 00055 // Wx includes 00056 #include <wx/wx.h> 00057 00058 // Local includes 00059 #include "ros_rtt_texture.h" 00060 #include "but_rostexture.h" 00061 #include "but_depthtexture.h" 00062 00063 namespace rviz 00064 { 00065 class WindowManagerInterface; 00066 } 00067 00068 namespace srs_ui_but 00069 { 00070 00071 /*********************************************************************************************************************/ 00072 00076 class CMaterialListener : public Ogre::MaterialManager::Listener 00077 { 00078 protected: 00080 Ogre::Material * m_materialPtr; 00081 00083 std::string m_schemeName; 00084 00086 bool m_bNotPaused; 00087 00089 float m_testingDistance; 00090 00092 bool m_bDistanceChanged; 00093 00095 bool m_bMatricesChanged; 00096 00098 Ogre::Vector4 m_camPosition; 00099 00101 Ogre::Matrix4 m_projMatrix; 00102 00104 Ogre::Vector4 m_camPlane; 00105 00107 boost::mutex m_lock; 00108 00109 public: 00111 //CMaterialListener( const std::string & materialName, const std::string & groupName, const std::string & schemeName ); 00112 00114 CMaterialListener( Ogre::Material * material, const std::string & schemeName ); 00115 00117 ~CMaterialListener(); 00118 00120 void setPaused( bool bPaused ) { m_bNotPaused = !bPaused; } 00121 00123 void setTestedDistance( float distance ); 00124 00126 void setCameraPosition( const Ogre::Vector4 & position, const Ogre::Vector4 & camPlane, const Ogre::Matrix4 & projMatrix ); 00127 00129 float getTestedDistance() { return m_testingDistance; } 00130 00132 Ogre::Technique *handleSchemeNotFound(unsigned short, const Ogre::String& schemeName, Ogre::Material*mat, unsigned short, const Ogre::Renderable*); 00133 }; // class CMaterialListener 00134 00135 /*********************************************************************************************************************/ 00136 00140 class CProjectionData 00141 { 00142 //typedef rviz::CRosTexture tRosTexture; 00143 typedef CRosTopicTexture tRosTextureRGB; 00144 00146 typedef CRosDepthTexture tRosTextureDepth; 00147 00148 protected: 00149 enum ETextureMode 00150 { 00151 TM_INTERNAL, // Create and use internal ogre texture 00152 TM_ROS // Use ros texture (typically connected to some topic) 00153 }; 00154 00155 public: 00157 CProjectionData( Ogre::SceneManager * manager, const ros::NodeHandle &nh, const std::string & materialName, const std::string & groupName = Ogre::ResourceGroupManager::DEFAULT_RESOURCE_GROUP_NAME ); 00158 00160 virtual ~CProjectionData(); 00161 00163 Ogre::Material * getMaterialPtr() { return m_materialPtr.get(); } 00164 00166 void setListenerPtr(CMaterialListener * ptr ) { m_materialListener = ptr; if( ptr != 0 ) updateMatrices(); } 00167 00169 void setFrustrumSize( Ogre::Vector2 size ); 00170 00172 void setTextureSize( int width, int height ); 00173 00175 void setRGBTextureTopic( const std::string & topic ); 00176 00178 void setDepthTextureTopic( const std::string & topic ); 00179 00181 int getTextureWidth() { return m_texW; } 00182 00184 int getTextureHeight() { return m_texH; } 00185 00187 void clear(); 00188 00190 void update() { if( m_textureRosRGB != 0 ) m_textureRosRGB->update(); } 00191 00193 void setProjectorPosition( const Ogre::Vector3 & v ){ m_projectorNode->setPosition(v); } 00194 00196 void setProjectorOrientation( const Ogre::Quaternion & q ) { m_projectorNode->setOrientation( q ); } 00197 00199 void setProjectorEquation( const Ogre::Vector4 & e ) { m_cameraEquation = e; } 00200 00202 void updateMatrices(); 00203 00205 void setFOVy( Ogre::Radian fovy ) { m_frustum->setFOVy( fovy ); } 00206 00208 void setAspectRatio( Ogre::Real ar ) { m_frustum->setAspectRatio( ar ); } 00209 00211 void setCameraModel(const sensor_msgs::CameraInfo& msg) { m_textureRosDepth->setCameraModel(msg); } 00212 00213 protected: 00215 CMaterialListener * m_materialListener; 00216 00218 Ogre::MaterialPtr m_materialPtr; 00219 00221 Ogre::Vector2 m_frustrumSize; 00222 00224 size_t m_texW, m_texH; 00225 00227 ETextureMode m_mode; 00228 00230 tRosTextureRGB * m_textureRosRGB; 00231 tRosTextureDepth* m_textureRosDepth; 00232 00234 Ogre::SceneNode * m_projectorNode; 00235 00237 Ogre::Frustum * m_frustum; 00238 00240 tf::TransformListener m_tfListener; 00241 00243 Ogre::TextureUnitState * m_texState; 00244 00246 boost::mutex m_lock; 00247 00249 Ogre::SceneManager * m_manager; 00250 00252 Ogre::Vector3 m_cameraPosition; 00253 00255 Ogre::Vector4 m_cameraEquation; 00256 00257 }; // class CProjectionData 00258 00259 /*********************************************************************************************************************/ 00260 00261 00265 class CButProjection : public rviz::Display 00266 { 00267 public: 00268 00272 class CControllPane : public wxPanel 00273 { 00274 public: 00276 typedef boost::signal< void (bool) > tSigCheckboxState; 00277 00279 typedef boost::signal< void ( std::string ) > tSigSave; 00280 00281 public: 00283 CControllPane(wxWindow *parent, const wxString& title, rviz::WindowManagerInterface * wmi ); 00284 00286 void OnChckToggle(wxCommandEvent& event); 00287 00289 virtual void OnSave(wxCommandEvent& event); 00290 00292 tSigCheckboxState & getSigChckBox(){ return m_sigCheckBox; } 00293 00295 tSigSave & getSigSave(){ return m_sigSave; } 00296 00297 protected: 00299 rviz::WindowManagerInterface * m_wmi; 00300 00302 wxCheckBox * m_chkb; 00303 00305 wxButton * m_button; 00306 00308 tSigCheckboxState m_sigCheckBox; 00309 00311 tSigSave m_sigSave; 00312 private: 00313 DECLARE_EVENT_TABLE() 00314 }; // class CControllPane 00315 00316 public: 00318 CButProjection(const std::string & name,rviz::VisualizationManager * manager); 00319 00321 ~CButProjection(); 00322 00323 //OverridesfromDisplay 00324 virtual void targetFrameChanged(){} 00325 virtual void fixedFrameChanged(){} 00326 virtual void createProperties(); 00327 00329 const std::string& getRgbTopic() { return m_imageRGBInputTopicName; } 00330 00332 void setRgbTopic(const std::string& topic); 00333 00335 const std::string& getDepthTopic() { return m_imageDepthInputTopicName; } 00336 00338 void setDepthTopic(const std::string& topic); 00339 00341 virtual void update (float wall_dt, float ros_dt); 00342 00343 protected: 00344 //overridesfromDisplay 00345 virtual void onEnable(); 00346 virtual void onDisable(); 00347 00349 void subscribe(); 00350 00352 void unsubscribe(); 00353 00355 bool createGeometry(const ros::NodeHandle & nh); 00356 00358 void destroyGeometry(); 00359 00361 //void setTimerPeriod(float period); 00362 00364 void onTimerPublish(const ros::TimerEvent&); 00365 00367 void onPublishStateChanged(bool state); 00368 00370 void onSave( std::string filename ); 00371 00373 void createMaterials(Ogre::Camera * camera); 00374 00376 void removeMaterials(); 00377 00379 void clear(); 00380 00382 void cameraInfoCB(const sensor_msgs::CameraInfo::ConstPtr &cam_info); 00383 00385 void connectML( bool bConnect ); 00386 00388 void setTestedDistance( float distance ); 00389 00391 float getTestedDistance(); 00392 00393 protected: 00395 Ogre::SceneNode * m_sceneNode; 00396 00398 std::string m_imageRGBInputTopicName, m_imageDepthInputTopicName; 00399 00401 ros::Timer m_timer; 00402 00404 rviz::ROSTopicStringPropertyWPtr m_rgb_topic_property; 00405 00407 rviz::ROSTopicStringPropertyWPtr m_depth_topic_property; 00408 00410 rviz::FloatPropertyWPtr m_distance_property; 00411 00413 double m_timerPeriod; 00414 00416 CControllPane * m_pane; 00417 00419 CProjectionData * m_projectionData; 00420 00422 std::string m_camera_info_topic; 00423 00424 // TF transformation listener for camera info message 00425 tf::TransformListener *m_tf_cam_info_Listener; 00426 00428 message_filters::Subscriber< sensor_msgs::CameraInfo > * m_ciSubscriber; 00429 00431 tf::MessageFilter<sensor_msgs::CameraInfo> * m_camInfoTransformFilter; 00432 00434 image_geometry::PinholeCameraModel m_camera_model; 00435 00437 cv::Size m_camera_size; 00438 00440 boost::mutex m_cameraInfoLock; 00441 00443 CMaterialListener * m_ml; 00444 00446 bool m_bMLConnected; 00447 00449 bool m_bCameraInitialized; 00450 00451 00452 00453 };//class CButCamCast 00454 00455 } // namespace srs_ui_but 00456 00457 #endif // BUT_PROJECTION_H 00458 00459