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);
116 unsigned int last_vertex_count_ { 0 };
131 const std::string&
getName()
const {
return name_; }
155 #endif // ROBOT_NAV_RVIZ_PLUGINS_POLYGON_PARTS_H
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...
Ogre::SceneManager & scene_manager_
std::string material_name_
Ogre::SceneNode & scene_node_
Ogre::SceneNode & scene_node_
Ogre::SceneManager & scene_manager_
Constructs a manual ogre object to display the polygon area as a triangle mesh.
PolygonOutline(Ogre::SceneManager &scene_manager, Ogre::SceneNode &scene_node)
Constructs a manual ogre object to display the polygon outline as a line strip.
virtual ~PolygonOutline()
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.
const std::string & getName() const
Ogre::ManualObject * manual_object_
bool shouldDrawOutlines() const
DisplayMode getDisplayMode() const
Several reusable pieces for displaying polygons.
rviz::EnumProperty * property_
bool shouldDrawFiller() const
Ogre::ManualObject * manual_object_
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.
Ogre::MaterialPtr material_