00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030 #include "tf_display.h"
00031 #include "rviz/visualization_manager.h"
00032 #include "rviz/selection/selection_manager.h"
00033 #include "rviz/selection/forwards.h"
00034 #include "rviz/common.h"
00035 #include "rviz/properties/property.h"
00036 #include "rviz/properties/property_manager.h"
00037 #include "rviz/frame_manager.h"
00038
00039 #include <ogre_tools/arrow.h>
00040 #include <ogre_tools/axes.h>
00041 #include <ogre_tools/movable_text.h>
00042
00043 #include <boost/bind.hpp>
00044
00045 #include <OGRE/OgreSceneNode.h>
00046 #include <OGRE/OgreSceneManager.h>
00047
00048 #include <tf/transform_listener.h>
00049
00050
00051 namespace rviz
00052 {
00053
00054 struct FrameInfo
00055 {
00056 FrameInfo();
00057
00058 const Ogre::Vector3& getPositionInRobotSpace() { return robot_space_position_; }
00059 const Ogre::Quaternion& getOrientationInRobotSpace() { return robot_space_orientation_; }
00060 const std::string& getParent() { return parent_; }
00061
00062 bool isEnabled() { return enabled_; }
00063
00064 std::string name_;
00065 std::string parent_;
00066 ogre_tools::Axes* axes_;
00067 CollObjectHandle axes_coll_;
00068 ogre_tools::Arrow* parent_arrow_;
00069 ogre_tools::MovableText* name_text_;
00070 Ogre::SceneNode* name_node_;
00071
00072 Ogre::Vector3 position_;
00073 Ogre::Quaternion orientation_;
00074 float distance_to_parent_;
00075 Ogre::Quaternion arrow_orientation_;
00076
00077 Ogre::Vector3 robot_space_position_;
00078 Ogre::Quaternion robot_space_orientation_;
00079
00080 bool enabled_;
00081
00082 ros::Time last_update_;
00083 ros::Time last_time_to_fixed_;
00084
00085 CategoryPropertyWPtr category_;
00086 Vector3PropertyWPtr position_property_;
00087 QuaternionPropertyWPtr orientation_property_;
00088 StringPropertyWPtr parent_property_;
00089 BoolPropertyWPtr enabled_property_;
00090
00091 CategoryPropertyWPtr tree_property_;
00092 };
00093
00094 FrameInfo::FrameInfo()
00095 : axes_( NULL )
00096 , axes_coll_(NULL)
00097 , parent_arrow_( NULL )
00098 , name_text_( NULL )
00099 , position_(Ogre::Vector3::ZERO)
00100 , orientation_(Ogre::Quaternion::IDENTITY)
00101 , distance_to_parent_( 0.0f )
00102 , arrow_orientation_(Ogre::Quaternion::IDENTITY)
00103 , robot_space_position_(Ogre::Vector3::ZERO)
00104 , robot_space_orientation_(Ogre::Quaternion::IDENTITY)
00105 , enabled_(true)
00106 {
00107
00108 }
00109
00110 void TFDisplay::setFrameEnabled(FrameInfo* frame, bool enabled)
00111 {
00112 frame->enabled_ = enabled;
00113
00114 propertyChanged(frame->enabled_property_);
00115
00116 if (frame->name_node_)
00117 {
00118 frame->name_node_->setVisible(show_names_ && enabled);
00119 }
00120
00121 if (frame->axes_)
00122 {
00123 frame->axes_->getSceneNode()->setVisible(show_axes_ && enabled);
00124 }
00125
00126 if (frame->parent_arrow_)
00127 {
00128 if (frame->distance_to_parent_ > 0.001f)
00129 {
00130 frame->parent_arrow_->getSceneNode()->setVisible(show_arrows_ && enabled);
00131 }
00132 else
00133 {
00134 frame->parent_arrow_->getSceneNode()->setVisible(false);
00135 }
00136 }
00137
00138 if (all_enabled_ && !enabled)
00139 {
00140 all_enabled_ = false;
00141
00142 propertyChanged(all_enabled_property_);
00143 }
00144
00145 causeRender();
00146 }
00147
00148 class FrameSelectionHandler : public SelectionHandler
00149 {
00150 public:
00151 FrameSelectionHandler(FrameInfo* frame, TFDisplay* display);
00152 virtual ~FrameSelectionHandler();
00153
00154 virtual void createProperties(const Picked& obj, PropertyManager* property_manager);
00155
00156 private:
00157 FrameInfo* frame_;
00158 TFDisplay* display_;
00159 };
00160
00161 FrameSelectionHandler::FrameSelectionHandler(FrameInfo* frame, TFDisplay* display)
00162 : frame_(frame)
00163 , display_(display)
00164 {
00165 }
00166
00167 FrameSelectionHandler::~FrameSelectionHandler()
00168 {
00169 }
00170
00171 void FrameSelectionHandler::createProperties(const Picked& obj, PropertyManager* property_manager)
00172 {
00173 std::stringstream ss;
00174 ss << frame_->name_ << " Frame " << frame_->name_;
00175
00176 CategoryPropertyWPtr cat = property_manager->createCategory( "Frame " + frame_->name_, ss.str(), CategoryPropertyWPtr() );
00177 properties_.push_back(cat);
00178
00179 properties_.push_back(property_manager->createProperty<BoolProperty>( "Enabled", ss.str(), boost::bind( &FrameInfo::isEnabled, frame_ ),
00180 boost::bind( &TFDisplay::setFrameEnabled, display_, frame_, _1 ), cat, this ));
00181 properties_.push_back(property_manager->createProperty<StringProperty>( "Parent", ss.str(), boost::bind( &FrameInfo::getParent, frame_ ),
00182 StringProperty::Setter(), cat, this ));
00183 properties_.push_back(property_manager->createProperty<Vector3Property>( "Position", ss.str(), boost::bind( &FrameInfo::getPositionInRobotSpace, frame_ ),
00184 Vector3Property::Setter(), cat, this ));
00185 properties_.push_back(property_manager->createProperty<QuaternionProperty>( "Orientation", ss.str(), boost::bind( &FrameInfo::getOrientationInRobotSpace, frame_ ),
00186 QuaternionProperty::Setter(), cat, this ));
00187 }
00188
00189 typedef std::set<FrameInfo*> S_FrameInfo;
00190
00191 TFDisplay::TFDisplay( const std::string& name, VisualizationManager* manager )
00192 : Display( name, manager )
00193 , update_timer_( 0.0f )
00194 , update_rate_( 0.0f )
00195 , show_names_( true )
00196 , show_arrows_( true )
00197 , show_axes_( true )
00198 , frame_timeout_(15.0f)
00199 , all_enabled_(true)
00200 {
00201 root_node_ = scene_manager_->getRootSceneNode()->createChildSceneNode();
00202
00203 names_node_ = root_node_->createChildSceneNode();
00204 arrows_node_ = root_node_->createChildSceneNode();
00205 axes_node_ = root_node_->createChildSceneNode();
00206 }
00207
00208 TFDisplay::~TFDisplay()
00209 {
00210 clear();
00211
00212 root_node_->removeAndDestroyAllChildren();
00213 scene_manager_->destroySceneNode( root_node_->getName() );
00214 }
00215
00216 void TFDisplay::clear()
00217 {
00218 property_manager_->deleteChildren(tree_category_.lock());
00219
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 );
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_ );
00248 arrows_node_->setVisible( show_arrows_ );
00249 axes_node_->setVisible( show_axes_ );
00250 }
00251
00252 void TFDisplay::onDisable()
00253 {
00254 root_node_->setVisible( false );
00255 clear();
00256 }
00257
00258 void TFDisplay::setShowNames( bool show )
00259 {
00260 show_names_ = show;
00261
00262 names_node_->setVisible( show );
00263
00264 M_FrameInfo::iterator it = frames_.begin();
00265 M_FrameInfo::iterator end = frames_.end();
00266 for (; it != end; ++it)
00267 {
00268 FrameInfo* frame = it->second;
00269
00270 setFrameEnabled(frame, frame->enabled_);
00271 }
00272
00273 propertyChanged(show_names_property_);
00274 }
00275
00276 void TFDisplay::setShowAxes( bool show )
00277 {
00278 show_axes_ = show;
00279
00280 axes_node_->setVisible( show );
00281
00282 M_FrameInfo::iterator it = frames_.begin();
00283 M_FrameInfo::iterator end = frames_.end();
00284 for (; it != end; ++it)
00285 {
00286 FrameInfo* frame = it->second;
00287
00288 setFrameEnabled(frame, frame->enabled_);
00289 }
00290
00291 propertyChanged(show_axes_property_);
00292 }
00293
00294 void TFDisplay::setShowArrows( bool show )
00295 {
00296 show_arrows_ = show;
00297
00298 arrows_node_->setVisible( show );
00299
00300 M_FrameInfo::iterator it = frames_.begin();
00301 M_FrameInfo::iterator end = frames_.end();
00302 for (; it != end; ++it)
00303 {
00304 FrameInfo* frame = it->second;
00305
00306 setFrameEnabled(frame, frame->enabled_);
00307 }
00308
00309 propertyChanged(show_arrows_property_);
00310 }
00311
00312 void TFDisplay::setAllEnabled(bool enabled)
00313 {
00314 all_enabled_ = enabled;
00315
00316 M_FrameInfo::iterator it = frames_.begin();
00317 M_FrameInfo::iterator end = frames_.end();
00318 for (; it != end; ++it)
00319 {
00320 FrameInfo* frame = it->second;
00321
00322 setFrameEnabled(frame, enabled);
00323 }
00324
00325 propertyChanged(all_enabled_property_);
00326 }
00327
00328 void TFDisplay::setFrameTimeout(float timeout)
00329 {
00330 frame_timeout_ = timeout;
00331 propertyChanged(frame_timeout_property_);
00332 }
00333
00334 void TFDisplay::setUpdateRate( float rate )
00335 {
00336 update_rate_ = rate;
00337
00338 propertyChanged(update_rate_property_);
00339 }
00340
00341 void TFDisplay::update(float wall_dt, float ros_dt)
00342 {
00343 update_timer_ += wall_dt;
00344 if ( update_rate_ < 0.0001f || update_timer_ > update_rate_ )
00345 {
00346 updateFrames();
00347
00348 update_timer_ = 0.0f;
00349 }
00350 }
00351
00352 FrameInfo* TFDisplay::getFrameInfo( const std::string& frame )
00353 {
00354 M_FrameInfo::iterator it = frames_.find( frame );
00355 if ( it == frames_.end() )
00356 {
00357 return NULL;
00358 }
00359
00360 return it->second;
00361 }
00362
00363 void TFDisplay::updateFrames()
00364 {
00365 typedef std::vector<std::string> V_string;
00366 V_string frames;
00367 vis_manager_->getTFClient()->getFrameStrings( frames );
00368 std::sort(frames.begin(), frames.end());
00369
00370 S_FrameInfo current_frames;
00371
00372 {
00373 V_string::iterator it = frames.begin();
00374 V_string::iterator end = frames.end();
00375 for ( ; it != end; ++it )
00376 {
00377 const std::string& frame = *it;
00378
00379 if ( frame.empty() )
00380 {
00381 continue;
00382 }
00383
00384 FrameInfo* info = getFrameInfo( frame );
00385 if (!info)
00386 {
00387 info = createFrame(frame);
00388 }
00389 else
00390 {
00391 updateFrame(info);
00392 }
00393
00394 current_frames.insert( info );
00395 }
00396 }
00397
00398 {
00399 S_FrameInfo to_delete;
00400 M_FrameInfo::iterator frame_it = frames_.begin();
00401 M_FrameInfo::iterator frame_end = frames_.end();
00402 for ( ; frame_it != frame_end; ++frame_it )
00403 {
00404 if ( current_frames.find( frame_it->second ) == current_frames.end() )
00405 {
00406 to_delete.insert( frame_it->second );
00407 }
00408 }
00409
00410 S_FrameInfo::iterator delete_it = to_delete.begin();
00411 S_FrameInfo::iterator delete_end = to_delete.end();
00412 for ( ; delete_it != delete_end; ++delete_it )
00413 {
00414 deleteFrame( *delete_it );
00415 }
00416 }
00417
00418 causeRender();
00419 }
00420
00421 static const Ogre::ColourValue ARROW_HEAD_COLOR(1.0f, 0.1f, 0.6f, 1.0f);
00422 static const Ogre::ColourValue ARROW_SHAFT_COLOR(0.8f, 0.8f, 0.3f, 1.0f);
00423
00424 FrameInfo* TFDisplay::createFrame(const std::string& frame)
00425 {
00426 FrameInfo* info = new FrameInfo;
00427 frames_.insert( std::make_pair( frame, info ) );
00428
00429 info->name_ = frame;
00430 info->last_update_ = ros::Time::now();
00431 info->axes_ = new ogre_tools::Axes( scene_manager_, axes_node_, 0.2, 0.02 );
00432 info->axes_->getSceneNode()->setVisible( show_axes_ );
00433 info->axes_coll_ = vis_manager_->getSelectionManager()->createCollisionForObject(info->axes_, SelectionHandlerPtr(new FrameSelectionHandler(info, this)));
00434
00435 info->name_text_ = new ogre_tools::MovableText( frame, "Arial", 0.1 );
00436 info->name_text_->setTextAlignment(ogre_tools::MovableText::H_CENTER, ogre_tools::MovableText::V_BELOW);
00437 info->name_node_ = names_node_->createChildSceneNode();
00438 info->name_node_->attachObject( info->name_text_ );
00439 info->name_node_->setVisible( show_names_ );
00440
00441 info->parent_arrow_ = new ogre_tools::Arrow( scene_manager_, arrows_node_, 1.0f, 0.01, 1.0f, 0.08 );
00442 info->parent_arrow_->getSceneNode()->setVisible( false );
00443 info->parent_arrow_->setHeadColor(ARROW_HEAD_COLOR);
00444 info->parent_arrow_->setShaftColor(ARROW_SHAFT_COLOR);
00445
00446 info->enabled_ = true;
00447
00448 info->category_ = property_manager_->createCategory( info->name_, property_prefix_ + info->name_, frames_category_, this );
00449 info->enabled_property_ = property_manager_->createProperty<BoolProperty>( "Enabled", property_prefix_ + info->name_, boost::bind( &FrameInfo::isEnabled, info ),
00450 boost::bind( &TFDisplay::setFrameEnabled, this, info, _1 ), info->category_, this );
00451 setPropertyHelpText(info->enabled_property_, "Enable or disable this individual frame.");
00452 info->parent_property_ = property_manager_->createProperty<StringProperty>( "Parent", property_prefix_ + info->name_, boost::bind( &FrameInfo::getParent, info ),
00453 StringProperty::Setter(), info->category_, this );
00454 setPropertyHelpText(info->parent_property_, "Parent of this frame. (Not editable)");
00455 info->position_property_ = property_manager_->createProperty<Vector3Property>( "Position", property_prefix_ + info->name_, boost::bind( &FrameInfo::getPositionInRobotSpace, info ),
00456 Vector3Property::Setter(), info->category_, this );
00457 setPropertyHelpText(info->position_property_, "Position of this frame, in the current Fixed Frame. (Not editable)");
00458 info->orientation_property_ = property_manager_->createProperty<QuaternionProperty>( "Orientation", property_prefix_ + info->name_, boost::bind( &FrameInfo::getOrientationInRobotSpace, info ),
00459 QuaternionProperty::Setter(), info->category_, this );
00460 setPropertyHelpText(info->orientation_property_, "Orientation of this frame, in the current Fixed Frame. (Not editable)");
00461 updateFrame( info );
00462
00463 return info;
00464 }
00465
00466 Ogre::ColourValue lerpColor(const Ogre::ColourValue& start, const Ogre::ColourValue& end, float t)
00467 {
00468 return start * t + end * (1 - t);
00469 }
00470
00471 void TFDisplay::updateFrame(FrameInfo* frame)
00472 {
00473 tf::TransformListener* tf = vis_manager_->getTFClient();
00474
00475
00476 ros::Time latest_time;
00477 tf->getLatestCommonTime(fixed_frame_, frame->name_, latest_time, 0);
00478 if (latest_time != frame->last_time_to_fixed_)
00479 {
00480 frame->last_update_ = ros::Time::now();
00481 frame->last_time_to_fixed_ = latest_time;
00482 }
00483
00484
00485 ros::Duration age = ros::Time::now() - frame->last_update_;
00486 float one_third_timeout = frame_timeout_ * 0.3333333f;
00487 if (age > ros::Duration(frame_timeout_))
00488 {
00489 frame->parent_arrow_->getSceneNode()->setVisible(false);
00490 frame->axes_->getSceneNode()->setVisible(false);
00491 frame->name_node_->setVisible(false);
00492 return;
00493 }
00494 else if (age > ros::Duration(one_third_timeout))
00495 {
00496 Ogre::ColourValue grey(0.7, 0.7, 0.7, 1.0);
00497
00498 if (age > ros::Duration(one_third_timeout * 2))
00499 {
00500 float a = std::max(0.0, (frame_timeout_ - age.toSec())/one_third_timeout);
00501 Ogre::ColourValue c = Ogre::ColourValue(grey.r, grey.g, grey.b, a);
00502
00503 frame->axes_->setXColor(c);
00504 frame->axes_->setYColor(c);
00505 frame->axes_->setZColor(c);
00506 frame->name_text_->setColor(c);
00507 frame->parent_arrow_->setColor(c.r, c.g, c.b, c.a);
00508 }
00509 else
00510 {
00511 float t = std::max(0.0, (one_third_timeout * 2 - age.toSec())/one_third_timeout);
00512 frame->axes_->setXColor(lerpColor(frame->axes_->getDefaultXColor(), grey, t));
00513 frame->axes_->setYColor(lerpColor(frame->axes_->getDefaultYColor(), grey, t));
00514 frame->axes_->setZColor(lerpColor(frame->axes_->getDefaultZColor(), grey, t));
00515 frame->name_text_->setColor(lerpColor(Ogre::ColourValue::White, grey, t));
00516 frame->parent_arrow_->setShaftColor(lerpColor(ARROW_SHAFT_COLOR, grey, t));
00517 frame->parent_arrow_->setHeadColor(lerpColor(ARROW_HEAD_COLOR, grey, t));
00518 }
00519 }
00520 else
00521 {
00522 frame->axes_->setToDefaultColors();
00523 frame->name_text_->setColor(Ogre::ColourValue::White);
00524 frame->parent_arrow_->setHeadColor(ARROW_HEAD_COLOR);
00525 frame->parent_arrow_->setShaftColor(ARROW_SHAFT_COLOR);
00526 }
00527
00528 setStatus(status_levels::Ok, frame->name_, "Transform OK");
00529
00530 if (!vis_manager_->getFrameManager()->getTransform(frame->name_, ros::Time(), frame->position_, frame->orientation_, false))
00531 {
00532 std::stringstream ss;
00533 ss << "No transform from [" << frame->name_ << "] to frame [" << fixed_frame_ << "]";
00534 setStatus(status_levels::Warn, frame->name_, ss.str());
00535 ROS_DEBUG("Error transforming frame '%s' to frame '%s'", frame->name_.c_str(), fixed_frame_.c_str());
00536 }
00537
00538 frame->robot_space_position_ = frame->position_;
00539 ogreToRobot( frame->robot_space_position_ );
00540
00541 frame->robot_space_orientation_ = frame->orientation_;
00542 ogreToRobot( frame->robot_space_orientation_ );
00543
00544 frame->axes_->setPosition( frame->position_ );
00545 frame->axes_->setOrientation( frame->orientation_ );
00546 frame->axes_->getSceneNode()->setVisible(show_axes_ && frame->enabled_);
00547
00548 frame->name_node_->setPosition( frame->position_ );
00549 frame->name_node_->setVisible(show_names_ && frame->enabled_);
00550
00551 propertyChanged(frame->position_property_);
00552 propertyChanged(frame->orientation_property_);
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 {
00560 CategoryPropertyPtr cat_prop = frame->tree_property_.lock();
00561 if ( !cat_prop || old_parent != frame->parent_ )
00562 {
00563 M_FrameInfo::iterator parent_it = frames_.find( frame->parent_ );
00564
00565 if ( parent_it != frames_.end() )
00566 {
00567 FrameInfo* parent = parent_it->second;
00568
00569 property_manager_->deleteProperty( cat_prop );
00570 cat_prop.reset();
00571
00572 if ( parent->tree_property_.lock() )
00573 {
00574 frame->tree_property_ = property_manager_->createCategory( frame->name_, property_prefix_ + frame->name_ + "Tree", parent->tree_property_, this );
00575 }
00576 }
00577 }
00578 }
00579
00580 if ( show_arrows_ )
00581 {
00582 Ogre::Vector3 parent_position;
00583 Ogre::Quaternion parent_orientation;
00584 if (!vis_manager_->getFrameManager()->getTransform(frame->parent_, ros::Time(), parent_position, parent_orientation, false))
00585 {
00586 ROS_DEBUG("Error transforming frame '%s' (parent of '%s') to frame '%s'", frame->parent_.c_str(), frame->name_.c_str(), fixed_frame_.c_str());
00587 }
00588
00589 Ogre::Vector3 direction = parent_position - frame->position_;
00590 float distance = direction.length();
00591 direction.normalise();
00592
00593 Ogre::Quaternion orient = Ogre::Vector3::NEGATIVE_UNIT_Z.getRotationTo( direction );
00594
00595 Ogre::Vector3 old_pos = frame->parent_arrow_->getPosition();
00596
00597 bool distance_changed = fabsf(distance - frame->distance_to_parent_) > 0.0001f;
00598 if ( distance_changed )
00599 {
00600 frame->distance_to_parent_ = distance;
00601 float head_length = ( distance < 0.1 ) ? (0.1*distance) : 0.1;
00602 float shaft_length = distance - head_length;
00603 frame->parent_arrow_->set( shaft_length, 0.02, head_length, 0.08 );
00604 }
00605
00606 if ( distance > 0.001f )
00607 {
00608 frame->parent_arrow_->getSceneNode()->setVisible( show_arrows_ && frame->enabled_ );
00609 }
00610 else
00611 {
00612 frame->parent_arrow_->getSceneNode()->setVisible( false );
00613 }
00614
00615 frame->parent_arrow_->setPosition( frame->position_ );
00616 frame->parent_arrow_->setOrientation( orient );
00617 }
00618 else
00619 {
00620 frame->parent_arrow_->getSceneNode()->setVisible( false );
00621 }
00622 }
00623 else
00624 {
00625 CategoryPropertyPtr tree_prop = frame->tree_property_.lock();
00626 if ( !tree_prop || old_parent != frame->parent_ )
00627 {
00628 property_manager_->deleteProperty( tree_prop );
00629 frame->tree_property_ = property_manager_->createCategory( frame->name_, property_prefix_ + frame->name_ + "Tree", tree_category_, this );
00630 }
00631
00632 frame->parent_arrow_->getSceneNode()->setVisible( false );
00633 }
00634
00635 propertyChanged(frame->parent_property_);
00636 }
00637
00638 void TFDisplay::deleteFrame(FrameInfo* frame)
00639 {
00640 M_FrameInfo::iterator it = frames_.find( frame->name_ );
00641 ROS_ASSERT( it != frames_.end() );
00642
00643 frames_.erase( it );
00644
00645 delete frame->axes_;
00646 vis_manager_->getSelectionManager()->removeObject(frame->axes_coll_);
00647 delete frame->parent_arrow_;
00648 delete frame->name_text_;
00649 scene_manager_->destroySceneNode( frame->name_node_->getName() );
00650 property_manager_->deleteProperty( frame->category_.lock() );
00651 property_manager_->deleteProperty( frame->tree_property_.lock() );
00652 delete frame;
00653 }
00654
00655 void TFDisplay::createProperties()
00656 {
00657 show_names_property_ = property_manager_->createProperty<BoolProperty>( "Show Names", property_prefix_, boost::bind( &TFDisplay::getShowNames, this ),
00658 boost::bind( &TFDisplay::setShowNames, this, _1 ), parent_category_, this );
00659 setPropertyHelpText(show_names_property_, "Whether or not names should be shown next to the frames.");
00660 show_axes_property_ = property_manager_->createProperty<BoolProperty>( "Show Axes", property_prefix_, boost::bind( &TFDisplay::getShowAxes, this ),
00661 boost::bind( &TFDisplay::setShowAxes, this, _1 ), parent_category_, this );
00662 setPropertyHelpText(show_axes_property_, "Whether or not the axes of each frame should be shown.");
00663 show_arrows_property_ = property_manager_->createProperty<BoolProperty>( "Show Arrows", property_prefix_, boost::bind( &TFDisplay::getShowArrows, this ),
00664 boost::bind( &TFDisplay::setShowArrows, this, _1 ), parent_category_, this );
00665 setPropertyHelpText(show_arrows_property_, "Whether or not arrows from child to parent should be shown.");
00666 update_rate_property_ = property_manager_->createProperty<FloatProperty>( "Update Interval", property_prefix_, boost::bind( &TFDisplay::getUpdateRate, this ),
00667 boost::bind( &TFDisplay::setUpdateRate, this, _1 ), parent_category_, this );
00668 setPropertyHelpText(update_rate_property_, "The interval, in seconds, at which to update the frame transforms. 0 means to do so every update cycle.");
00669 FloatPropertyPtr float_prop = update_rate_property_.lock();
00670 float_prop->setMin( 0.0 );
00671 float_prop->addLegacyName("Update Rate");
00672
00673 frame_timeout_property_ = property_manager_->createProperty<FloatProperty>( "Frame Timeout", property_prefix_, boost::bind( &TFDisplay::getFrameTimeout, this ),
00674 boost::bind( &TFDisplay::setFrameTimeout, this, _1 ), parent_category_, this );
00675 setPropertyHelpText(frame_timeout_property_, "The length of time, in seconds, before a frame that has not been updated is considered \"dead\". For 1/3 of this time"
00676 " the frame will appear correct, for the second 1/3rd it will fade to gray, and then it will fade out completely.");
00677 float_prop = frame_timeout_property_.lock();
00678 float_prop->setMin( 1.0 );
00679
00680 frames_category_ = property_manager_->createCategory( "Frames", property_prefix_, parent_category_, this );
00681 setPropertyHelpText(frames_category_, "The list of all frames.");
00682 CategoryPropertyPtr cat_prop = frames_category_.lock();
00683 cat_prop->collapse();
00684
00685 all_enabled_property_ = property_manager_->createProperty<BoolProperty>( "All Enabled", property_prefix_, boost::bind( &TFDisplay::getAllEnabled, this ),
00686 boost::bind( &TFDisplay::setAllEnabled, this, _1 ), frames_category_, this );
00687 setPropertyHelpText(all_enabled_property_, "Whether all the frames should be enabled or not.");
00688
00689 tree_category_ = property_manager_->createCategory( "Tree", property_prefix_, parent_category_, this );
00690 setPropertyHelpText(tree_category_, "A tree-view of the frames, showing the parent/child relationships.");
00691 cat_prop = tree_category_.lock();
00692 cat_prop->collapse();
00693 }
00694
00695 void TFDisplay::targetFrameChanged()
00696 {
00697 update_timer_ = update_rate_;
00698 }
00699
00700 void TFDisplay::reset()
00701 {
00702 Display::reset();
00703 clear();
00704 }
00705
00706 }
00707