34 #ifndef ROBOT_NAV_RVIZ_PLUGINS_POLYGONS_DISPLAY_H 35 #define ROBOT_NAV_RVIZ_PLUGINS_POLYGONS_DISPLAY_H 37 #include <nav_2d_msgs/Polygon2DCollection.h> 43 #include <OgreManualObject.h> 44 #include <OgreMaterial.h> 59 void reset()
override;
62 void processMessage(
const nav_2d_msgs::Polygon2DCollection::ConstPtr& msg)
override;
92 #endif // ROBOT_NAV_RVIZ_PLUGINS_POLYGONS_DISPLAY_H
rviz::FloatProperty * filler_alpha_property_
std::vector< nav_2d_msgs::Polygon2D > saved_outlines_
rviz::ColorProperty * outline_color_property_
Displays a nav_2d_msgs::Polygon2DCollection message in Rviz.
std::vector< PolygonFill * > filler_objects_
std::vector< std_msgs::ColorRGBA > unique_colors_
std::vector< PolygonOutline * > outline_objects_
rviz::EnumProperty * color_mode_property_
rviz::FloatProperty * zoffset_property_
Several reusable pieces for displaying polygons.
nav_2d_msgs::Polygon2DCollection saved_polygons_
PolygonDisplayModeProperty * mode_property_
Wrapper that creates a flat semi-transparent Ogre material and gives it a name.
Wrapper for EnumProperty + enum for whether to display the outline, area, or both.
PolygonMaterial polygon_material_
FillColorMode getFillColorMode() const
rviz::ColorProperty * filler_color_property_
virtual int getOptionInt()
void processMessage(const nav_2d_msgs::Polygon2DCollection::ConstPtr &msg) override
virtual ~PolygonsDisplay()