30 #include <boost/bind.hpp> 32 #include <OgreSceneNode.h> 33 #include <OgreSceneManager.h> 98 new Property(
"Frame " + QString::fromStdString(
frame_->
name_), QVariant(),
"", parent_property);
101 SLOT(updateVisibilityFromSelection()),
frame_);
170 new BoolProperty(
"Show Names",
true,
"Whether or not names should be shown next to the frames.",
174 new BoolProperty(
"Show Axes",
true,
"Whether or not the axes of each frame should be shown.",
this,
178 "Whether or not arrows from child to parent should be shown.",
182 new FloatProperty(
"Marker Scale", 1,
"Scaling factor for all names, axes and arrows.",
this);
185 "The interval, in seconds, at which to update the frame " 186 "transforms. 0 means to do so every update cycle.",
192 "The length of time, in seconds, before a frame that has not been updated is considered \"dead\"." 193 " For 1/3 of this time the frame will appear correct, for the second 1/3rd it will fade to gray," 194 " and then it will fade out completely.",
201 new BoolProperty(
"All Enabled",
true,
"Whether all the frames should be enabled or not.",
205 "Tree", QVariant(),
"A tree-view of the frames, showing the parent/child relationships.",
this);
239 QString key = iter.currentKey();
240 if (key !=
"All Enabled")
242 const Config& child = iter.currentChild();
286 M_FrameInfo::iterator it =
frames_.begin();
287 M_FrameInfo::iterator end =
frames_.end();
288 for (; it != end; ++it)
300 M_FrameInfo::iterator it =
frames_.begin();
301 M_FrameInfo::iterator end =
frames_.end();
302 for (; it != end; ++it)
314 M_FrameInfo::iterator it =
frames_.begin();
315 M_FrameInfo::iterator end =
frames_.end();
316 for (; it != end; ++it)
332 M_FrameInfo::iterator it =
frames_.begin();
333 M_FrameInfo::iterator end =
frames_.end();
334 for (; it != end; ++it)
346 if (update_rate < 0.0001f || update_timer_ > update_rate)
356 M_FrameInfo::iterator it =
frames_.find(frame);
367 typedef std::vector<std::string>
V_string;
371 #pragma GCC diagnostic push 372 #pragma GCC diagnostic ignored "-Wdeprecated-declarations" 378 #pragma GCC diagnostic pop 380 std::sort(frames.begin(), frames.end());
382 S_FrameInfo current_frames;
385 for (
const std::string& frame : frames)
402 current_frames.insert(info);
407 M_FrameInfo::iterator frame_it =
frames_.begin();
408 M_FrameInfo::iterator frame_end =
frames_.end();
409 while (frame_it != frame_end)
411 if (current_frames.find(frame_it->second) == current_frames.end())
427 frames_.insert(std::make_pair(frame, info));
448 "Enable or disable this individual frame.",
457 "Position of this frame, in the current Fixed Frame. (Not editable)",
463 "Orientation of this frame, in the current Fixed Frame. (Not editable)",
469 "Position of this frame, relative to it's parent frame. (Not editable)",
475 "Orientation of this frame, relative to it's parent frame. (Not editable)",
491 Ogre::ColourValue
lerpColor(
const Ogre::ColourValue& start,
const Ogre::ColourValue& end,
float t)
493 return start * t + end * (1 - t);
500 #pragma GCC diagnostic push 501 #pragma GCC diagnostic ignored "-Wdeprecated-declarations" 507 #pragma GCC diagnostic pop 523 float one_third_timeout = frame_timeout * 0.3333333f;
533 Ogre::ColourValue grey(0.7, 0.7, 0.7, 1.0);
537 float a = std::max(0.0, (frame_timeout - age.
toSec()) / one_third_timeout);
538 Ogre::ColourValue c = Ogre::ColourValue(grey.r, grey.g, grey.b, a);
548 float t = std::max(0.0, (one_third_timeout * 2 - age.
toSec()) / one_third_timeout);
567 Ogre::Vector3 position;
568 Ogre::Quaternion orientation;
571 std::stringstream ss;
572 ss <<
"No transform from [" << frame->
name_ <<
"] to frame [" <<
fixed_frame_.toStdString() <<
"]";
574 ROS_DEBUG(
"Error transforming frame '%s' to frame '%s'", frame->
name_.c_str(),
595 frame->
name_node_->setScale(scale, scale, scale);
600 std::string old_parent = frame->
parent_;
610 #pragma GCC diagnostic push 611 #pragma GCC diagnostic ignored "-Wdeprecated-declarations" 617 #pragma GCC diagnostic pop 623 ROS_DEBUG(
"Error transforming frame '%s' (parent of '%s') to frame '%s'", frame->
parent_.c_str(),
637 Ogre::Vector3 parent_position;
638 Ogre::Quaternion parent_orientation;
642 ROS_DEBUG(
"Error transforming frame '%s' (parent of '%s') to frame '%s'", frame->
parent_.c_str(),
646 Ogre::Vector3 direction = parent_position - position;
647 float distance = direction.length();
648 direction.normalise();
650 Ogre::Quaternion orient = Ogre::Vector3::NEGATIVE_UNIT_Z.getRotationTo(direction);
653 float head_length = (distance < 0.1 * scale) ? (0.1 * scale * distance) : 0.1 * scale;
654 float shaft_length = distance - head_length;
657 frame->
parent_arrow_->
set(shaft_length, 0.01 * scale, head_length, 0.04 * scale);
659 if (distance > 0.001
f)
695 if (!parent_tree_property)
700 new Property(QString::fromStdString(frame->
name_), QVariant(),
"", parent_tree_property);
724 if (delete_properties)
751 , parent_arrow_(nullptr)
752 , name_text_(nullptr)
753 , distance_to_parent_(0.0
f)
754 , arrow_orientation_(
Ogre::Quaternion::IDENTITY)
755 , tree_property_(nullptr)
Ogre::ColourValue lerpColor(const Ogre::ColourValue &start, const Ogre::ColourValue &end, float t)
Property * frames_category_
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...
FrameInfo(TFDisplay *display)
FloatProperty * scale_property_
void setOrientation(const Ogre::Quaternion &orientation) override
Set the orientation of the object.
~FrameSelectionHandler() override
bool changing_single_frame_enabled_state_
void updateVisibilityFromSelection()
Update whether the frame is visible or not, based on the enabled_property_ in the selection handler...
void reset() override
Called to tell the display to clear its state.
Property * category_property_
BoolProperty * show_arrows_property_
virtual bool setVector(const Ogre::Vector3 &vector)
Ogre::SceneNode * root_node_
virtual tf::TransformListener * getTFClient() const =0
Convenience function: returns getFrameManager()->getTFClient().
std::set< FrameInfo * > S_FrameInfo
QVariant getValue() const
If this config object is valid and is a Value type, this returns its value. Otherwise it returns an i...
StringProperty * parent_property_
DisplayContext * context_
This DisplayContext pointer is the main connection a Display has into the rest of rviz...
Property * getParent() const
Return the parent Property.
M_FrameInfo::iterator deleteFrame(M_FrameInfo::iterator it, bool delete_properties)
Ogre::SceneNode * names_node_
StringProperty * parent_property_
void setPosition(const Ogre::Vector3 &position) override
Set the position of the base of the arrow.
Property * tree_category_
void setEnabled(bool enabled)
Ogre::SceneNode * arrows_node_
Displays a visual representation of the TF hierarchy.
A single element of a property tree, with a name, value, description, and possibly children...
float distance_to_parent_
void setReadOnly(bool read_only) override
Overridden from Property to propagate read-only-ness to children.
M_EnabledState frame_config_enabled_state_
static const Ogre::ColourValue & getDefaultYColor()
void removeObject(CollObjectHandle obj)
void load(const Config &config) override
Load the settings for this display from the given Config node, which must be a map.
Internal class needed only by TFDisplay.
FrameSelectionHandler(FrameInfo *frame, TFDisplay *display, DisplayContext *context)
bool isValid()
Return true if the iterator currently points to a valid entry, false if not.
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...
void setZColor(const Ogre::ColourValue &col)
static const Ogre::ColourValue & getDefaultXColor()
Property specialized to enforce floating point max/min.
void set(float shaft_length, float shaft_diameter, float head_length, float head_diameter)
Set the parameters for this arrow.
BoolProperty * show_names_property_
VectorProperty * rel_position_property_
void setReadOnly(bool read_only) override
Overridden from Property to propagate read-only-ness to children.
geometry_msgs::TransformStamped t
void setYColor(const Ogre::ColourValue &col)
Ogre::SceneNode * scene_node_
The Ogre::SceneNode to hold all 3D scene elements shown by this Display.
Ogre::SceneNode * getSceneNode()
Get the scene node associated with this arrow.
static const Ogre::ColourValue ARROW_SHAFT_COLOR(0.8f, 0.8f, 0.3f, 1.0f)
void createProperties(const Picked &obj, Property *parent_property) override
Override to create properties of the given picked object(s).
Property * takeChild(Property *child)
Remove a given child object and return a pointer to it.
Configuration data storage class.
VectorProperty * position_property_
QString fixed_frame_
A convenience variable equal to context_->getFixedFrame().
void updateFrame(FrameInfo *frame)
FrameInfo * getFrameInfo(const std::string &frame)
QuaternionProperty * rel_orientation_property_
void destroyProperties(const Picked &obj, Property *parent_property) override
Destroy all properties for the given picked object(s).
void setXColor(const Ogre::ColourValue &col)
static const Ogre::ColourValue ARROW_HEAD_COLOR(1.0f, 0.1f, 0.6f, 1.0f)
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...
Pure-virtual base class for objects which give Display subclasses context in which to work...
virtual void clearStatuses()
Delete all status children. This is thread-safe.
CollObjectHandle axes_coll_
virtual void reset()
Called to tell the display to clear its state.
const boost::shared_ptr< tf::TransformListener > & getTFClientPtr()
Return a boost shared pointer to the tf::TransformListener used to receive transform data...
void setToDefaultColors()
void onDisable() override
Derived classes override this to do the actual work of disabling themselves.
void updateVisibilityFromFrame()
Update whether the frame is visible or not, based on the enabled_property_ in this FrameInfo...
BoolProperty * all_enabled_property_
BoolProperty * enabled_property_
Ogre::SceneNode * axes_node_
Iterator class for looping over all entries in a Map type Config Node.
virtual bool setQuaternion(const Ogre::Quaternion &quaternion)
void setEnabled(bool enabled)
Set this frame to be visible or invisible.
virtual FrameManager * getFrameManager() const =0
Return the FrameManager instance.
virtual SelectionManager * getSelectionManager() const =0
Return a pointer to the SelectionManager.
BoolProperty * enabled_property_
Property(const QString &name=QString(), const QVariant default_value=QVariant(), const QString &description=QString(), Property *parent=nullptr, const char *changed_slot=nullptr, QObject *receiver=nullptr)
Constructor.
void setOrientation(const Ogre::Quaternion &orientation)
void setParentName(std::string parent_name)
void setTextAlignment(const HorizontalAlignment &horizontalAlignment, const VerticalAlignment &verticalAlignment)
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].
Ogre::SceneNode * name_node_
An object that displays a set of X/Y/Z axes, with X=Red, Y=Green, Z=Blue.
std::vector< std::string > V_string
Ogre::SceneManager * scene_manager_
A convenience variable equal to context_->getSceneManager().
FrameSelectionHandlerPtr selection_handler_
FrameInfo * createFrame(const std::string &frame)
VectorProperty * position_property_
void setPosition(const Ogre::Vector3 &position) override
Set the position of this object.
BoolProperty(const QString &name=QString(), bool default_value=false, const QString &description=QString(), Property *parent=nullptr, const char *changed_slot=nullptr, QObject *receiver=nullptr)
FloatProperty * update_rate_property_
Property specialized for string values.
virtual void queueRender()=0
Queues a render. Multiple calls before a render happens will only cause a single render.
BoolProperty * show_axes_property_
void setColor(const Ogre::ColourValue &color)
Property specialized to provide getter for booleans.
void onInitialize() override
Override this function to do subclass-specific initialization.
virtual float getFloat() const
void setPosition(const Ogre::Vector3 &position)
virtual void addChild(Property *child, int index=-1)
Add a child 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.
An arrow consisting of a cylinder and a cone.
void fixedFrameChanged() override
Called by setFixedFrame(). Override to respond to changes to fixed_frame_.
void setOrientation(const Ogre::Quaternion &orientation) override
Set the orientation.
void onEnable() override
Derived classes override this to do the actual work of enabling themselves.
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. Values are in the range [0, 1].
MapIterator mapIterator() const
Return a new iterator for looping over key/value pairs.
void load(const Config &config) override
Load the value of this property and/or its children from the given Config reference.
bool initialized() const
Returns true if the display has been initialized.
Ogre::SceneNode * getSceneNode()
Get the scene node associated with this object.
Property * tree_property_
virtual bool getBool() const
ros::Time last_time_to_fixed_
virtual void setReadOnly(bool read_only)
Prevent or allow users to edit this property from a PropertyTreeWidget.
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].
bool setStdString(const std::string &std_str)
FloatProperty * frame_timeout_property_
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
static const Ogre::ColourValue & getDefaultZColor()
void setScale(const Ogre::Vector3 &scale) override
Set the scale of the object. Always relative to the identity orientation of the object.
void update(float wall_dt, float ros_dt) override
Called periodically by the visualization manager.
QuaternionProperty * orientation_property_
QuaternionProperty * orientation_property_