30 #ifndef MAPVIZ_PLUGINS_MARTI_NAV_PATH_PLUGIN_H_ 31 #define MAPVIZ_PLUGINS_MARTI_NAV_PATH_PLUGIN_H_ 35 #include <boost/circular_buffer.hpp> 47 #include <marti_nav_msgs/Path.h> 51 #include "ui_marti_nav_path_config.h" 59 Ui::marti_nav_path_config
ui_;
65 boost::circular_buffer<marti_nav_msgs::Path>
items_;
73 void Draw(
double x,
double y,
double scale);
76 void LoadConfig(
const YAML::Node& node,
const std::string& path);
77 void SaveConfig(YAML::Emitter& emitter,
const std::string& path);
83 void PrintInfo(
const std::string& message);
91 void handlePath(
const marti_nav_msgs::Path& path);
101 #endif // MAPVIZ_PLUGINS_MARTI_NAV_PATH_PLUGIN_H_
void setColorForDirection(const bool in_reverse)
void handlePath(const marti_nav_msgs::Path &path)
void LoadConfig(const YAML::Node &node, const std::string &path)
void PrintInfo(const std::string &message)
void Draw(double x, double y, double scale)
void handlePathPoint(const marti_nav_msgs::PathPoint &pt)
QWidget * GetConfigWidget(QWidget *parent)
bool Initialize(QGLWidget *canvas)
boost::circular_buffer< marti_nav_msgs::Path > items_
Ui::marti_nav_path_config ui_
void PrintWarning(const std::string &message)
void messageCallback(const topic_tools::ShapeShifter::ConstPtr &msg)
ros::Subscriber subscriber_
void PrintError(const std::string &message)
void SaveConfig(YAML::Emitter &emitter, const std::string &path)