marble_plugin.h
Go to the documentation of this file.
00001 // this is for emacs file handling -*- mode: c++; indent-tabs-mode: nil -*-
00002 
00003 /* -- BEGIN LICENSE BLOCK ----------------------------------------------
00004 
00005 Copyright (c) 2013, TB
00006 All rights reserved.
00007 
00008 Redistribution and use in source and binary forms are permitted
00009 provided that the above copyright notice and this paragraph are
00010 advertising materials, and other materials related to such
00011 distribution and use acknowledge that the software was developed
00012 by TB.  The name of the
00013 TB may not be used to endorse or promote products derived
00014 from this software without specific prior written permission.
00015 THIS SOFTWARE IS PROVIDED ``AS IS'' AND WITHOUT ANY EXPRESS OR
00016 IMPLIED WARRANTIES, INCLUDING, WITHOUT LIMITATION, THE IMPLIED
00017 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE.
00018 
00019   -- END LICENSE BLOCK ----------------------------------------------*/
00020 
00021 //----------------------------------------------------------------------
00029 //----------------------------------------------------------------------
00030 
00031 #ifndef _MARBLE_PLUGIN_H
00032 #define _MARBLE_PLUGIN_H
00033 
00034 // ROS Plugin Includes
00035 #include <rqt_gui_cpp/plugin.h>
00036 #include <ros/ros.h>
00037 
00038 // Message Includes
00039 #include <sensor_msgs/NavSatFix.h>
00040 #include <geometry_msgs/Twist.h>
00041 
00042 // Qt Includes
00043 #include <QtCore/QObject>
00044 #include <QMutex>
00045 
00046 #include <marble/MapThemeManager.h>
00047 
00048 // Own Includes
00049 #include <ui_marble_plugin.h>
00050 #include "drawable_marble_widget.h"
00051 #include "manage_kml_dialog.h"
00052 
00053 namespace rqt_marble_plugin {
00054 
00055 class MarblePlugin
00056   : public rqt_gui_cpp::Plugin
00057 {
00058 
00059 
00060   Q_OBJECT
00061 
00062 
00063 public:
00064 
00065 
00066   MarblePlugin();
00067   virtual void initPlugin(qt_gui_cpp::PluginContext& context);
00068   virtual void shutdownPlugin();
00069   virtual void saveSettings(qt_gui_cpp::Settings& plugin_settings, qt_gui_cpp::Settings& instance_settings) const;
00070   virtual void restoreSettings(const qt_gui_cpp::Settings& plugin_settings, const qt_gui_cpp::Settings& instance_settings);
00071 
00072   // Comment in to signal that the plugin has a way to configure it
00073   //bool hasConfiguration() const;
00074   //void triggerConfiguration();
00075 
00076   void GpsCallbackCurrent( const sensor_msgs::NavSatFixConstPtr& gpspt );
00077   void GpsCallbackMatched( const sensor_msgs::NavSatFixConstPtr& gpspt );
00078 
00079 
00080 private slots:
00081   void gpsCoordinateSelected(qreal lon, qreal lat, GeoDataCoordinates::Unit unit);
00082   void processMarkerCheckBoxCLicked();
00083 
00084 private:
00085 
00086 Q_SIGNALS:
00087 
00088   void NewGPSPosition(qreal,qreal);
00089 
00090   void ZoomIn(FlyToMode);
00091   void ZoomOut(FlyToMode);
00092   void flyTo(GeoDataLookAt, FlyToMode);
00093 
00094   private Q_SLOTS:
00095 
00096   void ChangeGPSTopicCurrentGPS(const QString &topic_name);
00097   void ChangeGPSTopicMatchedGPS(const QString &topic_name);
00098 
00099   void ChangeMarbleModelTheme(int idx );
00100   void FindNavSatFixTopics();
00101 
00102   void ManageKML();
00103 
00104   private:
00105 
00106   void subscribeVisualization();
00107   void clearKMLData();
00108   void addKMLData(std::map<QString, bool>& kml_files, bool overwrite);
00109   void mapcontrolCallback(const geometry_msgs::TwistConstPtr &msg);
00110 
00111   Ui_Form ui_;
00112 
00113   QWidget* widget_;
00114 
00115   Marble::MapThemeManager m_map_theme_manager;
00116 
00117   ros::Subscriber m_current_pos_subscriber;
00118   ros::Subscriber m_matched_pos_subscriber;
00119   ros::Subscriber m_visualization_subscriber;
00120   ros::Subscriber m_visualization_marker_array_subscriber;
00121   ros::Subscriber m_reference_gps_subscriber;
00122   ros::Publisher m_selected_gps_pos_publisher;
00123 
00124   ros::Subscriber m_mapcontrol_subscriber;
00125 
00126   std::map< QString, bool> m_last_kml_data;
00127 
00128 };
00129 } // namespace
00130 #endif // _MARBLE_PLUGIN_H
00131 


marble_plugin
Author(s): Tobias Bär
autogenerated on Mon Oct 6 2014 02:13:12