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