tf_display.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2012, Willow Garage, Inc.
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of the Willow Garage, Inc. nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  */
29 
30 #include <boost/bind/bind.hpp>
31 #include <regex>
32 
33 #include <OgreSceneNode.h>
34 #include <OgreSceneManager.h>
35 #include <QValidator>
36 #include <QLineEdit>
37 #include <QToolTip>
38 
39 #include <rviz/display_context.h>
40 #include <rviz/frame_manager.h>
42 #include <rviz/ogre_helpers/axes.h>
51 
53 
54 namespace rviz
55 {
57 {
58 public:
61  {
62  }
63 
64  void createProperties(const Picked& obj, Property* parent_property) override;
65  void destroyProperties(const Picked& obj, Property* parent_property) override;
66 
67  bool getEnabled();
68  void setEnabled(bool enabled);
69  void setParentName(const std::string& parent_name);
70  void setPosition(const Ogre::Vector3& position);
71  void setOrientation(const Ogre::Quaternion& orientation);
72 
73 private:
80 };
81 
83  : SelectionHandler(context)
84  , frame_(frame)
85  , category_property_(nullptr)
86  , enabled_property_(nullptr)
87  , parent_property_(nullptr)
88  , position_property_(nullptr)
89  , orientation_property_(nullptr)
90 {
91 }
92 
93 void FrameSelectionHandler::createProperties(const Picked& /*obj*/, Property* parent_property)
94 {
96  new Property("Frame " + QString::fromStdString(frame_->name_), QVariant(), "", parent_property);
97 
98  enabled_property_ = new BoolProperty("Enabled", true, "", category_property_,
100 
101  parent_property_ = new StringProperty("Parent", "", "", category_property_);
103 
104  position_property_ = new VectorProperty("Position", Ogre::Vector3::ZERO, "", category_property_);
106 
108  new QuaternionProperty("Orientation", Ogre::Quaternion::IDENTITY, "", category_property_);
110 }
111 
112 void FrameSelectionHandler::destroyProperties(const Picked& /*obj*/, Property* /*parent_property*/)
113 {
114  delete category_property_; // This deletes its children as well.
115  category_property_ = nullptr;
116  enabled_property_ = nullptr;
117  parent_property_ = nullptr;
118  position_property_ = nullptr;
119  orientation_property_ = nullptr;
120 }
121 
123 {
124  if (enabled_property_)
125  {
126  return enabled_property_->getBool();
127  }
128  return false; // should never happen, but don't want to crash if it does.
129 }
130 
132 {
133  if (enabled_property_)
134  {
135  enabled_property_->setBool(enabled);
136  }
137 }
138 
139 void FrameSelectionHandler::setParentName(const std::string& parent_name)
140 {
141  if (parent_property_)
142  {
143  parent_property_->setStdString(parent_name);
144  }
145 }
146 
147 void FrameSelectionHandler::setPosition(const Ogre::Vector3& position)
148 {
149  if (position_property_)
150  {
151  position_property_->setVector(position);
152  }
153 }
154 
155 void FrameSelectionHandler::setOrientation(const Ogre::Quaternion& orientation)
156 {
158  {
159  orientation_property_->setQuaternion(orientation);
160  }
161 }
162 
163 class RegexValidator : public QValidator
164 {
165  QLineEdit* editor_;
166 
167 public:
168  RegexValidator(QLineEdit* editor) : QValidator(editor), editor_(editor)
169  {
170  }
171  QValidator::State validate(QString& input, int& /*pos*/) const override
172  {
173  try
174  {
175  std::regex(input.toLocal8Bit().constData());
176  editor_->setStyleSheet(QString());
177  QToolTip::hideText();
178  return QValidator::Acceptable;
179  }
180  catch (const std::regex_error& e)
181  {
182  editor_->setStyleSheet("background: #ffe4e4");
183  QToolTip::showText(editor_->mapToGlobal(QPoint(0, 5)), tr(e.what()), editor_, QRect(), 5000);
184  return QValidator::Intermediate;
185  }
186  }
187 };
188 
190 {
191  std::regex default_;
192  std::regex regex_;
193 
195  {
196  const auto& value = getString();
197  if (value.isEmpty())
198  regex_ = default_;
199  else
200  {
201  try
202  {
203  regex_.assign(value.toLocal8Bit().constData(), std::regex_constants::optimize);
204  }
205  catch (const std::regex_error& e)
206  {
207  regex_ = default_;
208  }
209  }
210  }
211 
212 public:
213  RegexFilterProperty(const QString& name, const std::regex& regex, Property* parent)
214  : StringProperty(name, "", "regular expression", parent), default_(regex), regex_(regex)
215  {
216  QObject::connect(this, &RegexFilterProperty::changed, this, [this]() { onValueChanged(); });
217  }
218  const std::regex& regex() const
219  {
220  return regex_;
221  }
222 
223  QWidget* createEditor(QWidget* parent, const QStyleOptionViewItem& option) override
224  {
225  auto* editor = qobject_cast<QLineEdit*>(StringProperty::createEditor(parent, option));
226  if (editor)
227  editor->setValidator(new RegexValidator(editor));
228  return editor;
229  }
230 };
231 
232 typedef std::set<FrameInfo*> S_FrameInfo;
233 
234 TFDisplay::TFDisplay() : Display(), update_timer_(0.0f), changing_single_frame_enabled_state_(false)
235 {
237  new BoolProperty("Show Names", true, "Whether or not names should be shown next to the frames.",
239 
241  new BoolProperty("Show Axes", true, "Whether or not the axes of each frame should be shown.", this,
243 
244  show_arrows_property_ = new BoolProperty("Show Arrows", true,
245  "Whether or not arrows from child to parent should be shown.",
247 
249  new FloatProperty("Marker Scale", 1, "Scaling factor for all names, axes and arrows.", this);
250 
251  alpha_property_ = new FloatProperty("Marker Alpha", 1, "Alpha channel value for all axes.", this);
254 
255  update_rate_property_ = new FloatProperty("Update Interval", 0,
256  "The interval, in seconds, at which to update the frame "
257  "transforms. 0 means to do so every update cycle.",
258  this);
260 
262  "Frame Timeout", 15,
263  "The length of time, in seconds, before a frame that has not been updated is considered \"dead\"."
264  " For 1/3 of this time the frame will appear correct, for the second 1/3rd it will fade to gray,"
265  " and then it will fade out completely.",
266  this);
268 
269  filter_whitelist_property_ = new RegexFilterProperty("Filter (whitelist)", std::regex(""), this);
270  filter_blacklist_property_ = new RegexFilterProperty("Filter (blacklist)", std::regex(), this);
271 
272  frames_category_ = new Property("Frames", QVariant(), "The list of all frames.", this);
273 
275  new BoolProperty("All Enabled", true, "Whether all the frames should be enabled or not.",
277 
278  tree_category_ = new Property(
279  "Tree", QVariant(), "A tree-view of the frames, showing the parent/child relationships.", this);
280 }
281 
283 {
284  clear();
285  if (initialized())
286  {
287  root_node_->removeAndDestroyAllChildren();
288  scene_manager_->destroySceneNode(root_node_);
289  }
290 }
291 
293 {
295 
296  root_node_ = scene_node_->createChildSceneNode();
297 
298  names_node_ = root_node_->createChildSceneNode();
299  arrows_node_ = root_node_->createChildSceneNode();
300  axes_node_ = root_node_->createChildSceneNode();
301 }
302 
303 void TFDisplay::load(const Config& config)
304 {
306 
307  // Load the enabled state for all frames specified in the config, and store
308  // the values in a map so that the enabled state can be properly set once
309  // the frame is created
310  Config c = config.mapGetChild("Frames");
311  for (Config::MapIterator iter = c.mapIterator(); iter.isValid(); iter.advance())
312  {
313  QString key = iter.currentKey();
314  if (key != "All Enabled")
315  {
316  const Config& child = iter.currentChild();
317  bool enabled = child.mapGetChild("Value").getValue().toBool();
318 
319  frame_config_enabled_state_[key.toStdString()] = enabled;
320  }
321  }
322 }
323 
325 {
326  // Clear the tree.
328 
329  // Clear the frames category, except for the "All enabled" property, which is first.
331 
332  // Clear all frames
333  while (!frames_.empty())
334  deleteFrame(frames_.begin(), false);
335 
336  update_timer_ = 0.0f;
337 
338  clearStatuses();
339 }
340 
342 {
343  root_node_->setVisible(true);
344 
345  names_node_->setVisible(show_names_property_->getBool());
347  axes_node_->setVisible(show_axes_property_->getBool());
348 }
349 
351 {
352  root_node_->setVisible(false);
353  clear();
354 }
355 
357 {
358  names_node_->setVisible(show_names_property_->getBool());
359 
360  M_FrameInfo::iterator it = frames_.begin();
361  M_FrameInfo::iterator end = frames_.end();
362  for (; it != end; ++it)
363  {
364  FrameInfo* frame = it->second;
365 
366  frame->updateVisibilityFromFrame();
367  }
368 }
369 
371 {
372  axes_node_->setVisible(show_axes_property_->getBool());
373 
374  M_FrameInfo::iterator it = frames_.begin();
375  M_FrameInfo::iterator end = frames_.end();
376  for (; it != end; ++it)
377  {
378  FrameInfo* frame = it->second;
379 
380  frame->updateVisibilityFromFrame();
381  }
382 }
383 
385 {
387 
388  M_FrameInfo::iterator it = frames_.begin();
389  M_FrameInfo::iterator end = frames_.end();
390  for (; it != end; ++it)
391  {
392  FrameInfo* frame = it->second;
393 
394  frame->updateVisibilityFromFrame();
395  }
396 }
397 
399 {
401  {
402  return;
403  }
404  bool enabled = all_enabled_property_->getBool();
405 
406  M_FrameInfo::iterator it = frames_.begin();
407  M_FrameInfo::iterator end = frames_.end();
408  for (; it != end; ++it)
409  {
410  FrameInfo* frame = it->second;
411 
412  frame->enabled_property_->setBool(enabled);
413  }
414 }
415 
416 void TFDisplay::update(float wall_dt, float /*ros_dt*/)
417 {
418  update_timer_ += wall_dt;
419  float update_rate = update_rate_property_->getFloat();
420  if (update_rate < 0.0001f || update_timer_ > update_rate)
421  {
422  updateFrames();
423 
424  update_timer_ = 0.0f;
425  }
426 }
427 
428 FrameInfo* TFDisplay::getFrameInfo(const std::string& frame)
429 {
430  M_FrameInfo::iterator it = frames_.find(frame);
431  if (it == frames_.end())
432  {
433  return nullptr;
434  }
435 
436  return it->second;
437 }
438 
440 {
441  typedef std::vector<std::string> V_string;
442  V_string frames;
443  context_->getTF2BufferPtr()->_getFrameStrings(frames);
444 
445  // filter frames according to white- and black-list regular expressions
446  auto it = frames.begin(), end = frames.end();
447  while (it != end)
448  {
449  if (it->empty() || !std::regex_search(*it, filter_whitelist_property_->regex()) ||
450  std::regex_search(*it, filter_blacklist_property_->regex()))
451  std::swap(*it, *--end); // swap current to-be-dropped name with last one
452  else
453  ++it;
454  }
455 
456  S_FrameInfo current_frames;
457  for (it = frames.begin(); it != end; ++it)
458  {
459  FrameInfo* info = getFrameInfo(*it);
460  if (!info)
461  {
462  info = createFrame(*it);
463  }
464  else
465  {
466  updateFrame(info);
467  }
468 
469  current_frames.insert(info);
470  }
471 
472  for (auto frame_it = frames_.begin(), frame_end = frames_.end(); frame_it != frame_end;)
473  {
474  if (current_frames.find(frame_it->second) == current_frames.end())
475  frame_it = deleteFrame(frame_it, true);
476  else
477  ++frame_it;
478  }
479 
481 }
482 
483 static const Ogre::ColourValue ARROW_HEAD_COLOR(1.0f, 0.1f, 0.6f, 1.0f);
484 static const Ogre::ColourValue ARROW_SHAFT_COLOR(0.8f, 0.8f, 0.3f, 1.0f);
485 
486 FrameInfo* TFDisplay::createFrame(const std::string& frame)
487 {
488  FrameInfo* info = new FrameInfo(this);
489  frames_.insert(std::make_pair(frame, info));
490 
491  info->name_ = frame;
492  info->last_update_ = ros::Time::now();
493  info->axes_ = new Axes(scene_manager_, axes_node_, 0.2, 0.02);
494  info->axes_->getSceneNode()->setVisible(show_axes_property_->getBool());
495  info->selection_handler_.reset(new FrameSelectionHandler(info, context_));
496  info->selection_handler_->addTrackedObjects(info->axes_->getSceneNode());
497 
498  info->name_text_ = new MovableText(frame, "Liberation Sans", 0.1);
500  info->name_node_ = names_node_->createChildSceneNode();
501  info->name_node_->attachObject(info->name_text_);
502  info->name_node_->setVisible(show_names_property_->getBool());
503 
504  info->parent_arrow_ = new Arrow(scene_manager_, arrows_node_, 1.0f, 0.01, 1.0f, 0.08);
505  info->parent_arrow_->getSceneNode()->setVisible(false);
508 
509  info->enabled_property_ = new BoolProperty(QString::fromStdString(info->name_), true,
510  "Enable or disable this individual frame.", nullptr,
513 
514  info->parent_property_ =
515  new StringProperty("Parent", "", "Parent of this frame. (Not editable)", info->enabled_property_);
516  info->parent_property_->setReadOnly(true);
517 
518  info->position_property_ =
519  new VectorProperty("Position", Ogre::Vector3::ZERO,
520  "Position of this frame, in the current Fixed Frame. (Not editable)",
521  info->enabled_property_);
522  info->position_property_->setReadOnly(true);
523 
524  info->orientation_property_ =
525  new QuaternionProperty("Orientation", Ogre::Quaternion::IDENTITY,
526  "Orientation of this frame, in the current Fixed Frame. (Not editable)",
527  info->enabled_property_);
528  info->orientation_property_->setReadOnly(true);
529 
530  info->rel_position_property_ =
531  new VectorProperty("Relative Position", Ogre::Vector3::ZERO,
532  "Position of this frame, relative to it's parent frame. (Not editable)",
533  info->enabled_property_);
534  info->rel_position_property_->setReadOnly(true);
535 
537  new QuaternionProperty("Relative Orientation", Ogre::Quaternion::IDENTITY,
538  "Orientation of this frame, relative to it's parent frame. (Not editable)",
539  info->enabled_property_);
541 
542  // If the current frame was specified as disabled in the config file
543  // then its enabled state must be updated accordingly
544  if (frame_config_enabled_state_.count(frame) > 0 && !frame_config_enabled_state_[frame])
545  {
546  info->enabled_property_->setBool(false);
547  }
548 
549  updateFrame(info);
550 
551  return info;
552 }
553 
554 Ogre::ColourValue lerpColor(const Ogre::ColourValue& start, const Ogre::ColourValue& end, float t)
555 {
556  return start * t + end * (1 - t);
557 }
558 
560 {
561  while (child != root)
562  {
563  if (child == parent)
564  return true;
565  child = child->getParent();
566  }
567  return false;
568 }
569 
571 {
572  auto tf = context_->getTF2BufferPtr();
573  tf2::CompactFrameID target_id = tf->_lookupFrameNumber(fixed_frame_.toStdString());
574  tf2::CompactFrameID source_id = tf->_lookupFrameNumber(frame->name_);
575 
576  // Check last received time so we can grey out/fade out frames that have stopped being published
577  ros::Time latest_time;
578  tf->_getLatestCommonTime(target_id, source_id, latest_time, nullptr);
579 
580  if ((latest_time != frame->last_time_to_fixed_) || (latest_time == ros::Time()))
581  {
582  frame->last_update_ = ros::Time::now();
583  frame->last_time_to_fixed_ = latest_time;
584  }
585 
586  // Fade from color -> grey, then grey -> fully transparent
587  ros::Duration age = ros::Time::now() - frame->last_update_;
588  float frame_timeout = frame_timeout_property_->getFloat();
589  float one_third_timeout = frame_timeout * 0.3333333f;
590  if (age > ros::Duration(frame_timeout))
591  {
592  frame->parent_arrow_->getSceneNode()->setVisible(false);
593  frame->axes_->getSceneNode()->setVisible(false);
594  frame->name_node_->setVisible(false);
595  return;
596  }
597  else if (age > ros::Duration(one_third_timeout))
598  {
599  Ogre::ColourValue grey(0.7, 0.7, 0.7, 1.0);
600 
601  if (age > ros::Duration(one_third_timeout * 2))
602  {
603  float a = std::max(0.0, (frame_timeout - age.toSec()) / one_third_timeout);
604  Ogre::ColourValue c = Ogre::ColourValue(grey.r, grey.g, grey.b, a);
605 
606  frame->axes_->setXColor(c);
607  frame->axes_->setYColor(c);
608  frame->axes_->setZColor(c);
609  frame->name_text_->setColor(c);
610  frame->parent_arrow_->setColor(c.r, c.g, c.b, c.a);
611  }
612  else
613  {
614  float t = std::max(0.0, (one_third_timeout * 2 - age.toSec()) / one_third_timeout);
615  frame->axes_->setXColor(lerpColor(frame->axes_->getDefaultXColor(), grey, t));
616  frame->axes_->setYColor(lerpColor(frame->axes_->getDefaultYColor(), grey, t));
617  frame->axes_->setZColor(lerpColor(frame->axes_->getDefaultZColor(), grey, t));
618  frame->name_text_->setColor(lerpColor(Ogre::ColourValue::White, grey, t));
621  }
622  }
623  else
624  {
625  frame->axes_->setToDefaultColors();
626  frame->name_text_->setColor(Ogre::ColourValue::White);
629  }
630 
631  setStatusStd(StatusProperty::Ok, frame->name_, "Transform OK");
632 
633  float scale = scale_property_->getFloat();
634  bool frame_enabled = frame->enabled_property_->getBool();
635 
636  Ogre::Vector3 position;
637  Ogre::Quaternion orientation;
638  if (!context_->getFrameManager()->getTransform(frame->name_, ros::Time(), position, orientation))
639  {
640  std::stringstream ss;
641  ss << "No transform from [" << frame->name_ << "] to frame [" << fixed_frame_.toStdString() << "]";
642  setStatusStd(StatusProperty::Warn, frame->name_, ss.str());
643  ROS_DEBUG("Error transforming frame '%s' to frame '%s'", frame->name_.c_str(),
644  qPrintable(fixed_frame_));
645  frame->name_node_->setVisible(false);
646  frame->axes_->getSceneNode()->setVisible(false);
647  frame->parent_arrow_->getSceneNode()->setVisible(false);
648  }
649  else
650  {
651  frame->selection_handler_->setPosition(position);
652  frame->selection_handler_->setOrientation(orientation);
653 
654  frame->axes_->setPosition(position);
655  frame->axes_->setOrientation(orientation);
656  frame->axes_->getSceneNode()->setVisible(show_axes_property_->getBool() && frame_enabled);
657  frame->axes_->setScale(Ogre::Vector3(scale, scale, scale));
659 
660  frame->name_node_->setPosition(position);
661  frame->name_node_->setVisible(show_names_property_->getBool() && frame_enabled);
662  frame->name_node_->setScale(scale, scale, scale);
663 
664  frame->position_property_->setVector(position);
665  frame->orientation_property_->setQuaternion(orientation);
666  }
667 
668  std::string old_parent = frame->parent_;
669  frame->parent_.clear();
670  bool has_parent = tf->_getParent(frame->name_, ros::Time(), frame->parent_);
671  if (has_parent)
672  {
673  geometry_msgs::TransformStamped transform;
674  try
675  {
676  transform = tf->lookupTransform(frame->parent_, frame->name_, ros::Time());
677  }
678  catch (tf2::TransformException& e)
679  {
680  ROS_DEBUG("Error transforming frame '%s' (parent of '%s') to frame '%s'", frame->parent_.c_str(),
681  frame->name_.c_str(), qPrintable(fixed_frame_));
682  transform.transform.rotation.w = 1.0;
683  }
684 
685  // get the position/orientation relative to the parent frame
686  const auto& translation = transform.transform.translation;
687  const auto& quat = transform.transform.rotation;
688  Ogre::Vector3 relative_position(translation.x, translation.y, translation.z);
689  Ogre::Quaternion relative_orientation(quat.w, quat.x, quat.y, quat.z);
690  frame->rel_position_property_->setVector(relative_position);
691  frame->rel_orientation_property_->setQuaternion(relative_orientation);
692 
694  {
695  Ogre::Vector3 parent_position;
696  Ogre::Quaternion parent_orientation;
697  if (!context_->getFrameManager()->getTransform(frame->parent_, ros::Time(), parent_position,
698  parent_orientation))
699  {
700  ROS_DEBUG("Error transforming frame '%s' (parent of '%s') to frame '%s'", frame->parent_.c_str(),
701  frame->name_.c_str(), qPrintable(fixed_frame_));
702  }
703 
704  Ogre::Vector3 direction = parent_position - position;
705  float distance = direction.length();
706  direction.normalise();
707 
708  Ogre::Quaternion orient = Ogre::Vector3::NEGATIVE_UNIT_Z.getRotationTo(direction);
709 
710  frame->distance_to_parent_ = distance;
711  float head_length = (distance < 0.1 * scale) ? (0.1 * scale * distance) : 0.1 * scale;
712  float shaft_length = distance - head_length;
713  // aleeper: This was changed from 0.02 and 0.08 to 0.01 and 0.04 to match proper radius handling in
714  // arrow.cpp
715  frame->parent_arrow_->set(shaft_length, 0.01 * scale, head_length, 0.04 * scale);
716 
717  if (distance > 0.001f)
718  {
719  frame->parent_arrow_->getSceneNode()->setVisible(show_arrows_property_->getBool() &&
720  frame_enabled);
721  }
722  else
723  {
724  frame->parent_arrow_->getSceneNode()->setVisible(false);
725  }
726 
727  frame->parent_arrow_->setPosition(position);
728  frame->parent_arrow_->setOrientation(orient);
729  }
730  else
731  {
732  frame->parent_arrow_->getSceneNode()->setVisible(false);
733  }
734  }
735  else
736  {
737  frame->parent_arrow_->getSceneNode()->setVisible(false);
738  }
739 
740  // If this frame has no tree property yet or the parent has changed,
741  if (!frame->tree_property_ || old_parent != frame->parent_ ||
742  // or its actual parent was not yet created
743  (has_parent && frame->tree_property_->getParent() == tree_category_))
744  {
745  // Look up the new parent.
746  FrameInfo* parent = has_parent ? getFrameInfo(frame->parent_) : nullptr;
747  // Retrieve tree property to add the new child at
748  rviz::Property* parent_tree_property;
749  if (parent && parent->tree_property_) // parent already created
750  {
751  parent_tree_property = parent->tree_property_;
752  if (hasLoop(parent_tree_property, frame->tree_property_, tree_category_))
753  parent_tree_property = tree_category_; // insert loops at root node
754  }
755  else // create (temporarily) at root
756  parent_tree_property = tree_category_;
757 
758  if (!frame->tree_property_)
759  { // create new tree node
760  frame->tree_property_ = new Property(QString::fromStdString(frame->name_));
761  parent_tree_property->insertChildSorted(frame->tree_property_);
762  }
763  else if (frame->tree_property_->getParent() != parent_tree_property)
764  { // re-parent existing tree property
766  parent_tree_property->insertChildSorted(frame->tree_property_);
767  }
768  }
769 
770  frame->parent_property_->setStdString(frame->parent_);
771  frame->selection_handler_->setParentName(frame->parent_);
772 }
773 
774 TFDisplay::M_FrameInfo::iterator TFDisplay::deleteFrame(M_FrameInfo::iterator it, bool delete_properties)
775 {
776  FrameInfo* frame = it->second;
777  it = frames_.erase(it);
778 
779  delete frame->axes_;
781  delete frame->parent_arrow_;
782  delete frame->name_text_;
783  scene_manager_->destroySceneNode(frame->name_node_);
784  if (delete_properties)
785  {
786  delete frame->enabled_property_;
787  // re-parent all children to root tree node
788  for (int i = frame->tree_property_->numChildren() - 1; i >= 0; --i)
789  {
790  auto* child = frame->tree_property_->takeChild(frame->tree_property_->childAtUnchecked(i));
792  }
793  delete frame->tree_property_;
794  }
795  delete frame;
796  return it;
797 }
798 
800 {
802 }
803 
805 {
806  Display::reset();
807  clear();
808 }
809 
811 // FrameInfo
812 
814  : display_(display)
815  , axes_(nullptr)
816  , axes_coll_(0)
817  , parent_arrow_(nullptr)
818  , name_text_(nullptr)
819  , distance_to_parent_(0.0f)
820  , arrow_orientation_(Ogre::Quaternion::IDENTITY)
821  , tree_property_(nullptr)
822 {
823 }
824 
826 {
827  bool enabled = enabled_property_->getBool();
828  selection_handler_->setEnabled(enabled);
829  setEnabled(enabled);
830 }
831 
833 {
834  bool enabled = selection_handler_->getEnabled();
835  enabled_property_->setBool(enabled);
836  setEnabled(enabled);
837 }
838 
839 void FrameInfo::setEnabled(bool enabled)
840 {
841  if (name_node_)
842  {
843  name_node_->setVisible(display_->show_names_property_->getBool() && enabled);
844  }
845 
846  if (axes_)
847  {
848  axes_->getSceneNode()->setVisible(display_->show_axes_property_->getBool() && enabled);
849  }
850 
851  if (parent_arrow_)
852  {
853  if (distance_to_parent_ > 0.001f)
854  {
855  parent_arrow_->getSceneNode()->setVisible(display_->show_arrows_property_->getBool() && enabled);
856  }
857  else
858  {
859  parent_arrow_->getSceneNode()->setVisible(false);
860  }
861  }
862 
863  if (display_->all_enabled_property_->getBool() && !enabled)
864  {
868  }
869 
870  // Update the configuration that stores the enabled state of all frames
871  display_->frame_config_enabled_state_[this->name_] = enabled;
872 
874 }
875 
876 } // namespace rviz
877 
rviz::MovableText::setTextAlignment
void setTextAlignment(const HorizontalAlignment &horizontalAlignment, const VerticalAlignment &verticalAlignment)
Definition: movable_text.cpp:182
rviz::Arrow::set
void set(float shaft_length, float shaft_diameter, float head_length, float head_diameter)
Set the parameters for this arrow.
Definition: arrow.cpp:74
rviz::hasLoop
bool hasLoop(rviz::Property *child, rviz::Property *parent, rviz::Property *root)
Definition: tf_display.cpp:559
rviz::FrameInfo::axes_
Axes * axes_
Definition: tf_display.h:157
rviz::Property::insertChildSorted
void insertChildSorted(Property *child)
Insert a child property, sorted by name.
Definition: property.cpp:385
rviz::FrameInfo::parent_arrow_
Arrow * parent_arrow_
Definition: tf_display.h:160
rviz::BoolProperty::getBool
virtual bool getBool() const
Definition: bool_property.cpp:48
rviz::TFDisplay::reset
void reset() override
Called to tell the display to clear its state.
Definition: tf_display.cpp:804
rviz::TFDisplay::frames_
M_FrameInfo frames_
Definition: tf_display.h:108
axes.h
rviz::Axes::getSceneNode
Ogre::SceneNode * getSceneNode()
Get the scene node associated with this object.
Definition: axes.h:96
rviz::Axes::getDefaultYColor
const Ogre::ColourValue & getDefaultYColor()
Definition: axes.cpp:163
rviz::TFDisplay::show_arrows_property_
BoolProperty * show_arrows_property_
Definition: tf_display.h:116
rviz::FrameInfo::tree_property_
Property * tree_property_
Definition: tf_display.h:177
rviz::RegexValidator
Definition: tf_display.cpp:163
rviz::Axes::getDefaultZColor
const Ogre::ColourValue & getDefaultZColor()
Definition: axes.cpp:168
rviz::TFDisplay::arrows_node_
Ogre::SceneNode * arrows_node_
Definition: tf_display.h:105
Ogre
Definition: axes_display.h:35
frame_manager.h
rviz::DisplayContext::queueRender
virtual void queueRender()=0
Queues a render. Multiple calls before a render happens will only cause a single render.
rviz::FrameSelectionHandler::~FrameSelectionHandler
~FrameSelectionHandler() override
Definition: tf_display.cpp:60
rviz::FrameInfo::last_update_
ros::Time last_update_
Definition: tf_display.h:167
rviz::Arrow
An arrow consisting of a cylinder and a cone.
Definition: arrow.h:57
rviz::Display::initialized
bool initialized() const
Returns true if the display has been initialized.
Definition: display.h:275
rviz::FrameInfo::orientation_property_
QuaternionProperty * orientation_property_
Definition: tf_display.h:173
rviz::Axes::setScale
void setScale(const Ogre::Vector3 &scale) override
Set the scale of the object. Always relative to the identity orientation of the object.
Definition: axes.cpp:102
rviz::TFDisplay::allEnabledChanged
void allEnabledChanged()
Definition: tf_display.cpp:398
forwards.h
rviz::TFDisplay::deleteFrame
M_FrameInfo::iterator deleteFrame(M_FrameInfo::iterator it, bool delete_properties)
Definition: tf_display.cpp:774
rviz::FrameSelectionHandler::category_property_
Property * category_property_
Definition: tf_display.cpp:75
rviz::Config::MapIterator::isValid
bool isValid()
Return true if the iterator currently points to a valid entry, false if not.
Definition: config.cpp:392
rviz::FrameSelectionHandler::setParentName
void setParentName(const std::string &parent_name)
Definition: tf_display.cpp:139
rviz::Arrow::setOrientation
void setOrientation(const Ogre::Quaternion &orientation) override
Set the orientation.
Definition: arrow.cpp:119
rviz::TFDisplay::tree_category_
Property * tree_category_
Definition: tf_display.h:128
rviz::Display::clearStatuses
virtual void clearStatuses()
Delete all status children. This is thread-safe.
Definition: display.cpp:212
rviz::BoolProperty::setBool
bool setBool(bool value)
Definition: bool_property.h:84
rviz::BoolProperty
Property specialized to provide getter for booleans.
Definition: bool_property.h:38
rviz::FloatProperty::setMax
void setMax(float max)
Definition: float_property.cpp:57
rviz::TFDisplay::changing_single_frame_enabled_state_
bool changing_single_frame_enabled_state_
Definition: tf_display.h:130
rviz::FrameSelectionHandler::parent_property_
StringProperty * parent_property_
Definition: tf_display.cpp:77
rviz::Axes::setXColor
void setXColor(const Ogre::ColourValue &col)
Definition: axes.cpp:129
rviz::FrameInfo::name_
std::string name_
Definition: tf_display.h:155
rviz::TFDisplay::alpha_property_
FloatProperty * alpha_property_
Definition: tf_display.h:123
float_property.h
rviz::FrameSelectionHandler::setEnabled
void setEnabled(bool enabled)
Definition: tf_display.cpp:131
rviz::Property::numChildren
virtual int numChildren() const
Return the number of child objects (Property or otherwise).
Definition: property.h:287
rviz::TFDisplay::getFrameInfo
FrameInfo * getFrameInfo(const std::string &frame)
Definition: tf_display.cpp:428
rviz::FrameInfo::rel_position_property_
VectorProperty * rel_position_property_
Definition: tf_display.h:170
selection_manager.h
rviz::Display::fixed_frame_
QString fixed_frame_
A convenience variable equal to context_->getFixedFrame().
Definition: display.h:312
rviz::TFDisplay::root_node_
Ogre::SceneNode * root_node_
Definition: tf_display.h:103
rviz::QuaternionProperty::setReadOnly
void setReadOnly(bool read_only) override
Overridden from Property to propagate read-only-ness to children.
Definition: quaternion_property.cpp:158
bool_property.h
rviz::FrameSelectionHandler::FrameSelectionHandler
FrameSelectionHandler(FrameInfo *frame, DisplayContext *context)
Definition: tf_display.cpp:82
rviz::MovableText
Definition: movable_text.h:59
rviz::TFDisplay::updateShowAxes
void updateShowAxes()
Definition: tf_display.cpp:370
rviz::Property::Property
Property(const QString &name=QString(), const QVariant &default_value=QVariant(), const QString &description=QString(), Property *parent=nullptr)
Constructor.
Definition: property.cpp:59
rviz::BoolProperty::BoolProperty
BoolProperty(const QString &name=QString(), bool default_value=false, const QString &description=QString(), Property *parent=nullptr)
Definition: bool_property.cpp:36
rviz::TFDisplay::updateShowNames
void updateShowNames()
Definition: tf_display.cpp:356
rviz::MovableText::V_BELOW
@ V_BELOW
Definition: movable_text.h:70
rviz::TFDisplay::names_node_
Ogre::SceneNode * names_node_
Definition: tf_display.h:104
rviz::FrameInfo::parent_property_
StringProperty * parent_property_
Definition: tf_display.h:174
rviz::FloatProperty::setMin
void setMin(float min)
Definition: float_property.cpp:51
rviz::RegexValidator::RegexValidator
RegexValidator(QLineEdit *editor)
Definition: tf_display.cpp:168
rviz::lerpColor
Ogre::ColourValue lerpColor(const Ogre::ColourValue &start, const Ogre::ColourValue &end, float t)
Definition: tf_display.cpp:554
rviz::TFDisplay::clear
void clear()
Definition: tf_display.cpp:324
f
f
rviz::MovableText::H_CENTER
@ H_CENTER
Definition: movable_text.h:66
quaternion_property.h
rviz::Display
Definition: display.h:63
rviz::TFDisplay::updateFrame
void updateFrame(FrameInfo *frame)
Definition: tf_display.cpp:570
rviz::QuaternionProperty
Definition: quaternion_property.h:38
rviz::FloatProperty
Property specialized to enforce floating point max/min.
Definition: float_property.h:37
tf2::CompactFrameID
uint32_t CompactFrameID
rviz::Picked
Definition: forwards.h:53
rviz::TFDisplay::show_names_property_
BoolProperty * show_names_property_
Definition: tf_display.h:115
rviz::Property
A single element of a property tree, with a name, value, description, and possibly children.
Definition: property.h:100
rviz::FrameInfo::distance_to_parent_
float distance_to_parent_
Definition: tf_display.h:164
rviz::RegexFilterProperty::createEditor
QWidget * createEditor(QWidget *parent, const QStyleOptionViewItem &option) override
Create an editor widget to edit the value of this property.
Definition: tf_display.cpp:223
rviz::TFDisplay::TFDisplay
TFDisplay()
Definition: tf_display.cpp:234
rviz::Arrow::setHeadColor
void setHeadColor(float r, float g, float b, float a=1.0f)
Set the color of the arrow's head. Values are in the range [0, 1].
Definition: arrow.cpp:109
rviz::TFDisplay::frame_config_enabled_state_
M_EnabledState frame_config_enabled_state_
Definition: tf_display.h:111
rviz::V_string
std::vector< std::string > V_string
Definition: effort_display.h:72
rviz::Config::mapGetChild
Config mapGetChild(const QString &key) const
If the referenced Node is a Map and it has a child with the given key, return a reference to the chil...
Definition: config.cpp:207
rviz::RegexFilterProperty::default_
std::regex default_
Definition: tf_display.cpp:191
rviz::TFDisplay::updateShowArrows
void updateShowArrows()
Definition: tf_display.cpp:384
rviz::FrameSelectionHandler::frame_
FrameInfo * frame_
Definition: tf_display.cpp:74
PLUGINLIB_EXPORT_CLASS
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
rviz::RegexValidator::editor_
QLineEdit * editor_
Definition: tf_display.cpp:165
rviz::FrameSelectionHandler::createProperties
void createProperties(const Picked &obj, Property *parent_property) override
Override to create properties of the given picked object(s).
Definition: tf_display.cpp:93
rviz::TFDisplay::filter_whitelist_property_
RegexFilterProperty * filter_whitelist_property_
Definition: tf_display.h:125
rviz::FrameInfo::position_property_
VectorProperty * position_property_
Definition: tf_display.h:172
rviz::FloatProperty::getFloat
virtual float getFloat() const
Definition: float_property.h:79
rviz::Property::createEditor
virtual QWidget * createEditor(QWidget *parent, const QStyleOptionViewItem &option)
Create an editor widget to edit the value of this property.
Definition: property.cpp:539
rviz::Axes::setZColor
void setZColor(const Ogre::ColourValue &col)
Definition: axes.cpp:139
rviz::TFDisplay::~TFDisplay
~TFDisplay() override
Definition: tf_display.cpp:282
ROS_DEBUG
#define ROS_DEBUG(...)
rviz::S_FrameInfo
std::set< FrameInfo * > S_FrameInfo
Definition: tf_display.cpp:232
rviz
Definition: add_display_dialog.cpp:54
rviz::FrameSelectionHandler::enabled_property_
BoolProperty * enabled_property_
Definition: tf_display.cpp:76
tf_display.h
rviz::Display::scene_node_
Ogre::SceneNode * scene_node_
The Ogre::SceneNode to hold all 3D scene elements shown by this Display.
Definition: display.h:295
rviz::FrameSelectionHandler::destroyProperties
void destroyProperties(const Picked &obj, Property *parent_property) override
Destroy all properties for the given picked object(s).
Definition: tf_display.cpp:112
rviz::VectorProperty::setVector
virtual bool setVector(const Ogre::Vector3 &vector)
Definition: vector_property.cpp:55
rviz::Axes::updateAlpha
void updateAlpha(float alpha)
Definition: axes.cpp:144
rviz::QuaternionProperty::setQuaternion
virtual bool setQuaternion(const Ogre::Quaternion &quaternion)
Definition: quaternion_property.cpp:60
rviz::RegexFilterProperty::onValueChanged
void onValueChanged()
Definition: tf_display.cpp:194
rviz::TFDisplay::axes_node_
Ogre::SceneNode * axes_node_
Definition: tf_display.h:106
rviz::StringProperty
Property specialized for string values.
Definition: string_property.h:39
rviz::StatusProperty::Ok
@ Ok
Definition: status_property.h:44
rviz::TFDisplay::createFrame
FrameInfo * createFrame(const std::string &frame)
Definition: tf_display.cpp:486
rviz::Axes::getDefaultXColor
const Ogre::ColourValue & getDefaultXColor()
Definition: axes.cpp:158
rviz::StatusProperty::Warn
@ Warn
Definition: status_property.h:45
rviz::FrameInfo::axes_coll_
CollObjectHandle axes_coll_
Definition: tf_display.h:158
rviz::Display::scene_manager_
Ogre::SceneManager * scene_manager_
A convenience variable equal to context_->getSceneManager().
Definition: display.h:292
arrow.h
rviz::StringProperty::getString
QString getString()
Definition: string_property.h:75
rviz::TFDisplay::updateFrames
void updateFrames()
Definition: tf_display.cpp:439
rviz::FrameInfo::name_text_
MovableText * name_text_
Definition: tf_display.h:161
rviz::Axes::setYColor
void setYColor(const Ogre::ColourValue &col)
Definition: axes.cpp:134
rviz::FrameSelectionHandler::setOrientation
void setOrientation(const Ogre::Quaternion &orientation)
Definition: tf_display.cpp:155
rviz::Display::load
void load(const Config &config) override
Load the settings for this display from the given Config node, which must be a map.
Definition: display.cpp:231
rviz::FrameInfo::rel_orientation_property_
QuaternionProperty * rel_orientation_property_
Definition: tf_display.h:171
rviz::FrameInfo::updateVisibilityFromFrame
void updateVisibilityFromFrame()
Update whether the frame is visible or not, based on the enabled_property_ in this FrameInfo.
Definition: tf_display.cpp:825
rviz::FrameInfo::name_node_
Ogre::SceneNode * name_node_
Definition: tf_display.h:162
rviz::TFDisplay::all_enabled_property_
BoolProperty * all_enabled_property_
Definition: tf_display.h:120
rviz::RegexFilterProperty
Definition: tf_display.cpp:189
rviz::DisplayContext
Pure-virtual base class for objects which give Display subclasses context in which to work.
Definition: display_context.h:81
rviz::DisplayContext::getFrameManager
virtual FrameManager * getFrameManager() const =0
Return the FrameManager instance.
rviz::FrameInfo::selection_handler_
FrameSelectionHandlerPtr selection_handler_
Definition: tf_display.h:159
string_property.h
rviz::ARROW_SHAFT_COLOR
static const Ogre::ColourValue ARROW_SHAFT_COLOR(0.8f, 0.8f, 0.3f, 1.0f)
rviz::Axes
An object that displays a set of X/Y/Z axes, with X=Red, Y=Green, Z=Blue.
Definition: axes.h:57
rviz::Property::getParent
Property * getParent() const
Return the parent Property.
Definition: property.cpp:231
rviz::SelectionManager::removeObject
void removeObject(CollObjectHandle obj)
Definition: selection_manager.cpp:480
rviz::FrameInfo::enabled_property_
BoolProperty * enabled_property_
Definition: tf_display.h:175
rviz::FrameInfo::parent_
std::string parent_
Definition: tf_display.h:156
rviz::TFDisplay::fixedFrameChanged
void fixedFrameChanged() override
Called by setFixedFrame(). Override to respond to changes to fixed_frame_.
Definition: tf_display.cpp:799
rviz::ARROW_HEAD_COLOR
static const Ogre::ColourValue ARROW_HEAD_COLOR(1.0f, 0.1f, 0.6f, 1.0f)
rviz::TFDisplay::onDisable
void onDisable() override
Derived classes override this to do the actual work of disabling themselves.
Definition: tf_display.cpp:350
start
ROSCPP_DECL void start()
rviz::TFDisplay::show_axes_property_
BoolProperty * show_axes_property_
Definition: tf_display.h:117
rviz::FrameManager::getTransform
bool getTransform(const Header &header, Ogre::Vector3 &position, Ogre::Quaternion &orientation)
Return the pose for a header, relative to the fixed frame, in Ogre classes.
Definition: frame_manager.h:125
rviz::Display::setStatusStd
void setStatusStd(StatusProperty::Level level, const std::string &name, const std::string &text)
Show status level and text, using a std::string. Convenience function which converts std::string to Q...
Definition: display.h:163
rviz::Display::context_
DisplayContext * context_
This DisplayContext pointer is the main connection a Display has into the rest of rviz....
Definition: display.h:287
rviz::TFDisplay::filter_blacklist_property_
RegexFilterProperty * filter_blacklist_property_
Definition: tf_display.h:126
ros::Time
rviz::FrameInfo::setEnabled
void setEnabled(bool enabled)
Set this frame to be visible or invisible.
Definition: tf_display.cpp:839
movable_text.h
rviz::Axes::setToDefaultColors
void setToDefaultColors()
Definition: axes.cpp:151
rviz::Property::setReadOnly
virtual void setReadOnly(bool read_only)
Prevent or allow users to edit this property from a PropertyTreeWidget.
Definition: property.h:497
rviz::FrameSelectionHandler::position_property_
VectorProperty * position_property_
Definition: tf_display.cpp:78
vector_property.h
rviz::Arrow::setShaftColor
void setShaftColor(float r, float g, float b, float a=1.0f)
Set the color of the arrow's shaft. Values are in the range [0, 1].
Definition: arrow.cpp:104
rviz::FrameInfo::last_time_to_fixed_
ros::Time last_time_to_fixed_
Definition: tf_display.h:168
rviz::TFDisplay::update_rate_property_
FloatProperty * update_rate_property_
Definition: tf_display.h:118
rviz::SelectionHandler
Definition: selection_handler.h:64
rviz::FrameInfo::display_
TFDisplay * display_
Definition: tf_display.h:154
rviz::TFDisplay::update_timer_
float update_timer_
Definition: tf_display.h:113
rviz::VectorProperty::setReadOnly
void setReadOnly(bool read_only) override
Overridden from Property to propagate read-only-ness to children.
Definition: vector_property.cpp:143
rviz::TFDisplay::update
void update(float wall_dt, float ros_dt) override
Called periodically by the visualization manager.
Definition: tf_display.cpp:416
rviz::FrameSelectionHandler::getEnabled
bool getEnabled()
Definition: tf_display.cpp:122
rviz::StringProperty::setStdString
bool setStdString(const std::string &std_str)
Definition: string_property.h:85
rviz::RegexValidator::validate
QValidator::State validate(QString &input, int &) const override
Definition: tf_display.cpp:171
class_list_macros.hpp
rviz::Display::reset
virtual void reset()
Called to tell the display to clear its state.
Definition: display.cpp:290
rviz::Property::changed
void changed()
Emitted by setValue() just after the value has changed.
rviz::FrameSelectionHandler::setPosition
void setPosition(const Ogre::Vector3 &position)
Definition: tf_display.cpp:147
tf
rviz::Axes::setPosition
void setPosition(const Ogre::Vector3 &position) override
Set the position of this object.
Definition: axes.cpp:92
rviz::DisplayContext::getSelectionManager
virtual SelectionManager * getSelectionManager() const =0
Return a pointer to the SelectionManager.
rviz::TFDisplay::FrameInfo
friend class FrameInfo
Definition: tf_display.h:131
display_context.h
rviz::VectorProperty
Definition: vector_property.h:39
rviz::RegexFilterProperty::regex_
std::regex regex_
Definition: tf_display.cpp:192
rviz::FrameSelectionHandler
Definition: tf_display.cpp:56
DurationBase< Duration >::toSec
double toSec() const
rviz::TFDisplay::frames_category_
Property * frames_category_
Definition: tf_display.h:127
rviz::RegexFilterProperty::regex
const std::regex & regex() const
Definition: tf_display.cpp:218
rviz::Config::MapIterator
Iterator class for looping over all entries in a Map type Config Node.
Definition: config.h:291
root
root
rviz::Arrow::setPosition
void setPosition(const Ogre::Vector3 &position) override
Set the position of the base of the arrow.
Definition: arrow.cpp:114
rviz::TFDisplay::onEnable
void onEnable() override
Derived classes override this to do the actual work of enabling themselves.
Definition: tf_display.cpp:341
rviz::RegexFilterProperty::RegexFilterProperty
RegexFilterProperty(const QString &name, const std::regex &regex, Property *parent)
Definition: tf_display.cpp:213
rviz::TFDisplay::scale_property_
FloatProperty * scale_property_
Definition: tf_display.h:122
rviz::Axes::setOrientation
void setOrientation(const Ogre::Quaternion &orientation) override
Set the orientation of the object.
Definition: axes.cpp:97
rviz::Arrow::getSceneNode
Ogre::SceneNode * getSceneNode()
Get the scene node associated with this arrow.
Definition: arrow.h:147
rviz::TFDisplay::load
void load(const Config &config) override
Load the value of this property and/or its children from the given Config reference.
Definition: tf_display.cpp:303
tf2::TransformException
rviz::Property::removeChildren
virtual void removeChildren(int start_index=0, int count=-1)
Remove and delete some or all child Properties. Does not change the value of this Property.
Definition: property.cpp:104
rviz::FrameInfo::updateVisibilityFromSelection
void updateVisibilityFromSelection()
Update whether the frame is visible or not, based on the enabled_property_ in the selection handler.
Definition: tf_display.cpp:832
rviz::Arrow::setColor
void setColor(float r, float g, float b, float a) override
Set the color of this arrow. Sets both the head and shaft color to the same value....
Definition: arrow.cpp:89
rviz::MovableText::setColor
void setColor(const Ogre::ColourValue &color)
Definition: movable_text.cpp:146
rviz::TFDisplay::onInitialize
void onInitialize() override
Override this function to do subclass-specific initialization.
Definition: tf_display.cpp:292
rviz::Property::childAtUnchecked
virtual Property * childAtUnchecked(int index) const
Return the child Property with the given index, without checking whether the index is within bounds.
Definition: property.cpp:213
rviz::Config::mapIterator
MapIterator mapIterator() const
Return a new iterator for looping over key/value pairs.
Definition: config.cpp:351
config
config
ros::Duration
rviz::TFDisplay
Displays a visual representation of the TF hierarchy.
Definition: tf_display.h:65
rviz::Property::takeChild
Property * takeChild(Property *child)
Remove a given child object and return a pointer to it.
Definition: property.cpp:322
rviz::DisplayContext::getTF2BufferPtr
std::shared_ptr< tf2_ros::Buffer > getTF2BufferPtr() const
Convenience function: returns getFrameManager()->getTF2BufferPtr().
Definition: display_context.h:98
rviz::Config
Configuration data storage class.
Definition: config.h:124
t
geometry_msgs::TransformStamped t
rviz::TFDisplay::frame_timeout_property_
FloatProperty * frame_timeout_property_
Definition: tf_display.h:119
rviz::FrameInfo
Internal class needed only by TFDisplay.
Definition: tf_display.h:135
rviz::FrameInfo::FrameInfo
FrameInfo(TFDisplay *display)
Definition: tf_display.cpp:813
rviz::Config::getValue
QVariant getValue() const
If this config object is valid and is a Value type, this returns its value. Otherwise it returns an i...
Definition: config.cpp:319
rviz::FrameSelectionHandler::orientation_property_
QuaternionProperty * orientation_property_
Definition: tf_display.cpp:79
ros::Time::now
static Time now()


rviz
Author(s): Dave Hershberger, David Gossow, Josh Faust, William Woodall
autogenerated on Sat Jun 1 2024 02:31:53