30 #ifndef MAPVIZ_PLUGINS_ODOMETRY_PLUGIN_H_ 31 #define MAPVIZ_PLUGINS_ODOMETRY_PLUGIN_H_ 48 #include <nav_msgs/Odometry.h> 53 #include "ui_odometry_config.h" 70 void Paint(QPainter* painter,
double x,
double y,
double scale);
71 void Draw(
double x,
double y,
double scale);
72 void LoadConfig(
const YAML::Node& node,
const std::string& path);
73 void SaveConfig(YAML::Emitter& emitter,
const std::string& path);
84 void PrintInfo(
const std::string& message);
94 Ui::odometry_config
ui_;
103 #endif // MAPVIZ_PLUGINS_ODOMETRY_PLUGIN_H_ bool Initialize(QGLWidget *canvas)
void Draw(double x, double y, double scale)
ros::Subscriber odometry_sub_
void PrintError(const std::string &message)
void odometryCallback(const nav_msgs::OdometryConstPtr odometry)
void Paint(QPainter *painter, double x, double y, double scale)
QWidget * GetConfigWidget(QWidget *parent)
void PrintWarning(const std::string &message)
void PrintInfo(const std::string &message)
void SaveConfig(YAML::Emitter &emitter, const std::string &path)
void LoadConfig(const YAML::Node &node, const std::string &path)
virtual ~OdometryPlugin()