display_group.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 <stdio.h> // for debug-write printf
00031 
00032 #include <QColor>
00033 
00034 #include "rviz/display_context.h"
00035 #include "rviz/display_factory.h"
00036 #include "rviz/failed_display.h"
00037 #include "rviz/properties/property_tree_model.h"
00038 
00039 #include "display_group.h"
00040 
00041 namespace rviz
00042 {
00043 
00044 DisplayGroup::DisplayGroup()
00045 {
00046 }
00047 
00048 DisplayGroup::~DisplayGroup()
00049 {
00050   removeAllDisplays();
00051 }
00052 
00053 Qt::ItemFlags DisplayGroup::getViewFlags( int column ) const
00054 {
00055   return Display::getViewFlags( column ) | Qt::ItemIsDropEnabled;
00056 }
00057 
00058 void DisplayGroup::load( const Config& config )
00059 {
00060   removeAllDisplays(); // Only remove Display children, property children must stay.
00061 
00062   // Load Property values, plus name and enabled/disabled.
00063   Display::load( config );
00064 
00065   // Now load Displays.
00066   Config display_list_config = config.mapGetChild( "Displays" );
00067   int num_displays = display_list_config.listLength();
00068 
00069   if( model_ )
00070   {
00071     model_->beginInsert( this, Display::numChildren(), num_displays );
00072   }
00073 
00074   std::map<Display*,Config> display_config_map;
00075 
00076   // The following two-step loading procedure was motivated by the
00077   // 'display group visibility' property, which needs all other displays
00078   // to be created and named before it can load its settings.
00079 
00080   // hersh says: Is this really necessary?  Can't we make
00081   // DisplayGroupVisibilityProperty self-sufficient in this regard?
00082   // Also, does it really work?  What about saving and loading a
00083   // hierarchy of Displays, will they really all have the right
00084   // visibility settings?
00085 
00086   // first, create all displays and set their names
00087   for( int i = 0; i < num_displays; i++ )
00088   {
00089     Config display_config = display_list_config.listChildAt( i );
00090     QString display_class = "(no class name found)";
00091     display_config.mapGetString( "Class", &display_class );
00092     Display* disp = createDisplay( display_class );
00093     addDisplayWithoutSignallingModel( disp );
00094     QString display_name;
00095     display_config.mapGetString( "Name", &display_name );
00096     disp->setObjectName( display_name );
00097 
00098     display_config_map[ disp ] = display_config;
00099   }
00100 
00101   // now, initialize all displays and load their properties.
00102   for( std::map<Display*,Config>::iterator it = display_config_map.begin(); it != display_config_map.end(); ++it )
00103   {
00104     Config display_config = it->second;
00105     Display* disp = it->first;
00106     disp->initialize( context_ );
00107     disp->load( display_config );
00108   }
00109 
00110   if( model_ )
00111   {
00112     model_->endInsert();
00113   }
00114 }
00115 
00116 Display* DisplayGroup::createDisplay( const QString& class_id )
00117 {
00118   DisplayFactory* factory = context_->getDisplayFactory();
00119   QString error;
00120   Display* disp = factory->make( class_id, &error );
00121   if( !disp )
00122   {
00123     return new FailedDisplay( class_id, error );
00124   }
00125   return disp;
00126 }
00127 
00128 void DisplayGroup::onEnableChanged()
00129 {
00130   Display::onEnableChanged();
00131   for( int i = displays_.size() - 1; i >= 0; i-- )
00132   {
00133     displays_[ i ]->onEnableChanged();
00134   }
00135 }
00136 
00137 void DisplayGroup::save( Config config ) const
00138 {
00139   Display::save( config );
00140 
00141   // Save Displays in a sequence under the key "Displays".
00142   Config display_list_config = config.mapMakeChild( "Displays" );
00143 
00144   int num_displays = displays_.size();
00145   for( int i = 0; i < num_displays; i++ )
00146   {
00147     displays_.at( i )->save( display_list_config.listAppendNew() );
00148   }
00149 }
00150 
00151 void DisplayGroup::removeAllDisplays()
00152 {
00153   int num_non_display_children = Display::numChildren();
00154 
00155   if( model_ )
00156   {
00157     model_->beginRemove( this, num_non_display_children, displays_.size() );
00158   }
00159   for( int i = displays_.size() - 1; i >= 0; i-- )
00160   {
00161 //    printf("  displaygroup2 displays_.takeAt( %d )\n", i );
00162     Display* child = displays_.takeAt( i );
00163     Q_EMIT displayRemoved( child );
00164     child->setParent( NULL ); // prevent child destructor from calling getParent()->takeChild().
00165     delete child;
00166   }
00167   if( model_ )
00168   {
00169     model_->endRemove();
00170   }
00171   Q_EMIT childListChanged( this );
00172 }
00173 
00174 Display* DisplayGroup::takeDisplay( Display* child )
00175 {
00176   Display* result = NULL;
00177   int num_displays = displays_.size();
00178   for( int i = 0; i < num_displays; i++ )
00179   {
00180     if( displays_.at( i ) == child )
00181     {
00182       if( model_ )
00183       {
00184         model_->beginRemove( this, Display::numChildren() + i, 1 );
00185       }
00186 //      printf("  displaygroup3 displays_.takeAt( %d )\n", i );
00187       result = displays_.takeAt( i );
00188       Q_EMIT displayRemoved( result );
00189       result->setParent( NULL );
00190       result->setModel( NULL );
00191       child_indexes_valid_ = false;
00192       if( model_ )
00193       {
00194         model_->endRemove();
00195       }
00196       Q_EMIT childListChanged( this );
00197       break;
00198     }
00199   }
00200   return result;
00201 }
00202 
00203 Display* DisplayGroup::getDisplayAt( int index ) const
00204 {
00205   if( 0 <= index && index < displays_.size() )
00206   {
00207     return displays_.at( index );
00208   }
00209   return NULL;
00210 }
00211 
00212 DisplayGroup* DisplayGroup::getGroupAt( int index ) const
00213 {
00214   return qobject_cast<DisplayGroup*>( getDisplayAt( index ));
00215 }
00216 
00217 void DisplayGroup::fixedFrameChanged()
00218 {
00219   int num_children = displays_.size();
00220   for( int i = 0; i < num_children; i++ )
00221   {
00222     displays_.at( i )->setFixedFrame( fixed_frame_ );
00223   }  
00224 }
00225 
00226 void DisplayGroup::update( float wall_dt, float ros_dt )
00227 {
00228   int num_children = displays_.size();
00229   for( int i = 0; i < num_children; i++ )
00230   {
00231     Display* display = displays_.at( i );
00232     if( display->isEnabled() )
00233     {
00234       display->update( wall_dt, ros_dt );
00235     }
00236   }  
00237 }
00238 
00239 void DisplayGroup::reset()
00240 {
00241   Display::reset();
00242 
00243   int num_children = displays_.size();
00244   for( int i = 0; i < num_children; i++ )
00245   {
00246     displays_.at( i )->reset();
00247   }  
00248 }
00249 
00250 void DisplayGroup::addDisplayWithoutSignallingModel( Display* child )
00251 {
00252 //  printf("  displaygroup4 displays_.append( child )\n" );
00253   displays_.append( child );
00254   child_indexes_valid_ = false;
00255   child->setModel( model_ );
00256   child->setParent( this );
00257   Q_EMIT displayAdded( child );
00258 }
00259 
00260 void DisplayGroup::addDisplay( Display* child )
00261 {
00262   if( model_ )
00263   {
00264     model_->beginInsert( this, numChildren(), 1 );
00265   }
00266   addDisplayWithoutSignallingModel( child );
00267   if( model_ )
00268   {
00269     model_->endInsert();
00270   }
00271   Q_EMIT childListChanged( this );
00272 }
00273 
00274 void DisplayGroup::addChild( Property* child, int index )
00275 {
00276   Display* display = qobject_cast<Display*>( child );
00277   if( !display )
00278   {
00279     Display::addChild( child, index );
00280     return;
00281   }
00282   if( index < 0 || index > numChildren() )
00283   {
00284     index = numChildren();
00285   }
00286   int disp_index = index - Display::numChildren();
00287   if( disp_index < 0 )
00288   {
00289     disp_index = 0;
00290   }
00291   if( model_ )
00292   {
00293     model_->beginInsert( this, index );
00294   }
00295 
00296   displays_.insert( disp_index, display );
00297   Q_EMIT displayAdded( display );
00298   child_indexes_valid_ = false;
00299   display->setModel( model_ );
00300   display->setParent( this );
00301 
00302   if( model_ )
00303   {
00304     model_->endInsert();
00305   }
00306   Q_EMIT childListChanged( this );
00307 }
00308 
00309 Property* DisplayGroup::takeChildAt( int index )
00310 {
00311   if( index < Display::numChildren() )
00312   {
00313     return Display::takeChildAt( index );
00314   }
00315   int disp_index = index - Display::numChildren();
00316   if( model_ )
00317   {
00318     model_->beginRemove( this, index, 1 );
00319   }
00320 //  printf("  displaygroup5 displays_.takeAt( %d ) ( index = %d )\n", disp_index, index );
00321   Display* child = displays_.takeAt( disp_index );
00322   Q_EMIT displayRemoved( child );
00323   child->setModel( NULL );
00324   child->setParent( NULL );
00325   child_indexes_valid_ = false;
00326   if( model_ )
00327   {
00328     model_->endRemove();
00329   }
00330   Q_EMIT childListChanged( this );
00331   return child;
00332 }
00333 
00334 int DisplayGroup::numDisplays() const
00335 {
00336   return displays_.size();
00337 }
00338 
00339 int DisplayGroup::numChildren() const
00340 {
00341   return Display::numChildren() + displays_.size();
00342 }
00343 
00344 Property* DisplayGroup::childAtUnchecked( int index ) const
00345 {
00346   int first_child_count = Display::numChildren();
00347   if( index < first_child_count )
00348   {
00349     return Display::childAtUnchecked( index );
00350   }
00351   index -= first_child_count;
00352   return displays_.at( index );
00353 }
00354 
00355 } // end namespace rviz


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