30 #ifndef MAPVIZ_PLUGINS_PLAN_ROUTE_PLUGIN_H_ 31 #define MAPVIZ_PLUGINS_PLAN_ROUTE_PLUGIN_H_ 53 #include <geometry_msgs/Pose.h> 54 #include <marti_nav_msgs/Route.h> 57 #include "ui_plan_route_config.h" 75 void Draw(
double x,
double y,
double scale);
76 void Paint(QPainter* painter,
double x,
double y,
double scale);
80 void LoadConfig(
const YAML::Node& node,
const std::string& path);
81 void SaveConfig(YAML::Emitter& emitter,
const std::string& path);
92 void PrintInfo(
const std::string& message);
108 Ui::plan_route_config
ui_;
132 #endif // MAPVIZ_PLUGINS_PLAN_ROUTE_PLUGIN_H_
void Retry(const ros::TimerEvent &e)
std::vector< geometry_msgs::Pose > waypoints_
void SaveConfig(YAML::Emitter &emitter, const std::string &path)
void Paint(QPainter *painter, double x, double y, double scale)
swri_route_util::RoutePtr route_preview_
virtual ~PlanRoutePlugin()
TFSIMD_FORCE_INLINE const tfScalar & y() const
bool handleMousePress(QMouseEvent *)
void LoadConfig(const YAML::Node &node, const std::string &path)
void PrintError(const std::string &message)
void PrintInfo(const std::string &message)
void Draw(double x, double y, double scale)
bool eventFilter(QObject *object, QEvent *event)
bool handleMouseMove(QMouseEvent *)
ros::Publisher route_pub_
TFSIMD_FORCE_INLINE const tfScalar & x() const
Ui::plan_route_config ui_
void VisibilityChanged(bool)
bool Initialize(QGLWidget *canvas)
mapviz::MapCanvas * map_canvas_
void PrintWarning(const std::string &message)
bool handleMouseRelease(QMouseEvent *)
QWidget * GetConfigWidget(QWidget *parent)