31 #ifndef RVIZ_PATH_DISPLAY_H 32 #define RVIZ_PATH_DISPLAY_H 34 #include <nav_msgs/Path.h> 72 virtual void onInitialize();
75 void processMessage(
const nav_msgs::Path::ConstPtr& msg );
78 void updateBufferLength();
80 void updateLineWidth();
82 void updatePoseStyle();
83 void updatePoseAxisGeometry();
84 void updatePoseArrowColor();
85 void updatePoseArrowGeometry();
88 void destroyObjects();
89 void allocateArrowVector(std::vector<rviz::Arrow*>& arrow_vect,
int num);
90 void allocateAxesVector(std::vector<rviz::Axes*>& axes_vect,
int num);
91 void destroyPoseAxesChain();
92 void destroyPoseArrowChain();
std::vector< Ogre::ManualObject * > manual_objects_
std::vector< rviz::BillboardLine * > billboard_lines_
FloatProperty * line_width_property_
ColorProperty * pose_arrow_color_property_
EnumProperty * style_property_
FloatProperty * pose_arrow_shaft_diameter_property_
FloatProperty * pose_arrow_head_diameter_property_
FloatProperty * pose_arrow_shaft_length_property_
VectorProperty * offset_property_
FloatProperty * pose_axes_radius_property_
Property specialized to enforce floating point max/min.
ColorProperty * color_property_
Property specialized to provide max/min enforcement for integers.
Displays a nav_msgs::Path message.
Display subclass using a tf::MessageFilter, templated on the ROS message type.
std::vector< std::vector< rviz::Arrow * > > arrow_chain_
FloatProperty * alpha_property_
IntProperty * buffer_length_property_
std::vector< std::vector< rviz::Axes * > > axes_chain_
EnumProperty * pose_style_property_
FloatProperty * pose_arrow_head_length_property_
FloatProperty * pose_axes_length_property_