$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 00028 #include "but_projection.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/OgreCompositorManager.h" 00039 #include <ogre_tools/initialization.h> 00040 #include "OgreHardwarePixelBuffer.h" 00041 00042 #include <pcl/ros/conversions.h> 00043 #include <pcl_ros/transforms.h> 00044 00045 // Rviz includes 00046 #include <rviz/render_panel.h> 00047 #include <rviz/visualization_manager.h> 00048 #include <rviz/window_manager_interface.h> 00049 #include <rviz/frame_manager.h> 00050 #include <rviz/validate_floats.h> 00051 00052 #include <wx/filedlg.h> 00053 00054 // Ros image message 00055 #include <sensor_msgs/Image.h> 00056 00057 // Std includes 00058 #include <sstream> 00059 00060 #define DEFAULT_IMAGE_INPUT_TOPIC_NAME std::string("/cam3d/rgb/image_raw") 00061 #define DEFAULT_DEPTH_IMAGE_TOPIC_NAME std::string("/srs_ui_but/depth/image") 00062 #define CAMERA_INFO_TOPIC_NAME std::string("/cam3d/rgb/camera_info") 00063 #define DEFAULT_PUBLISHING_PERIOD double(0.1) 00064 00068 /* 00069 srs_ui_but::CMaterialListener::CMaterialListener( const std::string & materialName, const std::string & groupName, const std::string & schemeName ) 00070 : m_schemeName( schemeName ) 00071 { 00072 std::cerr << "Listener constructor 1" << std::endl; 00073 00074 // Create material 00075 // m_materialPtr = Ogre::MaterialManager::getSingleton().getByName( materialName, groupName ); 00076 00077 // Test if success 00078 if( m_materialPtr.get() == 0 ) 00079 { 00080 std::cerr << "Cannot get material..." << std::endl; 00081 } 00082 else 00083 { 00084 // Load it 00085 //m_materialPtr->load(); 00086 00087 // Write info 00088 std::cerr << "Material " << groupName << ":" << materialName << " loaded..." << std::endl; 00089 std::cerr << "Num of techniques: " << m_materialPtr->getNumTechniques() << std::endl; 00090 m_materialPtr->getTechnique(0); 00091 } 00092 00093 std::cerr << "Listener constructor 1 done" << std::endl; 00094 } 00095 */ 00096 00100 srs_ui_but::CMaterialListener::CMaterialListener( Ogre::Material * material, const std::string & schemeName ) 00101 : m_materialPtr( material ) 00102 , m_schemeName( schemeName ) 00103 , m_bDistanceChanged( true ) 00104 , m_bMatricesChanged( true ) 00105 , m_testingDistance( 1.0 ) 00106 { 00107 return; 00108 00109 // std::cerr << "Listener constructor 2" << std::endl; 00110 00111 // Test if success 00112 if( m_materialPtr == 0 ) 00113 { 00114 std::cerr << "Cannot get material..." << std::endl; 00115 } 00116 else 00117 { 00118 // Load it 00119 //m_materialPtr->load(); 00120 00121 // Write info 00122 // std::cerr << "Material assigned..." << std::endl; 00123 // std::cerr << "Num of techniques: " << m_materialPtr->getNumTechniques() << std::endl; 00124 m_materialPtr->getTechnique(0); 00125 } 00126 00127 // std::cerr << "Listener constructor 2 done" << std::endl; 00128 } 00129 00133 srs_ui_but::CMaterialListener::~CMaterialListener() 00134 { 00135 // m_materialPtr->removeAllTechniques(); 00136 // m_materialPtr->unload(); 00137 // m_materialPtr.setNull(); 00138 } 00139 00143 Ogre::Technique *srs_ui_but::CMaterialListener::handleSchemeNotFound(unsigned short, const Ogre::String& schemeName, Ogre::Material*mat, unsigned short, const Ogre::Renderable*) 00144 { 00145 if (schemeName == m_schemeName) 00146 { 00147 00148 boost::mutex::scoped_lock lock(m_lock); 00149 00150 // Change shader settings? 00151 if( m_bDistanceChanged ) 00152 { 00153 m_bDistanceChanged = false; 00154 00155 00156 Ogre::GpuProgramParametersSharedPtr paramsFP( m_materialPtr->getBestTechnique()->getPass(0)->getFragmentProgramParameters() ); 00157 00158 if( paramsFP->_findNamedConstantDefinition("testedDistance")) 00159 { 00160 paramsFP->setNamedConstant( "testedDistance", m_testingDistance ); 00161 } 00162 else 00163 { 00164 std::cerr << "Named constant not found: projectionMatrix " << std::endl; 00165 } 00166 00167 } 00168 00169 if( m_bMatricesChanged ) 00170 { 00171 m_bMatricesChanged = false; 00172 00173 // Set vertex program parameters 00174 Ogre::GpuProgramParametersSharedPtr paramsVP( m_materialPtr->getTechnique(0)->getPass(0)->getVertexProgramParameters() ); 00175 00176 00177 if( paramsVP->_findNamedConstantDefinition("texViewProjMatrix")) 00178 { 00179 paramsVP->setNamedConstant( "texViewProjMatrix", m_projMatrix ); 00180 } 00181 else 00182 { 00183 std::cerr << "Named constant not found..." << std::endl; 00184 } 00185 00186 if( paramsVP->_findNamedConstantDefinition("cameraPosition")) 00187 { 00188 paramsVP->setNamedConstant( "cameraPosition", m_camPosition ); 00189 } 00190 else 00191 { 00192 std::cerr << "Named constant not found: cameraPosition " << std::endl; 00193 } 00194 00195 if( paramsVP->_findNamedConstantDefinition("cameraPlane")) 00196 { 00197 paramsVP->setNamedConstant( "cameraPlane", m_camPlane ); 00198 } 00199 else 00200 { 00201 std::cerr << "Named constant not found: cameraPlane " << std::endl; 00202 } 00203 } 00204 00205 //LogManager::getSingleton().logMessage(">> adding glow to material: "+mat->getName()); 00206 return m_materialPtr->getBestTechnique(); 00207 } 00208 return NULL; 00209 } 00210 00214 void srs_ui_but::CMaterialListener::setTestedDistance( float distance ) 00215 { 00216 boost::mutex::scoped_lock lock(m_lock); 00217 00218 ROS_INFO("Setting new projection tested distance: %f", distance ); 00219 m_bDistanceChanged = true; 00220 m_testingDistance = distance; 00221 } 00222 00224 void srs_ui_but::CMaterialListener::setCameraPosition( const Ogre::Vector4 & position, const Ogre::Vector4 & camPlane, const Ogre::Matrix4 & projMatrix ) 00225 { 00226 boost::mutex::scoped_lock lock(m_lock); 00227 m_camPosition = position; 00228 m_camPlane = camPlane; 00229 m_projMatrix = projMatrix; 00230 m_bMatricesChanged = true; 00231 } 00232 00234 00235 00239 srs_ui_but::CProjectionData::CProjectionData( Ogre::SceneManager * manager, const ros::NodeHandle &nh, const std::string & materialName, const std::string & groupName ) 00240 : m_texW( 512 ) 00241 , m_texH( 512 ) 00242 , m_mode( TM_ROS ) 00243 , m_manager( manager ) 00244 { 00245 m_materialListener = 0; 00246 00247 // std::cerr << "CProjectionData constructor" << std::endl; 00248 00249 // Create frustum and projector node 00250 m_frustum = new Ogre::Frustum(); 00251 m_frustum->setNearClipDistance( 0.8 ); 00252 00253 m_projectorNode = manager->getRootSceneNode()->createChildSceneNode("DecalProjectorNode"); 00254 m_projectorNode->attachObject(m_frustum); 00255 m_projectorNode->setPosition(0,5,0); 00256 00257 00258 // Create ros textures 00259 m_textureRosRGB = new tRosTextureRGB( nh, "rgb_texture", "rgb8" ); 00260 assert( m_textureRosRGB != 0 ); 00261 m_textureRosDepth = new tRosTextureDepth( nh, "depth_texture", DEFAULT_DEPTH_IMAGE_TOPIC_NAME, "32FC4" ); 00262 assert( m_textureRosDepth != 0 ); 00263 00264 // Create and init material 00265 m_materialPtr = (Ogre::MaterialPtr)Ogre::MaterialManager::getSingleton().getByName(materialName, groupName); 00266 m_materialPtr->load(); 00267 // std::cerr << "Num of techniques: " << m_materialPtr->getNumTechniques() << std::endl; 00268 m_materialPtr->getTechnique(0)->setLightingEnabled(false); 00269 00270 Ogre::Pass *pass = m_materialPtr->getTechnique(0)->getPass(0); 00271 00272 pass->setSceneBlending(Ogre::SBT_TRANSPARENT_ALPHA); 00273 pass->setDepthBias(1); 00274 pass->setLightingEnabled(false); 00275 00276 // Connect rgb texture and material 00277 m_texState = pass->createTextureUnitState(m_textureRosRGB->getTexture()->getName()); 00278 m_texState->setTextureAddressingMode(Ogre::TextureUnitState::TAM_CLAMP); 00279 m_texState->setTextureFiltering(Ogre::FO_POINT, Ogre::FO_LINEAR, Ogre::FO_NONE); 00280 00281 Ogre::LayerBlendOperationEx op = Ogre::LBX_MODULATE; 00282 m_texState->setColourOperationEx(op, Ogre::LBS_TEXTURE, Ogre::LBS_TEXTURE); 00283 00284 // Connect Depth texture and material 00285 m_texState = pass->createTextureUnitState(m_textureRosDepth->getTexture()->getName()); 00286 m_texState->setDesiredFormat( Ogre::PF_FLOAT32_RGB ); 00287 m_texState->setTextureAddressingMode(Ogre::TextureUnitState::TAM_CLAMP); 00288 m_texState->setTextureFiltering(Ogre::FO_POINT, Ogre::FO_LINEAR, Ogre::FO_NONE); 00289 00290 m_texState->setColourOperationEx(op, Ogre::LBS_TEXTURE, Ogre::LBS_TEXTURE); 00291 00292 updateMatrices(); 00293 00294 // std::cerr << "CProjectionData constructor done" << std::endl; 00295 00296 00297 } 00298 00303 00304 srs_ui_but::CProjectionData::~CProjectionData() 00305 { 00306 // std::cerr << "CProjection data destructor start." << std::endl; 00307 // m_material->unload(); 00308 //Ogre::MaterialManager::getSingleton().remove( m_material->getHandle() ); 00309 // Ogre::MaterialManager::getSingleton().remove( m_material->getName() ); 00310 00311 // m_projectorNode->detachAllObjects(); 00312 m_manager->destroySceneNode( m_projectorNode ); 00313 00314 // Remove all 00315 delete m_textureRosDepth; 00316 delete m_textureRosRGB; 00317 // delete m_projectorNode; m_projectorNode = 0; 00318 delete m_frustum; 00319 00320 // std::cerr << "CProjection data destructor end." << std::endl; 00321 } 00322 00326 void srs_ui_but::CProjectionData::setFrustrumSize( Ogre::Vector2 size ) 00327 { 00328 if( size.y == 0 ) 00329 return; // wrong size 00330 00331 if( m_frustrumSize != size ) 00332 { 00333 m_frustrumSize = size; 00334 00335 m_frustum->setAspectRatio( size.x / size.y ); 00336 00337 m_frustum->setOrthoWindowHeight( size.y ); 00338 } 00339 00340 // Update projection matrix 00341 updateMatrices(); 00342 } 00343 00347 void srs_ui_but::CProjectionData::setRGBTextureTopic( const std::string & topic ) 00348 { 00349 if( m_mode == TM_ROS && m_textureRosRGB != 0 ) 00350 { 00351 m_textureRosRGB->setTopic( topic ); 00352 } 00353 } 00354 00358 void srs_ui_but::CProjectionData::setDepthTextureTopic( const std::string & topic ) 00359 { 00360 if( m_mode == TM_ROS && m_textureRosDepth != 0 ) 00361 { 00362 m_textureRosDepth->setTopic( topic ); 00363 00364 // std::cerr << std::endl << "Depth texture topic set: " << m_textureRosDepth->getTopic() << std::endl; 00365 } 00366 } 00367 00371 void srs_ui_but::CProjectionData::clear() 00372 { 00373 if( m_textureRosRGB != 0 ) 00374 m_textureRosRGB->clear(); 00375 00376 if( m_textureRosDepth != 0 ) 00377 m_textureRosDepth->clear(); 00378 } 00379 00380 00382 void srs_ui_but::CProjectionData::updateMatrices() 00383 { 00384 00385 if( m_materialPtr.get() == 0 ) 00386 return; 00387 /* 00388 Ogre::Matrix4 wt; 00389 00390 // std::cerr << "SetProjectionMatrix" << std::endl; 00391 00392 // Get camera to world matrix 00393 { 00394 tf::StampedTransform tfTransform; 00395 00396 // Get transform 00397 try { 00398 // Transformation - to, from, time, waiting time 00399 m_tfListener.waitForTransform("/map", "/head_cam3d_link", 00400 ros::Time(0), ros::Duration(5)); 00401 00402 m_tfListener.lookupTransform("/map", "/head_cam3d_link", 00403 ros::Time(0), tfTransform); 00404 00405 } catch (tf::TransformException& ex) { 00406 ROS_ERROR_STREAM("Transform error: " << ex.what() << ", quitting callback"); 00407 // PERROR( "Transform error."); 00408 return; 00409 } 00410 00411 Eigen::Matrix4f trMatrix; 00412 00413 // Get transformation matrix 00414 pcl_ros::transformAsMatrix(tfTransform, trMatrix); // Sensor TF to defined base TF 00415 00416 for( int i = 0; i < 4; ++i) 00417 for( int j = 0; j < 4; ++j) 00418 { 00419 wt[i][j] = trMatrix(i, j); 00420 } 00421 } 00422 */ 00423 00424 00425 00426 00427 Ogre::Matrix4 pm( Ogre::Matrix4::CLIPSPACE2DTOIMAGESPACE * m_frustum->getProjectionMatrixWithRSDepth() ); 00428 00429 // Compute projection matrix. CLIPSPACE2DTOIMAGESPACE: Useful little matrix which takes 2D clipspace {-1, 1} to {0,1} and inverts the Y. 00430 Ogre::Matrix4 fm( pm * m_frustum->getViewMatrix() ); 00431 00432 00433 // m_frustum->getWorldTransforms( &wt ); 00434 00435 // std::cerr << "WT:" << std::endl << wt << std::endl; 00436 00437 m_textureRosDepth->setMatrix( pm ); 00438 //m_textureRosDepth->setCameraModel( m_camera_model ); 00439 00440 // Set parameters to the material listener 00441 if( m_materialListener != 0 ) 00442 { 00443 Ogre::Vector4 position( m_cameraPosition[0], m_cameraPosition[1], m_cameraPosition[2], 1.0 ); 00444 Ogre::Vector4 plane( m_cameraEquation[0], m_cameraEquation[1], m_cameraEquation[2], m_cameraEquation[3] ); 00445 m_materialListener->setCameraPosition( position, plane, fm ); 00446 } 00447 } 00448 00449 00450 00452 00453 /* 00454 * Constructor 00455 */ 00456 srs_ui_but::CButProjection::CButProjection(const std::string & name,rviz::VisualizationManager * manager) 00457 : Display( name, manager ) 00458 , m_pane( 0 ) 00459 , m_projectionData( 0 ) 00460 , m_camera_info_topic( CAMERA_INFO_TOPIC_NAME ) 00461 , m_ml(0) 00462 , m_bMLConnected( false ) 00463 , m_bCameraInitialized(false) 00464 { 00465 // std::cerr << "CButProjection::CButProjection S" << std::endl; 00466 00467 // Create and connect pane 00468 rviz::WindowManagerInterface * wi( manager->getWindowManager() ); 00469 00470 if( wi != 0 ) 00471 { 00472 // Arm manipulation controls 00473 m_pane = new CControllPane( wi->getParentWindow(), wxT("Material test"), wi); 00474 00475 if( m_pane != 0 ) 00476 { 00477 wi->addPane( "Material test", m_pane ); 00478 wi->showPane( m_pane ); 00479 00480 // Connect signal 00481 m_pane->getSigChckBox().connect( boost::bind( &CButProjection::onPublishStateChanged, this, _1) ); 00482 m_pane->getSigSave().connect( boost::bind( &CButProjection::onSave, this, _1 ) ); 00483 } 00484 00485 }else{ 00486 std::cerr << "No window manager, no panes :( " << std::endl; 00487 } 00488 00489 00490 // Get node handle 00491 ros::NodeHandle private_nh("/"); 00492 00493 // Set parameters 00494 00495 // Get image input topic names 00496 private_nh.param("rgb_image_input_topic", m_imageRGBInputTopicName, DEFAULT_IMAGE_INPUT_TOPIC_NAME ); 00497 private_nh.param("depth_image_input_topic", m_imageDepthInputTopicName, DEFAULT_DEPTH_IMAGE_TOPIC_NAME ); 00498 00499 // Get timer period 00500 private_nh.param("publishig_period", m_timerPeriod, DEFAULT_PUBLISHING_PERIOD ); 00501 00502 // Get scene node 00503 m_sceneNode = scene_manager_->getRootSceneNode()->createChildSceneNode(); 00504 00505 // Add camera info subscriber 00506 m_ciSubscriber = new message_filters::Subscriber< sensor_msgs::CameraInfo >(private_nh, m_camera_info_topic, 10 ); 00507 00508 //*m_ciSubscriber = private_nh.subscribe( m_camera_info_topic, 10, &srs_ui_but::CButProjection::cameraInfoCB, this ); 00509 00510 00511 // initializing of listeners for tf transformation and tf message filter 00512 m_tf_cam_info_Listener = new tf::TransformListener(); 00513 m_camInfoTransformFilter = new tf::MessageFilter<sensor_msgs::CameraInfo>(*m_ciSubscriber, 00514 *m_tf_cam_info_Listener, "/map", 10); 00515 00516 m_camInfoTransformFilter->registerCallback( boost::bind( &srs_ui_but::CButProjection::cameraInfoCB, this, _1 )); 00517 00518 // Create geometry 00519 createGeometry(private_nh); 00520 00521 // Create publishing timer 00522 m_timer = private_nh.createTimer( ros::Duration(m_timerPeriod), boost::bind( &srs_ui_but::CButProjection::onTimerPublish, this, _1) ); 00523 00524 m_timer.start(); 00525 00526 // std::cerr << "CButProjection::CButProjection E" << std::endl; 00527 00528 } 00529 00530 /* 00531 * Destructor 00532 */ 00533 srs_ui_but::CButProjection::~CButProjection() 00534 { 00535 00536 // std::cerr << "CButProjection destructor start." << std::endl; 00537 00538 lockRender(); 00539 00540 m_timer.stop(); 00541 00542 // Unsubscribe from topics 00543 unsubscribe(); 00544 m_ciSubscriber->unsubscribe(); 00545 00546 // Destroy all geometry 00547 destroyGeometry(); 00548 00549 // Destroy materials 00550 removeMaterials(); 00551 00552 unlockRender(); 00553 00554 // std::cerr << "CButProjection destructor end." << std::endl; 00555 00556 } 00557 00558 00559 /* 00560 * Display enabled callback 00561 */ 00562 void srs_ui_but::CButProjection::onEnable() 00563 { 00564 m_sceneNode->setVisible( true ); 00565 connectML( true ); 00566 } 00567 00568 /* 00569 * Display disabled callback 00570 */ 00571 void srs_ui_but::CButProjection::onDisable() 00572 { 00573 m_sceneNode->setVisible( false ); 00574 connectML( false ); 00575 } 00576 00580 void srs_ui_but::CButProjection::createProperties() 00581 { 00582 m_rgb_topic_property = property_manager_->createProperty<rviz::ROSTopicStringProperty>( "RGB image Topic", property_prefix_, boost::bind( &CButProjection::getRgbTopic, this ), 00583 boost::bind( &CButProjection::setRgbTopic, this, _1 ), parent_category_, this ); 00584 00585 m_depth_topic_property = property_manager_->createProperty<rviz::ROSTopicStringProperty>( "Depth image Topic", property_prefix_, boost::bind( &CButProjection::getDepthTopic, this ), 00586 boost::bind( &CButProjection::setDepthTopic, this, _1 ), parent_category_, this ); 00587 00588 m_distance_property = property_manager_->createProperty<rviz::FloatProperty>( "Tested distance", property_prefix_, boost::bind( &CButProjection::getTestedDistance, this ), 00589 boost::bind( &CButProjection::setTestedDistance, this, _1), parent_category_, this ); 00590 00591 // Set distance limits 00592 rviz::FloatPropertyPtr distp( m_distance_property.lock()); 00593 distp->setMin( 0.0 ); distp->setMax( 10.0 ); 00594 00595 setPropertyHelpText(m_rgb_topic_property, "sensor_msgs::Image topic to subscribe to."); 00596 rviz::ROSTopicStringPropertyPtr topic_prop = m_rgb_topic_property.lock(); 00597 topic_prop->setMessageType(ros::message_traits::datatype<sensor_msgs::Image>()); 00598 00599 // Set topics 00600 setRgbTopic( m_imageRGBInputTopicName ); 00601 setDepthTopic( m_imageDepthInputTopicName ); 00602 00603 } 00604 00608 void srs_ui_but::CButProjection::subscribe() 00609 { 00610 if( m_projectionData != 0 ) 00611 { 00612 m_projectionData->setRGBTextureTopic(m_imageRGBInputTopicName); 00613 m_projectionData->setDepthTextureTopic(m_imageDepthInputTopicName); 00614 } 00615 00616 if ( !isEnabled() ) 00617 { 00618 return; 00619 } 00620 00621 00622 } 00623 00627 void srs_ui_but::CButProjection::unsubscribe() 00628 { 00629 if( m_projectionData != 0 ) 00630 { 00631 m_projectionData->setRGBTextureTopic(""); 00632 m_projectionData->setDepthTextureTopic(""); 00633 } 00634 } 00635 00639 void srs_ui_but::CButProjection::setRgbTopic( const std::string& topic ) 00640 { 00641 unsubscribe(); 00642 00643 m_imageRGBInputTopicName = topic; 00644 clear(); 00645 00646 subscribe(); 00647 00648 propertyChanged(m_rgb_topic_property); 00649 } 00650 00654 void srs_ui_but::CButProjection::setDepthTopic( const std::string& topic ) 00655 { 00656 unsubscribe(); 00657 00658 m_imageDepthInputTopicName = topic; 00659 clear(); 00660 00661 subscribe(); 00662 00663 propertyChanged(m_depth_topic_property); 00664 } 00665 00669 void srs_ui_but::CButProjection::clear() 00670 { 00671 if( m_projectionData != 0 ) 00672 { 00673 m_projectionData->clear(); 00674 } 00675 00676 setStatus(rviz::status_levels::Warn, "Image", "No Image received"); 00677 } 00678 00682 void srs_ui_but::CButProjection::createMaterials(Ogre::Camera * camera) 00683 { 00684 // std::cerr << "CButProjection::createMaterials S" << std::endl; 00685 00686 00687 // std::cerr << "1" << std::endl; 00688 00689 // Load materials 00690 // Ogre::String nameOfResourceGroup( "MaterialGroup1" ); 00691 { 00692 // Create resource group 00693 Ogre::ResourceGroupManager& lRgMgr = Ogre::ResourceGroupManager::getSingleton(); 00694 // lRgMgr.createResourceGroup(nameOfResourceGroup); 00695 00696 // std::cerr << "2" << std::endl; 00697 00698 // Get path 00699 std::string package_path( ros::package::getPath("srs_ui_but") ); 00700 00701 ogre_tools::V_string paths; 00702 Ogre::String resource_path(package_path + "/src/but_display/materials"); 00703 00704 // std::cerr << "3" << std::endl; 00705 00706 // std::cerr << "Materials path: " << resource_path.c_str() << std::endl; 00707 00708 // std::cerr << "Exisist: " << lRgMgr.resourceGroupExists("srs_ui_but") << std::endl; 00709 00710 if( ! lRgMgr.resourceGroupExists("srs_ui_but")) 00711 { 00712 // std::cerr << "Creating resource group: srs_ui_but" << std::endl; 00713 lRgMgr.createResourceGroup("srs_ui_but"); 00714 } 00715 00716 // std::cerr << "4" << std::endl; 00717 00718 if( ! lRgMgr.isResourceGroupInitialised("srs_ui_but") ) 00719 { 00720 // std::cerr << "Initializing resource group: srs_ui_but" << std::endl; 00721 lRgMgr.addResourceLocation(resource_path, "FileSystem", "srs_ui_but"); 00722 lRgMgr.initialiseResourceGroup("srs_ui_but"); 00723 } 00724 00725 if( ! lRgMgr.isResourceGroupLoaded("srs_ui_but") ) 00726 { 00727 // std::cerr << "Loading resource group: srs_ui_but" << std::endl; 00728 lRgMgr.addResourceLocation(resource_path, "FileSystem", "srs_ui_but"); 00729 lRgMgr.loadResourceGroup("srs_ui_but"); 00730 } 00731 00732 00733 // std::cerr << "5" << std::endl; 00734 00735 // std::cerr << "Loaded materials: " << std::endl; 00736 /* 00737 00738 // Get material manager 00739 Ogre::MaterialManager& lMaterialManager = Ogre::MaterialManager::getSingleton(); 00740 00741 // List loaded materials 00742 Ogre::ResourceManager::ResourceMapIterator materialIterator = lMaterialManager.getResourceIterator(); 00743 00744 // Write materials 00745 int count(0); 00746 while (materialIterator.hasMoreElements()) 00747 { 00748 00749 Ogre::String name( (static_cast<Ogre::MaterialPtr>(materialIterator.peekNextValue()))->getName() ); 00750 00751 std::cerr << name << std::endl; 00752 00753 materialIterator.moveNext(); 00754 count++; 00755 } 00756 00757 std::cerr << "Num of materials: " << count << std::endl; 00758 //*/ 00759 } 00760 00761 00762 // Load compositor 00763 { 00764 if( Ogre::CompositorManager::getSingleton().addCompositor(camera->getViewport(), "zTestedProjection") == 0 ) 00765 { 00766 std::cerr << "COMPOSITOR FAILED TO LOAD." << std::endl; 00767 } 00768 else 00769 { 00770 Ogre::CompositorManager::getSingleton().setCompositorEnabled(camera->getViewport(), "zTestedProjection", true); 00771 00772 // std::cerr << "Creating Projection data" << std::endl; 00773 00775 m_projectionData = new CProjectionData( scene_manager_, update_nh_, "tested_projection", "srs_ui_but" ); 00776 00777 // std::cerr << "Projection data done. Running CMaterialListener" << std::endl; 00778 00779 // Create material listener 00780 m_ml = new CMaterialListener( m_projectionData->getMaterialPtr(), "myscheme" ); 00781 m_projectionData->setListenerPtr( m_ml ); 00782 connectML( true ); 00783 00784 } 00785 } 00786 //*/ 00787 // std::cerr << "CButProjection::createMaterials E" << std::endl; 00788 } 00789 00791 void srs_ui_but::CButProjection::removeMaterials() 00792 { 00793 connectML(false); 00794 00795 // std::cerr << "Removing compositior" << std::endl; 00796 00797 // Get camera and discard compositor. 00798 rviz::RenderPanel * panel = vis_manager_->getRenderPanel(); 00799 if( panel != 0 ) 00800 { 00801 Ogre::Camera * camera = panel->getCamera(); 00802 00803 Ogre::CompositorManager::getSingleton().setCompositorEnabled(camera->getViewport(), "zTestedProjection", false); 00804 Ogre::CompositorManager::getSingleton().removeCompositor( camera->getViewport(), "zTestedProjection" ); 00805 } 00806 00807 00808 // std::cerr << m_projectionData->getMaterialPtr() << std::endl; 00809 // std::cerr << "Removing listener" << std::endl; 00810 delete m_ml; 00811 00812 // std::cerr << m_projectionData->getMaterialPtr() << std::endl; 00813 // std::cerr << "Removing projection data " << std::endl; 00814 if( m_projectionData != 0 ) 00815 { 00816 delete m_projectionData; 00817 } 00818 00819 // std::cerr << m_projectionData->getMaterialPtr() << std::endl; 00820 00821 // std::cerr << "Destroying resource groups." << std::endl; 00822 00823 // Ogre::String nameOfResourceGroup( "MaterialGroup1" ); 00824 Ogre::ResourceGroupManager& lRgMgr = Ogre::ResourceGroupManager::getSingleton(); 00825 //Ogre::MaterialManager &mMgr = Ogre::MaterialManager::getSingleton(); 00826 00827 // std::cerr << "RG: srs_ui_but. Status: " << lRgMgr.isResourceGroupInGlobalPool( "srs_ui_but" ) << ", " << lRgMgr.isResourceGroupInitialised("srs_ui_but") << ", " << lRgMgr.isResourceGroupLoaded("srs_ui_but") << std::endl; 00828 00829 // lRgMgr.unloadResourceGroup("srs_ui_but"); 00830 lRgMgr.destroyResourceGroup("srs_ui_but"); 00831 // lRgMgr.clearResourceGroup(nameOfResourceGroup); 00832 00833 // std::cerr << "RG: " << nameOfResourceGroup << std::endl; 00834 00835 // lRgMgr.destroyResourceGroup( nameOfResourceGroup ); 00836 00837 00838 } 00839 00840 00841 void srs_ui_but::CButProjection::connectML( bool bConnect ) 00842 { 00843 if( bConnect == m_bMLConnected || m_ml == 0 ) 00844 return; 00845 00846 if( bConnect ) 00847 { 00848 Ogre::MaterialManager::getSingleton().addListener( m_ml ); 00849 // std::cerr << "AAA: Listener added..." << std::endl; 00850 } 00851 else 00852 { 00853 Ogre::MaterialManager::getSingleton().removeListener( m_ml ); 00854 // std::cerr << "AAA: Listener removed..." << std::endl; 00855 } 00856 00857 m_bMLConnected = bConnect; 00858 } 00859 00860 /* 00861 * Create geometry 00862 */ 00863 bool srs_ui_but::CButProjection::createGeometry(const ros::NodeHandle & nh) 00864 { 00865 // std::cerr << "CButProjection::createGeometry S" << std::endl; 00866 00867 // Get camera. 00868 rviz::RenderPanel * panel = vis_manager_->getRenderPanel(); 00869 if( panel == 0 ) 00870 { 00871 ROS_DEBUG( "No render panel... "); 00872 return false; 00873 } 00874 00875 Ogre::Camera * camera = panel->getCamera(); 00876 00877 // Create rtt texture 00878 //m_textureWithRtt = new CRosRttTexture( 512, 512, camera ); 00879 00880 /* 00881 Ogre::String lNameOfTheMesh = "MeshCube"; 00882 { 00883 // Here, I create a 3D element, by using the interface of ManualObject. 00884 // ManualObject is very close to the opengl old simple way to specify geometry. 00885 // There are other interfaces (Hardwarebuffers), you can check the ogremanual fo them and wiki. 00886 // For each vertex I will provide positions and attributes (normal, vertex color, texture coordinates...). 00887 // Then for each primitive (given its type : triangle, line, line strip etc...), 00888 // I give the corresponding group of vertex index. 00889 Ogre::ManualObject* lManualObject = NULL; 00890 { 00891 // The manualObject creation requires a name. 00892 Ogre::String lManualObjectName = "CubeWithAxes"; 00893 lManualObject = scene_manager_->createManualObject(lManualObjectName); 00894 00895 // Always tell if you want to update the 3D (vertex/index) later or not. 00896 bool lDoIWantToUpdateItLater = false; 00897 lManualObject->setDynamic(lDoIWantToUpdateItLater); 00898 00899 // Here I create a cube in a first part with triangles, and then axes (in red/green/blue). 00900 00901 // BaseWhiteNoLighting is the name of a material that already exist inside Ogre. 00902 // Ogre::RenderOperation::OT_TRIANGLE_LIST is a kind of primitive. 00903 float lSize = 5.0f; 00904 lManualObject->begin("BaseWhiteNoLighting", Ogre::RenderOperation::OT_TRIANGLE_LIST); 00905 { 00906 float cp = 1.0f * lSize ; 00907 float cm = -1.0f * lSize; 00908 00909 lManualObject->position(cm, cp, cm);// a vertex 00910 lManualObject->colour(Ogre::ColourValue(0.0f,1.0f,0.0f,1.0f)); 00911 lManualObject->textureCoord(0.0, 1.0); 00912 lManualObject->position(cp, cp, cm);// a vertex 00913 lManualObject->colour(Ogre::ColourValue(1.0f,1.0f,0.0f,1.0f)); 00914 lManualObject->textureCoord(1.0, 1.0); 00915 lManualObject->position(cp, cm, cm);// a vertex 00916 lManualObject->colour(Ogre::ColourValue(1.0f,0.0f,0.0f,1.0f)); 00917 lManualObject->textureCoord(1.0, 0.0); 00918 lManualObject->position(cm, cm, cm);// a vertex 00919 lManualObject->colour(Ogre::ColourValue(0.0f,0.0f,0.0f,1.0f)); 00920 lManualObject->textureCoord(0.0, 0.0); 00921 00922 lManualObject->position(cm, cp, cp);// a vertex 00923 lManualObject->colour(Ogre::ColourValue(0.0f,1.0f,1.0f,1.0f)); 00924 lManualObject->textureCoord(0.0, 1.0); 00925 lManualObject->position(cp, cp, cp);// a vertex 00926 lManualObject->colour(Ogre::ColourValue(1.0f,1.0f,1.0f,1.0f)); 00927 lManualObject->textureCoord(1.0, 1.0); 00928 lManualObject->position(cp, cm, cp);// a vertex 00929 lManualObject->colour(Ogre::ColourValue(1.0f,0.0f,1.0f,1.0f)); 00930 lManualObject->textureCoord(1.0, 0.0); 00931 lManualObject->position(cm, cm, cp);// a vertex 00932 lManualObject->colour(Ogre::ColourValue(0.0f,0.0f,1.0f,1.0f)); 00933 lManualObject->textureCoord(0.0, 0.0); 00934 00935 // face behind / front 00936 lManualObject->triangle(0,1,2); 00937 lManualObject->triangle(2,3,0); 00938 lManualObject->triangle(4,6,5); 00939 lManualObject->triangle(6,4,7); 00940 00941 // face top / down 00942 lManualObject->triangle(0,4,5); 00943 lManualObject->triangle(5,1,0); 00944 lManualObject->triangle(2,6,7); 00945 lManualObject->triangle(7,3,2); 00946 00947 // face left / right 00948 lManualObject->triangle(0,7,4); 00949 lManualObject->triangle(7,0,3); 00950 lManualObject->triangle(1,5,6); 00951 lManualObject->triangle(6,2,1); 00952 } 00953 lManualObject->end(); 00954 // Here I have finished my ManualObject construction. 00955 // It is possible to add more begin()-end() thing, in order to use 00956 // different rendering operation types, or different materials in 1 ManualObject. 00957 } 00958 00959 lManualObject->convertToMesh(lNameOfTheMesh, Ogre::ResourceGroupManager::DEFAULT_RESOURCE_GROUP_NAME); 00960 00961 // Now I can create several entities using that mesh 00962 int lNumberOfEntities = 1; 00963 for(int iter = 0; iter < lNumberOfEntities; ++iter) 00964 { 00965 Ogre::Entity* lEntity = scene_manager_->createEntity(lNameOfTheMesh); 00966 // Now I attach it to a scenenode, so that it becomes present in the scene. 00967 Ogre::SceneNode* lNode = scene_manager_->getRootSceneNode()->createChildSceneNode(); 00968 lNode->attachObject(lEntity); 00969 // I move the SceneNode so that it is visible to the camera. 00970 float lPositionOffset = float(1+ iter * 5.0) - (float(lNumberOfEntities)); 00971 lNode->translate(lPositionOffset, lPositionOffset, -10.0f); 00972 } 00973 } 00974 00975 // Create entity on screen 00976 00977 Ogre::Entity* lAdditionalEntity = scene_manager_->createEntity( lNameOfTheMesh ); 00978 // lAdditionalEntity->setMaterialName( m_textureWithRtt->getMaterialName() ); 00979 Ogre::SceneNode* lVisibleOnlyByFirstCam = scene_manager_->getRootSceneNode()->createChildSceneNode(); 00980 lVisibleOnlyByFirstCam->attachObject( lAdditionalEntity ); 00981 lVisibleOnlyByFirstCam->setPosition( 1.5,-0.5,-5); 00982 //*/ 00983 00984 // Create and initialize materials 00985 createMaterials( camera ); 00986 00987 // std::cerr << "CButProjection::createGeometry E" << std::endl; 00988 00989 return true; 00990 } 00991 00992 void srs_ui_but::CButProjection::destroyGeometry() 00993 { 00994 // Destroy scene 00995 if( m_sceneNode != 0 ) 00996 scene_manager_->destroySceneNode(m_sceneNode->getName()); 00997 } 00998 01000 void srs_ui_but::CButProjection::update (float wall_dt, float ros_dt) 01001 { 01002 rviz::RenderPanel * panel = vis_manager_->getRenderPanel(); 01003 if( panel == 0 ) 01004 { 01005 ROS_DEBUG( "No render panel... "); 01006 } 01007 01008 Ogre::Camera * camera = panel->getCamera(); 01009 01010 if( camera == 0 ) 01011 { 01012 ROS_DEBUG( "No camera "); 01013 } 01014 01015 try 01016 { 01017 if( m_projectionData != 0 ) 01018 { 01019 m_projectionData->update(); 01020 } 01021 } 01022 catch (UnsupportedImageEncoding& e) 01023 { 01024 setStatus(rviz::status_levels::Error, "Image", e.what()); 01025 } 01026 } 01027 01028 /* 01029 * Timer publishing callback function 01030 */ 01031 01032 void srs_ui_but::CButProjection::onTimerPublish(const ros::TimerEvent&) 01033 { 01034 01035 // m_projectionData->fillTexture( 255 - m_c, 128 + m_c, m_c ); 01036 // ++m_c; 01037 /* 01038 if( m_bPublish && (m_camCastPublisher.getNumSubscribers() > 0 ) && m_textureWithRtt->hasData() ) 01039 { 01040 // Publish image 01041 m_camCastPublisher.publish( m_textureWithRtt->getImage() ); 01042 } 01043 */ 01044 } 01045 01046 01050 void srs_ui_but::CButProjection::onPublishStateChanged(bool state) 01051 { 01052 01053 if( state ) 01054 { 01055 m_timer.start(); 01056 } 01057 else 01058 m_timer.stop(); 01059 } 01060 01064 void srs_ui_but::CButProjection::onSave( std::string filename ) 01065 { 01066 // m_textureWithRtt->saveImage( filename ); 01067 } 01068 01069 01070 void srs_ui_but::CButProjection::cameraInfoCB(const sensor_msgs::CameraInfo::ConstPtr &cam_info) 01071 { 01072 // std::cerr << "Camera callback. Frame id: " << cam_info->header.frame_id << std::endl; 01073 01074 boost::mutex::scoped_lock( m_cameraInfoLock ); 01075 01076 // Get camera info 01077 ROS_DEBUG("OctMapPlugin: Set camera info: %d x %d\n", cam_info->height, cam_info->width); 01078 if( !m_camera_model.fromCameraInfo(*cam_info) ) 01079 return; 01080 01081 m_camera_size = m_camera_model.fullResolution(); 01082 01083 Ogre::Vector3 position; 01084 Ogre::Quaternion orientation; 01085 if( ! vis_manager_->getFrameManager()->getTransform(cam_info->header, position, orientation) ) 01086 return; 01087 01088 // const cv::Mat_<double> pm( m_camera_model.projectionMatrix() ); 01089 01090 // convert vision (Z-forward) frame to ogre frame (Z-out) 01091 orientation = orientation * Ogre::Quaternion(Ogre::Degree(180), Ogre::Vector3::UNIT_X); 01092 01093 // Get z-axis 01094 Ogre::Vector3 normal( orientation.zAxis() ); 01095 normal.normalise(); 01096 01097 // Compute camera plane equation 01098 Ogre::Vector4 equation( normal.x, normal.y, normal.z, -normal.dotProduct( position) ); 01099 01100 01101 float width = cam_info->width; 01102 float height = cam_info->height; 01103 01104 // Possibly malformed camera info... 01105 if( width == 0.0 || height == 0.0 ) 01106 return; 01107 01108 double fx = cam_info->P[0]; 01109 double fy = cam_info->P[5]; 01110 01111 // Malformed camera info? 01112 if( fx != fx || fy != fy || fx == 0.0 || fy == 0.0 ) 01113 return; 01114 01115 // Add the camera's translation relative to the left camera (from P[3]); 01116 // Tx = -1*(P[3] / P[0]) 01117 double tx = -1.0 * (cam_info->P[3] / fx); 01118 Ogre::Vector3 right = orientation * Ogre::Vector3::UNIT_X; 01119 position = position + (right * tx); 01120 01121 // std::cerr << right * tx << std::endl; 01122 01123 double ty = -1 * (cam_info->P[7] / fy); 01124 Ogre::Vector3 down = orientation * Ogre::Vector3::UNIT_Y; 01125 position = position + (down * ty); 01126 01127 if( !rviz::validateFloats( position )) 01128 { 01129 return; 01130 } 01131 01132 01133 if( m_projectionData != 0 ) 01134 { 01135 m_projectionData->setProjectorPosition( position ); 01136 m_projectionData->setProjectorOrientation( orientation ); 01137 01138 // f.setFOVy( fovX ); 01139 // m_projectionData->setFOVy( fovy ); 01140 // m_projectionData->setAspectRatio( aspect_ratio ); 01141 01142 m_projectionData->setCameraModel( *cam_info ); 01143 m_projectionData->setProjectorEquation( equation ); 01144 m_projectionData->updateMatrices(); 01145 01146 m_bCameraInitialized = true; 01147 } 01148 } 01149 01151 const int ID_CHECKBOX(100); 01152 const int ID_SAVE_BUTTON(101); 01153 01154 srs_ui_but::CButProjection::CControllPane::CControllPane(wxWindow *parent, const wxString& title, rviz::WindowManagerInterface * wmi): wxPanel( parent, wxID_ANY, wxDefaultPosition, wxSize(280, 180), wxTAB_TRAVERSAL, title) 01155 , m_wmi( wmi ) 01156 { 01157 // Create controls 01158 m_button = new wxButton(this, ID_SAVE_BUTTON, wxT("Save screenshot"), wxDefaultPosition, wxDefaultSize, wxBU_EXACTFIT); 01159 01160 m_chkb = new wxCheckBox(this, ID_CHECKBOX, wxT("Publish images"), 01161 wxPoint(20, 20)); 01162 m_chkb->SetValue( true ); 01163 01164 // Create layout 01165 wxSizer *sizer = new wxBoxSizer(wxVERTICAL); 01166 this->SetSizer(sizer); 01167 01168 wxSizer *hsizer = new wxBoxSizer(wxHORIZONTAL); 01169 hsizer->Add(m_chkb, ID_CHECKBOX, wxALIGN_LEFT); 01170 hsizer->Add(m_button, ID_SAVE_BUTTON, wxALIGN_RIGHT); 01171 01172 sizer->Add(hsizer, 0, wxALIGN_LEFT); 01173 01174 sizer->SetSizeHints(this); 01175 01176 01177 } 01178 01180 01184 void srs_ui_but::CButProjection::CControllPane::OnChckToggle(wxCommandEvent& event) 01185 { 01186 // Call signal 01187 m_sigCheckBox( m_chkb->GetValue() ); 01188 } 01189 01191 01195 void srs_ui_but::CButProjection::CControllPane::OnSave(wxCommandEvent& event) 01196 { 01197 wxFileDialog fileDlg(this, _("Choose file to save"), wxEmptyString, _("screenshot.png"), _("*.*"), wxFD_SAVE | wxFD_OVERWRITE_PROMPT ); 01198 01199 wxString filename, directory; 01200 01201 // Pause timer 01202 if(m_chkb->GetValue()) 01203 m_sigCheckBox( false ); 01204 01205 if( fileDlg.ShowModal() == wxID_OK ) 01206 { 01207 filename = fileDlg.GetFilename(); 01208 directory = fileDlg.GetDirectory(); 01209 01210 std::string path(std::string( wxString(directory + wxFileName::GetPathSeparator() + filename).mb_str() ) ); 01211 01212 m_sigSave( path ); 01213 } 01214 01215 // Start timer 01216 if(m_chkb->GetValue()) 01217 m_sigCheckBox( true ); 01218 01219 01220 } 01221 01225 void srs_ui_but::CButProjection::setTestedDistance( float distance ) 01226 { 01227 m_ml->setTestedDistance( distance ); 01228 } 01229 01233 float srs_ui_but::CButProjection::getTestedDistance() 01234 { 01235 return m_ml->getTestedDistance(); 01236 } 01237 01238 01240 BEGIN_EVENT_TABLE(srs_ui_but::CButProjection::CControllPane, wxPanel) 01241 EVT_BUTTON(ID_SAVE_BUTTON, srs_ui_but::CButProjection::CControllPane::OnSave) 01242 EVT_CHECKBOX(ID_CHECKBOX, srs_ui_but::CButProjection::CControllPane::OnChckToggle ) 01243 END_EVENT_TABLE()