Go to the documentation of this file.
31 #ifndef RVIZ_PATH_DISPLAY_H
32 #define RVIZ_PATH_DISPLAY_H
34 #include <nav_msgs/Path.h>
67 void reset()
override;
Display subclass using a tf2_ros::MessageFilter, templated on the ROS message type.
Displays a nav_msgs::Path message.
FloatProperty * alpha_property_
VectorProperty * offset_property_
void reset() override
Overridden from Display.
EnumProperty * style_property_
EnumProperty * pose_style_property_
FloatProperty * line_width_property_
void destroyPoseArrowChain()
void destroyPoseAxesChain()
void updatePoseArrowGeometry()
FloatProperty * pose_arrow_head_length_property_
Property specialized to enforce floating point max/min.
void updatePoseAxisGeometry()
ColorProperty * color_property_
ColorProperty * pose_arrow_color_property_
void allocateArrowVector(std::vector< rviz::Arrow * > &arrow_vect, size_t num)
FloatProperty * pose_arrow_head_diameter_property_
void processMessage(const nav_msgs::Path::ConstPtr &msg) override
Overridden from MessageFilterDisplay.
void onInitialize() override
Overridden from Display.
FloatProperty * pose_axes_length_property_
std::vector< rviz::BillboardLine * > billboard_lines_
FloatProperty * pose_arrow_shaft_diameter_property_
FloatProperty * pose_arrow_shaft_length_property_
void updateBufferLength()
std::vector< std::vector< rviz::Arrow * > > arrow_chain_
void allocateAxesVector(std::vector< rviz::Axes * > &axes_vect, size_t num)
std::vector< Ogre::ManualObject * > manual_objects_
FloatProperty * pose_axes_radius_property_
void updatePoseArrowColor()
std::vector< std::vector< rviz::Axes * > > axes_chain_
IntProperty * buffer_length_property_
Property specialized to provide max/min enforcement for integers.
rviz
Author(s): Dave Hershberger, David Gossow, Josh Faust, William Woodall
autogenerated on Fri Dec 13 2024 03:31:02