116 Ogre::Vector3 position;
117 Ogre::Quaternion orientation;
120 ROS_DEBUG(
"Error transforming from frame '%s' to frame '%s'",
121 msg->header.frame_id.c_str(), qPrintable(
fixed_frame_));
126 bool empty = msg->polygon.points.empty();
virtual QColor getColor() const
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...
PolygonOutline * outline_object_
virtual void onInitialize()
DisplayContext * context_
Constructs a manual ogre object to display the polygon area as a triangle mesh.
virtual float getFloat() const
Constructs a manual ogre object to display the polygon outline as a line strip.
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
PolygonMaterial polygon_material_
Ogre::SceneNode * scene_node_
Ogre::ColourValue qtToOgre(const QColor &c)
bool shouldDrawOutlines() const
PolygonDisplayModeProperty * mode_property_
virtual ~PolygonDisplay()
Several reusable pieces for displaying polygons.
rviz::ColorProperty * filler_color_property_
void onInitialize() override
virtual FrameManager * getFrameManager() const =0
bool shouldDrawFiller() const
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...
Ogre::SceneManager * scene_manager_
rviz::FloatProperty * zoffset_property_
PolygonFill * filler_object_
void processMessage(const nav_2d_msgs::Polygon2DStamped::ConstPtr &msg) override
rviz::FloatProperty * filler_alpha_property_
bool getTransform(const Header &header, Ogre::Vector3 &position, Ogre::Quaternion &orientation)
Wrapper for EnumProperty + enum for whether to display the outline, area, or both.
Displays a nav_2d_msgs::Polygon2DStamped message in Rviz.
bool validateFloats(const nav_grid::NavGridInfo &info)
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
virtual void setStatus(StatusProperty::Level level, const QString &name, const QString &text)
rviz::ColorProperty * outline_color_property_