tf_display.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 <boost/bind.hpp>
00031 
00032 #include <OGRE/OgreSceneNode.h>
00033 #include <OGRE/OgreSceneManager.h>
00034 
00035 #include <tf/transform_listener.h>
00036 
00037 #include "rviz/display_context.h"
00038 #include "rviz/frame_manager.h"
00039 #include "rviz/ogre_helpers/arrow.h"
00040 #include "rviz/ogre_helpers/axes.h"
00041 #include "rviz/ogre_helpers/movable_text.h"
00042 #include "rviz/properties/bool_property.h"
00043 #include "rviz/properties/float_property.h"
00044 #include "rviz/properties/quaternion_property.h"
00045 #include "rviz/properties/string_property.h"
00046 #include "rviz/properties/vector_property.h"
00047 #include "rviz/selection/forwards.h"
00048 #include "rviz/selection/selection_manager.h"
00049 
00050 #include "rviz/default_plugin/tf_display.h"
00051 
00052 namespace rviz
00053 {
00054 
00055 class FrameSelectionHandler: public SelectionHandler
00056 {
00057 public:
00058   FrameSelectionHandler( FrameInfo* frame, TFDisplay* display, DisplayContext* context );
00059   virtual ~FrameSelectionHandler() {}
00060 
00061   virtual void createProperties( const Picked& obj, Property* parent_property );
00062   virtual void destroyProperties( const Picked& obj, Property* parent_property );
00063 
00064   bool getEnabled();
00065   void setEnabled( bool enabled );
00066   void setParentName( std::string parent_name );
00067   void setPosition( const Ogre::Vector3& position );
00068   void setOrientation( const Ogre::Quaternion& orientation );
00069 
00070 private:
00071   FrameInfo* frame_;
00072   TFDisplay* display_;
00073   Property* category_property_;
00074   BoolProperty* enabled_property_;
00075   StringProperty* parent_property_;
00076   VectorProperty* position_property_;
00077   QuaternionProperty* orientation_property_;
00078 };
00079 
00080 FrameSelectionHandler::FrameSelectionHandler(FrameInfo* frame, TFDisplay* display, DisplayContext* context )
00081   : SelectionHandler( context )
00082   , frame_( frame )
00083   , display_( display )
00084   , category_property_( NULL )
00085   , enabled_property_( NULL )
00086   , parent_property_( NULL )
00087   , position_property_( NULL )
00088   , orientation_property_( NULL )
00089 {
00090 }
00091 
00092 void FrameSelectionHandler::createProperties( const Picked& obj, Property* parent_property )
00093 {
00094   category_property_ = new Property( "Frame " + QString::fromStdString( frame_->name_ ), QVariant(), "", parent_property );
00095 
00096   enabled_property_ = new BoolProperty( "Enabled", true, "", category_property_, SLOT( updateVisibilityFromSelection() ), frame_ );
00097 
00098   parent_property_ = new StringProperty( "Parent", "", "", category_property_ );
00099   parent_property_->setReadOnly( true );
00100 
00101   position_property_ = new VectorProperty( "Position", Ogre::Vector3::ZERO, "", category_property_ );
00102   position_property_->setReadOnly( true );
00103 
00104   orientation_property_ = new QuaternionProperty( "Orientation", Ogre::Quaternion::IDENTITY, "", category_property_ );
00105   orientation_property_->setReadOnly( true );
00106 }
00107 
00108 void FrameSelectionHandler::destroyProperties( const Picked& obj, Property* parent_property )
00109 {
00110   delete category_property_; // This deletes its children as well.
00111   category_property_ = NULL;
00112   enabled_property_ = NULL;
00113   parent_property_ = NULL;
00114   position_property_ = NULL;
00115   orientation_property_ = NULL;
00116 }
00117 
00118 bool FrameSelectionHandler::getEnabled()
00119 {
00120   if( enabled_property_ )
00121   {
00122     return enabled_property_->getBool();
00123   }
00124   return false; // should never happen, but don't want to crash if it does.
00125 }
00126 
00127 void FrameSelectionHandler::setEnabled( bool enabled )
00128 {
00129   if( enabled_property_ )
00130   {
00131     enabled_property_->setBool( enabled );
00132   }
00133 }
00134 
00135 void FrameSelectionHandler::setParentName( std::string parent_name )
00136 {
00137   if( parent_property_ )
00138   {
00139     parent_property_->setStdString( parent_name );
00140   }
00141 }
00142 
00143 void FrameSelectionHandler::setPosition( const Ogre::Vector3& position )
00144 {
00145   if( position_property_ )
00146   {
00147     position_property_->setVector( position );
00148   }
00149 }
00150 
00151 void FrameSelectionHandler::setOrientation( const Ogre::Quaternion& orientation )
00152 {
00153   if( orientation_property_ )
00154   {
00155     orientation_property_->setQuaternion( orientation );
00156   }
00157 }
00158 
00159 typedef std::set<FrameInfo*> S_FrameInfo;
00160 
00161 TFDisplay::TFDisplay()
00162   : Display()
00163   , update_timer_( 0.0f )
00164   , changing_single_frame_enabled_state_( false )
00165 {
00166   show_names_property_ = new BoolProperty( "Show Names", true, "Whether or not names should be shown next to the frames.",
00167                                            this, SLOT( updateShowNames() ));
00168 
00169   show_axes_property_ = new BoolProperty( "Show Axes", true, "Whether or not the axes of each frame should be shown.",
00170                                           this, SLOT( updateShowAxes() ));
00171 
00172   show_arrows_property_ = new BoolProperty( "Show Arrows", true, "Whether or not arrows from child to parent should be shown.",
00173                                             this, SLOT( updateShowArrows() ));
00174 
00175   scale_property_ = new FloatProperty( "Marker Scale", 1, "Scaling factor for all names, axes and arrows.", this );
00176 
00177   update_rate_property_ = new FloatProperty( "Update Interval", 0,
00178                                              "The interval, in seconds, at which to update the frame transforms.  0 means to do so every update cycle.",
00179                                              this );
00180   update_rate_property_->setMin( 0 );
00181 
00182   frame_timeout_property_ = new FloatProperty( "Frame Timeout", 15,
00183                                                "The length of time, in seconds, before a frame that has not been updated is considered \"dead\"."
00184                                                "  For 1/3 of this time the frame will appear correct, for the second 1/3rd it will fade to gray,"
00185                                                " and then it will fade out completely.",
00186                                                this );
00187   frame_timeout_property_->setMin( 1 );
00188 
00189   frames_category_ = new Property( "Frames", QVariant(), "The list of all frames.", this );
00190 
00191   all_enabled_property_ = new BoolProperty( "All Enabled", true,
00192                                             "Whether all the frames should be enabled or not.",
00193                                             frames_category_, SLOT( allEnabledChanged() ), this );
00194 
00195   tree_category_ = new Property( "Tree", QVariant(), "A tree-view of the frames, showing the parent/child relationships.", this );
00196 }
00197 
00198 TFDisplay::~TFDisplay()
00199 {
00200   root_node_->removeAndDestroyAllChildren();
00201   scene_manager_->destroySceneNode( root_node_->getName() );
00202 }
00203 
00204 void TFDisplay::onInitialize()
00205 {
00206   root_node_ = scene_node_->createChildSceneNode();
00207 
00208   names_node_ = root_node_->createChildSceneNode();
00209   arrows_node_ = root_node_->createChildSceneNode();
00210   axes_node_ = root_node_->createChildSceneNode();
00211 }
00212 
00213 void TFDisplay::clear()
00214 {
00215   // Clear the tree.
00216   tree_category_->removeChildren();
00217 
00218   // Clear the frames category, except for the "All enabled" property, which is first.
00219   frames_category_->removeChildren( 1 );
00220 
00221   S_FrameInfo to_delete;
00222   M_FrameInfo::iterator frame_it = frames_.begin();
00223   M_FrameInfo::iterator frame_end = frames_.end();
00224   for ( ; frame_it != frame_end; ++frame_it )
00225   {
00226     to_delete.insert( frame_it->second );
00227   }
00228 
00229   S_FrameInfo::iterator delete_it = to_delete.begin();
00230   S_FrameInfo::iterator delete_end = to_delete.end();
00231   for ( ; delete_it != delete_end; ++delete_it )
00232   {
00233     deleteFrame( *delete_it, false );
00234   }
00235 
00236   frames_.clear();
00237 
00238   update_timer_ = 0.0f;
00239 
00240   clearStatuses();
00241 }
00242 
00243 void TFDisplay::onEnable()
00244 {
00245   root_node_->setVisible( true );
00246 
00247   names_node_->setVisible( show_names_property_->getBool() );
00248   arrows_node_->setVisible( show_arrows_property_->getBool() );
00249   axes_node_->setVisible( show_axes_property_->getBool() );
00250 }
00251 
00252 void TFDisplay::onDisable()
00253 {
00254   root_node_->setVisible( false );
00255   clear();
00256 }
00257 
00258 void TFDisplay::updateShowNames()
00259 {
00260   names_node_->setVisible( show_names_property_->getBool() );
00261 
00262   M_FrameInfo::iterator it = frames_.begin();
00263   M_FrameInfo::iterator end = frames_.end();
00264   for (; it != end; ++it)
00265   {
00266     FrameInfo* frame = it->second;
00267 
00268     frame->updateVisibilityFromFrame();
00269   }
00270 }
00271 
00272 void TFDisplay::updateShowAxes()
00273 {
00274   axes_node_->setVisible( show_axes_property_->getBool() );
00275 
00276   M_FrameInfo::iterator it = frames_.begin();
00277   M_FrameInfo::iterator end = frames_.end();
00278   for (; it != end; ++it)
00279   {
00280     FrameInfo* frame = it->second;
00281 
00282     frame->updateVisibilityFromFrame();
00283   }
00284 }
00285 
00286 void TFDisplay::updateShowArrows()
00287 {
00288   arrows_node_->setVisible( show_arrows_property_->getBool() );
00289 
00290   M_FrameInfo::iterator it = frames_.begin();
00291   M_FrameInfo::iterator end = frames_.end();
00292   for (; it != end; ++it)
00293   {
00294     FrameInfo* frame = it->second;
00295 
00296     frame->updateVisibilityFromFrame();
00297   }
00298 }
00299 
00300 void TFDisplay::allEnabledChanged()
00301 {
00302   if( changing_single_frame_enabled_state_ )
00303   {
00304     return;
00305   }
00306   bool enabled = all_enabled_property_->getBool();
00307 
00308   M_FrameInfo::iterator it = frames_.begin();
00309   M_FrameInfo::iterator end = frames_.end();
00310   for (; it != end; ++it)
00311   {
00312     FrameInfo* frame = it->second;
00313 
00314     frame->enabled_property_->setBool( enabled );
00315   }
00316 }
00317 
00318 void TFDisplay::update(float wall_dt, float ros_dt)
00319 {
00320   update_timer_ += wall_dt;
00321   float update_rate = update_rate_property_->getFloat();
00322   if( update_rate < 0.0001f || update_timer_ > update_rate )
00323   {
00324     updateFrames();
00325 
00326     update_timer_ = 0.0f;
00327   }
00328 }
00329 
00330 FrameInfo* TFDisplay::getFrameInfo( const std::string& frame )
00331 {
00332   M_FrameInfo::iterator it = frames_.find( frame );
00333   if ( it == frames_.end() )
00334   {
00335     return NULL;
00336   }
00337 
00338   return it->second;
00339 }
00340 
00341 void TFDisplay::updateFrames()
00342 {
00343   typedef std::vector<std::string> V_string;
00344   V_string frames;
00345   context_->getTFClient()->getFrameStrings( frames );
00346   std::sort(frames.begin(), frames.end());
00347 
00348   S_FrameInfo current_frames;
00349 
00350   {
00351     V_string::iterator it = frames.begin();
00352     V_string::iterator end = frames.end();
00353     for ( ; it != end; ++it )
00354     {
00355       const std::string& frame = *it;
00356 
00357       if ( frame.empty() )
00358       {
00359         continue;
00360       }
00361 
00362       FrameInfo* info = getFrameInfo( frame );
00363       if (!info)
00364       {
00365         info = createFrame(frame);
00366       }
00367       else
00368       {
00369         updateFrame(info);
00370       }
00371 
00372       current_frames.insert( info );
00373     }
00374   }
00375 
00376   {
00377     S_FrameInfo to_delete;
00378     M_FrameInfo::iterator frame_it = frames_.begin();
00379     M_FrameInfo::iterator frame_end = frames_.end();
00380     for ( ; frame_it != frame_end; ++frame_it )
00381     {
00382       if ( current_frames.find( frame_it->second ) == current_frames.end() )
00383       {
00384         to_delete.insert( frame_it->second );
00385       }
00386     }
00387 
00388     S_FrameInfo::iterator delete_it = to_delete.begin();
00389     S_FrameInfo::iterator delete_end = to_delete.end();
00390     for ( ; delete_it != delete_end; ++delete_it )
00391     {
00392       deleteFrame( *delete_it, true );
00393     }
00394   }
00395 
00396   context_->queueRender();
00397 }
00398 
00399 static const Ogre::ColourValue ARROW_HEAD_COLOR(1.0f, 0.1f, 0.6f, 1.0f);
00400 static const Ogre::ColourValue ARROW_SHAFT_COLOR(0.8f, 0.8f, 0.3f, 1.0f);
00401 
00402 FrameInfo* TFDisplay::createFrame(const std::string& frame)
00403 {
00404   FrameInfo* info = new FrameInfo( this );
00405   frames_.insert( std::make_pair( frame, info ) );
00406 
00407   info->name_ = frame;
00408   info->last_update_ = ros::Time::now();
00409   info->axes_ = new Axes( scene_manager_, axes_node_, 0.2, 0.02 );
00410   info->axes_->getSceneNode()->setVisible( show_axes_property_->getBool() );
00411   info->selection_handler_.reset( new FrameSelectionHandler( info, this, context_ ));
00412   info->selection_handler_->addTrackedObjects( info->axes_->getSceneNode() );
00413 
00414   info->name_text_ = new MovableText( frame, "Arial", 0.1 );
00415   info->name_text_->setTextAlignment(MovableText::H_CENTER, MovableText::V_BELOW);
00416   info->name_node_ = names_node_->createChildSceneNode();
00417   info->name_node_->attachObject( info->name_text_ );
00418   info->name_node_->setVisible( show_names_property_->getBool() );
00419 
00420   info->parent_arrow_ = new Arrow( scene_manager_, arrows_node_, 1.0f, 0.01, 1.0f, 0.08 );
00421   info->parent_arrow_->getSceneNode()->setVisible( false );
00422   info->parent_arrow_->setHeadColor(ARROW_HEAD_COLOR);
00423   info->parent_arrow_->setShaftColor(ARROW_SHAFT_COLOR);
00424 
00425   info->enabled_property_ = new BoolProperty( QString::fromStdString( info->name_ ), true, "Enable or disable this individual frame.",
00426                                               frames_category_, SLOT( updateVisibilityFromFrame() ), info );
00427 
00428   info->parent_property_ = new StringProperty( "Parent", "", "Parent of this frame.  (Not editable)",
00429                                                info->enabled_property_ );
00430   info->parent_property_->setReadOnly( true );
00431 
00432   info->position_property_ = new VectorProperty( "Position", Ogre::Vector3::ZERO,
00433                                                  "Position of this frame, in the current Fixed Frame.  (Not editable)",
00434                                                  info->enabled_property_ );
00435   info->position_property_->setReadOnly( true );
00436 
00437   info->orientation_property_ = new QuaternionProperty( "Orientation", Ogre::Quaternion::IDENTITY,
00438                                                         "Orientation of this frame, in the current Fixed Frame.  (Not editable)",
00439                                                         info->enabled_property_ );
00440   info->orientation_property_->setReadOnly( true );
00441 
00442   info->rel_position_property_ = new VectorProperty( "Relative Position", Ogre::Vector3::ZERO,
00443                                                  "Position of this frame, relative to it's parent frame.  (Not editable)",
00444                                                  info->enabled_property_ );
00445   info->rel_position_property_->setReadOnly( true );
00446 
00447   info->rel_orientation_property_ = new QuaternionProperty( "Relative Orientation", Ogre::Quaternion::IDENTITY,
00448                                                         "Orientation of this frame, relative to it's parent frame.  (Not editable)",
00449                                                         info->enabled_property_ );
00450   info->rel_orientation_property_->setReadOnly( true );
00451 
00452   updateFrame( info );
00453 
00454   return info;
00455 }
00456 
00457 Ogre::ColourValue lerpColor(const Ogre::ColourValue& start, const Ogre::ColourValue& end, float t)
00458 {
00459   return start * t + end * (1 - t);
00460 }
00461 
00462 void TFDisplay::updateFrame( FrameInfo* frame )
00463 {
00464   tf::TransformListener* tf = context_->getTFClient();
00465 
00466   // Check last received time so we can grey out/fade out frames that have stopped being published
00467   ros::Time latest_time;
00468   tf->getLatestCommonTime( fixed_frame_.toStdString(), frame->name_, latest_time, 0 );
00469   if( latest_time != frame->last_time_to_fixed_ )
00470   {
00471     frame->last_update_ = ros::Time::now();
00472     frame->last_time_to_fixed_ = latest_time;
00473   }
00474 
00475   // Fade from color -> grey, then grey -> fully transparent
00476   ros::Duration age = ros::Time::now() - frame->last_update_;
00477   float frame_timeout = frame_timeout_property_->getFloat();
00478   float one_third_timeout = frame_timeout * 0.3333333f;
00479   if( age > ros::Duration( frame_timeout ))
00480   {
00481     frame->parent_arrow_->getSceneNode()->setVisible(false);
00482     frame->axes_->getSceneNode()->setVisible(false);
00483     frame->name_node_->setVisible(false);
00484     return;
00485   }
00486   else if (age > ros::Duration(one_third_timeout))
00487   {
00488     Ogre::ColourValue grey(0.7, 0.7, 0.7, 1.0);
00489 
00490     if (age > ros::Duration(one_third_timeout * 2))
00491     {
00492       float a = std::max(0.0, (frame_timeout - age.toSec())/one_third_timeout);
00493       Ogre::ColourValue c = Ogre::ColourValue(grey.r, grey.g, grey.b, a);
00494 
00495       frame->axes_->setXColor(c);
00496       frame->axes_->setYColor(c);
00497       frame->axes_->setZColor(c);
00498       frame->name_text_->setColor(c);
00499       frame->parent_arrow_->setColor(c.r, c.g, c.b, c.a);
00500     }
00501     else
00502     {
00503       float t = std::max(0.0, (one_third_timeout * 2 - age.toSec())/one_third_timeout);
00504       frame->axes_->setXColor(lerpColor(frame->axes_->getDefaultXColor(), grey, t));
00505       frame->axes_->setYColor(lerpColor(frame->axes_->getDefaultYColor(), grey, t));
00506       frame->axes_->setZColor(lerpColor(frame->axes_->getDefaultZColor(), grey, t));
00507       frame->name_text_->setColor(lerpColor(Ogre::ColourValue::White, grey, t));
00508       frame->parent_arrow_->setShaftColor(lerpColor(ARROW_SHAFT_COLOR, grey, t));
00509       frame->parent_arrow_->setHeadColor(lerpColor(ARROW_HEAD_COLOR, grey, t));
00510     }
00511   }
00512   else
00513   {
00514     frame->axes_->setToDefaultColors();
00515     frame->name_text_->setColor(Ogre::ColourValue::White);
00516     frame->parent_arrow_->setHeadColor(ARROW_HEAD_COLOR);
00517     frame->parent_arrow_->setShaftColor(ARROW_SHAFT_COLOR);
00518   }
00519 
00520   setStatusStd(StatusProperty::Ok, frame->name_, "Transform OK");
00521 
00522   Ogre::Vector3 position;
00523   Ogre::Quaternion orientation;
00524   if( !context_->getFrameManager()->getTransform( frame->name_, ros::Time(), position, orientation ))
00525   {
00526     std::stringstream ss;
00527     ss << "No transform from [" << frame->name_ << "] to frame [" << fixed_frame_.toStdString() << "]";
00528     setStatusStd(StatusProperty::Warn, frame->name_, ss.str());
00529     ROS_DEBUG( "Error transforming frame '%s' to frame '%s'", frame->name_.c_str(), qPrintable( fixed_frame_ ));
00530     frame->name_node_->setVisible( false );
00531     frame->axes_->getSceneNode()->setVisible( false );
00532     frame->parent_arrow_->getSceneNode()->setVisible( false );
00533     return;
00534   }
00535 
00536   frame->selection_handler_->setPosition( position );
00537   frame->selection_handler_->setOrientation( orientation );
00538 
00539   bool frame_enabled = frame->enabled_property_->getBool();
00540 
00541   frame->axes_->setPosition( position );
00542   frame->axes_->setOrientation( orientation );
00543   frame->axes_->getSceneNode()->setVisible( show_axes_property_->getBool() && frame_enabled);
00544   float scale = scale_property_->getFloat();
00545   frame->axes_->setScale( Ogre::Vector3( scale, scale, scale ));
00546 
00547   frame->name_node_->setPosition( position );
00548   frame->name_node_->setVisible( show_names_property_->getBool() && frame_enabled );
00549   frame->name_node_->setScale( scale, scale, scale );
00550 
00551   frame->position_property_->setVector( position );
00552   frame->orientation_property_->setQuaternion( orientation );
00553 
00554   std::string old_parent = frame->parent_;
00555   frame->parent_.clear();
00556   bool has_parent = tf->getParent( frame->name_, ros::Time(), frame->parent_ );
00557   if( has_parent )
00558   {
00559     // If this frame has no tree property or the parent has changed,
00560     if( !frame->tree_property_ || old_parent != frame->parent_ )
00561     {
00562       // Look up the new parent.
00563       M_FrameInfo::iterator parent_it = frames_.find( frame->parent_ );
00564       if( parent_it != frames_.end() )
00565       {
00566         FrameInfo* parent = parent_it->second;
00567 
00568         // Delete the old tree property.
00569         delete frame->tree_property_;
00570         frame->tree_property_ = NULL;
00571 
00572         // If the parent has a tree property, make a new tree property for this frame.
00573         if( parent->tree_property_ )
00574         {
00575           frame->tree_property_ = new Property( QString::fromStdString( frame->name_ ), QVariant(), "", parent->tree_property_ );
00576         }
00577       }
00578     }
00579 
00580     tf::StampedTransform transform;
00581     try {
00582       context_->getFrameManager()->getTFClientPtr()->lookupTransform(frame->parent_,frame->name_,ros::Time(0),transform);
00583     }
00584     catch(tf::TransformException& e)
00585     {
00586       ROS_DEBUG( "Error transforming frame '%s' (parent of '%s') to frame '%s'",
00587                  frame->parent_.c_str(), frame->name_.c_str(), qPrintable( fixed_frame_ ));
00588     }
00589 
00590     // get the position/orientation relative to the parent frame
00591     Ogre::Vector3 relative_position( transform.getOrigin().x(), transform.getOrigin().y(), transform.getOrigin().z() );
00592     Ogre::Quaternion relative_orientation( transform.getRotation().w(), transform.getRotation().x(), transform.getRotation().y(), transform.getRotation().z() );
00593     frame->rel_position_property_->setVector( relative_position );
00594     frame->rel_orientation_property_->setQuaternion( relative_orientation );
00595 
00596     if( show_arrows_property_->getBool() )
00597     {
00598       Ogre::Vector3 parent_position;
00599       Ogre::Quaternion parent_orientation;
00600       if (!context_->getFrameManager()->getTransform(frame->parent_, ros::Time(), parent_position, parent_orientation))
00601       {
00602         ROS_DEBUG( "Error transforming frame '%s' (parent of '%s') to frame '%s'",
00603                    frame->parent_.c_str(), frame->name_.c_str(), qPrintable( fixed_frame_ ));
00604       }
00605 
00606       Ogre::Vector3 direction = parent_position - position;
00607       float distance = direction.length();
00608       direction.normalise();
00609 
00610       Ogre::Quaternion orient = Ogre::Vector3::NEGATIVE_UNIT_Z.getRotationTo( direction );
00611 
00612       frame->distance_to_parent_ = distance;
00613       float head_length = ( distance < 0.1*scale ) ? (0.1*scale*distance) : 0.1*scale;
00614       float shaft_length = distance - head_length;
00615       // aleeper: This was changed from 0.02 and 0.08 to 0.01 and 0.04 to match proper radius handling in arrow.cpp
00616       frame->parent_arrow_->set( shaft_length, 0.01*scale, head_length, 0.04*scale );
00617 
00618       if ( distance > 0.001f )
00619       {
00620         frame->parent_arrow_->getSceneNode()->setVisible( show_arrows_property_->getBool() && frame_enabled );
00621       }
00622       else
00623       {
00624         frame->parent_arrow_->getSceneNode()->setVisible( false );
00625       }
00626 
00627       frame->parent_arrow_->setPosition( position );
00628       frame->parent_arrow_->setOrientation( orient );
00629     }
00630     else
00631     {
00632       frame->parent_arrow_->getSceneNode()->setVisible( false );
00633     }
00634   }
00635   else
00636   {
00637     if ( !frame->tree_property_ || old_parent != frame->parent_ )
00638     {
00639       delete frame->tree_property_;
00640       frame->tree_property_ = new Property( QString::fromStdString( frame->name_ ), QVariant(), "", tree_category_ );
00641     }
00642 
00643     frame->parent_arrow_->getSceneNode()->setVisible( false );
00644   }
00645 
00646   frame->parent_property_->setStdString( frame->parent_ );
00647   frame->selection_handler_->setParentName( frame->parent_ );
00648 }
00649 
00650 void TFDisplay::deleteFrame( FrameInfo* frame, bool delete_properties )
00651 {
00652   M_FrameInfo::iterator it = frames_.find( frame->name_ );
00653   ROS_ASSERT( it != frames_.end() );
00654 
00655   frames_.erase( it );
00656 
00657   delete frame->axes_;
00658   context_->getSelectionManager()->removeObject( frame->axes_coll_ );
00659   delete frame->parent_arrow_;
00660   delete frame->name_text_;
00661   scene_manager_->destroySceneNode( frame->name_node_->getName() );
00662   if( delete_properties )
00663   {
00664     delete frame->enabled_property_;
00665     delete frame->tree_property_;
00666   }
00667   delete frame;
00668 }
00669 
00670 void TFDisplay::fixedFrameChanged()
00671 {
00672   update_timer_ = update_rate_property_->getFloat();
00673 }
00674 
00675 void TFDisplay::reset()
00676 {
00677   Display::reset();
00678   clear();
00679 }
00680 
00682 // FrameInfo
00683 
00684 FrameInfo::FrameInfo( TFDisplay* display )
00685   : display_( display )
00686   , axes_( NULL )
00687   , axes_coll_( 0 )
00688   , parent_arrow_( NULL )
00689   , name_text_( NULL )
00690   , distance_to_parent_( 0.0f )
00691   , arrow_orientation_(Ogre::Quaternion::IDENTITY)
00692   , tree_property_( NULL )
00693 {}
00694 
00695 void FrameInfo::updateVisibilityFromFrame()
00696 {
00697   bool enabled = enabled_property_->getBool();
00698   selection_handler_->setEnabled( enabled );
00699   setEnabled( enabled );
00700 }
00701 
00702 void FrameInfo::updateVisibilityFromSelection()
00703 {
00704   bool enabled = selection_handler_->getEnabled();
00705   enabled_property_->setBool( enabled );
00706   setEnabled( enabled );
00707 }
00708 
00709 void FrameInfo::setEnabled( bool enabled )
00710 {
00711   if( name_node_ )
00712   {
00713     name_node_->setVisible( display_->show_names_property_->getBool() && enabled );
00714   }
00715 
00716   if( axes_ )
00717   {
00718     axes_->getSceneNode()->setVisible( display_->show_axes_property_->getBool() && enabled );
00719   }
00720 
00721   if( parent_arrow_ )
00722   {
00723     if( distance_to_parent_ > 0.001f )
00724     {
00725       parent_arrow_->getSceneNode()->setVisible( display_->show_arrows_property_->getBool() && enabled );
00726     }
00727     else
00728     {
00729       parent_arrow_->getSceneNode()->setVisible( false );
00730     }
00731   }
00732 
00733   if( display_->all_enabled_property_->getBool() && !enabled)
00734   {
00735     display_->changing_single_frame_enabled_state_ = true;
00736     display_->all_enabled_property_->setBool( false );
00737     display_->changing_single_frame_enabled_state_ = false;
00738   }
00739 
00740   display_->context_->queueRender();
00741 }
00742 
00743 } // namespace rviz
00744 
00745 #include <pluginlib/class_list_macros.h>
00746 PLUGINLIB_EXPORT_CLASS( rviz::TFDisplay, rviz::Display )


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