pose_array_plugin.h
Go to the documentation of this file.
1 
31 #ifndef MAPVIZ_PLUGINS_POSE_ARRAY_PLUGIN_H_
32 #define MAPVIZ_PLUGINS_POSE_ARRAY_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 #include <mapviz/map_canvas.h>
39 
40 // QT libraries
41 #include <QGLWidget>
42 #include <QObject>
43 #include <QWidget>
44 
45 // ROS libraries
46 #include <ros/ros.h>
47 #include <tf/transform_datatypes.h>
48 #include <geometry_msgs/PoseArray.h>
49 #include <geometry_msgs/PoseStamped.h>
51 
52 
53 // QT autogenerated files
54 #include "ui_pose_array_config.h"
55 
56 namespace mapviz_plugins
57 {
59  {
60  Q_OBJECT
61 
62  public:
64  virtual ~PoseArrayPlugin();
65 
66  bool Initialize(QGLWidget* canvas);
67  void Shutdown()
68  {
69  }
70 
71  void Draw(double x, double y, double scale);
72 
73  void LoadConfig(const YAML::Node& node, const std::string& path);
74  void SaveConfig(YAML::Emitter& emitter, const std::string& path);
75 
76  QWidget* GetConfigWidget(QWidget* parent);
77 
78  protected:
79  void PrintError(const std::string& message);
80  void PrintInfo(const std::string& message);
81  void PrintWarning(const std::string& message);
82 
83  protected Q_SLOTS:
84  void SelectTopic();
85  void TopicEdited();
86 
87  private:
88  Ui::pose_array_config ui_;
89  QWidget* config_widget_;
90 
91  std::string topic_;
92 
95 
96  void PoseArrayCallback(const geometry_msgs::PoseArrayConstPtr& msg);
97  };
98 }
99 
100 #endif // MAPVIZ_PLUGINS_POSE_ARRAY_PLUGIN_H_
void LoadConfig(const YAML::Node &node, const std::string &path)
QWidget * GetConfigWidget(QWidget *parent)
bool Initialize(QGLWidget *canvas)
TFSIMD_FORCE_INLINE const tfScalar & y() const
void SaveConfig(YAML::Emitter &emitter, const std::string &path)
void Draw(double x, double y, double scale)
TFSIMD_FORCE_INLINE const tfScalar & x() const
void PrintInfo(const std::string &message)
void PoseArrayCallback(const geometry_msgs::PoseArrayConstPtr &msg)
void PrintWarning(const std::string &message)
void PrintError(const std::string &message)


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