20 #ifndef MAPVIZ_PLUGINS_NAVSAT_PLUGIN_H_ 21 #define MAPVIZ_PLUGINS_NAVSAT_PLUGIN_H_ 39 #include <sensor_msgs/NavSatFix.h> 43 #include "ui_navsat_config.h" 60 void Draw(
double x,
double y,
double scale);
62 void LoadConfig(
const YAML::Node& node,
const std::string& path);
63 void SaveConfig(YAML::Emitter& emitter,
const std::string& path);
69 void PrintInfo(
const std::string& message);
77 Ui::navsat_config
ui_;
91 #endif // MAPVIZ_PLUGINS_NAVSAT_PLUGIN_H_
void PrintInfo(const std::string &message)
QWidget * GetConfigWidget(QWidget *parent)
swri_transform_util::LocalXyWgs84Util local_xy_util_
TFSIMD_FORCE_INLINE const tfScalar & y() const
ros::Subscriber navsat_sub_
void Draw(double x, double y, double scale)
void NavSatFixCallback(const sensor_msgs::NavSatFixConstPtr navsat)
TFSIMD_FORCE_INLINE const tfScalar & x() const
void PrintWarning(const std::string &message)
void LoadConfig(const YAML::Node &node, const std::string &path)
bool Initialize(QGLWidget *canvas)
void PrintError(const std::string &message)
void SaveConfig(YAML::Emitter &emitter, const std::string &path)