#include <marble_plugin.h>

| Signals | |
| void | flyTo (GeoDataLookAt, FlyToMode) | 
| void | NewGPSPosition (qreal, qreal) | 
| void | ZoomIn (FlyToMode) | 
| void | ZoomOut (FlyToMode) | 
| Public Member Functions | |
| void | GpsCallbackCurrent (const sensor_msgs::NavSatFixConstPtr &gpspt) | 
| void | GpsCallbackMatched (const sensor_msgs::NavSatFixConstPtr &gpspt) | 
| virtual void | initPlugin (qt_gui_cpp::PluginContext &context) | 
| MarblePlugin () | |
| virtual void | restoreSettings (const qt_gui_cpp::Settings &plugin_settings, const qt_gui_cpp::Settings &instance_settings) | 
| virtual void | saveSettings (qt_gui_cpp::Settings &plugin_settings, qt_gui_cpp::Settings &instance_settings) const | 
| virtual void | shutdownPlugin () | 
| Private Slots | |
| void | ChangeGPSTopicCurrentGPS (const QString &topic_name) | 
| void | ChangeGPSTopicMatchedGPS (const QString &topic_name) | 
| void | ChangeMarbleModelTheme (int idx) | 
| void | FindNavSatFixTopics () | 
| void | gpsCoordinateSelected (qreal lon, qreal lat, GeoDataCoordinates::Unit unit) | 
| void | ManageKML () | 
| void | processMarkerCheckBoxCLicked () | 
| Private Member Functions | |
| void | addKMLData (std::map< QString, bool > &kml_files, bool overwrite) | 
| void | clearKMLData () | 
| void | mapcontrolCallback (const geometry_msgs::TwistConstPtr &msg) | 
| void | subscribeVisualization () | 
| Private Attributes | |
| ros::Subscriber | m_current_pos_subscriber | 
| std::map< QString, bool > | m_last_kml_data | 
| Marble::MapThemeManager | m_map_theme_manager | 
| ros::Subscriber | m_mapcontrol_subscriber | 
| ros::Subscriber | m_matched_pos_subscriber | 
| ros::Subscriber | m_reference_gps_subscriber | 
| ros::Publisher | m_selected_gps_pos_publisher | 
| ros::Subscriber | m_visualization_marker_array_subscriber | 
| ros::Subscriber | m_visualization_subscriber | 
| Ui_Form | ui_ | 
| QWidget * | widget_ | 
Definition at line 55 of file marble_plugin.h.
Definition at line 64 of file marble_plugin.cpp.
| void rqt_marble_plugin::MarblePlugin::addKMLData | ( | std::map< QString, bool > & | kml_files, | 
| bool | overwrite | ||
| ) |  [private] | 
Definition at line 160 of file marble_plugin.cpp.
| void rqt_marble_plugin::MarblePlugin::ChangeGPSTopicCurrentGPS | ( | const QString & | topic_name | ) |  [private, slot] | 
Definition at line 257 of file marble_plugin.cpp.
| void rqt_marble_plugin::MarblePlugin::ChangeGPSTopicMatchedGPS | ( | const QString & | topic_name | ) |  [private, slot] | 
Definition at line 270 of file marble_plugin.cpp.
| void rqt_marble_plugin::MarblePlugin::ChangeMarbleModelTheme | ( | int | idx | ) |  [private, slot] | 
Definition at line 248 of file marble_plugin.cpp.
| void rqt_marble_plugin::MarblePlugin::clearKMLData | ( | ) |  [private] | 
Definition at line 214 of file marble_plugin.cpp.
| void rqt_marble_plugin::MarblePlugin::FindNavSatFixTopics | ( | ) |  [private, slot] | 
Definition at line 225 of file marble_plugin.cpp.
| void rqt_marble_plugin::MarblePlugin::flyTo | ( | GeoDataLookAt | , | 
| FlyToMode | |||
| ) |  [signal] | 
| void rqt_marble_plugin::MarblePlugin::GpsCallbackCurrent | ( | const sensor_msgs::NavSatFixConstPtr & | gpspt | ) | 
Definition at line 314 of file marble_plugin.cpp.
| void rqt_marble_plugin::MarblePlugin::GpsCallbackMatched | ( | const sensor_msgs::NavSatFixConstPtr & | gpspt | ) | 
Definition at line 284 of file marble_plugin.cpp.
| void rqt_marble_plugin::MarblePlugin::gpsCoordinateSelected | ( | qreal | lon, | 
| qreal | lat, | ||
| GeoDataCoordinates::Unit | unit | ||
| ) |  [private, slot] | 
Definition at line 329 of file marble_plugin.cpp.
| void rqt_marble_plugin::MarblePlugin::initPlugin | ( | qt_gui_cpp::PluginContext & | context | ) |  [virtual] | 
Reimplemented from qt_gui_cpp::Plugin.
Definition at line 74 of file marble_plugin.cpp.
| void rqt_marble_plugin::MarblePlugin::ManageKML | ( | ) |  [private, slot] | 
Definition at line 150 of file marble_plugin.cpp.
| void rqt_marble_plugin::MarblePlugin::mapcontrolCallback | ( | const geometry_msgs::TwistConstPtr & | msg | ) |  [private] | 
Definition at line 181 of file marble_plugin.cpp.
| void rqt_marble_plugin::MarblePlugin::NewGPSPosition | ( | qreal | , | 
| qreal | |||
| ) |  [signal] | 
| void rqt_marble_plugin::MarblePlugin::processMarkerCheckBoxCLicked | ( | ) |  [private, slot] | 
Definition at line 342 of file marble_plugin.cpp.
| void rqt_marble_plugin::MarblePlugin::restoreSettings | ( | const qt_gui_cpp::Settings & | plugin_settings, | 
| const qt_gui_cpp::Settings & | instance_settings | ||
| ) |  [virtual] | 
Reimplemented from qt_gui_cpp::Plugin.
Definition at line 395 of file marble_plugin.cpp.
| void rqt_marble_plugin::MarblePlugin::saveSettings | ( | qt_gui_cpp::Settings & | plugin_settings, | 
| qt_gui_cpp::Settings & | instance_settings | ||
| ) | const  [virtual] | 
Reimplemented from qt_gui_cpp::Plugin.
Definition at line 363 of file marble_plugin.cpp.
| void rqt_marble_plugin::MarblePlugin::shutdownPlugin | ( | ) |  [virtual] | 
Reimplemented from rqt_gui_cpp::Plugin.
Definition at line 428 of file marble_plugin.cpp.
| void rqt_marble_plugin::MarblePlugin::subscribeVisualization | ( | ) |  [private] | 
Definition at line 356 of file marble_plugin.cpp.
| void rqt_marble_plugin::MarblePlugin::ZoomIn | ( | FlyToMode | ) |  [signal] | 
| void rqt_marble_plugin::MarblePlugin::ZoomOut | ( | FlyToMode | ) |  [signal] | 
Definition at line 117 of file marble_plugin.h.
| std::map< QString, bool> rqt_marble_plugin::MarblePlugin::m_last_kml_data  [private] | 
Definition at line 126 of file marble_plugin.h.
| Marble::MapThemeManager rqt_marble_plugin::MarblePlugin::m_map_theme_manager  [private] | 
Definition at line 115 of file marble_plugin.h.
Definition at line 124 of file marble_plugin.h.
Definition at line 118 of file marble_plugin.h.
Definition at line 121 of file marble_plugin.h.
Definition at line 122 of file marble_plugin.h.
Definition at line 120 of file marble_plugin.h.
Definition at line 119 of file marble_plugin.h.
| Ui_Form rqt_marble_plugin::MarblePlugin::ui_  [private] | 
Definition at line 111 of file marble_plugin.h.
| QWidget* rqt_marble_plugin::MarblePlugin::widget_  [private] | 
Definition at line 113 of file marble_plugin.h.