Go to the documentation of this file.
31 #ifndef RVIZ_POSE_DISPLAY_H_
32 #define RVIZ_POSE_DISPLAY_H_
34 #include <boost/shared_ptr.hpp>
36 #include <geometry_msgs/PoseStamped.h>
68 void reset()
override;
84 void processMessage(
const geometry_msgs::PoseStamped::ConstPtr& message)
override;
FloatProperty * shaft_length_property_
Display subclass using a tf2_ros::MessageFilter, templated on the ROS message type.
FloatProperty * axes_length_property_
An arrow consisting of a cylinder and a cone.
FloatProperty * shaft_radius_property_
void updateShapeVisibility()
PoseDisplaySelectionHandlerPtr coll_handler_
Property specialized to enforce floating point max/min.
EnumProperty * shape_property_
boost::shared_ptr< PoseDisplaySelectionHandler > PoseDisplaySelectionHandlerPtr
void updateArrowGeometry()
void onInitialize() override
Override this function to do subclass-specific initialization.
void reset() override
Called to tell the display to clear its state.
void updateAxisGeometry()
void processMessage(const geometry_msgs::PoseStamped::ConstPtr &message) override
FloatProperty * alpha_property_
Accumulates and displays the pose from a geometry_msgs::PoseStamped message.
An object that displays a set of X/Y/Z axes, with X=Red, Y=Green, Z=Blue.
FloatProperty * head_radius_property_
FloatProperty * head_length_property_
ColorProperty * color_property_
void updateColorAndAlpha()
void onEnable() override
Overridden from MessageFilterDisplay to get arrow/axes visibility correct.
FloatProperty * axes_radius_property_
rviz
Author(s): Dave Hershberger, David Gossow, Josh Faust, William Woodall
autogenerated on Fri Aug 2 2024 08:43:10