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 void ToolManager::handleChar( QKeyEvent* event, RenderPanel* panel )
00115 {
00116   if( event->key() == Qt::Key_Escape )
00117   {
00118     setCurrentTool( getDefaultTool() );
00119     return;
00120   }
00121   if( current_tool_ )
00122   {
00123     current_tool_->processKeyEvent( event, panel );
00124   }
00125 }
00126 
00127 void ToolManager::setCurrentTool( Tool* tool )
00128 {
00129   if( current_tool_ )
00130   {
00131     current_tool_->deactivate();
00132   }
00133   current_tool_ = tool;
00134 
00135   if( current_tool_ )
00136   {
00137     current_tool_->activate();
00138   }
00139 
00140   Q_EMIT toolChanged( tool );
00141 }
00142 
00143 void ToolManager::setDefaultTool( Tool* tool )
00144 {
00145   default_tool_ = tool;
00146 }
00147 
00148 Tool* ToolManager::getTool( int index )
00149 {
00150   ROS_ASSERT( index >= 0 );
00151   ROS_ASSERT( index < (int)tools_.size() );
00152 
00153   return tools_[ index ];
00154 }
00155 
00156 void ToolManager::updatePropertyVisibility( Property* container )
00157 {
00158   if( container->numChildren() > 0 )
00159   {
00160     if( !property_tree_model_->getRoot()->contains( container ))
00161     {
00162       property_tree_model_->getRoot()->addChild( container );
00163       container->expand();
00164     }
00165   }
00166   else
00167   {
00168     property_tree_model_->getRoot()->takeChild( container );
00169   }
00170 }
00171 
00172 Tool* ToolManager::addTool( const QString& class_id )
00173 {
00174   QString error;
00175   bool failed = false;
00176   Tool* tool = factory_->make( class_id, &error );
00177   if( !tool )
00178   {
00179     tool = new FailedTool( class_id, error );
00180     failed = true;
00181   }
00182 
00183   tools_.append( tool );
00184   tool->setName( addSpaceToCamelCase( factory_->getClassName( class_id )));
00185   tool->setIcon( factory_->getIcon( class_id ) );
00186   tool->initialize( context_ );
00187   Property* container = tool->getPropertyContainer();
00188   connect( container, SIGNAL( childListChanged( Property* )), this, SLOT( updatePropertyVisibility( Property* )));
00189   updatePropertyVisibility( container );
00190 
00191   Q_EMIT toolAdded( tool );
00192 
00193   // If the default tool is unset and this tool loaded correctly, set
00194   // it as the default and current.
00195   if( default_tool_ == NULL && !failed )
00196   {
00197     setDefaultTool( tool );
00198     setCurrentTool( tool );
00199   }
00200 
00201   Q_EMIT configChanged();
00202 
00203   return tool;
00204 }
00205 
00206 void ToolManager::removeTool( int index )
00207 {
00208   Tool* tool = tools_.takeAt( index );
00209   Tool* fallback = NULL;
00210   if( tools_.size() > 0 )
00211   {
00212     fallback = tools_[ 0 ];
00213   }
00214   if( tool == current_tool_ )
00215   {
00216     setCurrentTool( fallback );
00217   }
00218   if( tool == default_tool_ )
00219   {
00220     setDefaultTool( fallback );
00221   }
00222   Q_EMIT toolRemoved( tool );
00223   delete tool;
00224   Q_EMIT configChanged();
00225 }
00226 
00227 QStringList ToolManager::getToolClasses()
00228 {
00229   QStringList class_names;
00230   for( int i = 0; i < tools_.size(); i++ )
00231   {
00232     class_names.append( tools_[ i ]->getClassId() );
00233   }
00234   return class_names;
00235 }
00236 
00237 } // end namespace rviz


rviz
Author(s): Dave Hershberger, David Gossow, Josh Faust
autogenerated on Mon Oct 6 2014 07:26:36