but_materialtest1.cpp
Go to the documentation of this file.
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 
00028 #include "but_materialtest1.h"
00029 
00030 // Ros includes
00031 #include <ros/package.h>
00032 
00033 // Ogre includes
00034 #include <OGRE/OgreSceneManager.h>
00035 #include "OGRE/OgreWindowEventUtilities.h"
00036 #include "OGRE/OgreManualObject.h"
00037 #include "OGRE/OgreEntity.h"
00038 #include "OGRE/OgreMaterialManager.h"
00039 #include "OGRE/OgreCompositorManager.h"
00040 #include <ogre_tools/initialization.h>
00041 
00042 
00043 // Rviz includes
00044 #include <rviz/render_panel.h>
00045 #include <rviz/visualization_manager.h>
00046 #include <rviz/window_manager_interface.h>
00047 
00048 #include <wx/filedlg.h>
00049 
00050 // Ros image message
00051 #include <sensor_msgs/Image.h>
00052 
00053 // Std includes
00054 #include <sstream>
00055 
00056 #define CAMERA_SCREENCAST_TOPIC_NAME std::string("rviz_cam_rgb")
00057 #define DEFAULT_PUBLISHING_PERIOD double(0.1)
00058 
00059 class CMaterialListener : public Ogre::MaterialManager::Listener
00060 {
00061 protected:
00062         Ogre::MaterialPtr m_materialPtr;
00063 public:
00064         CMaterialListener( const std::string & materialName, const std::string & groupName )
00065         {
00066                 // Create material
00067                 m_materialPtr = Ogre::MaterialManager::getSingleton().getByName( materialName, groupName );
00068 
00069                 // Test if success
00070                 if( m_materialPtr.get() == 0 )
00071                 {
00072                         std::cerr << "Cannot get material..." << std::endl;
00073                 }
00074                 else
00075                 {
00076                         // Load it
00077                         m_materialPtr->load();
00078 
00079                         // Write info
00080                         std::cerr << "Material " << groupName << ":" << materialName << " loaded..." << std::endl;
00081                         std::cerr << "Num of techniques: " << m_materialPtr->getNumTechniques() << std::endl;
00082                         m_materialPtr->getTechnique(0);
00083                 }
00084         }
00085 
00087         Ogre::Technique *handleSchemeNotFound(unsigned short, const Ogre::String& schemeName, Ogre::Material*mat, unsigned short, const Ogre::Renderable*)
00088         {
00089                 if (schemeName == "myscheme")
00090                 {
00091                         //LogManager::getSingleton().logMessage(">> adding glow to material: "+mat->getName());
00092                         //std::cerr << "gettech" << std::endl;
00093                         return m_materialPtr->getBestTechnique();
00094                 }
00095                 return NULL;
00096         }
00097 };
00098 
00099 
00100 /*
00101  *  Constructor
00102  */
00103 srs_ui_but::CButMaterialTest1::CButMaterialTest1(const std::string & name,rviz::VisualizationManager * manager)
00104 : Display( name, manager )
00105 , m_bPublish(true)
00106 {
00107   // Create and connect pane
00108   rviz::WindowManagerInterface * wi( manager->getWindowManager() );
00109 
00110   if( wi != 0 )
00111   {
00112     // Arm manipulation controls
00113     m_pane = new CControllPane( wi->getParentWindow(), wxT("Material test"), wi);
00114 
00115     if( m_pane != 0 )
00116     {
00117       wi->addPane( "Material test", m_pane );
00118       wi->showPane( m_pane );
00119 
00120       // Connect signal
00121       m_pane->getSigChckBox().connect( boost::bind( &CButMaterialTest1::onPublishStateChanged, this, _1) );
00122       m_pane->getSigSave().connect( boost::bind( &CButMaterialTest1::onSave, this, _1 ) );
00123     }
00124 
00125   }else{
00126     std::cerr << "No window manager, no panes :( " << std::endl;
00127   }
00128 
00129 
00130   // Get node handle
00131   ros::NodeHandle private_nh("/");
00132 
00133   // Set parameters
00134 
00135   // Get camera screencasting topic name
00136   private_nh.param("rviz_screencast_topic_name", m_camCastPublisherName, CAMERA_SCREENCAST_TOPIC_NAME);
00137 
00138   // Get timer period
00139   private_nh.param("publishig_period", m_timerPeriod, DEFAULT_PUBLISHING_PERIOD );
00140 
00141   // Get scene node
00142   m_sceneNode = scene_manager_->getRootSceneNode()->createChildSceneNode();
00143 
00144   // Create publisher
00145   this->m_camCastPublisher = private_nh.advertise< sensor_msgs::Image >(m_camCastPublisherName, 100, false);
00146 
00147   // Create geometry
00148   createGeometry(private_nh);
00149 
00150   // Create publishing timer
00151   m_timer = private_nh.createTimer( ros::Duration(m_timerPeriod), boost::bind( &CButMaterialTest1::onTimerPublish, this, _1) );
00152 
00153   // Set publishing parameters
00154   //m_textureWithRtt->setFrame("/map");
00155 
00156 }
00157 
00158 /*
00159  *  Destructor
00160  */
00161 srs_ui_but::CButMaterialTest1::~CButMaterialTest1()
00162 {
00163   // Destroy all geometry
00164   destroyGeometry();
00165 
00166 }
00167 
00168 
00169 /*
00170  *  Display enablet callback
00171  */
00172 void srs_ui_but::CButMaterialTest1::onEnable()
00173 {
00174   m_sceneNode->setVisible( true );
00175 }
00176 
00177 /*
00178  *  Display disabled callback
00179  */
00180 void srs_ui_but::CButMaterialTest1::onDisable()
00181 {
00182   m_sceneNode->setVisible( false );
00183 }
00184 
00185 void srs_ui_but::CButMaterialTest1::createMaterials(Ogre::Camera * camera)
00186 {
00187         // Get material manager
00188         Ogre::MaterialManager& lMaterialManager = Ogre::MaterialManager::getSingleton();
00189 
00190         // Load materials
00191         Ogre::String nameOfResourceGroup( "MaterialGroup1" );
00192         {
00193                 // Create resource group
00194                 Ogre::ResourceGroupManager& lRgMgr = Ogre::ResourceGroupManager::getSingleton();
00195                 lRgMgr.createResourceGroup(nameOfResourceGroup);
00196 
00197                 // Get path
00198                 std::string package_path( ros::package::getPath("srs_ui_but") );
00199 
00200                 ogre_tools::V_string paths;
00201                 Ogre::String resource_path(package_path + "/src/but_projection/materials");
00202 
00203                 std::cerr << "Materials path: " << resource_path.c_str() << std::endl;
00204 
00205                 // List loaded materials
00206                 Ogre::ResourceManager::ResourceMapIterator materialIterator = lMaterialManager.getResourceIterator();
00207 
00208                 lRgMgr.createResourceGroup("srs_ui_but");
00209                 lRgMgr.addResourceLocation(resource_path, "FileSystem", "srs_ui_but");
00210                 lRgMgr.initialiseResourceGroup("srs_ui_but");
00211                 lRgMgr.loadResourceGroup("srs_ui_but");
00212 
00213                 std::cerr << "Loaded materials: " << std::endl;
00214                 int count(0);
00215                 while (materialIterator.hasMoreElements())
00216                 {
00217 
00218                         Ogre::String name( (static_cast<Ogre::MaterialPtr>(materialIterator.peekNextValue()))->getName() );
00219 
00220                         std::cerr << name << std::endl;
00221 
00222                     materialIterator.moveNext();
00223                     count++;
00224                 }
00225 
00226                 std::cerr << "Num of materials: " << count << std::endl;
00227         }
00228 
00229         // Load compositor
00230         {
00231                 if( Ogre::CompositorManager::getSingleton().addCompositor(camera->getViewport(), "DepthMap") == 0 )
00232                 {
00233                         std::cout << "COMPOSITOR FAILED TO LOAD." << std::endl;
00234                 }
00235                 else
00236                 {
00237                         Ogre::CompositorManager::getSingleton().setCompositorEnabled(camera->getViewport(), "DepthMap", true);
00238                         CMaterialListener *gml = new CMaterialListener( "depth", "srs_ui_but" );
00239                         Ogre::MaterialManager::getSingleton().addListener(gml);
00240                 }
00241         }
00242 }
00243 
00244 /*
00245  *  Create geometry
00246  */
00247 bool srs_ui_but::CButMaterialTest1::createGeometry(const ros::NodeHandle & nh)
00248 {
00249   // Get camera.
00250   rviz::RenderPanel * panel = vis_manager_->getRenderPanel();
00251   if( panel == 0 )
00252   {
00253     ROS_DEBUG( "No render panel... ");
00254     return false;
00255   }
00256 
00257   Ogre::Camera * camera = panel->getCamera();
00258 
00259   // Create rtt texture
00260   //m_textureWithRtt = new CRosRttTexture( 512, 512, camera );
00261 
00262   //*
00263   Ogre::String lNameOfTheMesh = "MeshCube";
00264   {
00265     // Here, I create a 3D element, by using the interface of ManualObject.
00266     // ManualObject is very close to the opengl old simple way to specify geometry.
00267     // There are other interfaces (Hardwarebuffers), you can check the ogremanual fo them and wiki.
00268     // For each vertex I will provide positions and attributes (normal, vertex color, texture coordinates...).
00269     // Then for each primitive (given its type : triangle, line, line strip etc...),
00270     // I give the corresponding group of vertex index.
00271     Ogre::ManualObject* lManualObject = NULL;
00272     {
00273       // The manualObject creation requires a name.
00274       Ogre::String lManualObjectName = "CubeWithAxes";
00275       lManualObject = scene_manager_->createManualObject(lManualObjectName);
00276 
00277       // Always tell if you want to update the 3D (vertex/index) later or not.
00278       bool lDoIWantToUpdateItLater = false;
00279       lManualObject->setDynamic(lDoIWantToUpdateItLater);
00280 
00281       // Here I create a cube in a first part with triangles, and then axes (in red/green/blue).
00282 
00283       // BaseWhiteNoLighting is the name of a material that already exist inside Ogre.
00284       // Ogre::RenderOperation::OT_TRIANGLE_LIST is a kind of primitive.
00285       float lSize = 0.7f;
00286       lManualObject->begin("BaseWhiteNoLighting", Ogre::RenderOperation::OT_TRIANGLE_LIST);
00287       {
00288         float cp = 1.0f * lSize ;
00289         float cm = -1.0f * lSize;
00290 
00291         lManualObject->position(cm, cp, cm);// a vertex
00292         lManualObject->colour(Ogre::ColourValue(0.0f,1.0f,0.0f,1.0f));
00293         lManualObject->textureCoord(0.0, 1.0);
00294         lManualObject->position(cp, cp, cm);// a vertex
00295         lManualObject->colour(Ogre::ColourValue(1.0f,1.0f,0.0f,1.0f));
00296         lManualObject->textureCoord(1.0, 1.0);
00297         lManualObject->position(cp, cm, cm);// a vertex
00298         lManualObject->colour(Ogre::ColourValue(1.0f,0.0f,0.0f,1.0f));
00299         lManualObject->textureCoord(1.0, 0.0);
00300         lManualObject->position(cm, cm, cm);// a vertex
00301         lManualObject->colour(Ogre::ColourValue(0.0f,0.0f,0.0f,1.0f));
00302         lManualObject->textureCoord(0.0, 0.0);
00303 
00304         lManualObject->position(cm, cp, cp);// a vertex
00305         lManualObject->colour(Ogre::ColourValue(0.0f,1.0f,1.0f,1.0f));
00306         lManualObject->textureCoord(0.0, 1.0);
00307         lManualObject->position(cp, cp, cp);// a vertex
00308         lManualObject->colour(Ogre::ColourValue(1.0f,1.0f,1.0f,1.0f));
00309         lManualObject->textureCoord(1.0, 1.0);
00310         lManualObject->position(cp, cm, cp);// a vertex
00311         lManualObject->colour(Ogre::ColourValue(1.0f,0.0f,1.0f,1.0f));
00312         lManualObject->textureCoord(1.0, 0.0);
00313         lManualObject->position(cm, cm, cp);// a vertex
00314         lManualObject->colour(Ogre::ColourValue(0.0f,0.0f,1.0f,1.0f));
00315         lManualObject->textureCoord(0.0, 0.0);
00316 
00317         // face behind / front
00318         lManualObject->triangle(0,1,2);
00319         lManualObject->triangle(2,3,0);
00320         lManualObject->triangle(4,6,5);
00321         lManualObject->triangle(6,4,7);
00322 
00323         // face top / down
00324         lManualObject->triangle(0,4,5);
00325         lManualObject->triangle(5,1,0);
00326         lManualObject->triangle(2,6,7);
00327         lManualObject->triangle(7,3,2);
00328 
00329         // face left / right
00330         lManualObject->triangle(0,7,4);
00331         lManualObject->triangle(7,0,3);
00332         lManualObject->triangle(1,5,6);
00333         lManualObject->triangle(6,2,1);
00334       }
00335       lManualObject->end();
00336       // Here I have finished my ManualObject construction.
00337       // It is possible to add more begin()-end() thing, in order to use
00338       // different rendering operation types, or different materials in 1 ManualObject.
00339     }
00340 
00341     lManualObject->convertToMesh(lNameOfTheMesh, Ogre::ResourceGroupManager::DEFAULT_RESOURCE_GROUP_NAME);
00342 
00343     // Now I can create several entities using that mesh
00344     int lNumberOfEntities = 5;
00345     for(int iter = 0; iter < lNumberOfEntities; ++iter)
00346     {
00347       Ogre::Entity* lEntity = scene_manager_->createEntity(lNameOfTheMesh);
00348       // Now I attach it to a scenenode, so that it becomes present in the scene.
00349       Ogre::SceneNode* lNode = scene_manager_->getRootSceneNode()->createChildSceneNode();
00350       lNode->attachObject(lEntity);
00351       // I move the SceneNode so that it is visible to the camera.
00352       float lPositionOffset = float(1+ iter * 2) - (float(lNumberOfEntities));
00353       lNode->translate(lPositionOffset, lPositionOffset, -10.0f);
00354     }
00355   }
00356 
00357   // Create entity on screen
00358 
00359   Ogre::Entity* lAdditionalEntity = scene_manager_->createEntity( lNameOfTheMesh );
00360  // lAdditionalEntity->setMaterialName( m_textureWithRtt->getMaterialName() );
00361   Ogre::SceneNode* lVisibleOnlyByFirstCam = scene_manager_->getRootSceneNode()->createChildSceneNode();
00362   lVisibleOnlyByFirstCam->attachObject( lAdditionalEntity );
00363   lVisibleOnlyByFirstCam->setPosition( 1.5,-0.5,-5);
00364 //*/
00365 
00366   // Create and initialize materials
00367   createMaterials( camera );
00368 
00369   return true;
00370 }
00371 
00372 void srs_ui_but::CButMaterialTest1::destroyGeometry()
00373 {
00374   // Destroy scene
00375   if( m_sceneNode != 0 )
00376     scene_manager_->destroySceneNode(m_sceneNode->getName());
00377 }
00378 
00380 void srs_ui_but::CButMaterialTest1::update (float wall_dt, float ros_dt)
00381 {
00382   rviz::RenderPanel * panel = vis_manager_->getRenderPanel();
00383   if( panel == 0 )
00384   {
00385     ROS_DEBUG( "No render panel... ");
00386   }
00387 
00388   Ogre::Camera * camera = panel->getCamera();
00389 
00390   if( camera == 0 )
00391   {
00392     ROS_DEBUG( "No camera ");
00393   }
00394 }
00395 
00396 /*
00397  * Timer publishing callback function
00398  */
00399 
00400 void srs_ui_but::CButMaterialTest1::onTimerPublish(const ros::TimerEvent&)
00401 {
00402 
00403 /*
00404   if( m_bPublish && (m_camCastPublisher.getNumSubscribers() > 0 ) && m_textureWithRtt->hasData() )
00405   {
00406     // Publish image
00407     m_camCastPublisher.publish( m_textureWithRtt->getImage() );
00408   }
00409   */
00410 }
00411 
00412 
00416 void srs_ui_but::CButMaterialTest1::onPublishStateChanged(bool state)
00417 {
00418   if( state )
00419     m_timer.start();
00420   else
00421     m_timer.stop();
00422 }
00423 
00427 void srs_ui_but::CButMaterialTest1::onSave( std::string filename )
00428 {
00429  // m_textureWithRtt->saveImage( filename );
00430 }
00431 
00432 
00433 
00435 const int ID_CHECKBOX(100);
00436 const int ID_SAVE_BUTTON(101);
00437 
00438 srs_ui_but::CButMaterialTest1::CControllPane::CControllPane(wxWindow *parent, const wxString& title, rviz::WindowManagerInterface * wmi): wxPanel( parent, wxID_ANY, wxDefaultPosition, wxSize(280, 180), wxTAB_TRAVERSAL, title)
00439 , m_wmi( wmi )
00440 {
00441   // Create controls
00442   m_button = new wxButton(this, ID_SAVE_BUTTON, wxT("Save screenshot"), wxDefaultPosition, wxDefaultSize, wxBU_EXACTFIT);
00443 
00444   m_chkb = new wxCheckBox(this, ID_CHECKBOX, wxT("Publish images"),
00445       wxPoint(20, 20));
00446   m_chkb->SetValue( true );
00447 
00448   // Create layout
00449   wxSizer *sizer = new wxBoxSizer(wxVERTICAL);
00450   this->SetSizer(sizer);
00451 
00452   wxSizer *hsizer = new wxBoxSizer(wxHORIZONTAL);
00453   hsizer->Add(m_chkb, ID_CHECKBOX, wxALIGN_LEFT);
00454   hsizer->Add(m_button, ID_SAVE_BUTTON, wxALIGN_RIGHT);
00455 
00456   sizer->Add(hsizer, 0, wxALIGN_LEFT);
00457 
00458   sizer->SetSizeHints(this);
00459 
00460 }
00461 
00463 
00467 void srs_ui_but::CButMaterialTest1::CControllPane::OnChckToggle(wxCommandEvent& event)
00468 {
00469   // Call signal
00470   m_sigCheckBox( m_chkb->GetValue() );
00471 }
00472 
00474 
00478 void srs_ui_but::CButMaterialTest1::CControllPane::OnSave(wxCommandEvent& event)
00479 {
00480   wxFileDialog fileDlg(this, _("Choose file to save"), wxEmptyString, _("screenshot.png"), _("*.*"), wxFD_SAVE | wxFD_OVERWRITE_PROMPT );
00481 
00482   wxString filename, directory;
00483 
00484   // Pause timer
00485   if(m_chkb->GetValue())
00486     m_sigCheckBox( false );
00487 
00488   if( fileDlg.ShowModal() == wxID_OK )
00489   {
00490     filename = fileDlg.GetFilename();
00491     directory = fileDlg.GetDirectory();
00492 
00493     std::string path(std::string( wxString(directory + wxFileName::GetPathSeparator() + filename).mb_str() ) );
00494 
00495      m_sigSave( path );
00496   }
00497 
00498   // Start timer
00499   if(m_chkb->GetValue())
00500     m_sigCheckBox( true );
00501 
00502 
00503 }
00504 
00505 
00506 
00508 BEGIN_EVENT_TABLE(srs_ui_but::CButMaterialTest1::CControllPane, wxPanel)
00509 EVT_BUTTON(ID_SAVE_BUTTON,  srs_ui_but::CButMaterialTest1::CControllPane::OnSave)
00510 EVT_CHECKBOX(ID_CHECKBOX, srs_ui_but::CButMaterialTest1::CControllPane::OnChckToggle )
00511 END_EVENT_TABLE()


srs_ui_but
Author(s): Vit Stancl (stancl@fit.vutbr.cz), Michal Spanel (spanel@fit.vutbr.cz), Tomas Lokaj
autogenerated on Sun Jan 5 2014 12:12:49