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 | |
| 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. More... | |
| 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... | |
| void | setOrientation (const Ogre::Quaternion &orientation) override |
| Sets orientation of the frame this covariance is attached. More... | |
| void | setOrientationColor (const Ogre::ColourValue &color) |
| 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 | 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... | |
| void | setPosition (const Ogre::Vector3 &position) override |
| Sets position of the frame this covariance is attached. More... | |
| void | setPositionColor (const Ogre::ColourValue &color) |
| 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 | 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... | |
| void | setUserData (const Ogre::Any &data) override |
| Sets user data on all ogre objects we own. More... | |
| virtual void | setVisible (bool visible) |
| Sets visibility of this covariance. More... | |
| ~CovarianceVisual () override | |
Public Member Functions inherited from rviz::Object | |
| Object (Ogre::SceneManager *scene_manager) | |
| virtual | ~Object () |
Private Member Functions | |
| const Ogre::Quaternion & | getOrientation () override |
| Get the local orientation of this object. More... | |
| const Ogre::Vector3 & | getPosition () override |
| Get the local position of this object. More... | |
| void | setColor (float, float, float, float) override |
| Set the color of the object. Values are in the range [0, 1]. More... | |
| void | setScale (const Ogre::Vector3 &) override |
| 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 | |
| const static 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.
| rviz::CovarianceVisual::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.
| 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 224 of file covariance_visual.cpp.
|
override |
Definition at line 310 of file covariance_visual.cpp.
|
overrideprivatevirtual |
Get the local orientation of this object.
Implements rviz::Object.
Definition at line 609 of file covariance_visual.cpp.
|
inline |
Get the root scene node of the orientation part of this covariance.
Definition at line 155 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 637 of file covariance_visual.cpp.
|
overrideprivatevirtual |
Get the local position of this object.
Implements rviz::Object.
Definition at line 604 of file covariance_visual.cpp.
|
virtual |
Definition at line 564 of file covariance_visual.cpp.
|
virtual |
Definition at line 559 of file covariance_visual.cpp.
|
inline |
Get the root scene node of the position part of this covariance.
Definition at line 146 of file covariance_visual.h.
|
inline |
Get the shape used to display position covariance.
Definition at line 164 of file covariance_visual.h.
|
inlineoverrideprivatevirtual |
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 245 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 326 of file covariance_visual.cpp.
|
overridevirtual |
Sets orientation of the frame this covariance is attached.
Implements rviz::Object.
Definition at line 619 of file covariance_visual.cpp.
| void rviz::CovarianceVisual::setOrientationColor | ( | const Ogre::ColourValue & | color | ) |
Definition at line 533 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 554 of file covariance_visual.cpp.
| void rviz::CovarianceVisual::setOrientationColorToRGB | ( | float | a | ) |
Definition at line 541 of file covariance_visual.cpp.
| void rviz::CovarianceVisual::setOrientationOffset | ( | float | ori_offset | ) |
Definition at line 471 of file covariance_visual.cpp.
| void rviz::CovarianceVisual::setOrientationScale | ( | float | ori_scale | ) |
Definition at line 495 of file covariance_visual.cpp.
|
virtual |
Sets visibility of the orientation part of this covariance.
Definition at line 589 of file covariance_visual.cpp.
|
overridevirtual |
Sets position of the frame this covariance is attached.
Implements rviz::Object.
Definition at line 614 of file covariance_visual.cpp.
| void rviz::CovarianceVisual::setPositionColor | ( | const Ogre::ColourValue & | color | ) |
Definition at line 528 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 549 of file covariance_visual.cpp.
| void rviz::CovarianceVisual::setPositionScale | ( | float | pos_scale | ) |
Definition at line 463 of file covariance_visual.cpp.
|
virtual |
Sets visibility of the position part of this covariance.
Definition at line 584 of file covariance_visual.cpp.
|
virtual |
Sets which frame to attach the covariance of the orientation.
Definition at line 624 of file covariance_visual.cpp.
|
inlineoverrideprivatevirtual |
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 242 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 457 of file covariance_visual.cpp.
|
overridevirtual |
Sets user data on all ogre objects we own.
Implements rviz::Object.
Definition at line 569 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 578 of file covariance_visual.cpp.
|
private |
Definition at line 390 of file covariance_visual.cpp.
|
private |
Definition at line 595 of file covariance_visual.cpp.
|
private |
Definition at line 366 of file covariance_visual.cpp.
|
friend |
Definition at line 252 of file covariance_visual.h.
|
private |
Definition at line 234 of file covariance_visual.h.
|
private |
Definition at line 235 of file covariance_visual.h.
|
private |
Definition at line 218 of file covariance_visual.h.
|
private |
Definition at line 228 of file covariance_visual.h.
|
staticprivate |
Definition at line 237 of file covariance_visual.h.
|
private |
Definition at line 223 of file covariance_visual.h.
|
private |
Definition at line 222 of file covariance_visual.h.
|
private |
Cylinders used for the orientation covariance.
Definition at line 226 of file covariance_visual.h.
|
private |
If the orientation component is visible.
Definition at line 232 of file covariance_visual.h.
|
private |
Definition at line 230 of file covariance_visual.h.
|
private |
Definition at line 220 of file covariance_visual.h.
|
private |
Definition at line 219 of file covariance_visual.h.
|
private |
Ellipse used for the position covariance.
Definition at line 225 of file covariance_visual.h.
|
private |
Definition at line 217 of file covariance_visual.h.