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> 43 #include <OgreVector3.h> 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);
107 void setPositionScale(
float pos_scale);
108 void setOrientationOffset(
float ori_offset);
109 void setOrientationScale(
float ori_scale);
118 virtual void setPositionColor(
float r,
float g,
float b,
float a);
119 void setPositionColor(
const Ogre::ColourValue& color);
128 virtual void setOrientationColor(
float r,
float g,
float b,
float a);
129 void setOrientationColor(
const Ogre::ColourValue& color);
130 void setOrientationColorToRGB(
float a);
137 virtual void setCovariance(
const geometry_msgs::PoseWithCovariance& pose);
139 virtual const Ogre::Vector3& getPositionCovarianceScale();
140 virtual const Ogre::Quaternion& getPositionCovarianceOrientation();
148 return position_scale_node_;
157 return orientation_root_node_;
166 return position_shape_;
178 void setUserData(
const Ogre::Any& data)
override;
190 virtual void setPositionVisible(
bool visible);
195 virtual void setOrientationVisible(
bool visible);
200 void setPosition(
const Ogre::Vector3& position)
override;
205 void setOrientation(
const Ogre::Quaternion& orientation)
override;
210 virtual void setRotatingFrame(
bool use_rotating_frame);
215 void updateOrientationVisibility();
223 Ogre::SceneNode* orientation_offset_node_[kNumOriShapes];
234 Ogre::Vector3 current_ori_scale_[kNumOriShapes];
245 void setColor(
float ,
float ,
float ,
float )
override 248 const Ogre::Vector3& getPosition()
override;
249 const Ogre::Quaternion& getOrientation()
override;
CovarianceVisual consisting in a ellipse for position and 2D ellipses along the axis for orientation...
Ogre::SceneNode * position_node_
void setColor(float, float, float, float) override
Set the color of the object. Values are in the range [0, 1].
void setVisible(PanelDockWidget *widget, bool visible)
Ogre::SceneNode * getPositionSceneNode()
Get the root scene node of the position part of this covariance.
Base class for visible objects, providing a minimal generic interface.
Ogre::SceneNode * orientation_root_node_
Matrix< double, 6, 6 > Matrix6d
Ogre::SceneNode * fixed_orientation_node_
float current_ori_scale_factor_
bool orientation_visible_
If the orientation component is visible.
Ogre::SceneNode * position_scale_node_
rviz::Shape * getPositionShape()
Get the shape used to display position covariance.
Property specialized to provide getter for booleans.
void setScale(const Ogre::Vector3 &) override
Set the scale of the object. Always relative to the identity orientation of the object.
rviz::Shape * position_shape_
Ellipse used for the position covariance.
static const float max_degrees
Ogre::SceneNode * root_node_
Ogre::SceneNode * getOrientationSceneNode()
Get the root scene node of the orientation part of this covariance.