navsat_plugin.h
Go to the documentation of this file.
00001 // *****************************************************************************
00002 //
00003 // Copyright (C) 2013 All Right Reserved, Southwest Research Institute® (SwRI®)
00004 //
00005 // Contract No.  10-58058A
00006 // Contractor    Southwest Research Institute® (SwRI®)
00007 // Address       6220 Culebra Road, San Antonio, Texas 78228-0510
00008 // Contact       Steve Dellenback <sdellenback@swri.org> (210) 522-3914
00009 //
00010 // This code was developed as part of an internal research project fully funded
00011 // by Southwest Research Institute®.
00012 //
00013 // THIS CODE AND INFORMATION ARE PROVIDED "AS IS" WITHOUT WARRANTY OF ANY
00014 // KIND, EITHER EXPRESSED OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE
00015 // IMPLIED WARRANTIES OF MERCHANTABILITY AND/OR FITNESS FOR A
00016 // PARTICULAR PURPOSE.
00017 //
00018 // *****************************************************************************
00019 
00020 #ifndef MAPVIZ_PLUGINS_NAVSAT_PLUGIN_H_
00021 #define MAPVIZ_PLUGINS_NAVSAT_PLUGIN_H_
00022 
00023 #include <mapviz/mapviz_plugin.h>
00024 #include <mapviz/map_canvas.h>
00025 #include <mapviz_plugins/point_drawing_plugin.h>
00026 // C++ standard libraries
00027 #include <list>
00028 #include <string>
00029 #include <vector>
00030 
00031 // QT libraries
00032 #include <QGLWidget>
00033 #include <QObject>
00034 #include <QWidget>
00035 
00036 // ROS libraries
00037 #include <ros/ros.h>
00038 #include <tf/transform_datatypes.h>
00039 #include <sensor_msgs/NavSatFix.h>
00040 #include <swri_transform_util/local_xy_util.h>
00041 
00042 // QT autogenerated files
00043 #include "ui_navsat_config.h"
00044 
00045 namespace mapviz_plugins
00046 {
00047   class NavSatPlugin : public mapviz_plugins::PointDrawingPlugin
00048   {
00049     Q_OBJECT
00050 
00051    public:
00052     NavSatPlugin();
00053     virtual ~NavSatPlugin();
00054 
00055     bool Initialize(QGLWidget* canvas);
00056     void Shutdown()
00057     {
00058     }
00059 
00060     void Draw(double x, double y, double scale);
00061 
00062     void LoadConfig(const YAML::Node& node, const std::string& path);
00063     void SaveConfig(YAML::Emitter& emitter, const std::string& path);
00064 
00065     QWidget* GetConfigWidget(QWidget* parent);
00066 
00067    protected:
00068     void PrintError(const std::string& message);
00069     void PrintInfo(const std::string& message);
00070     void PrintWarning(const std::string& message);
00071 
00072    protected Q_SLOTS:
00073     void SelectTopic();
00074     void TopicEdited();
00075 
00076    private:
00077     Ui::navsat_config ui_;
00078     QWidget* config_widget_;
00079 
00080     std::string topic_;
00081 
00082     ros::Subscriber navsat_sub_;
00083     bool has_message_;
00084 
00085     swri_transform_util::LocalXyWgs84Util local_xy_util_;
00086 
00087     void NavSatFixCallback(const sensor_msgs::NavSatFixConstPtr navsat);
00088   };
00089 }
00090 
00091 #endif  // MAPVIZ_PLUGINS_NAVSAT_PLUGIN_H_


mapviz_plugins
Author(s): Marc Alban
autogenerated on Thu Aug 24 2017 02:46:09