pose_plugin.h
Go to the documentation of this file.
1 
31 #ifndef MAPVIZ_PLUGINS_POSE_PLUGIN_H_
32 #define MAPVIZ_PLUGINS_POSE_PLUGIN_H_
33 
34 // Include mapviz_plugin.h first to ensure GL deps are included in the right order
35 #include <mapviz/mapviz_plugin.h>
36 
37 #include <mapviz/map_canvas.h>
39 
40 // C++ standard libraries
41 #include <list>
42 #include <string>
43 #include <vector>
44 
45 // QT libraries
46 #include <QGLWidget>
47 #include <QObject>
48 #include <QWidget>
49 
50 // ROS libraries
51 #include <ros/ros.h>
52 #include <tf/transform_datatypes.h>
53 #include <geometry_msgs/PoseStamped.h>
55 
56 // QT autogenerated files
57 #include "ui_pose_config.h"
58 
59 namespace mapviz_plugins
60 {
62  {
63  Q_OBJECT
64 
65  public:
66  PosePlugin();
67  virtual ~PosePlugin();
68 
69  bool Initialize(QGLWidget* canvas);
70  void Shutdown()
71  {
72  }
73 
74  void Draw(double x, double y, double scale);
75 
76  void LoadConfig(const YAML::Node& node, const std::string& path);
77  void SaveConfig(YAML::Emitter& emitter, const std::string& path);
78 
79  QWidget* GetConfigWidget(QWidget* parent);
80 
81  protected:
82  void PrintError(const std::string& message);
83  void PrintInfo(const std::string& message);
84  void PrintWarning(const std::string& message);
85 
86  protected Q_SLOTS:
87  void SelectTopic();
88  void TopicEdited();
89 
90  private:
91  Ui::pose_config ui_;
92  QWidget* config_widget_;
93 
94  std::string topic_;
95 
98 
99  void PoseCallback(const geometry_msgs::PoseStampedConstPtr& pose);
100  };
101 }
102 
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_
Definition: pose_plugin.h:96
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)


mapviz_plugins
Author(s): Marc Alban
autogenerated on Fri Mar 19 2021 02:44:32