$search
00001 /* 00002 * Copyright (c) 2008, Willow Garage, Inc. 00003 * All rights reserved. 00004 * 00005 * Redistribution and use in source and binary forms, with or without 00006 * modification, are permitted provided that the following conditions are met: 00007 * 00008 * * Redistributions of source code must retain the above copyright 00009 * notice, this list of conditions and the following disclaimer. 00010 * * Redistributions in binary form must reproduce the above copyright 00011 * notice, this list of conditions and the following disclaimer in the 00012 * documentation and/or other materials provided with the distribution. 00013 * * Neither the name of the Willow Garage, Inc. nor the names of its 00014 * contributors may be used to endorse or promote products derived from 00015 * this software without specific prior written permission. 00016 * 00017 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 00018 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 00019 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 00020 * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE 00021 * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 00022 * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 00023 * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 00024 * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 00025 * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 00026 * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00027 * POSSIBILITY OF SUCH DAMAGE. 00028 */ 00029 00030 #include "visualization_manager.h" 00031 #include "selection/selection_manager.h" 00032 #include "render_panel.h" 00033 #include "displays_panel.h" 00034 #include "viewport_mouse_event.h" 00035 #include "frame_manager.h" 00036 00037 #include "view_controller.h" 00038 #include "view_controllers/xy_orbit_view_controller.h" 00039 #include "view_controllers/orbit_view_controller.h" 00040 #include "view_controllers/fps_view_controller.h" 00041 #include "view_controllers/fixed_orientation_ortho_view_controller.h" 00042 00043 #include "display.h" 00044 #include "display_wrapper.h" 00045 #include "properties/property_manager.h" 00046 #include "properties/property.h" 00048 00049 #include "tools/tool.h" 00050 #include "tools/move_tool.h" 00051 #include "tools/goal_tool.h" 00052 #include "tools/initial_pose_tool.h" 00053 #include "tools/selection_tool.h" 00054 #include "tools/interaction_tool.h" 00055 00056 #include <ogre_tools/qt_ogre_render_window.h> 00057 00058 #include <tf/transform_listener.h> 00059 00060 #include <ros/package.h> 00061 00062 #include "config.h" 00063 00064 #include <boost/bind.hpp> 00065 00066 #include <OGRE/OgreRoot.h> 00067 #include <OGRE/OgreSceneManager.h> 00068 #include <OGRE/OgreSceneNode.h> 00069 #include <OGRE/OgreLight.h> 00070 #include <OGRE/OgreViewport.h> 00071 #include <OGRE/OgreMaterialManager.h> 00072 #include <OGRE/OgreMaterial.h> 00073 #include <OGRE/OgreRenderWindow.h> 00074 00075 #include <algorithm> 00076 00077 namespace rviz 00078 { 00079 00080 VisualizationManager::VisualizationManager( RenderPanel* render_panel, WindowManagerInterface* wm ) 00081 : ogre_root_( Ogre::Root::getSingletonPtr() ) 00082 , update_timer_(0) 00083 , shutting_down_(false) 00084 , current_tool_( NULL ) 00085 , render_panel_( render_panel ) 00086 , time_update_timer_(0.0f) 00087 , frame_update_timer_(0.0f) 00088 , view_controller_(0) 00089 , render_requested_(1) 00090 , frame_count_(0) 00091 , window_manager_(wm) 00092 , disable_update_(false) 00093 , target_frame_is_fixed_frame_(false) 00094 { 00095 frame_manager_ = FrameManager::instance(); 00096 00097 render_panel->setAutoRender(false); 00098 00099 threaded_nh_.setCallbackQueue(&threaded_queue_); 00100 00101 scene_manager_ = ogre_root_->createSceneManager( Ogre::ST_GENERIC ); 00102 00103 target_scene_node_ = scene_manager_->getRootSceneNode()->createChildSceneNode(); 00104 00105 Ogre::Light* directional_light = scene_manager_->createLight( "MainDirectional" ); 00106 directional_light->setType( Ogre::Light::LT_DIRECTIONAL ); 00107 directional_light->setDirection( Ogre::Vector3( -1, 0, -1 ) ); 00108 directional_light->setDiffuseColour( Ogre::ColourValue( 1.0f, 1.0f, 1.0f ) ); 00109 00110 property_manager_ = new PropertyManager(); 00111 tool_property_manager_ = new PropertyManager(); 00112 00113 CategoryPropertyWPtr options_category = property_manager_->createCategory( ".Global Options", "", CategoryPropertyWPtr(), this ); 00114 target_frame_property_ = property_manager_->createProperty<TFFrameProperty>( "Target Frame", "", boost::bind( &VisualizationManager::getTargetFrame, this ), 00115 boost::bind( &VisualizationManager::setTargetFrame, this, _1 ), options_category, this ); 00116 setPropertyHelpText(target_frame_property_, "Reference frame for the 3D camera view."); 00117 fixed_frame_property_ = property_manager_->createProperty<EditEnumProperty>( "Fixed Frame", "", boost::bind( &VisualizationManager::getFixedFrame, this ), 00118 boost::bind( &VisualizationManager::setFixedFrame, this, _1 ), options_category, this ); 00119 setPropertyHelpText(fixed_frame_property_, "Frame into which all data is transformed before being displayed."); 00120 background_color_property_ = property_manager_->createProperty<ColorProperty>( "Background Color", "", boost::bind( &VisualizationManager::getBackgroundColor, this ), 00121 boost::bind( &VisualizationManager::setBackgroundColor, this, _1 ), options_category, this ); 00122 setPropertyHelpText(background_color_property_, "Background color for the 3D view."); 00123 status_property_ = property_manager_->createStatus(".Global Status", "", CategoryPropertyWPtr(), this); 00124 00125 CategoryPropertyPtr cat_prop = options_category.lock(); 00126 cat_prop->collapse(); 00127 00128 setBackgroundColor(Color(0.0f, 0.0f, 0.0f)); 00129 00130 Ogre::ResourceGroupManager::getSingleton().createResourceGroup(ROS_PACKAGE_NAME ); 00131 00132 createColorMaterials(); 00133 00134 selection_manager_ = new SelectionManager(this); 00135 00136 threaded_queue_threads_.create_thread(boost::bind(&VisualizationManager::threadedQueueThreadFunc, this)); 00137 00138 display_class_loader_ = new pluginlib::ClassLoader<Display>( "rviz_qt", "rviz::Display" ); 00139 } 00140 00141 VisualizationManager::~VisualizationManager() 00142 { 00143 delete update_timer_; 00144 delete idle_timer_; 00145 00146 shutting_down_ = true; 00147 threaded_queue_threads_.join_all(); 00148 00149 if(selection_manager_) 00150 { 00151 selection_manager_->setSelection(M_Picked()); 00152 } 00153 00154 V_DisplayWrapper::iterator it = displays_.begin(); 00155 V_DisplayWrapper::iterator end = displays_.end(); 00156 for (; it != end; ++it) 00157 { 00158 delete *it; 00159 } 00160 displays_.clear(); 00161 00162 V_Tool::iterator tool_it = tools_.begin(); 00163 V_Tool::iterator tool_end = tools_.end(); 00164 for ( ; tool_it != tool_end; ++tool_it ) 00165 { 00166 delete *tool_it; 00167 } 00168 tools_.clear(); 00169 00170 delete display_class_loader_; 00171 delete property_manager_; 00172 delete tool_property_manager_; 00173 00174 delete selection_manager_; 00175 00176 scene_manager_->destroySceneNode( target_scene_node_ ); 00177 00178 if(ogre_root_) 00179 { 00180 ogre_root_->destroySceneManager( scene_manager_ ); 00181 } 00182 } 00183 00184 void VisualizationManager::initialize(const StatusCallback& cb, bool verbose) 00185 { 00186 if(cb) 00187 { 00188 cb("Initializing TF"); 00189 } 00190 00191 setFixedFrame("/map"); 00192 setTargetFrame(FIXED_FRAME_STRING); 00193 00194 render_panel_->getCamera()->setPosition(0, 10, 15); 00195 render_panel_->getCamera()->setNearClipDistance(0.01f); 00196 render_panel_->getCamera()->lookAt(0, 0, 0); 00197 00198 addViewController(XYOrbitViewController::getClassNameStatic(), "XYOrbit"); 00199 addViewController(OrbitViewController::getClassNameStatic(), "Orbit"); 00200 addViewController(FPSViewController::getClassNameStatic(), "FPS"); 00201 addViewController(FixedOrientationOrthoViewController::getClassNameStatic(), "TopDownOrtho"); 00202 setCurrentViewControllerType(OrbitViewController::getClassNameStatic()); 00203 00204 MoveTool *move_tool = createTool< MoveTool >( "Move Camera", 'm' ); 00205 setCurrentTool( move_tool ); 00206 setDefaultTool( move_tool ); 00207 00208 createTool< InteractionTool >( "Interact", 'i' ); 00209 createTool< SelectionTool >( "Select", 's' ); 00210 createTool< GoalTool >( "2D Nav Goal", 'g' ); 00211 createTool< InitialPoseTool >( "2D Pose Estimate", 'p' ); 00212 00213 selection_manager_->initialize( verbose ); 00214 00215 last_update_ros_time_ = ros::Time::now(); 00216 last_update_wall_time_ = ros::WallTime::now(); 00217 } 00218 00219 void VisualizationManager::startUpdate() 00220 { 00221 update_timer_ = new QTimer; 00222 connect( update_timer_, SIGNAL( timeout() ), this, SLOT( onUpdate() )); 00223 update_timer_->start( 33 ); 00224 00225 idle_timer_ = new QTimer; 00226 connect( idle_timer_, SIGNAL( timeout() ), this, SLOT( onIdle() )); 00227 idle_timer_->start( 33 ); 00228 } 00229 00230 void createColorMaterial(const std::string& name, const Ogre::ColourValue& color) 00231 { 00232 Ogre::MaterialPtr mat = Ogre::MaterialManager::getSingleton().create( name, ROS_PACKAGE_NAME ); 00233 mat->setAmbient(color * 0.5f); 00234 mat->setDiffuse(color); 00235 mat->setSelfIllumination(color); 00236 mat->setLightingEnabled(true); 00237 mat->setReceiveShadows(false); 00238 } 00239 00240 void VisualizationManager::createColorMaterials() 00241 { 00242 createColorMaterial("RVIZ/Red", Ogre::ColourValue(1.0f, 0.0f, 0.0f, 1.0f)); 00243 createColorMaterial("RVIZ/Green", Ogre::ColourValue(0.0f, 1.0f, 0.0f, 1.0f)); 00244 createColorMaterial("RVIZ/Blue", Ogre::ColourValue(0.0f, 0.0f, 1.0f, 1.0f)); 00245 createColorMaterial("RVIZ/Cyan", Ogre::ColourValue(0.0f, 1.0f, 1.0f, 1.0f)); 00246 } 00247 00248 void VisualizationManager::getDisplayNames(S_string& displays) 00249 { 00250 V_DisplayWrapper::iterator vis_it = displays_.begin(); 00251 V_DisplayWrapper::iterator vis_end = displays_.end(); 00252 for ( ; vis_it != vis_end; ++vis_it ) 00253 { 00254 displays.insert((*vis_it)->getName()); 00255 } 00256 } 00257 00258 std::string VisualizationManager::getTargetFrame() 00259 { 00260 if(target_frame_is_fixed_frame_) 00261 { 00262 return FIXED_FRAME_STRING; 00263 } 00264 00265 return target_frame_; 00266 } 00267 00268 void VisualizationManager::queueRender() 00269 { 00270 // I believe the QTimer with zero duration (idle_timer_) makes this unnecessary. The timer is always "awake". 00271 // if(!render_requested_) 00272 // { 00273 // w xWakeUpIdle(); 00274 // } 00275 render_requested_ = 1; 00276 } 00277 00278 void VisualizationManager::onUpdate() 00279 { 00280 if(disable_update_) 00281 { 00282 return; 00283 } 00284 00285 disable_update_ = true; 00286 00287 //process pending mouse events 00288 00289 std::deque<ViewportMouseEvent> event_queue; 00290 { 00291 boost::mutex::scoped_lock lock(vme_queue_mutex_); 00292 event_queue.swap( vme_queue_ ); 00293 } 00294 00295 std::deque<ViewportMouseEvent>::iterator event_it; 00296 00297 for ( event_it= event_queue.begin(); event_it!=event_queue.end(); event_it++ ) 00298 { 00299 ViewportMouseEvent &vme = *event_it; 00300 int flags = getCurrentTool()->processMouseEvent(vme); 00301 00302 if( flags & Tool::Render ) 00303 { 00304 queueRender(); 00305 } 00306 00307 if( flags & Tool::Finished ) 00308 { 00309 setCurrentTool( getDefaultTool() ); 00310 } 00311 } 00312 00313 00314 ros::WallTime update_start = ros::WallTime::now(); 00315 00316 ros::WallDuration wall_diff = ros::WallTime::now() - last_update_wall_time_; 00317 ros::Duration ros_diff = ros::Time::now() - last_update_ros_time_; 00318 float wall_dt = wall_diff.toSec(); 00319 float ros_dt = ros_diff.toSec(); 00320 00321 if(ros_dt < 0.0) 00322 { 00323 resetTime(); 00324 } 00325 00326 frame_manager_->update(); 00327 00328 ros::spinOnce(); 00329 00330 last_update_ros_time_ = ros::Time::now(); 00331 last_update_wall_time_ = ros::WallTime::now(); 00332 00333 V_DisplayWrapper::iterator vis_it = displays_.begin(); 00334 V_DisplayWrapper::iterator vis_end = displays_.end(); 00335 for ( ; vis_it != vis_end; ++vis_it ) 00336 { 00337 Display* display = (*vis_it)->getDisplay(); 00338 00339 if( display && display->isEnabled() ) 00340 { 00341 display->update( wall_dt, ros_dt ); 00342 } 00343 } 00344 00345 view_controller_->update(wall_dt, ros_dt); 00346 00347 time_update_timer_ += wall_dt; 00348 00349 if( time_update_timer_ > 0.1f ) 00350 { 00351 time_update_timer_ = 0.0f; 00352 00353 updateTime(); 00354 } 00355 00356 frame_update_timer_ += wall_dt; 00357 00358 if(frame_update_timer_ > 1.0f) 00359 { 00360 frame_update_timer_ = 0.0f; 00361 00362 updateFrames(); 00363 } 00364 00365 selection_manager_->update(); 00366 00367 if(frame_count_ % 6 == 0) 00368 { 00369 property_manager_->update(); 00370 tool_property_manager_->update(); 00371 } 00372 00373 current_tool_->update(wall_dt, ros_dt); 00374 00375 disable_update_ = false; 00376 00377 // I believe the QTimer with zero duration (idle_timer_) makes this unnecessary. The timer is always "awake". 00378 // w xWakeUpIdle(); 00379 } 00380 00381 void VisualizationManager::onIdle() 00382 { 00383 ros::WallTime cur = ros::WallTime::now(); 00384 double dt = (cur - last_render_).toSec(); 00385 00386 if(dt > 0.1f) 00387 { 00388 render_requested_ = 1; 00389 } 00390 00391 // Cap at 60fps 00392 if(render_requested_ && dt > 0.016f) 00393 { 00394 render_requested_ = 0; 00395 last_render_ = cur; 00396 frame_count_++; 00397 00398 boost::mutex::scoped_lock lock(render_mutex_); 00399 00400 // ros::WallTime start = ros::WallTime::now(); 00401 ogre_root_->renderOneFrame(); 00402 // ros::WallTime end = ros::WallTime::now(); 00403 // ros::WallDuration d = end - start; 00404 // ROS_INFO("Render took [%f] msec", d.toSec() * 1000.0f); 00405 } 00406 } 00407 00408 void VisualizationManager::updateTime() 00409 { 00410 if( ros_time_begin_.isZero() ) 00411 { 00412 ros_time_begin_ = ros::Time::now(); 00413 } 00414 00415 ros_time_elapsed_ = ros::Time::now() - ros_time_begin_; 00416 00417 if( wall_clock_begin_.isZero() ) 00418 { 00419 wall_clock_begin_ = ros::WallTime::now(); 00420 } 00421 00422 wall_clock_elapsed_ = ros::WallTime::now() - wall_clock_begin_; 00423 00424 Q_EMIT timeChanged(); 00425 } 00426 00427 void VisualizationManager::updateFrames() 00428 { 00429 typedef std::vector<std::string> V_string; 00430 V_string frames; 00431 frame_manager_->getTFClient()->getFrameStrings( frames ); 00432 std::sort(frames.begin(), frames.end()); 00433 00434 EditEnumPropertyPtr target_prop = target_frame_property_.lock(); 00435 EditEnumPropertyPtr fixed_prop = fixed_frame_property_.lock(); 00436 StatusPropertyPtr status_prop = status_property_.lock(); 00437 ROS_ASSERT(target_prop); 00438 ROS_ASSERT(fixed_prop); 00439 ROS_ASSERT(status_prop); 00440 00441 if(frames != available_frames_) 00442 { 00443 fixed_prop->clear(); 00444 00445 V_string::iterator it = frames.begin(); 00446 V_string::iterator end = frames.end(); 00447 for (; it != end; ++it) 00448 { 00449 const std::string& frame = *it; 00450 00451 if(frame.empty()) 00452 { 00453 continue; 00454 } 00455 00456 fixed_prop->addOption(frame); 00457 } 00458 00459 available_frames_ = frames; 00460 } 00461 00462 // Check the fixed frame to see if it's ok 00463 std::string error; 00464 if(frame_manager_->frameHasProblems(fixed_frame_, ros::Time(), error)) 00465 { 00466 if(frames.empty()) 00467 { 00468 fixed_prop->setToWarn(); 00469 std::stringstream ss; 00470 ss << "No tf data. Actual error: " << error; 00471 status_prop->setStatus(status_levels::Warn, "Fixed Frame", ss.str()); 00472 } 00473 else 00474 { 00475 fixed_prop->setToError(); 00476 status_prop->setStatus(status_levels::Error, "Fixed Frame", error); 00477 } 00478 } 00479 else 00480 { 00481 fixed_prop->setToOK(); 00482 status_prop->setStatus(status_levels::Ok, "Fixed Frame", "OK"); 00483 } 00484 00485 if(frame_manager_->transformHasProblems(target_frame_, ros::Time(), error)) 00486 { 00487 target_prop->setToError(); 00488 status_prop->setStatus(status_levels::Error, "Target Frame", error); 00489 } 00490 else 00491 { 00492 target_prop->setToOK(); 00493 status_prop->setStatus(status_levels::Ok, "Target Frame", "OK"); 00494 } 00495 } 00496 00497 tf::TransformListener* VisualizationManager::getTFClient() 00498 { 00499 return frame_manager_->getTFClient(); 00500 } 00501 00502 void VisualizationManager::resetTime() 00503 { 00504 resetDisplays(); 00505 frame_manager_->getTFClient()->clear(); 00506 00507 ros_time_begin_ = ros::Time(); 00508 wall_clock_begin_ = ros::WallTime(); 00509 00510 queueRender(); 00511 } 00512 00513 void VisualizationManager::onDisplayCreated(DisplayWrapper* wrapper) 00514 { 00515 Display* display = wrapper->getDisplay(); 00516 display->setRenderCallback( boost::bind( &VisualizationManager::queueRender, this ) ); 00517 display->setLockRenderCallback( boost::bind( &VisualizationManager::lockRender, this ) ); 00518 display->setUnlockRenderCallback( boost::bind( &VisualizationManager::unlockRender, this ) ); 00519 00520 display->setTargetFrame( target_frame_ ); 00521 display->setFixedFrame( fixed_frame_ ); 00522 } 00523 00524 bool VisualizationManager::addDisplay(DisplayWrapper* wrapper, bool enabled) 00525 { 00526 if(getDisplayWrapper(wrapper->getName())) 00527 { 00528 ROS_ERROR("Display of name [%s] already exists", wrapper->getName().c_str()); 00529 return false; 00530 } 00531 00532 Q_EMIT displayAdding( wrapper ); 00533 displays_.push_back(wrapper); 00534 00535 connect( wrapper, SIGNAL( displayCreated( DisplayWrapper* )), this, SLOT( onDisplayCreated( DisplayWrapper* ))); 00536 wrapper->setPropertyManager( property_manager_, CategoryPropertyWPtr() ); 00537 wrapper->createDisplay(); 00538 00539 Q_EMIT displayAdded( wrapper ); 00540 00541 wrapper->setEnabled(enabled); 00542 00543 return true; 00544 } 00545 00546 void VisualizationManager::removeDisplay( DisplayWrapper* display ) 00547 { 00548 V_DisplayWrapper::iterator it = std::find(displays_.begin(), displays_.end(), display); 00549 ROS_ASSERT( it != displays_.end() ); 00550 00551 Q_EMIT displayRemoving( display ); 00552 00553 displays_.erase( it ); 00554 00555 Q_EMIT displayRemoved( display ); 00556 00557 delete display; 00558 00559 queueRender(); 00560 } 00561 00562 void VisualizationManager::removeAllDisplays() 00563 { 00564 Q_EMIT displaysRemoving( displays_ ); 00565 00566 while (!displays_.empty()) 00567 { 00568 removeDisplay(displays_.back()); 00569 } 00570 00571 Q_EMIT displaysRemoved( V_DisplayWrapper() ); 00572 } 00573 00574 void VisualizationManager::removeDisplay( const std::string& name ) 00575 { 00576 DisplayWrapper* display = getDisplayWrapper( name ); 00577 00578 if( !display ) 00579 { 00580 return; 00581 } 00582 00583 removeDisplay( display ); 00584 } 00585 00586 void VisualizationManager::resetDisplays() 00587 { 00588 V_DisplayWrapper::iterator vis_it = displays_.begin(); 00589 V_DisplayWrapper::iterator vis_end = displays_.end(); 00590 for ( ; vis_it != vis_end; ++vis_it ) 00591 { 00592 Display* display = (*vis_it)->getDisplay(); 00593 00594 if(display) 00595 { 00596 display->reset(); 00597 } 00598 } 00599 } 00600 00601 void VisualizationManager::addTool( Tool* tool ) 00602 { 00603 tools_.push_back( tool ); 00604 00605 Q_EMIT toolAdded( tool ); 00606 } 00607 00608 void VisualizationManager::setCurrentTool( Tool* tool ) 00609 { 00610 if( current_tool_ ) 00611 { 00612 current_tool_->deactivate(); 00613 } 00614 00615 current_tool_ = tool; 00616 current_tool_->activate(); 00617 00618 Q_EMIT toolChanged( tool ); 00619 } 00620 00621 void VisualizationManager::setDefaultTool( Tool* tool ) 00622 { 00623 default_tool_ = tool; 00624 } 00625 00626 Tool* VisualizationManager::getTool( int index ) 00627 { 00628 ROS_ASSERT( index >= 0 ); 00629 ROS_ASSERT( index < (int)tools_.size() ); 00630 00631 return tools_[ index ]; 00632 } 00633 00634 DisplayWrapper* VisualizationManager::getDisplayWrapper( const std::string& name ) 00635 { 00636 V_DisplayWrapper::iterator vis_it = displays_.begin(); 00637 V_DisplayWrapper::iterator vis_end = displays_.end(); 00638 for ( ; vis_it != vis_end; ++vis_it ) 00639 { 00640 DisplayWrapper* wrapper = *vis_it; 00641 if( wrapper->getName() == name ) 00642 { 00643 return wrapper; 00644 } 00645 } 00646 00647 return 0; 00648 } 00649 00650 DisplayWrapper* VisualizationManager::getDisplayWrapper( Display* display ) 00651 { 00652 V_DisplayWrapper::iterator vis_it = displays_.begin(); 00653 V_DisplayWrapper::iterator vis_end = displays_.end(); 00654 for ( ; vis_it != vis_end; ++vis_it ) 00655 { 00656 DisplayWrapper* wrapper = *vis_it; 00657 if( wrapper->getDisplay() == display ) 00658 { 00659 return wrapper; 00660 } 00661 } 00662 00663 return 0; 00664 } 00665 00666 #define CAMERA_TYPE "Camera Type" 00667 #define CAMERA_CONFIG "Camera Config" 00668 00669 void VisualizationManager::loadGeneralConfig( const boost::shared_ptr<Config>& config, const StatusCallback& cb ) 00670 { 00671 // Legacy... read camera config from the general config (camera config is now saved in the display config). 00673 std::string camera_type; 00674 if(config->get(CAMERA_TYPE, &camera_type)) 00675 { 00676 if(setCurrentViewControllerType(camera_type)) 00677 { 00678 std::string camera_config; 00679 if(config->get(CAMERA_CONFIG, &camera_config)) 00680 { 00681 view_controller_->fromString(camera_config); 00682 } 00683 } 00684 } 00685 00686 // if(cb) 00687 // { 00688 // cb("Loading plugins"); 00689 // } 00690 // 00691 // plugin_manager_->loadConfig(config); 00692 00693 Q_EMIT generalConfigLoaded( config ); 00694 } 00695 00696 void VisualizationManager::saveGeneralConfig( const boost::shared_ptr<Config>& config ) 00697 { 00698 // plugin_manager_->saveConfig(config); 00699 Q_EMIT generalConfigSaving( config ); 00700 } 00701 00702 // Make a map from class name (like "rviz::GridDisplay") to lookup 00703 // name (like "rviz/Grid"). This is here because of a mismatch 00704 // between the old rviz plugin system and pluginlib (the new one). 00705 void makeClassNameToLookupNameMap( pluginlib::ClassLoader<Display>* class_loader, 00706 std::map<std::string, std::string>* map ) 00707 { 00708 std::vector<std::string> lookup_names = class_loader->getDeclaredClasses(); 00709 00710 std::vector<std::string>::const_iterator ni; 00711 for( ni = lookup_names.begin(); ni != lookup_names.end(); ni++ ) 00712 { 00713 std::string class_name = class_loader->getClassType( (*ni) ); 00714 (*map)[ class_name ] = (*ni); 00715 } 00716 } 00717 00718 void VisualizationManager::loadDisplayConfig( const boost::shared_ptr<Config>& config, const StatusCallback& cb ) 00719 { 00720 disable_update_ = true; 00721 00722 if(cb) 00723 { 00724 cb("Creating displays"); 00725 } 00726 00727 std::map<std::string, std::string> class_name_to_lookup_name; 00728 makeClassNameToLookupNameMap( display_class_loader_, &class_name_to_lookup_name ); 00729 00730 int i = 0; 00731 while (1) 00732 { 00733 std::stringstream name, package, class_name; 00734 name << "Display" << i << "/Name"; 00735 package << "Display" << i << "/Package"; 00736 class_name << "Display" << i << "/ClassName"; 00737 00738 std::string vis_name, vis_package, vis_class; 00739 if(!config->get(name.str(), &vis_name)) 00740 { 00741 break; 00742 } 00743 00744 if(!config->get(package.str(), &vis_package)) 00745 { 00746 break; 00747 } 00748 00749 if(!config->get(class_name.str(), &vis_class)) 00750 { 00751 break; 00752 } 00753 00754 // TODO: should just read class-lookup-name from config file, but 00755 // that would not be consistent with the old (v1.6) config file format. 00756 std::string lookup_name = class_name_to_lookup_name[ vis_class ]; 00757 if( lookup_name == "" ) 00758 { 00759 break; 00760 } 00761 00762 createDisplay( lookup_name, vis_name, false); 00763 00764 ++i; 00765 } 00766 00767 property_manager_->load( config, cb ); 00768 tool_property_manager_->load( config, cb ); 00769 00770 std::string camera_type; 00771 if(config->get(CAMERA_TYPE, &camera_type)) 00772 { 00773 if(setCurrentViewControllerType(camera_type)) 00774 { 00775 std::string camera_config; 00776 if(config->get(CAMERA_CONFIG, &camera_config)) 00777 { 00778 view_controller_->fromString(camera_config); 00779 } 00780 } 00781 } 00782 00783 Q_EMIT displaysConfigLoaded( config ); 00784 00785 disable_update_ = false; 00786 } 00787 00788 void VisualizationManager::saveDisplayConfig( const boost::shared_ptr<Config>& config ) 00789 { 00790 int i = 0; 00791 V_DisplayWrapper::iterator vis_it = displays_.begin(); 00792 V_DisplayWrapper::iterator vis_end = displays_.end(); 00793 for ( ; vis_it != vis_end; ++vis_it, ++i ) 00794 { 00795 DisplayWrapper* wrapper = *vis_it; 00796 00797 std::stringstream name, package_key, class_name_key; 00798 name << "Display" << i << "/Name"; 00799 package_key << "Display" << i << "/Package"; 00800 class_name_key << "Display" << i << "/ClassName"; 00801 config->set( name.str(), wrapper->getName() ); 00802 std::string lookup_name = wrapper->getClassLookupName(); 00803 // TODO: should just write class-lookup-name to config file, but 00804 // that would not be consistent with the old (v1.6) config file format. 00805 std::string class_name = display_class_loader_->getClassType( lookup_name ); 00806 std::string package = display_class_loader_->getClassPackage( lookup_name ); 00807 config->set( package_key.str(), package ); 00808 config->set( class_name_key.str(), class_name ); 00809 } 00810 00811 property_manager_->save( config ); 00812 tool_property_manager_->save( config ); 00813 00814 if(view_controller_) 00815 { 00816 config->set(CAMERA_TYPE, view_controller_->getClassName()); 00817 config->set(CAMERA_CONFIG, view_controller_->toString()); 00818 } 00819 00820 Q_EMIT displaysConfigSaved( config ); 00821 } 00822 00823 DisplayWrapper* VisualizationManager::createDisplay( const std::string& class_lookup_name, 00824 const std::string& name, 00825 bool enabled ) 00826 { 00827 // PluginPtr plugin = plugin_manager_->getPluginByPackage(package); 00828 // if(!plugin) 00829 // { 00830 // ROS_ERROR("Package [%s] does not have any plugins loaded available, for display of type [%s], and name [%s]", package.c_str(), class_name.c_str(), name.c_str()); 00831 // } 00832 00833 DisplayWrapper* wrapper = new DisplayWrapper( class_lookup_name, display_class_loader_, name, this); 00834 if(addDisplay(wrapper, enabled)) 00835 { 00836 return wrapper; 00837 } 00838 else 00839 { 00840 delete wrapper; 00841 return 0; 00842 } 00843 } 00844 00845 void VisualizationManager::setTargetFrame( const std::string& _frame ) 00846 { 00847 target_frame_is_fixed_frame_ = false; 00848 std::string frame = _frame; 00849 if(frame == FIXED_FRAME_STRING) 00850 { 00851 frame = fixed_frame_; 00852 target_frame_is_fixed_frame_ = true; 00853 } 00854 00855 std::string remapped_name = frame_manager_->getTFClient()->resolve(frame); 00856 00857 if(target_frame_ == remapped_name) 00858 { 00859 return; 00860 } 00861 00862 target_frame_ = remapped_name; 00863 00864 V_DisplayWrapper::iterator it = displays_.begin(); 00865 V_DisplayWrapper::iterator end = displays_.end(); 00866 for ( ; it != end; ++it ) 00867 { 00868 Display* display = (*it)->getDisplay(); 00869 00870 if(display) 00871 { 00872 display->setTargetFrame(target_frame_); 00873 } 00874 } 00875 00876 propertyChanged(target_frame_property_); 00877 00878 if(view_controller_) 00879 { 00880 view_controller_->setTargetFrame(target_frame_); 00881 } 00882 } 00883 00884 void VisualizationManager::setFixedFrame( const std::string& frame ) 00885 { 00886 std::string remapped_name = frame_manager_->getTFClient()->resolve(frame); 00887 00888 if(fixed_frame_ == remapped_name) 00889 { 00890 return; 00891 } 00892 00893 fixed_frame_ = remapped_name; 00894 00895 frame_manager_->setFixedFrame(fixed_frame_); 00896 00897 V_DisplayWrapper::iterator it = displays_.begin(); 00898 V_DisplayWrapper::iterator end = displays_.end(); 00899 for ( ; it != end; ++it ) 00900 { 00901 Display* display = (*it)->getDisplay(); 00902 00903 if(display) 00904 { 00905 display->setFixedFrame(fixed_frame_); 00906 } 00907 } 00908 00909 propertyChanged(fixed_frame_property_); 00910 00911 if(target_frame_is_fixed_frame_) 00912 { 00913 setTargetFrame(FIXED_FRAME_STRING); 00914 } 00915 } 00916 00917 bool VisualizationManager::isValidDisplay(const DisplayWrapper* display) 00918 { 00919 V_DisplayWrapper::iterator it = displays_.begin(); 00920 V_DisplayWrapper::iterator end = displays_.end(); 00921 for ( ; it != end; ++it ) 00922 { 00923 if(display == (*it)) 00924 { 00925 return true; 00926 } 00927 } 00928 00929 return false; 00930 } 00931 00932 double VisualizationManager::getWallClock() 00933 { 00934 return ros::WallTime::now().toSec(); 00935 } 00936 00937 double VisualizationManager::getROSTime() 00938 { 00939 return (ros_time_begin_ + ros_time_elapsed_).toSec(); 00940 } 00941 00942 double VisualizationManager::getWallClockElapsed() 00943 { 00944 return wall_clock_elapsed_.toSec(); 00945 } 00946 00947 double VisualizationManager::getROSTimeElapsed() 00948 { 00949 return ros_time_elapsed_.toSec(); 00950 } 00951 00952 void VisualizationManager::setBackgroundColor(const Color& c) 00953 { 00954 background_color_ = c; 00955 00956 render_panel_->setBackgroundColor(Ogre::ColourValue(c.r_, c.g_, c.b_, 1.0f)); 00957 00958 propertyChanged(background_color_property_); 00959 00960 queueRender(); 00961 } 00962 00963 const Color& VisualizationManager::getBackgroundColor() 00964 { 00965 return background_color_; 00966 } 00967 00968 void VisualizationManager::handleChar( QKeyEvent* event ) 00969 { 00970 if( event->key() == Qt::Key_Escape ) 00971 { 00972 setCurrentTool( getDefaultTool() ); 00973 00974 return; 00975 } 00976 getCurrentTool()->processKeyEvent(event); 00977 } 00978 00979 void VisualizationManager::addViewController(const std::string& class_name, const std::string& name) 00980 { 00981 Q_EMIT viewControllerTypeAdded( class_name, name ); 00982 } 00983 00984 bool VisualizationManager::setCurrentViewControllerType(const std::string& type) 00985 { 00986 if(view_controller_ && (view_controller_->getClassName() == type || view_controller_->getName() == type)) 00987 { 00988 return true; 00989 } 00990 00991 bool found = true; 00992 // hack hack hack hack until this becomes truly plugin based 00993 if(type == "rviz::OrbitViewController" || type == "Orbit") 00994 { 00995 view_controller_ = new OrbitViewController(this, "Orbit",target_scene_node_); 00996 } 00997 else if(type == "rviz::XYOrbitViewController" || type == "XYOrbit" || 00998 type == "rviz::SimpleOrbitViewController" || type == "SimpleOrbit" /* the old class name */) 00999 { 01000 view_controller_ = new XYOrbitViewController(this, "XYOrbit",target_scene_node_); 01001 } 01002 else if(type == "rviz::FPSViewController" || type == "FPS") 01003 { 01004 view_controller_ = new FPSViewController(this, "FPS",target_scene_node_); 01005 } 01006 else if(type == "rviz::FixedOrientationOrthoViewController" || type == "TopDownOrtho" || type == "Top-down Orthographic") 01007 { 01008 view_controller_ = new FixedOrientationOrthoViewController(this, "TopDownOrtho",target_scene_node_); 01009 } 01010 else if(!view_controller_) 01011 { 01012 view_controller_ = new OrbitViewController(this, "Orbit",target_scene_node_); 01013 } 01014 else 01015 { 01016 found = false; 01017 } 01018 01019 if(found) 01020 { 01021 render_panel_->setViewController(view_controller_); 01022 view_controller_->setTargetFrame( target_frame_ ); 01023 Q_EMIT viewControllerChanged( view_controller_ ); 01024 } 01025 01026 return found; 01027 } 01028 01029 std::string VisualizationManager::getCurrentViewControllerType() 01030 { 01031 return view_controller_->getClassName(); 01032 } 01033 01034 void VisualizationManager::handleMouseEvent(ViewportMouseEvent& vme) 01035 { 01036 boost::mutex::scoped_lock lock( vme_queue_mutex_ ); 01037 vme_queue_.push_back(vme); 01038 } 01039 01040 void VisualizationManager::threadedQueueThreadFunc() 01041 { 01042 while (!shutting_down_) 01043 { 01044 threaded_queue_.callOne(ros::WallDuration(0.1)); 01045 } 01046 } 01047 01048 void VisualizationManager::onPluginUnloading(const PluginStatus& status) 01049 { 01050 // We need to force an update of the property manager here, because the memory allocated for properties is done inside their shared objects. 01051 // If a plugin is unloaded and then later the update is called, the weak pointers can cause crashes, because the objects they point to are 01052 // no longer valid. 01053 property_manager_->update(); 01054 } 01055 01056 } // namespace rviz