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