mapviz.h
Go to the documentation of this file.
00001 // *****************************************************************************
00002 //
00003 // Copyright (c) 2014, Southwest Research Institute® (SwRI®)
00004 // All rights reserved.
00005 //
00006 // Redistribution and use in source and binary forms, with or without
00007 // modification, are permitted provided that the following conditions are met:
00008 //     * Redistributions of source code must retain the above copyright
00009 //       notice, this list of conditions and the following disclaimer.
00010 //     * Redistributions in binary form must reproduce the above copyright
00011 //       notice, this list of conditions and the following disclaimer in the
00012 //       documentation and/or other materials provided with the distribution.
00013 //     * Neither the name of Southwest Research Institute® (SwRI®) nor the
00014 //       names of its contributors may be used to endorse or promote products
00015 //       derived from this software without specific prior written permission.
00016 //
00017 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00018 // AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00019 // IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00020 // ARE DISCLAIMED. IN NO EVENT SHALL <COPYRIGHT HOLDER> BE LIABLE FOR ANY
00021 // DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
00022 // (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00023 // LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
00024 // ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
00025 // (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
00026 // SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00027 //
00028 // *****************************************************************************
00029 
00030 #ifndef MAPVIZ_MAPVIZ_H_
00031 #define MAPVIZ_MAPVIZ_H_
00032 
00033 // C++ standard libraries
00034 #include <string>
00035 #include <vector>
00036 #include <map>
00037 
00038 #include <boost/shared_ptr.hpp>
00039 
00040 #include <GL/glew.h>
00041 
00042 // QT libraries
00043 #include <QtGui/QtGui>
00044 #include <QDialog>
00045 #include <QMenu>
00046 #include <QTimer>
00047 #include <QString>
00048 #include <QShowEvent>
00049 #include <QCloseEvent>
00050 #include <QListWidgetItem>
00051 #include <QModelIndex>
00052 #include <QColor>
00053 #include <QWidget>
00054 #include <QStringList>
00055 #include <QMainWindow>
00056 
00057 // ROS libraries
00058 #include <ros/ros.h>
00059 #include <pluginlib/class_loader.h>
00060 #include <tf/transform_listener.h>
00061 #include <yaml-cpp/yaml.h>
00062 #include <GL/glut.h>
00063 #include <std_srvs/Empty.h>
00064 
00065 // Auto-generated UI files
00066 #include "ui_mapviz.h"
00067 #include "ui_pluginselect.h"
00068 
00069 #include <swri_transform_util/transform_manager.h>
00070 #include <mapviz/AddMapvizDisplay.h>
00071 #include <mapviz/mapviz_plugin.h>
00072 #include <mapviz/map_canvas.h>
00073 #include <mapviz/video_writer.h>
00074 
00075 #include "stopwatch.h"
00076 
00077 namespace mapviz
00078 {
00079   class Mapviz : public QMainWindow
00080   {
00081     Q_OBJECT
00082 
00083   public:
00084     Mapviz(bool is_standalone, int argc, char** argv, QWidget *parent = 0, Qt::WFlags flags = 0);
00085     ~Mapviz();
00086 
00087     void Initialize();
00088 
00089   public Q_SLOTS:
00090     void AutoSave();
00091     void OpenConfig();
00092     void SaveConfig();
00093     void SelectNewDisplay();
00094     void RemoveDisplay();
00095     void ReorderDisplays();
00096     void FixedFrameSelected(const QString& text);
00097     void TargetFrameSelected(const QString& text);
00098     void ToggleUseLatestTransforms(bool on);
00099     void UpdateFrames();
00100     void SpinOnce();
00101     void UpdateSizeHints();
00102     void ToggleConfigPanel(bool on);
00103     void ToggleStatusBar(bool on);
00104     void ToggleCaptureTools(bool on);
00105     void ToggleFixOrientation(bool on);
00106     void ToggleRotate90(bool on);
00107     void ToggleEnableAntialiasing(bool on);
00108     void ToggleShowPlugin(QListWidgetItem* item, bool visible);
00109     void ToggleRecord(bool on);
00110     void SetImageTransport(QAction* transport_action);
00111     void UpdateImageTransportMenu();
00112     void CaptureVideoFrame();
00113     void StopRecord();
00114     void Screenshot();
00115     void Force720p(bool on);
00116     void Force480p(bool on);
00117     void SetResizable(bool on);
00118     void SelectBackgroundColor(const QColor &color);
00119     void SetCaptureDirectory();
00120     void Hover(double x, double y, double scale);
00121     void Recenter();
00122     void HandleProfileTimer();
00123 
00124   Q_SIGNALS:
00131     void FrameGrabbed(QImage);
00132     void ImageTransportChanged();
00133 
00134   protected:
00135     Ui::mapviz ui_;
00136 
00137     QMenu* image_transport_menu_;
00138 
00139     QTimer frame_timer_;
00140     QTimer spin_timer_;
00141     QTimer save_timer_;
00142     QTimer record_timer_;
00143     QTimer profile_timer_;
00144 
00145     QLabel* xy_pos_label_;
00146     QLabel* lat_lon_pos_label_;
00147     
00148     QWidget* spacer1_;
00149     QWidget* spacer2_;
00150     QWidget* spacer3_;
00151     QPushButton* recenter_button_;
00152     QPushButton* rec_button_;
00153     QPushButton* stop_button_;
00154     QPushButton* screenshot_button_;
00155 
00156     int    argc_;
00157     char** argv_;
00158 
00159     bool is_standalone_;
00160     bool initialized_;
00161     bool force_720p_;
00162     bool force_480p_;
00163     bool resizable_;
00164     QColor background_;
00165     
00166     std::string capture_directory_;
00167     QThread video_thread_;
00168     VideoWriter* vid_writer_;
00169     
00170     bool updating_frames_;
00171 
00172     ros::NodeHandle* node_;
00173     ros::ServiceServer add_display_srv_;
00174     boost::shared_ptr<tf::TransformListener> tf_;
00175     swri_transform_util::TransformManager tf_manager_;
00176 
00177     pluginlib::ClassLoader<MapvizPlugin>* loader_;
00178     MapCanvas* canvas_;
00179     std::map<QListWidgetItem*, MapvizPluginPtr> plugins_;
00180 
00181     Stopwatch meas_spin_;
00182 
00183     void Open(const std::string& filename);
00184     void Save(const std::string& filename);
00185 
00186     MapvizPluginPtr CreateNewDisplay(
00187         const std::string& name,
00188         const std::string& type,
00189         bool visible,
00190         bool collapsed,
00191         int draw_order = 0);
00192 
00193     bool AddDisplay(
00194       AddMapvizDisplay::Request& req, 
00195       AddMapvizDisplay::Response& resp);
00196 
00197     void ClearDisplays();
00198     void AdjustWindowSize();
00199 
00200     virtual void showEvent(QShowEvent* event);
00201     virtual void closeEvent(QCloseEvent* event);
00202 
00203     static const QString ROS_WORKSPACE_VAR;
00204     static const QString MAPVIZ_CONFIG_FILE;
00205     static const std::string IMAGE_TRANSPORT_PARAM;
00206   };
00207 }
00208 
00209 #endif  // MAPVIZ_MAPVIZ_H_


mapviz
Author(s): Marc Alban
autogenerated on Thu Aug 24 2017 02:45:59