display.cpp
Go to the documentation of this file.
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 "display.h"
00031 #include "visualization_manager.h"
00032 #include "properties/property_manager.h"
00033 #include "properties/property.h"
00034 
00035 namespace rviz
00036 {
00037 
00038 Display::Display()
00039   : vis_manager_( 0 )
00040   , scene_manager_( 0 )
00041   , enabled_( false )
00042   , status_( status_levels::Ok )
00043   , target_frame_( "base" )
00044   , property_manager_( NULL )
00045 {
00046 }
00047 
00048 Display::~Display()
00049 {
00050   if ( property_manager_ )
00051   {
00052     property_manager_->deleteByUserData( this );
00053   }
00054 }
00055 
00056 void Display::initialize( const std::string& name, VisualizationManager* manager )
00057 {
00058   setName( name );
00059   vis_manager_ = manager;
00060   scene_manager_ = manager->getSceneManager();
00061   update_nh_.setCallbackQueue(manager->getUpdateQueue());
00062   threaded_nh_.setCallbackQueue(manager->getThreadedQueue());
00063 
00064   // Do subclass initialization, if implemented.
00065   onInitialize();
00066 }
00067 
00068 void Display::setName(const std::string& name)
00069 {
00070   name_ = name;
00071   property_prefix_ = name + ".";
00072 }
00073 
00074 void Display::enable( bool force )
00075 {
00076   if ( enabled_ && !force )
00077   {
00078     return;
00079   }
00080 
00081   enabled_ = true;
00082 
00083   if (StatusPropertyPtr status = status_property_.lock())
00084   {
00085     status->enable();
00086   }
00087 
00088   onEnable();
00089 
00090   Q_EMIT stateChanged( this );
00091 }
00092 
00093 void Display::disable( bool force )
00094 {
00095   if ( !enabled_ && !force )
00096   {
00097     return;
00098   }
00099 
00100   enabled_ = false;
00101 
00102   onDisable();
00103 
00104   if (StatusPropertyPtr status = status_property_.lock())
00105   {
00106     status->disable();
00107   }
00108 
00109   Q_EMIT stateChanged( this );
00110 }
00111 
00112 void Display::setEnabled(bool en, bool force)
00113 {
00114   if (en)
00115   {
00116     enable(force);
00117   }
00118   else
00119   {
00120     disable(force);
00121   }
00122 }
00123 
00124 void Display::setRenderCallback( boost::function<void ()> func )
00125 {
00126   render_callback_ = func;
00127 }
00128 
00129 void Display::setLockRenderCallback( boost::function<void ()> func )
00130 {
00131   render_lock_ = func;
00132 }
00133 
00134 void Display::setUnlockRenderCallback( boost::function<void ()> func )
00135 {
00136   render_unlock_ = func;
00137 }
00138 
00139 
00140 void Display::causeRender()
00141 {
00142   if ( render_callback_ )
00143   {
00144     render_callback_();
00145   }
00146 }
00147 
00148 void Display::lockRender()
00149 {
00150   if ( render_lock_ )
00151   {
00152     render_lock_();
00153   }
00154 }
00155 
00156 void Display::unlockRender()
00157 {
00158   if ( render_unlock_ )
00159   {
00160     render_unlock_();
00161   }
00162 }
00163 
00164 void Display::setTargetFrame( const std::string& frame )
00165 {
00166   target_frame_ = frame;
00167 
00168   targetFrameChanged();
00169 }
00170 
00171 void Display::setFixedFrame( const std::string& frame )
00172 {
00173   fixed_frame_ = frame;
00174 
00175   fixedFrameChanged();
00176 }
00177 
00178 StatusLevel Display::getStatus()
00179 {
00180   return status_;
00181 }
00182 
00183 void Display::setStatus(StatusLevel level, const std::string& name, const std::string& text)
00184 {
00185   if (StatusPropertyPtr status = status_property_.lock())
00186   {
00187     status->setStatus(level, name, text);
00188 
00189     StatusLevel new_status = status->getTopLevelStatus();
00190     if (new_status != status_)
00191     {
00192       status_ = new_status;
00193       Q_EMIT stateChanged( this );
00194     }
00195   }
00196 }
00197 
00198 void Display::deleteStatus(const std::string& name)
00199 {
00200   if (StatusPropertyPtr status = status_property_.lock())
00201   {
00202     status->deleteStatus(name);
00203 
00204     StatusLevel new_status = status->getTopLevelStatus();
00205     if (new_status != status_)
00206     {
00207       status_ = new_status;
00208       Q_EMIT stateChanged( this );
00209     }
00210   }
00211 }
00212 
00213 void Display::clearStatuses()
00214 {
00215   if (StatusPropertyPtr status = status_property_.lock())
00216   {
00217     status->clear();
00218 
00219     StatusLevel new_status = status->getTopLevelStatus();
00220     if (new_status != status_)
00221     {
00222       status_ = new_status;
00223       Q_EMIT stateChanged( this );
00224     }
00225   }
00226 }
00227 
00228 void Display::setPropertyManager( PropertyManager* manager, const CategoryPropertyWPtr& parent )
00229 {
00230   ROS_ASSERT(!property_manager_);
00231 
00232   property_manager_ = manager;
00233 
00234   parent_category_ = parent;
00235   status_property_ = property_manager_->createStatus("Status", property_prefix_, parent_category_, this);
00236 
00237   createProperties();
00238 }
00239 
00240 void Display::reset()
00241 {
00242   clearStatuses();
00243 }
00244 
00245 } // namespace rviz


rviz_qt
Author(s): Dave Hershberger
autogenerated on Fri Dec 6 2013 20:56:52