31 #ifndef RVIZ_PATH_VEC_DISPLAY_H 32 #define RVIZ_PATH_VEC_DISPLAY_H 34 #include <nav_msgs/Path.h> 35 #include <tuw_nav_msgs/PathVec.h> 78 virtual void onInitialize();
81 void processMessage(
const tuw_nav_msgs::PathVec::ConstPtr& msg );
84 void updateBufferLength();
86 void updateLineWidth();
88 void updatePoseStyle();
89 void updatePoseAxisGeometry();
90 void updatePoseArrowColor();
91 void updatePoseArrowGeometry();
94 void destroyObjects();
95 void allocateArrowVector(std::vector<rviz::Arrow*>& arrow_vect,
int num);
96 void allocateAxesVector(std::vector<rviz::Axes*>& axes_vect,
int num);
97 void destroyPoseAxesChain();
98 void destroyPoseArrowChain();
rviz::EnumProperty * pose_style_property_
rviz::EnumProperty * style_property_
rviz::FloatProperty * line_width_property_
rviz::FloatProperty * pose_arrow_shaft_diameter_property_
std::vector< size_t > pathsSize_
rviz::FloatProperty * pose_axes_length_property_
rviz::ColorProperty * pose_arrow_color_property_
rviz::VectorProperty * offset_property_
rviz::FloatProperty * pose_arrow_head_length_property_
std::vector< std::vector< rviz::BillboardLine * > > billboard_lines_
std::vector< std::vector< std::vector< rviz::Axes * > > > axes_chain_
rviz::FloatProperty * pose_arrow_head_diameter_property_
std::vector< std::vector< Ogre::ManualObject * > > manual_objects_
rviz::IntProperty * buffer_length_property_
std::vector< std::vector< std::vector< rviz::Arrow * > > > arrow_chain_
Displays a tuw_nav_msgs::PathVec message.
rviz::FloatProperty * alpha_property_
rviz::ColorProperty * color_property_
rviz::FloatProperty * pose_axes_radius_property_
rviz::FloatProperty * pose_arrow_shaft_length_property_