30 #ifndef MAPVIZ_PLUGINS_ROUTE_PLUGIN_H_ 31 #define MAPVIZ_PLUGINS_ROUTE_PLUGIN_H_ 48 #include <marti_nav_msgs/RoutePosition.h> 53 #include "ui_route_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);
90 void PrintInfo(
const std::string& message);
116 void RouteCallback(
const marti_nav_msgs::RouteConstPtr &msg);
121 #endif // MAPVIZ_PLUGINS_ROUTE_PLUGIN_H_
std::string position_topic_
void PrintInfo(const std::string &message)
marti_nav_msgs::RoutePositionConstPtr src_route_position_
void LoadConfig(const YAML::Node &node, const std::string &path)
ros::Subscriber position_sub_
void Draw(double x, double y, double scale)
bool Initialize(QGLWidget *canvas)
void PrintError(const std::string &message)
TFSIMD_FORCE_INLINE const tfScalar & y() const
swri_route_util::Route src_route_
void DrawRoutePoint(const swri_route_util::RoutePoint &point)
void PrintWarning(const std::string &message)
void DrawStopWaypoint(double x, double y)
TFSIMD_FORCE_INLINE const tfScalar & x() const
void PositionTopicEdited()
ros::Subscriber route_sub_
void PositionCallback(const marti_nav_msgs::RoutePositionConstPtr &msg)
void SelectPositionTopic()
void RouteCallback(const marti_nav_msgs::RouteConstPtr &msg)
void SaveConfig(YAML::Emitter &emitter, const std::string &path)
void SetDrawStyle(QString style)
void DrawRoute(const swri_route_util::Route &route)
QWidget * GetConfigWidget(QWidget *parent)