30 #ifndef MAPVIZ_PLUGINS_DRAW_POLYGON_PLUGIN_H_ 31 #define MAPVIZ_PLUGINS_DRAW_POLYGON_PLUGIN_H_ 52 #include <geometry_msgs/Polygon.h> 55 #include "ui_draw_polygon_config.h" 73 void Draw(
double x,
double y,
double scale);
77 void LoadConfig(
const YAML::Node& node,
const std::string& path);
78 void SaveConfig(YAML::Emitter& emitter,
const std::string& path);
84 void PrintInfo(
const std::string& message);
98 Ui::draw_polygon_config
ui_;
118 #endif // MAPVIZ_PLUGINS_DRAW_POLYGON_PLUGIN_H_
ros::Publisher polygon_pub_
void SaveConfig(YAML::Emitter &emitter, const std::string &path)
std::string polygon_topic_
bool handleMousePress(QMouseEvent *)
bool handleMouseRelease(QMouseEvent *)
void PrintWarning(const std::string &message)
std::vector< tf::Vector3 > transformed_vertices_
void LoadConfig(const YAML::Node &node, const std::string &path)
bool Initialize(QGLWidget *canvas)
void PrintInfo(const std::string &message)
Ui::draw_polygon_config ui_
TFSIMD_FORCE_INLINE const tfScalar & y() const
void PrintError(const std::string &message)
QWidget * GetConfigWidget(QWidget *parent)
TFSIMD_FORCE_INLINE const tfScalar & x() const
std::vector< tf::Vector3 > vertices_
virtual ~DrawPolygonPlugin()
bool eventFilter(QObject *object, QEvent *event)
void Draw(double x, double y, double scale)
bool handleMouseMove(QMouseEvent *)
mapviz::MapCanvas * map_canvas_