30 #ifndef POSE_WITH_COVARIANCE_DISPLAY_H 31 #define POSE_WITH_COVARIANCE_DISPLAY_H 33 #include <boost/shared_ptr.hpp> 35 #include <geometry_msgs/PoseWithCovarianceStamped.h> 50 class CovarianceVisual;
51 class CovarianceProperty;
73 void reset()
override;
89 void processMessage(
const geometry_msgs::PoseWithCovarianceStamped::ConstPtr& message)
override;
117 #endif // POSE_WITH_COVARIANCE_DISPLAY_H rviz::FloatProperty * head_length_property_
Displays the pose from a geometry_msgs::PoseWithCovarianceStamped message.
rviz::FloatProperty * axes_length_property_
void updateArrowGeometry()
~PoseWithCovarianceDisplay() override
void updateShapeVisibility()
PoseWithCovarianceDisplay()
void reset() override
Called to tell the display to clear its state.
Property specialized to enforce floating point max/min.
rviz::EnumProperty * shape_property_
rviz::FloatProperty * axes_radius_property_
boost::shared_ptr< PoseWithCovarianceDisplaySelectionHandler > PoseWithCovarianceDisplaySelectionHandlerPtr
CovarianceProperty * covariance_property_
boost::shared_ptr< CovarianceVisual > covariance_
rviz::FloatProperty * head_radius_property_
Display subclass using a tf2_ros::MessageFilter, templated on the ROS message type.
An object that displays a set of X/Y/Z axes, with X=Red, Y=Green, Z=Blue.
rviz::FloatProperty * alpha_property_
PoseWithCovarianceDisplaySelectionHandlerPtr coll_handler_
rviz::ColorProperty * color_property_
void updateColorAndAlpha()
void onInitialize() override
Override this function to do subclass-specific initialization.
void updateAxisGeometry()
Property specialized to provide getter for booleans.
rviz::FloatProperty * shaft_length_property_
An arrow consisting of a cylinder and a cone.
void processMessage(const geometry_msgs::PoseWithCovarianceStamped::ConstPtr &message) override
rviz::FloatProperty * shaft_radius_property_
void onEnable() override
Overridden from MessageFilterDisplay to get Arrow/Axes visibility correct.