Go to the documentation of this file.
39 #include <OgreSceneManager.h>
40 #include <OgreSceneNode.h>
46 const QString& description,
52 new BoolProperty(
"Position",
true,
"Whether or not to show the position part of covariances",
this,
57 new ColorProperty(
"Color", QColor(204, 51, 204),
"Color to draw the position covariance ellipse.",
62 new FloatProperty(
"Alpha", 0.3
f,
"0 is fully transparent, 1.0 is fully opaque.",
70 "Scale factor to be applied to covariance ellipse. "
71 "Corresponds to the number of standard deviations to display",
77 new BoolProperty(
"Orientation",
true,
"Whether or not to show the orientation part of covariances",
82 new EnumProperty(
"Frame",
"Local",
"The frame used to display the orientation covariance.",
89 "Color Style",
"Unique",
90 "Style to color the orientation covariance: XYZ with same unique color or following RGB order",
96 new ColorProperty(
"Color", QColor(255, 255, 127),
"Color to draw the covariance ellipse.",
101 new FloatProperty(
"Alpha", 0.5
f,
"0 is fully transparent, 1.0 is fully opaque.",
109 "For 3D poses is the distance where to position the ellipses representing orientation covariance. "
110 "For 2D poses is the height of the triangle representing the variance on yaw.",
117 "Scale factor to be applied to orientation covariance shapes. "
118 "Corresponds to the number of standard deviations to display.",
143 for (; it_cov != end_cov; ++it_cov)
152 visual->setPositionColor(pos_color.redF(), pos_color.greenF(), pos_color.blueF(), pos_alpha);
153 visual->setPositionScale(pos_scale);
161 visual->setOrientationColor(ori_color.redF(), ori_color.greenF(), ori_color.blueF(), ori_alpha);
165 visual->setOrientationColorToRGB(ori_alpha);
167 visual->setOrientationOffset(ori_offset);
168 visual->setOrientationScale(ori_scale);
175 for (; it_cov != end_cov; ++it_cov)
181 bool show_covariance =
getBool();
182 if (!show_covariance)
184 visual->setVisible(
false);
191 visual->setPositionVisible(show_position_covariance);
192 visual->setOrientationVisible(show_orientation_covariance);
200 for (; it_cov != end_cov; ++it_cov)
207 visual->setRotatingFrame(use_rotating_frame);
227 Ogre::SceneNode* parent_node)
rviz::FloatProperty * position_alpha_property_
virtual bool getBool() const
virtual int getOptionInt()
Return the int value of the currently-chosen option, or 0 if the current option string does not have ...
rviz::ColorProperty * position_color_property_
virtual QColor getColor() const
virtual void setHidden(bool hidden)
Hide or show this property in any PropertyTreeWidget viewing its parent.
rviz::BoolProperty * orientation_property_
rviz::FloatProperty * position_scale_property_
CovarianceVisualPtr createAndPushBackVisual(Ogre::SceneManager *scene_manager, Ogre::SceneNode *parent_node)
~CovarianceProperty() override
Property specialized to provide getter for booleans.
void setDisableChildrenIfFalse(bool disable)
bool getOrientationBool()
BoolProperty(const QString &name=QString(), bool default_value=false, const QString &description=QString(), Property *parent=nullptr)
QMetaObject::Connection connect(const QObject *receiver, const char *slot, Qt::ConnectionType type=Qt::AutoConnection)
Connect changed() signal to given slot of receiver.
void updateColorStyleChoice()
Property specialized to enforce floating point max/min.
A single element of a property tree, with a name, value, description, and possibly children.
D_Covariance covariances_
virtual float getFloat() const
virtual void addOption(const QString &option, int value=0)
rviz::ColorProperty * orientation_color_property_
rviz::FloatProperty * orientation_scale_property_
void updateColorAndAlphaAndScaleAndOffset()
rviz::FloatProperty * orientation_alpha_property_
rviz::EnumProperty * orientation_frame_property_
void changed()
Emitted by setValue() just after the value has changed.
rviz::EnumProperty * orientation_colorstyle_property_
CovarianceVisual consisting in a ellipse for position and 2D ellipses along the axis for orientation.
rviz::FloatProperty * orientation_offset_property_
rviz::BoolProperty * position_property_
void updateOrientationFrame()
CovarianceProperty(const QString &name="Covariance", bool default_value=false, const QString &description=QString(), rviz::Property *parent=nullptr)
rviz
Author(s): Dave Hershberger, David Gossow, Josh Faust, William Woodall
autogenerated on Fri Aug 2 2024 08:43:09