CovarianceVisual consisting in a ellipse for position and 2D ellipses along the axis for orientation. More...
#include <covariance_visual.h>
Public Types | |
enum | ShapeIndex { kRoll =0, kPitch =1, kYaw =2, kYaw2D =3, kNumOriShapes } |
Public Member Functions | |
Ogre::SceneNode * | getOrientationSceneNode () |
Get the root scene node of the orientation part of this covariance. More... | |
rviz::Shape * | getOrientationShape (ShapeIndex index) |
Get the shape used to display orientation covariance in an especific axis. More... | |
virtual const Ogre::Quaternion & | getPositionCovarianceOrientation () |
virtual const Ogre::Vector3 & | getPositionCovarianceScale () |
Ogre::SceneNode * | getPositionSceneNode () |
Get the root scene node of the position part of this covariance. More... | |
rviz::Shape * | getPositionShape () |
Get the shape used to display position covariance. More... | |
virtual void | setCovariance (const geometry_msgs::PoseWithCovariance &pose) |
Set the covariance. More... | |
virtual void | setOrientation (const Ogre::Quaternion &orientation) |
Sets orientation of the frame this covariance is attached. More... | |
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]. More... | |
void | setOrientationColor (const Ogre::ColourValue &color) |
void | setOrientationColorToRGB (float a) |
void | setOrientationOffset (float ori_offset) |
void | setOrientationScale (float ori_scale) |
virtual void | setOrientationVisible (bool visible) |
Sets visibility of the orientation part of this covariance. More... | |
virtual void | setPosition (const Ogre::Vector3 &position) |
Sets position of the frame this covariance is attached. More... | |
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]. More... | |
void | setPositionColor (const Ogre::ColourValue &color) |
void | setPositionScale (float pos_scale) |
virtual void | setPositionVisible (bool visible) |
Sets visibility of the position part of this covariance. More... | |
virtual void | setRotatingFrame (bool use_rotating_frame) |
Sets which frame to attach the covariance of the orientation. More... | |
void | setScales (float pos_scale, float ori_scale) |
Set the position and orientation scales for this covariance. More... | |
virtual void | setUserData (const Ogre::Any &data) |
Sets user data on all ogre objects we own. More... | |
virtual void | setVisible (bool visible) |
Sets visibility of this covariance. More... | |
virtual | ~CovarianceVisual () |
Public Member Functions inherited from rviz::Object | |
Object (Ogre::SceneManager *scene_manager) | |
virtual | ~Object () |
Private Member Functions | |
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) | |
Private Constructor. More... | |
virtual const Ogre::Quaternion & | getOrientation () |
Get the local orientation of this object. More... | |
virtual const Ogre::Vector3 & | getPosition () |
Get the local position of this object. More... | |
virtual void | setColor (float r, float g, float b, float a) |
Set the color of the object. Values are in the range [0, 1]. More... | |
virtual void | setScale (const Ogre::Vector3 &scale) |
Set the scale of the object. Always relative to the identity orientation of the object. More... | |
void | updateOrientation (const Eigen::Matrix6d &covariance, ShapeIndex index) |
void | updateOrientationVisibility () |
void | updatePosition (const Eigen::Matrix6d &covariance) |
Private Attributes | |
Ogre::Vector3 | current_ori_scale_ [kNumOriShapes] |
float | current_ori_scale_factor_ |
Ogre::SceneNode * | fixed_orientation_node_ |
bool | local_rotation_ |
Ogre::SceneNode * | orientation_offset_node_ [kNumOriShapes] |
Ogre::SceneNode * | orientation_root_node_ |
rviz::Shape * | orientation_shape_ [kNumOriShapes] |
Cylinders used for the orientation covariance. More... | |
bool | orientation_visible_ |
If the orientation component is visible. More... | |
bool | pose_2d_ |
Ogre::SceneNode * | position_node_ |
Ogre::SceneNode * | position_scale_node_ |
rviz::Shape * | position_shape_ |
Ellipse used for the position covariance. More... | |
Ogre::SceneNode * | root_node_ |
Static Private Attributes | |
static const float | max_degrees = 89.0 |
Friends | |
class | CovarianceProperty |
Additional Inherited Members | |
Protected Attributes inherited from rviz::Object | |
Ogre::SceneManager * | scene_manager_ |
Ogre scene manager this object is part of. More... | |
CovarianceVisual consisting in a ellipse for position and 2D ellipses along the axis for orientation.
Definition at line 68 of file covariance_visual.h.
Enumerator | |
---|---|
kRoll | |
kPitch | |
kYaw | |
kYaw2D | |
kNumOriShapes |
Definition at line 71 of file covariance_visual.h.
|
private |
Private Constructor.
CovarianceVisual can only be constructed by friend class CovarianceProperty.
scene_manager | The scene manager to use to construct any necessary objects |
parent_object | A rviz object that this covariance will be attached. |
is_local_rotation | Initial attachment of the rotation part |
is_visible | Initial visibility |
pos_scale | Scale of the position covariance |
ori_scale | Scale of the orientation covariance |
Definition at line 200 of file covariance_visual.cpp.
|
virtual |
Definition at line 267 of file covariance_visual.cpp.
|
privatevirtual |
Get the local orientation of this object.
Implements rviz::Object.
Definition at line 567 of file covariance_visual.cpp.
|
inline |
Get the root scene node of the orientation part of this covariance.
Definition at line 149 of file covariance_visual.h.
rviz::Shape * rviz::CovarianceVisual::getOrientationShape | ( | ShapeIndex | index | ) |
Get the shape used to display orientation covariance in an especific axis.
Definition at line 596 of file covariance_visual.cpp.
|
privatevirtual |
Get the local position of this object.
Implements rviz::Object.
Definition at line 562 of file covariance_visual.cpp.
|
virtual |
Definition at line 522 of file covariance_visual.cpp.
|
virtual |
Definition at line 517 of file covariance_visual.cpp.
|
inline |
Get the root scene node of the position part of this covariance.
Definition at line 143 of file covariance_visual.h.
|
inline |
Get the shape used to display position covariance.
Definition at line 155 of file covariance_visual.h.
|
inlineprivatevirtual |
Set the color of the object. Values are in the range [0, 1].
r | Red component |
g | Green component |
b | Blue component |
Implements rviz::Object.
Definition at line 231 of file covariance_visual.h.
|
virtual |
Set the covariance.
This effectively changes the orientation and scale of position and orientation covariance shapes
Definition at line 283 of file covariance_visual.cpp.
|
virtual |
Sets orientation of the frame this covariance is attached.
Implements rviz::Object.
Definition at line 577 of file covariance_visual.cpp.
|
virtual |
Set the color of the orientation covariance. Values are in the range [0, 1].
r | Red component |
g | Green component |
b | Blue component |
Definition at line 512 of file covariance_visual.cpp.
void rviz::CovarianceVisual::setOrientationColor | ( | const Ogre::ColourValue & | color | ) |
Definition at line 491 of file covariance_visual.cpp.
void rviz::CovarianceVisual::setOrientationColorToRGB | ( | float | a | ) |
Definition at line 499 of file covariance_visual.cpp.
void rviz::CovarianceVisual::setOrientationOffset | ( | float | ori_offset | ) |
Definition at line 430 of file covariance_visual.cpp.
void rviz::CovarianceVisual::setOrientationScale | ( | float | ori_scale | ) |
Definition at line 453 of file covariance_visual.cpp.
|
virtual |
Sets visibility of the orientation part of this covariance.
Definition at line 547 of file covariance_visual.cpp.
|
virtual |
Sets position of the frame this covariance is attached.
Implements rviz::Object.
Definition at line 572 of file covariance_visual.cpp.
|
virtual |
Set the color of the position covariance. Values are in the range [0, 1].
r | Red component |
g | Green component |
b | Blue component |
Definition at line 507 of file covariance_visual.cpp.
void rviz::CovarianceVisual::setPositionColor | ( | const Ogre::ColourValue & | color | ) |
Definition at line 486 of file covariance_visual.cpp.
void rviz::CovarianceVisual::setPositionScale | ( | float | pos_scale | ) |
Definition at line 422 of file covariance_visual.cpp.
|
virtual |
Sets visibility of the position part of this covariance.
Definition at line 542 of file covariance_visual.cpp.
|
virtual |
Sets which frame to attach the covariance of the orientation.
Definition at line 582 of file covariance_visual.cpp.
|
inlineprivatevirtual |
Set the scale of the object. Always relative to the identity orientation of the object.
Scale | vector scale to set to. |
Implements rviz::Object.
Definition at line 230 of file covariance_visual.h.
void rviz::CovarianceVisual::setScales | ( | float | pos_scale, |
float | ori_scale | ||
) |
Set the position and orientation scales for this covariance.
pos_scale | Scale of the position covariance |
ori_scale | Scale of the orientation covariance |
Definition at line 416 of file covariance_visual.cpp.
|
virtual |
Sets user data on all ogre objects we own.
Implements rviz::Object.
Definition at line 527 of file covariance_visual.cpp.
|
virtual |
Sets visibility of this covariance.
Convenience method that sets visibility of both position and orientation parts.
Definition at line 536 of file covariance_visual.cpp.
|
private |
Definition at line 349 of file covariance_visual.cpp.
|
private |
Definition at line 553 of file covariance_visual.cpp.
|
private |
Definition at line 326 of file covariance_visual.cpp.
|
friend |
Definition at line 236 of file covariance_visual.h.
|
private |
Definition at line 222 of file covariance_visual.h.
|
private |
Definition at line 223 of file covariance_visual.h.
|
private |
Definition at line 206 of file covariance_visual.h.
|
private |
Definition at line 216 of file covariance_visual.h.
|
staticprivate |
Definition at line 225 of file covariance_visual.h.
|
private |
Definition at line 211 of file covariance_visual.h.
|
private |
Definition at line 210 of file covariance_visual.h.
|
private |
Cylinders used for the orientation covariance.
Definition at line 214 of file covariance_visual.h.
|
private |
If the orientation component is visible.
Definition at line 220 of file covariance_visual.h.
|
private |
Definition at line 218 of file covariance_visual.h.
|
private |
Definition at line 208 of file covariance_visual.h.
|
private |
Definition at line 207 of file covariance_visual.h.
|
private |
Ellipse used for the position covariance.
Definition at line 213 of file covariance_visual.h.
|
private |
Definition at line 205 of file covariance_visual.h.