tool_manager.cpp
Go to the documentation of this file.
00001 /*
00002  * Copyright (c) 2012, 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 <QKeyEvent>
00031 #include <QRegExp>
00032 
00033 #include <ros/assert.h>
00034 
00035 #include "rviz/failed_tool.h"
00036 #include "rviz/properties/property.h"
00037 #include "rviz/properties/property_tree_model.h"
00038 
00039 #include "rviz/tool_manager.h"
00040 
00041 namespace rviz
00042 {
00043 
00044 QString addSpaceToCamelCase( QString input )
00045 {
00046   QRegExp re = QRegExp( "([A-Z])([a-z]*)" );
00047   input.replace( re, " \\1\\2" );
00048   return input.trimmed();
00049 }
00050 
00051 ToolManager::ToolManager( DisplayContext* context )
00052   : factory_( new PluginlibFactory<Tool>( "rviz", "rviz::Tool" ))
00053   , property_tree_model_( new PropertyTreeModel( new Property() ))
00054   , context_( context )
00055   , current_tool_( NULL )
00056   , default_tool_( NULL )
00057 {
00058   connect( property_tree_model_, SIGNAL( configChanged() ), this, SIGNAL( configChanged() ));
00059 }
00060 
00061 ToolManager::~ToolManager()
00062 {
00063   removeAll();
00064   delete factory_;
00065   delete property_tree_model_;
00066 }
00067 
00068 void ToolManager::initialize()
00069 {
00070   // Possibly this should be done with a loop over
00071   // factory_->getDeclaredClassIds(), but then I couldn't control the
00072   // order.
00073   addTool( "rviz/MoveCamera" );
00074   addTool( "rviz/Interact" );
00075   addTool( "rviz/Select" );
00076   addTool( "rviz/SetInitialPose" );
00077   addTool( "rviz/SetGoal" );
00078 }
00079 
00080 void ToolManager::removeAll()
00081 {
00082   for( int i = tools_.size() - 1; i >= 0; i-- )
00083   {
00084     removeTool( i );
00085   }
00086 }
00087 
00088 void ToolManager::load( const Config& config )
00089 {
00090   removeAll();
00091 
00092   int num_tools = config.listLength();
00093   for( int i = 0; i < num_tools; i++ )
00094   {
00095     Config tool_config = config.listChildAt( i );
00096 
00097     QString class_id;
00098     if( tool_config.mapGetString( "Class", &class_id ))
00099     {
00100       Tool* tool = addTool( class_id );
00101       tool->load( tool_config );
00102     }
00103   }
00104 }
00105 
00106 void ToolManager::save( Config config ) const
00107 {
00108   for( int i = 0; i < tools_.size(); i++ )
00109   {
00110     tools_[ i ]->save( config.listAppendNew() );
00111   }
00112 }
00113 
00114 bool ToolManager::toKey( QString const& str, uint& key )
00115 {
00116   QKeySequence seq( str );
00117 
00118   // We should only working with a single key here
00119   if( seq.count() == 1 )
00120   {
00121     key = seq[ 0 ];
00122     return true;
00123   }
00124   else
00125   {
00126     return false;
00127   }
00128 }
00129 
00130 void ToolManager::handleChar( QKeyEvent* event, RenderPanel* panel )
00131 {
00132   // if the incoming key is ESC fallback to the default tool
00133   if( event->key() == Qt::Key_Escape )
00134   {
00135     setCurrentTool( getDefaultTool() );
00136     return;
00137   }
00138 
00139   // check if the incoming key triggers the activation of another tool
00140   Tool* tool = NULL;
00141   if( shortkey_to_tool_map_.find(event->key()) != shortkey_to_tool_map_.end() )
00142   {
00143     tool = shortkey_to_tool_map_[ event->key() ];
00144   }
00145 
00146   if( tool )
00147   {
00148     // if there is a incoming tool check if it matches the current tool
00149     if( current_tool_ == tool)
00150     {
00151       // if yes, deactivate the current tool and fallback to default
00152       setCurrentTool( getDefaultTool() );
00153     }
00154     else
00155     {
00156       // if no, check if the current tool accesses all key events
00157       if( current_tool_->accessAllKeys() )
00158       {
00159         // if yes, pass the key
00160         current_tool_->processKeyEvent( event, panel );
00161       }
00162       else
00163       {
00164         // if no, switch the tool
00165         setCurrentTool( tool );
00166       }
00167     }
00168   }
00169   else
00170   {
00171     // if the incoming key triggers no other tool,
00172     // just hand down the key event
00173     current_tool_->processKeyEvent( event, panel );
00174   }
00175 }
00176 
00177 void ToolManager::setCurrentTool( Tool* tool )
00178 {
00179   if( current_tool_ )
00180   {
00181     current_tool_->deactivate();
00182   }
00183 
00184   current_tool_ = tool;
00185 
00186   if( current_tool_ )
00187   {
00188     current_tool_->activate();
00189   }
00190 
00191   Q_EMIT toolChanged( current_tool_ );
00192 }
00193 
00194 void ToolManager::setDefaultTool( Tool* tool )
00195 {
00196   default_tool_ = tool;
00197 }
00198 
00199 Tool* ToolManager::getTool( int index )
00200 {
00201   ROS_ASSERT( index >= 0 );
00202   ROS_ASSERT( index < (int)tools_.size() );
00203 
00204   return tools_[ index ];
00205 }
00206 
00207 void ToolManager::updatePropertyVisibility( Property* container )
00208 {
00209   if( container->numChildren() > 0 )
00210   {
00211     if( !property_tree_model_->getRoot()->contains( container ))
00212     {
00213       property_tree_model_->getRoot()->addChild( container );
00214       container->expand();
00215     }
00216   }
00217   else
00218   {
00219     property_tree_model_->getRoot()->takeChild( container );
00220   }
00221 }
00222 
00223 Tool* ToolManager::addTool( const QString& class_id )
00224 {
00225   QString error;
00226   bool failed = false;
00227   Tool* tool = factory_->make( class_id, &error );
00228   if( !tool )
00229   {
00230     tool = new FailedTool( class_id, error );
00231     failed = true;
00232   }
00233 
00234   tools_.append( tool );
00235   tool->setName( addSpaceToCamelCase( factory_->getClassName( class_id )));
00236   tool->setIcon( factory_->getIcon( class_id ) );
00237   tool->initialize( context_ );
00238 
00239   if( tool->getShortcutKey() != '\0' )
00240   {
00241     uint key;
00242     QString str = QString( tool->getShortcutKey() );
00243 
00244     if( toKey( str, key ) )
00245     {
00246       shortkey_to_tool_map_[ key ] = tool;
00247     }
00248   }
00249 
00250   Property* container = tool->getPropertyContainer();
00251   connect( container, SIGNAL( childListChanged( Property* )), this, SLOT( updatePropertyVisibility( Property* )));
00252   updatePropertyVisibility( container );
00253 
00254   Q_EMIT toolAdded( tool );
00255 
00256   // If the default tool is unset and this tool loaded correctly, set
00257   // it as the default and current.
00258   if( default_tool_ == NULL && !failed )
00259   {
00260     setDefaultTool( tool );
00261     setCurrentTool( tool );
00262   }
00263 
00264   Q_EMIT configChanged();
00265 
00266   return tool;
00267 }
00268 
00269 void ToolManager::removeTool( int index )
00270 {
00271   Tool* tool = tools_.takeAt( index );
00272   Tool* fallback = NULL;
00273   if( tools_.size() > 0 )
00274   {
00275     fallback = tools_[ 0 ];
00276   }
00277   if( tool == current_tool_ )
00278   {
00279     setCurrentTool( fallback );
00280   }
00281   if( tool == default_tool_ )
00282   {
00283     setDefaultTool( fallback );
00284   }
00285   Q_EMIT toolRemoved( tool );
00286 
00287   uint key;
00288   if( toKey(  QString( tool->getShortcutKey() ), key ) )
00289   {
00290     shortkey_to_tool_map_.erase( key );
00291   }
00292   delete tool;
00293   Q_EMIT configChanged();
00294 }
00295 
00296 void ToolManager::refreshTool( Tool* tool )
00297 {
00298   Q_EMIT toolRefreshed( tool );
00299 }
00300 
00301 QStringList ToolManager::getToolClasses()
00302 {
00303   QStringList class_names;
00304   for( int i = 0; i < tools_.size(); i++ )
00305   {
00306     class_names.append( tools_[ i ]->getClassId() );
00307   }
00308   return class_names;
00309 }
00310 
00311 } // end namespace rviz


rviz
Author(s): Dave Hershberger, David Gossow, Josh Faust
autogenerated on Tue Oct 3 2017 03:19:31