Go to the documentation of this file.
30 #include <OgreEntity.h>
31 #include <OgreSceneNode.h>
93 void setMessage(
const geometry_msgs::PoseStampedConstPtr& message)
103 Ogre::Vector3(message->pose.position.x, message->pose.position.y, message->pose.position.z));
105 Ogre::Quaternion(message->pose.orientation.w, message->pose.orientation.x,
106 message->pose.orientation.y, message->pose.orientation.z));
133 new FloatProperty(
"Shaft Length", 1,
"Length of the arrow's shaft, in meters.",
this,
138 new FloatProperty(
"Shaft Radius", 0.05,
"Radius of the arrow's shaft, in meters.",
this,
254 "Message contained invalid floating point values (nans or infs)");
261 "Pose '%s' contains unnormalized quaternions. "
262 "This warning will only be output once but may be true for others; "
263 "enable DEBUG messages for ros.rviz.quaternions to see more details.",
268 Ogre::Vector3 position;
269 Ogre::Quaternion orientation;
272 ROS_ERROR(
"Error transforming pose '%s' from frame '%s' to frame '%s'", qPrintable(
getName()),
273 message->header.frame_id.c_str(), qPrintable(
fixed_frame_));
void set(float shaft_length, float shaft_diameter, float head_length, float head_diameter)
Set the parameters for this arrow.
virtual int getOptionInt()
Return the int value of the currently-chosen option, or 0 if the current option string does not have ...
FloatProperty * shaft_length_property_
Ogre::SceneNode * getSceneNode()
Get the scene node associated with this object.
FloatProperty * axes_length_property_
virtual void setHidden(bool hidden)
Hide or show this property in any PropertyTreeWidget viewing its parent.
virtual void queueRender()=0
Queues a render. Multiple calls before a render happens will only cause a single render.
An arrow consisting of a cylinder and a cone.
bool initialized() const
Returns true if the display has been initialized.
void setOrientation(const Ogre::Quaternion &orientation) override
Set the orientation.
void getAABBs(const Picked &, V_AABB &aabbs) override
FloatProperty * shaft_radius_property_
bool validateFloats(const sensor_msgs::CameraInfo &msg)
QuaternionProperty * orientation_property_
#define ROS_WARN_ONCE_NAMED(name,...)
QString fixed_frame_
A convenience variable equal to context_->getFixedFrame().
void updateShapeVisibility()
void setReadOnly(bool read_only) override
Overridden from Property to propagate read-only-ness to children.
StringProperty * frame_property_
PoseDisplaySelectionHandlerPtr coll_handler_
Property specialized to enforce floating point max/min.
EnumProperty * shape_property_
A single element of a property tree, with a name, value, description, and possibly children.
virtual void setStatus(StatusProperty::Level level, const QString &name, const QString &text)
Show status level and text. This is thread-safe.
void createProperties(const Picked &, Property *parent_property) override
Override to create properties of the given picked object(s).
void updateArrowGeometry()
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
virtual float getFloat() const
virtual void addOption(const QString &option, int value=0)
#define ROS_DEBUG_NAMED(name,...)
Ogre::SceneNode * scene_node_
The Ogre::SceneNode to hold all 3D scene elements shown by this Display.
virtual bool setVector(const Ogre::Vector3 &vector)
virtual bool setQuaternion(const Ogre::Quaternion &quaternion)
Property specialized for string values.
void onInitialize() override
Override this function to do subclass-specific initialization.
bool validateQuaternions(const visualization_msgs::InteractiveMarker &marker)
friend class PoseDisplaySelectionHandler
Ogre::SceneManager * scene_manager_
A convenience variable equal to context_->getSceneManager().
void reset() override
Called to tell the display to clear its state.
void updateAxisGeometry()
void setMessage(const geometry_msgs::PoseStampedConstPtr &message)
void processMessage(const geometry_msgs::PoseStamped::ConstPtr &message) override
Ogre::Entity * getEntity()
Pure-virtual base class for objects which give Display subclasses context in which to work.
virtual FrameManager * getFrameManager() const =0
Return the FrameManager instance.
FloatProperty * alpha_property_
Accumulates and displays the pose from a geometry_msgs::PoseStamped message.
An object that displays a set of X/Y/Z axes, with X=Red, Y=Green, Z=Blue.
VectorProperty * position_property_
void onInitialize() override
std::vector< Ogre::AxisAlignedBox > V_AABB
virtual QString getName() const
Return the name of this Property as a QString.
DisplayContext * context_
This DisplayContext pointer is the main connection a Display has into the rest of rviz....
virtual void setReadOnly(bool read_only)
Prevent or allow users to edit this property from a PropertyTreeWidget.
FloatProperty * head_radius_property_
FloatProperty * head_length_property_
void setReadOnly(bool read_only) override
Overridden from Property to propagate read-only-ness to children.
QList< Property * > properties_
ColorProperty * color_property_
bool setStdString(const std::string &std_str)
void updateColorAndAlpha()
bool transform(const Header &header, const geometry_msgs::Pose &pose, Ogre::Vector3 &position, Ogre::Quaternion &orientation)
Transform a pose from a frame into the fixed frame.
void set(float length, float radius, float alpha=1.0f)
Set the parameters on this object.
PoseDisplaySelectionHandler(PoseDisplay *display, DisplayContext *context)
Ogre::SceneNode * getSceneNode()
Get the scene node associated with this arrow.
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....
Ogre::ColourValue getOgreColor() const
void onEnable() override
Overridden from MessageFilterDisplay to get arrow/axes visibility correct.
FloatProperty * axes_radius_property_
rviz
Author(s): Dave Hershberger, David Gossow, Josh Faust, William Woodall
autogenerated on Fri Aug 2 2024 08:43:10