Class MappedCovarianceVisual
Defined in File mapped_covariance_visual.hpp
Inheritance Relationships
Base Type
public rviz_rendering::Object
Class Documentation
-
class MappedCovarianceVisual : public rviz_rendering::Object
MappedCovarianceVisual consisting in a ellipse for position and 2D ellipses along the axis for orientation.
This is mostly a copy of CovarianceVisual from rviz/default_plugin/covariance_visual.h that allows MappedCovarianceProperty be a friend class of MappedCovarianceVisual, so it can call its constructor.
Public Types
Public Functions
-
~MappedCovarianceVisual() override
-
void setScales(float pos_scale, float ori_scale)
Set the position and orientation scales for this covariance.
- Parameters:
pos_scale – Scale of the position covariance
ori_scale – Scale of the orientation covariance
-
void setPositionScale(float pos_scale)
-
void setOrientationOffset(float ori_offset)
-
void setOrientationScale(float ori_scale)
-
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].
- Parameters:
r – Red component
g – Green component
b – Blue component
-
void setPositionColor(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].
- Parameters:
r – Red component
g – Green component
b – Blue component
-
void setOrientationColor(const Ogre::ColourValue &color)
-
void setOrientationColorToRGB(float a)
-
virtual void setCovariance(const geometry_msgs::msg::PoseWithCovariance &pose)
Set the covariance.
This effectively changes the orientation and scale of position and orientation covariance shapes
-
virtual const Ogre::Vector3 &getPositionCovarianceScale()
-
virtual const Ogre::Quaternion &getPositionCovarianceOrientation()
-
inline Ogre::SceneNode *getPositionSceneNode()
Get the root scene node of the position part of this covariance.
- Returns:
the root scene node of the position part of this covariance
-
inline Ogre::SceneNode *getOrientationSceneNode()
Get the root scene node of the orientation part of this covariance.
- Returns:
the root scene node of the orientation part of this covariance
-
inline rviz_rendering::Shape *getPositionShape()
Get the shape used to display position covariance.
- Returns:
the shape used to display position covariance
-
rviz_rendering::Shape *getOrientationShape(ShapeIndex index)
Get the shape used to display orientation covariance in an especific axis.
- Returns:
the shape used to display orientation covariance in an especific axis
-
virtual void setUserData(const Ogre::Any &data)
Sets user data on all ogre objects we own.
-
virtual void setVisible(bool visible)
Sets visibility of this covariance.
Convenience method that sets visibility of both position and orientation parts.
-
virtual void setPositionVisible(bool visible)
Sets visibility of the position part of this covariance.
-
virtual void setOrientationVisible(bool visible)
Sets visibility of the orientation part of this covariance.
-
virtual void setPosition(const Ogre::Vector3 &position)
Sets position of the frame this covariance is attached.
-
virtual void setOrientation(const Ogre::Quaternion &orientation)
Sets orientation of the frame this covariance is attached.
-
virtual void setRotatingFrame(bool use_rotating_frame)
Sets which frame to attach the covariance of the orientation.
-
~MappedCovarianceVisual() override