30 #ifndef MAPVIZ_PLUGINS_MARTI_NAV_PLAN_PLUGIN_H_ 31 #define MAPVIZ_PLUGINS_MARTI_NAV_PLAN_PLUGIN_H_ 48 #include <marti_nav_msgs/Plan.h> 49 #include <marti_nav_msgs/PlanTrack.h> 53 #include "ui_marti_nav_plan_config.h" 76 void Draw(
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);
83 void DrawRoute(
const marti_nav_msgs::Plan &route);
90 void PrintInfo(
const std::string& message);
102 Ui::marti_nav_plan_config
ui_;
121 #endif // MAPVIZ_PLUGINS_MARTI_NAV_PLAN_PLUGIN_H_ QWidget * GetConfigWidget(QWidget *parent)
virtual ~MartiNavPlanPlugin()
void SelectPositionTopic()
void RouteCallback(const marti_nav_msgs::PlanConstPtr &msg)
bool Initialize(QGLWidget *canvas)
void DrawRoutePoint(const marti_nav_msgs::PlanPoint &point)
marti_nav_msgs::PlanConstPtr src_route_
void SaveConfig(YAML::Emitter &emitter, const std::string &path)
void Draw(double x, double y, double scale)
void LoadConfig(const YAML::Node &node, const std::string &path)
void SetDrawStyle(QString style)
void PrintWarning(const std::string &message)
void PrintError(const std::string &message)
void PositionTopicEdited()
void PositionCallback(const marti_nav_msgs::PlanTrackConstPtr &msg)
void DrawStopWaypoint(double x, double y)
void DrawRoute(const marti_nav_msgs::Plan &route)
ros::Subscriber position_sub_
marti_nav_msgs::PlanTrackConstPtr src_route_position_
ros::Subscriber route_sub_
std::string position_topic_
void PrintInfo(const std::string &message)
Ui::marti_nav_plan_config ui_