31 #ifndef MAPVIZ_PLUGINS_POSE_PLUGIN_H_ 32 #define MAPVIZ_PLUGINS_POSE_PLUGIN_H_ 53 #include <geometry_msgs/PoseStamped.h> 57 #include "ui_pose_config.h" 74 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);
99 void PoseCallback(
const geometry_msgs::PoseStampedConstPtr& pose);
103 #endif // MAPVIZ_PLUGINS_POSE_PLUGIN_H_
void PrintError(const std::string &message)
void PrintInfo(const std::string &message)
TFSIMD_FORCE_INLINE const tfScalar & y() const
void SaveConfig(YAML::Emitter &emitter, const std::string &path)
void Draw(double x, double y, double scale)
QWidget * GetConfigWidget(QWidget *parent)
TFSIMD_FORCE_INLINE const tfScalar & x() const
ros::Subscriber pose_sub_
void PoseCallback(const geometry_msgs::PoseStampedConstPtr &pose)
bool Initialize(QGLWidget *canvas)
void PrintWarning(const std::string &message)
void LoadConfig(const YAML::Node &node, const std::string &path)