Go to the documentation of this file.
30 #include <OgreEntity.h>
31 #include <OgreSceneNode.h>
53 #include <Eigen/Dense>
80 new VectorProperty(
"Covariance Position", Ogre::Vector3::ZERO,
"", cat);
84 new VectorProperty(
"Covariance Orientation", Ogre::Vector3::ZERO,
"", cat);
108 aabbs.push_back(
display_->
covariance_->getPositionShape()->getEntity()->getWorldBoundingBox());
114 ->getWorldBoundingBox());
117 ->getWorldBoundingBox());
120 ->getWorldBoundingBox());
126 void setMessage(
const geometry_msgs::PoseWithCovarianceStampedConstPtr& message)
136 message->pose.pose.position.x, message->pose.pose.position.y, message->pose.pose.position.z));
138 Ogre::Quaternion(message->pose.pose.orientation.w, message->pose.pose.orientation.x,
139 message->pose.pose.orientation.y, message->pose.pose.orientation.z));
141 message->pose.covariance[1 + 1 * 6],
142 message->pose.covariance[2 + 2 * 6]));
145 message->pose.covariance[4 + 4 * 6],
146 message->pose.covariance[5 + 5 * 6]));
175 new FloatProperty(
"Shaft Length", 1,
"Length of the arrow's shaft, in meters.",
this,
180 new FloatProperty(
"Shaft Radius", 0.05,
"Radius of the arrow's shaft, in meters.",
this,
198 "Whether or not the covariances of the messages should be shown.",
this,
303 const geometry_msgs::PoseWithCovarianceStamped::ConstPtr& message)
308 "Message contained invalid floating point values (nans or infs)");
315 "PoseWithCovariance '%s' contains unnormalized quaternions. "
316 "This warning will only be output once but may be true for others; "
317 "enable DEBUG messages for ros.rviz.quaternions to see more details.",
319 ROS_DEBUG_NAMED(
"quaternions",
"PoseWithCovariance '%s' contains unnormalized quaternions.",
323 Ogre::Vector3 position;
324 Ogre::Quaternion orientation;
327 ROS_ERROR(
"Error transforming pose '%s' from frame '%s' to frame '%s'", qPrintable(
getName()),
328 message->header.frame_id.c_str(), qPrintable(
fixed_frame_));
339 arrow_->
setOrientation(orientation * Ogre::Quaternion(Ogre::Degree(-90), Ogre::Vector3::UNIT_Y));
void set(float shaft_length, float shaft_diameter, float head_length, float head_diameter)
Set the parameters for this arrow.
virtual bool getBool() const
virtual int getOptionInt()
Return the int value of the currently-chosen option, or 0 if the current option string does not have ...
Ogre::SceneNode * getSceneNode()
Get the scene node associated with this object.
void updateColorAndAlpha()
void onInitialize() override
Override this function to do subclass-specific initialization.
void updateAxisGeometry()
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.
PoseWithCovarianceDisplaySelectionHandler(PoseWithCovarianceDisplay *display, DisplayContext *context)
void queueRender()
Convenience function which calls context_->queueRender().
An arrow consisting of a cylinder and a cone.
bool initialized() const
Returns true if the display has been initialized.
void getAABBs(const Picked &, V_AABB &aabbs) override
void setOrientation(const Ogre::Quaternion &orientation) override
Set the orientation.
rviz::FloatProperty * head_length_property_
CovarianceVisualPtr createAndPushBackVisual(Ogre::SceneManager *scene_manager, Ogre::SceneNode *parent_node)
boost::shared_ptr< CovarianceVisual > covariance_
VectorProperty * position_property_
Property specialized to provide getter for booleans.
bool validateFloats(const sensor_msgs::CameraInfo &msg)
rviz::EnumProperty * shape_property_
rviz::FloatProperty * axes_radius_property_
#define ROS_WARN_ONCE_NAMED(name,...)
friend class PoseWithCovarianceDisplaySelectionHandler
bool getOrientationBool()
QString fixed_frame_
A convenience variable equal to context_->getFixedFrame().
void setMessage(const geometry_msgs::PoseWithCovarianceStampedConstPtr &message)
void setReadOnly(bool read_only) override
Overridden from Property to propagate read-only-ness to children.
QuaternionProperty * orientation_property_
VectorProperty * covariance_orientation_property_
~PoseWithCovarianceDisplay() override
PoseWithCovarianceDisplaySelectionHandlerPtr coll_handler_
Property specialized to enforce floating point max/min.
A single element of a property tree, with a name, value, description, and possibly children.
void reset() override
Called to tell the display to clear its state.
virtual void setStatus(StatusProperty::Level level, const QString &name, const QString &text)
Show status level and text. This is thread-safe.
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.
bool validateQuaternions(const visualization_msgs::InteractiveMarker &marker)
Ogre::SceneManager * scene_manager_
A convenience variable equal to context_->getSceneManager().
void processMessage(const geometry_msgs::PoseWithCovarianceStamped::ConstPtr &message) override
rviz::FloatProperty * shaft_radius_property_
Ogre::Entity * getEntity()
Pure-virtual base class for objects which give Display subclasses context in which to work.
rviz::FloatProperty * head_radius_property_
virtual FrameManager * getFrameManager() const =0
Return the FrameManager instance.
An object that displays a set of X/Y/Z axes, with X=Red, Y=Green, Z=Blue.
VectorProperty * covariance_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.
CovarianceProperty * covariance_property_
void setReadOnly(bool read_only) override
Overridden from Property to propagate read-only-ness to children.
QList< Property * > properties_
bool setStdString(const std::string &std_str)
rviz::FloatProperty * alpha_property_
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.
rviz::ColorProperty * color_property_
void onEnable() override
Overridden from MessageFilterDisplay to get Arrow/Axes visibility correct.
PoseWithCovarianceDisplay * display_
void setPosition(const Ogre::Vector3 &position) override
Set the position of this object.
void setPosition(const Ogre::Vector3 &position) override
Set the position of the base of the arrow.
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 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....
rviz::FloatProperty * shaft_length_property_
void updateShapeVisibility()
StringProperty * frame_property_
rviz::FloatProperty * axes_length_property_
void createProperties(const Picked &, Property *parent_property) override
Override to create properties of the given picked object(s).
PoseWithCovarianceDisplay()
Ogre::ColourValue getOgreColor() const
Displays the pose from a geometry_msgs::PoseWithCovarianceStamped message.
rviz
Author(s): Dave Hershberger, David Gossow, Josh Faust, William Woodall
autogenerated on Fri Aug 2 2024 08:43:10