navsat_plugin.h
Go to the documentation of this file.
1 // *****************************************************************************
2 //
3 // Copyright (C) 2013 All Right Reserved, Southwest Research Institute® (SwRI®)
4 //
5 // Contract No. 10-58058A
6 // Contractor Southwest Research Institute® (SwRI®)
7 // Address 6220 Culebra Road, San Antonio, Texas 78228-0510
8 // Contact Steve Dellenback <sdellenback@swri.org> (210) 522-3914
9 //
10 // This code was developed as part of an internal research project fully funded
11 // by Southwest Research Institute®.
12 //
13 // THIS CODE AND INFORMATION ARE PROVIDED "AS IS" WITHOUT WARRANTY OF ANY
14 // KIND, EITHER EXPRESSED OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE
15 // IMPLIED WARRANTIES OF MERCHANTABILITY AND/OR FITNESS FOR A
16 // PARTICULAR PURPOSE.
17 //
18 // *****************************************************************************
19 
20 #ifndef MAPVIZ_PLUGINS_NAVSAT_PLUGIN_H_
21 #define MAPVIZ_PLUGINS_NAVSAT_PLUGIN_H_
22 
23 #include <mapviz/mapviz_plugin.h>
24 #include <mapviz/map_canvas.h>
26 // C++ standard libraries
27 #include <list>
28 #include <string>
29 #include <vector>
30 
31 // QT libraries
32 #include <QGLWidget>
33 #include <QObject>
34 #include <QWidget>
35 
36 // ROS libraries
37 #include <ros/ros.h>
38 #include <tf/transform_datatypes.h>
39 #include <sensor_msgs/NavSatFix.h>
41 
42 // QT autogenerated files
43 #include "ui_navsat_config.h"
44 
45 namespace mapviz_plugins
46 {
48  {
49  Q_OBJECT
50 
51  public:
52  NavSatPlugin();
53  virtual ~NavSatPlugin();
54 
55  bool Initialize(QGLWidget* canvas);
56  void Shutdown()
57  {
58  }
59 
60  void Draw(double x, double y, double scale);
61 
62  void LoadConfig(const YAML::Node& node, const std::string& path);
63  void SaveConfig(YAML::Emitter& emitter, const std::string& path);
64 
65  QWidget* GetConfigWidget(QWidget* parent);
66 
67  protected:
68  void PrintError(const std::string& message);
69  void PrintInfo(const std::string& message);
70  void PrintWarning(const std::string& message);
71 
72  protected Q_SLOTS:
73  void SelectTopic();
74  void TopicEdited();
75 
76  private:
77  Ui::navsat_config ui_;
78  QWidget* config_widget_;
79 
80  std::string topic_;
81 
84 
85  void NavSatFixCallback(const sensor_msgs::NavSatFixConstPtr navsat);
86  };
87 }
88 
89 #endif // MAPVIZ_PLUGINS_NAVSAT_PLUGIN_H_
void PrintInfo(const std::string &message)
QWidget * GetConfigWidget(QWidget *parent)
TFSIMD_FORCE_INLINE const tfScalar & y() const
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)


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