20 #ifndef MAPVIZ_PLUGINS_GPS_PLUGIN_H_ 21 #define MAPVIZ_PLUGINS_GPS_PLUGIN_H_ 42 #include <gps_common/GPSFix.h> 46 #include "ui_gps_config.h" 63 void Draw(
double x,
double y,
double scale);
65 void LoadConfig(
const YAML::Node& node,
const std::string& path);
66 void SaveConfig(YAML::Emitter& emitter,
const std::string& path);
72 void PrintInfo(
const std::string& message);
92 #endif // MAPVIZ_PLUGINS_GPS_PLUGIN_H_
QWidget * GetConfigWidget(QWidget *parent)
void LoadConfig(const YAML::Node &node, const std::string &path)
bool Initialize(QGLWidget *canvas)
void GPSFixCallback(const gps_common::GPSFixConstPtr &gps)
void Draw(double x, double y, double scale)
void SaveConfig(YAML::Emitter &emitter, const std::string &path)
void PrintWarning(const std::string &message)
void PrintInfo(const std::string &message)
void PrintError(const std::string &message)