Go to the documentation of this file.
   30 #include <boost/bind/bind.hpp> 
   33 #include <OgreSceneNode.h> 
   34 #include <OgreSceneManager.h> 
   85   , category_property_(nullptr)
 
   86   , enabled_property_(nullptr)
 
   87   , parent_property_(nullptr)
 
   88   , position_property_(nullptr)
 
   89   , orientation_property_(nullptr)
 
   96       new Property(
"Frame " + QString::fromStdString(
frame_->
name_), QVariant(), 
"", parent_property);
 
  171   QValidator::State 
validate(QString& input, 
int& )
 const override 
  175       std::regex(input.toLocal8Bit().constData());
 
  176       editor_->setStyleSheet(QString());
 
  177       QToolTip::hideText();
 
  178       return QValidator::Acceptable;
 
  180     catch (
const std::regex_error& e)
 
  182       editor_->setStyleSheet(
"background: #ffe4e4");
 
  183       QToolTip::showText(
editor_->mapToGlobal(QPoint(0, 5)), tr(e.what()), 
editor_, QRect(), 5000);
 
  184       return QValidator::Intermediate;
 
  203         regex_.assign(value.toLocal8Bit().constData(), std::regex_constants::optimize);
 
  205       catch (
const std::regex_error& e)
 
  223   QWidget* 
createEditor(QWidget* parent, 
const QStyleOptionViewItem& option)
 override 
  237       new BoolProperty(
"Show Names", 
true, 
"Whether or not names should be shown next to the frames.",
 
  241       new BoolProperty(
"Show Axes", 
true, 
"Whether or not the axes of each frame should be shown.", 
this,
 
  245                                            "Whether or not arrows from child to parent should be shown.",
 
  249       new FloatProperty(
"Marker Scale", 1, 
"Scaling factor for all names, axes and arrows.", 
this);
 
  256                                             "The interval, in seconds, at which to update the frame " 
  257                                             "transforms. 0 means to do so every update cycle.",
 
  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.",
 
  275       new BoolProperty(
"All Enabled", 
true, 
"Whether all the frames should be enabled or not.",
 
  279       "Tree", QVariant(), 
"A tree-view of the frames, showing the parent/child relationships.", 
this);
 
  313     QString key = iter.currentKey();
 
  314     if (key != 
"All Enabled")
 
  316       const Config& child = iter.currentChild();
 
  360   M_FrameInfo::iterator it = 
frames_.begin();
 
  361   M_FrameInfo::iterator end = 
frames_.end();
 
  362   for (; it != end; ++it)
 
  374   M_FrameInfo::iterator it = 
frames_.begin();
 
  375   M_FrameInfo::iterator end = 
frames_.end();
 
  376   for (; it != end; ++it)
 
  388   M_FrameInfo::iterator it = 
frames_.begin();
 
  389   M_FrameInfo::iterator end = 
frames_.end();
 
  390   for (; it != end; ++it)
 
  406   M_FrameInfo::iterator it = 
frames_.begin();
 
  407   M_FrameInfo::iterator end = 
frames_.end();
 
  408   for (; it != end; ++it)
 
  420   if (update_rate < 0.0001f || update_timer_ > update_rate)
 
  430   M_FrameInfo::iterator it = 
frames_.find(frame);
 
  441   typedef std::vector<std::string> 
V_string;
 
  446   auto it = frames.begin(), end = frames.end();
 
  451       std::swap(*it, *--end); 
 
  457   for (it = frames.begin(); it != end; ++it)
 
  469     current_frames.insert(info);
 
  472   for (
auto frame_it = 
frames_.begin(), frame_end = 
frames_.end(); frame_it != frame_end;)
 
  474     if (current_frames.find(frame_it->second) == current_frames.end())
 
  489   frames_.insert(std::make_pair(frame, info));
 
  510                                              "Enable or disable this individual frame.", 
nullptr,
 
  520                          "Position of this frame, in the current Fixed Frame.  (Not editable)",
 
  526                              "Orientation of this frame, in the current Fixed Frame.  (Not editable)",
 
  532                          "Position of this frame, relative to it's parent frame.  (Not editable)",
 
  538                              "Orientation of this frame, relative to it's parent frame.  (Not editable)",
 
  554 Ogre::ColourValue 
lerpColor(
const Ogre::ColourValue& start, 
const Ogre::ColourValue& end, 
float t)
 
  556   return start * 
t + end * (1 - 
t);
 
  561   while (child != 
root)
 
  578   tf->_getLatestCommonTime(target_id, source_id, latest_time, 
nullptr);
 
  589   float one_third_timeout = frame_timeout * 0.3333333f;
 
  599     Ogre::ColourValue grey(0.7, 0.7, 0.7, 1.0);
 
  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);
 
  614       float t = std::max(0.0, (one_third_timeout * 2 - age.
toSec()) / one_third_timeout);
 
  636   Ogre::Vector3 position;
 
  637   Ogre::Quaternion orientation;
 
  640     std::stringstream ss;
 
  641     ss << 
"No transform from [" << frame->
name_ << 
"] to frame [" << 
fixed_frame_.toStdString() << 
"]";
 
  643     ROS_DEBUG(
"Error transforming frame '%s' to frame '%s'", frame->
name_.c_str(),
 
  662     frame->
name_node_->setScale(scale, scale, scale);
 
  668   std::string old_parent = frame->
parent_;
 
  673     geometry_msgs::TransformStamped transform;
 
  680       ROS_DEBUG(
"Error transforming frame '%s' (parent of '%s') to frame '%s'", frame->
parent_.c_str(),
 
  682       transform.transform.rotation.w = 1.0;
 
  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);
 
  695       Ogre::Vector3 parent_position;
 
  696       Ogre::Quaternion parent_orientation;
 
  700         ROS_DEBUG(
"Error transforming frame '%s' (parent of '%s') to frame '%s'", frame->
parent_.c_str(),
 
  704       Ogre::Vector3 direction = parent_position - position;
 
  705       float distance = direction.length();
 
  706       direction.normalise();
 
  708       Ogre::Quaternion orient = Ogre::Vector3::NEGATIVE_UNIT_Z.getRotationTo(direction);
 
  711       float head_length = (distance < 0.1 * scale) ? (0.1 * scale * distance) : 0.1 * scale;
 
  712       float shaft_length = distance - head_length;
 
  715       frame->
parent_arrow_->
set(shaft_length, 0.01 * scale, head_length, 0.04 * scale);
 
  717       if (distance > 0.001
f)
 
  784   if (delete_properties)
 
  817   , parent_arrow_(nullptr)
 
  818   , name_text_(nullptr)
 
  819   , distance_to_parent_(0.0
f)
 
  820   , arrow_orientation_(
Ogre::Quaternion::IDENTITY)
 
  821   , tree_property_(nullptr)
 
  
void setTextAlignment(const HorizontalAlignment &horizontalAlignment, const VerticalAlignment &verticalAlignment)
void set(float shaft_length, float shaft_diameter, float head_length, float head_diameter)
Set the parameters for this arrow.
bool hasLoop(rviz::Property *child, rviz::Property *parent, rviz::Property *root)
void insertChildSorted(Property *child)
Insert a child property, sorted by name.
virtual bool getBool() const
void reset() override
Called to tell the display to clear its state.
Ogre::SceneNode * getSceneNode()
Get the scene node associated with this object.
const Ogre::ColourValue & getDefaultYColor()
BoolProperty * show_arrows_property_
Property * tree_property_
const Ogre::ColourValue & getDefaultZColor()
Ogre::SceneNode * arrows_node_
virtual void queueRender()=0
Queues a render. Multiple calls before a render happens will only cause a single render.
~FrameSelectionHandler() override
An arrow consisting of a cylinder and a cone.
bool initialized() const
Returns true if the display has been initialized.
QuaternionProperty * orientation_property_
void setScale(const Ogre::Vector3 &scale) override
Set the scale of the object. Always relative to the identity orientation of the object.
M_FrameInfo::iterator deleteFrame(M_FrameInfo::iterator it, bool delete_properties)
Property * category_property_
bool isValid()
Return true if the iterator currently points to a valid entry, false if not.
void setParentName(const std::string &parent_name)
void setOrientation(const Ogre::Quaternion &orientation) override
Set the orientation.
Property * tree_category_
virtual void clearStatuses()
Delete all status children. This is thread-safe.
Property specialized to provide getter for booleans.
bool changing_single_frame_enabled_state_
StringProperty * parent_property_
void setXColor(const Ogre::ColourValue &col)
FloatProperty * alpha_property_
void setEnabled(bool enabled)
virtual int numChildren() const
Return the number of child objects (Property or otherwise).
FrameInfo * getFrameInfo(const std::string &frame)
VectorProperty * rel_position_property_
QString fixed_frame_
A convenience variable equal to context_->getFixedFrame().
Ogre::SceneNode * root_node_
void setReadOnly(bool read_only) override
Overridden from Property to propagate read-only-ness to children.
FrameSelectionHandler(FrameInfo *frame, DisplayContext *context)
Property(const QString &name=QString(), const QVariant &default_value=QVariant(), const QString &description=QString(), Property *parent=nullptr)
Constructor.
BoolProperty(const QString &name=QString(), bool default_value=false, const QString &description=QString(), Property *parent=nullptr)
Ogre::SceneNode * names_node_
StringProperty * parent_property_
RegexValidator(QLineEdit *editor)
Ogre::ColourValue lerpColor(const Ogre::ColourValue &start, const Ogre::ColourValue &end, float t)
void updateFrame(FrameInfo *frame)
Property specialized to enforce floating point max/min.
BoolProperty * show_names_property_
A single element of a property tree, with a name, value, description, and possibly children.
float distance_to_parent_
QWidget * createEditor(QWidget *parent, const QStyleOptionViewItem &option) override
Create an editor widget to edit the value of this property.
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].
M_EnabledState frame_config_enabled_state_
std::vector< std::string > V_string
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...
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
void createProperties(const Picked &obj, Property *parent_property) override
Override to create properties of the given picked object(s).
RegexFilterProperty * filter_whitelist_property_
VectorProperty * position_property_
virtual float getFloat() const
virtual QWidget * createEditor(QWidget *parent, const QStyleOptionViewItem &option)
Create an editor widget to edit the value of this property.
void setZColor(const Ogre::ColourValue &col)
std::set< FrameInfo * > S_FrameInfo
BoolProperty * enabled_property_
Ogre::SceneNode * scene_node_
The Ogre::SceneNode to hold all 3D scene elements shown by this Display.
void destroyProperties(const Picked &obj, Property *parent_property) override
Destroy all properties for the given picked object(s).
virtual bool setVector(const Ogre::Vector3 &vector)
void updateAlpha(float alpha)
virtual bool setQuaternion(const Ogre::Quaternion &quaternion)
Ogre::SceneNode * axes_node_
Property specialized for string values.
FrameInfo * createFrame(const std::string &frame)
const Ogre::ColourValue & getDefaultXColor()
CollObjectHandle axes_coll_
Ogre::SceneManager * scene_manager_
A convenience variable equal to context_->getSceneManager().
void setYColor(const Ogre::ColourValue &col)
void setOrientation(const Ogre::Quaternion &orientation)
void load(const Config &config) override
Load the settings for this display from the given Config node, which must be a map.
QuaternionProperty * rel_orientation_property_
void updateVisibilityFromFrame()
Update whether the frame is visible or not, based on the enabled_property_ in this FrameInfo.
Ogre::SceneNode * name_node_
BoolProperty * all_enabled_property_
Pure-virtual base class for objects which give Display subclasses context in which to work.
virtual FrameManager * getFrameManager() const =0
Return the FrameManager instance.
FrameSelectionHandlerPtr selection_handler_
static const Ogre::ColourValue ARROW_SHAFT_COLOR(0.8f, 0.8f, 0.3f, 1.0f)
An object that displays a set of X/Y/Z axes, with X=Red, Y=Green, Z=Blue.
Property * getParent() const
Return the parent Property.
void removeObject(CollObjectHandle obj)
BoolProperty * enabled_property_
void fixedFrameChanged() override
Called by setFixedFrame(). Override to respond to changes to fixed_frame_.
static const Ogre::ColourValue ARROW_HEAD_COLOR(1.0f, 0.1f, 0.6f, 1.0f)
void onDisable() override
Derived classes override this to do the actual work of disabling themselves.
BoolProperty * show_axes_property_
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.
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...
DisplayContext * context_
This DisplayContext pointer is the main connection a Display has into the rest of rviz....
RegexFilterProperty * filter_blacklist_property_
void setEnabled(bool enabled)
Set this frame to be visible or invisible.
void setToDefaultColors()
virtual void setReadOnly(bool read_only)
Prevent or allow users to edit this property from a PropertyTreeWidget.
VectorProperty * position_property_
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].
ros::Time last_time_to_fixed_
FloatProperty * update_rate_property_
void setReadOnly(bool read_only) override
Overridden from Property to propagate read-only-ness to children.
void update(float wall_dt, float ros_dt) override
Called periodically by the visualization manager.
bool setStdString(const std::string &std_str)
QValidator::State validate(QString &input, int &) const override
virtual void reset()
Called to tell the display to clear its state.
void changed()
Emitted by setValue() just after the value has changed.
void setPosition(const Ogre::Vector3 &position)
void setPosition(const Ogre::Vector3 &position) override
Set the position of this object.
virtual SelectionManager * getSelectionManager() const =0
Return a pointer to the SelectionManager.
Property * frames_category_
const std::regex & regex() const
Iterator class for looping over all entries in a Map type Config Node.
void setPosition(const Ogre::Vector3 &position) override
Set the position of the base of the arrow.
void onEnable() override
Derived classes override this to do the actual work of enabling themselves.
RegexFilterProperty(const QString &name, const std::regex ®ex, Property *parent)
FloatProperty * scale_property_
void setOrientation(const Ogre::Quaternion &orientation) override
Set the orientation of the object.
Ogre::SceneNode * getSceneNode()
Get the scene node associated with this arrow.
void load(const Config &config) override
Load the value of this property and/or its children from the given Config reference.
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.
void updateVisibilityFromSelection()
Update whether the frame is visible or not, based on the enabled_property_ in the selection handler.
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....
void setColor(const Ogre::ColourValue &color)
void onInitialize() override
Override this function to do subclass-specific initialization.
virtual Property * childAtUnchecked(int index) const
Return the child Property with the given index, without checking whether the index is within bounds.
MapIterator mapIterator() const
Return a new iterator for looping over key/value pairs.
Displays a visual representation of the TF hierarchy.
Property * takeChild(Property *child)
Remove a given child object and return a pointer to it.
std::shared_ptr< tf2_ros::Buffer > getTF2BufferPtr() const
Convenience function: returns getFrameManager()->getTF2BufferPtr().
Configuration data storage class.
geometry_msgs::TransformStamped t
FloatProperty * frame_timeout_property_
Internal class needed only by TFDisplay.
FrameInfo(TFDisplay *display)
QVariant getValue() const
If this config object is valid and is a Value type, this returns its value. Otherwise it returns an i...
QuaternionProperty * orientation_property_
rviz
Author(s): Dave Hershberger, David Gossow, Josh Faust, William Woodall 
autogenerated on Sun May 4 2025 02:31:27