Go to the documentation of this file.
35 #ifndef ROBOT_NAV_RVIZ_PLUGINS_POLYGON_PARTS_H
36 #define ROBOT_NAV_RVIZ_PLUGINS_POLYGON_PARTS_H
38 #include <nav_2d_msgs/Polygon2D.h>
39 #include <nav_2d_msgs/ComplexPolygon2D.h>
40 #include <OgreManualObject.h>
41 #include <OgreSceneManager.h>
45 #include <std_msgs/ColorRGBA.h>
68 PolygonOutline(Ogre::SceneManager& scene_manager, Ogre::SceneNode& scene_node);
79 void setPolygon(
const nav_2d_msgs::Polygon2D& polygon,
const Ogre::ColourValue& color,
double z_offset);
94 PolygonFill(Ogre::SceneManager& scene_manager, Ogre::SceneNode& scene_node,
const std::string& material_name);
105 void setPolygon(
const nav_2d_msgs::Polygon2D& polygon,
const std_msgs::ColorRGBA& color,
double z_offset);
113 void setPolygon(
const nav_2d_msgs::ComplexPolygon2D& polygon,
const std_msgs::ColorRGBA& color,
double z_offset);
155 #endif // ROBOT_NAV_RVIZ_PLUGINS_POLYGON_PARTS_H
virtual int getOptionInt()
Ogre::SceneNode & scene_node_
unsigned int last_vertex_count_
virtual ~PolygonOutline()
Several reusable pieces for displaying polygons.
DisplayMode getDisplayMode() const
std_msgs::ColorRGBA getColor(rviz::ColorProperty *color_property, rviz::FloatProperty *alpha_property=nullptr)
Given a Color Property and an optional Float property, return a ROS Color message.
Ogre::SceneNode & scene_node_
bool shouldDrawFiller() const
Ogre::ManualObject * manual_object_
void setPolygon(const nav_2d_msgs::Polygon2D &polygon, const Ogre::ColourValue &color, double z_offset)
Set the object to display the outline of the given polygon, in a specific color, possibly offset in z...
std::string material_name_
const std::string & getName() const
PolygonDisplayModeProperty(rviz::Property *parent, const char *changed_slot=0)
bool shouldDrawOutlines() const
PolygonFill(Ogre::SceneManager &scene_manager, Ogre::SceneNode &scene_node, const std::string &material_name)
Ogre::ManualObject * manual_object_
virtual ~PolygonMaterial()
PolygonOutline(Ogre::SceneManager &scene_manager, Ogre::SceneNode &scene_node)
Ogre::SceneManager & scene_manager_
Ogre::MaterialPtr material_
void setPolygon(const nav_2d_msgs::Polygon2D &polygon, const std_msgs::ColorRGBA &color, double z_offset)
Set the object to display the area of the given polygon, in a specific color, possibly offset in z.
Constructs a manual ogre object to display the polygon area as a triangle mesh.
Wrapper for EnumProperty + enum for whether to display the outline, area, or both.
Constructs a manual ogre object to display the polygon outline as a line strip.
Ogre::SceneManager & scene_manager_
Wrapper that creates a flat semi-transparent Ogre material and gives it a name.
rviz::EnumProperty * property_