Go to the documentation of this file.
30 #ifndef COVARIANCE_VISUAL_H
31 #define COVARIANCE_VISUAL_H
37 #include <boost/scoped_ptr.hpp>
39 #include <geometry_msgs/PoseWithCovariance.h>
41 #include <Eigen/Dense>
44 #include <OgreColourValue.h>
61 class CovarianceProperty;
92 Ogre::SceneNode* parent_node,
93 bool is_local_rotation,
94 bool is_visible =
true,
95 float pos_scale = 1.0f,
96 float ori_scale = 0.1f,
97 float ori_offset = 0.1f);
106 void setScales(
float pos_scale,
float ori_scale);
137 virtual void setCovariance(
const geometry_msgs::PoseWithCovariance& pose);
200 void setPosition(
const Ogre::Vector3& position)
override;
205 void setOrientation(
const Ogre::Quaternion& orientation)
override;
245 void setColor(
float ,
float ,
float ,
float )
override
Ogre::SceneNode * position_scale_node_
Matrix< double, 6, 6 > Matrix6d
virtual void setOrientationColor(float r, float g, float b, float a)
Set the color of the orientation covariance. Values are in the range [0, 1].
virtual void setRotatingFrame(bool use_rotating_frame)
Sets which frame to attach the covariance of the orientation.
rviz::Shape * getOrientationShape(ShapeIndex index)
Get the shape used to display orientation covariance in an especific axis.
virtual void setVisible(bool visible)
Sets visibility of this covariance.
virtual void setPositionVisible(bool visible)
Sets visibility of the position part of this covariance.
float current_ori_scale_factor_
bool orientation_visible_
If the orientation component is visible.
Ogre::SceneNode * getOrientationSceneNode()
Get the root scene node of the orientation part of this covariance.
Property specialized to provide getter for booleans.
Ogre::SceneNode * fixed_orientation_node_
virtual const Ogre::Vector3 & getPositionCovarianceScale()
virtual void setCovariance(const geometry_msgs::PoseWithCovariance &pose)
Set the covariance.
void setOrientationScale(float ori_scale)
void setOrientationOffset(float ori_offset)
Ogre::SceneNode * orientation_root_node_
virtual void setPositionColor(float r, float g, float b, float a)
Set the color of the position covariance. Values are in the range [0, 1].
virtual const Ogre::Quaternion & getPositionCovarianceOrientation()
Ogre::Vector3 current_ori_scale_[kNumOriShapes]
rviz::Shape * position_shape_
Ellipse used for the position covariance.
const static float max_degrees
CovarianceVisual(Ogre::SceneManager *scene_manager, Ogre::SceneNode *parent_node, bool is_local_rotation, bool is_visible=true, float pos_scale=1.0f, float ori_scale=0.1f, float ori_offset=0.1f)
Constructor.
rviz::Shape * orientation_shape_[kNumOriShapes]
Cylinders used for the orientation covariance.
const Ogre::Quaternion & getOrientation() override
Get the local orientation of this object.
void setOrientation(const Ogre::Quaternion &orientation) override
Sets orientation of the frame this covariance is attached.
virtual void setOrientationVisible(bool visible)
Sets visibility of the orientation part of this covariance.
const Ogre::Vector3 & getPosition() override
Get the local position of this object.
Ogre::SceneNode * root_node_
void updateOrientationVisibility()
void setScale(const Ogre::Vector3 &) override
Set the scale of the object. Always relative to the identity orientation of the object.
Ogre::SceneNode * getPositionSceneNode()
Get the root scene node of the position part of this covariance.
rviz::Shape * getPositionShape()
Get the shape used to display position covariance.
void updateOrientation(const Eigen::Matrix6d &covariance, ShapeIndex index)
void updatePosition(const Eigen::Matrix6d &covariance)
void setScales(float pos_scale, float ori_scale)
Set the position and orientation scales for this covariance.
void setOrientationColorToRGB(float a)
~CovarianceVisual() override
void setColor(float, float, float, float) override
Set the color of the object. Values are in the range [0, 1].
void setPositionScale(float pos_scale)
Ogre::SceneNode * orientation_offset_node_[kNumOriShapes]
Base class for visible objects, providing a minimal generic interface.
void setPosition(const Ogre::Vector3 &position) override
Sets position of the frame this covariance is attached.
Ogre::SceneNode * position_node_
CovarianceVisual consisting in a ellipse for position and 2D ellipses along the axis for orientation.
void setUserData(const Ogre::Any &data) override
Sets user data on all ogre objects we own.
rviz
Author(s): Dave Hershberger, David Gossow, Josh Faust, William Woodall
autogenerated on Fri Aug 2 2024 08:43:09