start_screen_widget.h
Go to the documentation of this file.
00001 /*********************************************************************
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2012, Willow Garage, Inc.
00005  *  All rights reserved.
00006  *
00007  *  Redistribution and use in source and binary forms, with or without
00008  *  modification, are permitted provided that the following conditions
00009  *  are met:
00010  *
00011  *   * Redistributions of source code must retain the above copyright
00012  *     notice, this list of conditions and the following disclaimer.
00013  *   * Redistributions in binary form must reproduce the above
00014  *     copyright notice, this list of conditions and the following
00015  *     disclaimer in the documentation and/or other materials provided
00016  *     with the distribution.
00017  *   * Neither the name of the Willow Garage nor the names of its
00018  *     contributors may be used to endorse or promote products derived
00019  *     from this software without specific prior written permission.
00020  *
00021  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032  *  POSSIBILITY OF SUCH DAMAGE.
00033  *********************************************************************/
00034 
00035 /* Author: Dave Coleman */
00036 
00037 #ifndef MOVEIT_MOVEIT_SETUP_ASSISTANT_WIDGETS_START_SCREEN_WIDGET_
00038 #define MOVEIT_MOVEIT_SETUP_ASSISTANT_WIDGETS_START_SCREEN_WIDGET_
00039 
00040 #include <QWidget>
00041 #include <QLineEdit>
00042 #include <QPushButton>
00043 #include <QLabel>
00044 #include <QProgressBar>
00045 
00046 #ifndef Q_MOC_RUN
00047 #include <urdf/model.h> // for testing a valid urdf is loaded
00048 #include <srdfdom/model.h> // for testing a valid srdf is loaded
00049 #include <moveit/setup_assistant/tools/moveit_config_data.h> // common datastructure class
00050 #endif
00051 
00052 #include "setup_screen_widget.h" // a base class for screens in the setup assistant
00053 
00054 
00055 namespace moveit_setup_assistant
00056 {
00057 
00058 
00059 // Class Prototypes
00060 class SelectModeWidget;
00061 class LoadPathWidget;
00062 //class LoadURDFWidget;
00063 
00067 class StartScreenWidget : public SetupScreenWidget
00068 {
00069   Q_OBJECT
00070 
00071   public:
00072   // ******************************************************************************************
00073   // Public Functions
00074   // ******************************************************************************************
00075 
00079   StartScreenWidget( QWidget* parent, moveit_setup_assistant::MoveItConfigDataPtr config_data );
00080 
00081   ~StartScreenWidget();
00082 
00083 
00084   // ******************************************************************************************
00085   // Qt Components
00086   // ******************************************************************************************
00087   SelectModeWidget *select_mode_;
00088   LoadPathWidget *stack_path_;
00089   LoadPathWidget *urdf_file_;
00090   //LoadPathWidget *srdf_file_;
00091   QPushButton *btn_load_;
00092   QLabel *next_label_;
00093   QProgressBar *progress_bar_;
00094   QImage *right_image_;
00095   QLabel *right_image_label_;
00096   QImage *logo_image_;
00097   QLabel *logo_image_label_;
00098 
00100   moveit_setup_assistant::MoveItConfigDataPtr config_data_;
00101 
00102 private Q_SLOTS:
00103 
00104   // ******************************************************************************************
00105   // Slot Event Functions
00106   // ******************************************************************************************
00107 
00109   void showNewOptions();
00110 
00112   void showExistingOptions();
00113 
00115   void loadFilesClick();
00116 
00117 Q_SIGNALS:
00118 
00119   // ******************************************************************************************
00120   // Emitted Signal Functions
00121   // ******************************************************************************************
00122 
00124   void readyToProgress();
00125 
00127   void loadRviz();
00128 
00129 private:
00130 
00131 
00132   // ******************************************************************************************
00133   // Variables
00134   // ******************************************************************************************
00135 
00137   bool create_new_package_;
00138 
00139   // ******************************************************************************************
00140   // Private Functions
00141   // ******************************************************************************************
00142 
00144   bool loadNewFiles();
00145 
00147   bool loadExistingFiles();
00148 
00150   bool loadURDFFile( const std::string& urdf_file_path );
00151 
00153   bool loadSRDFFile( const std::string& srdf_file_path );
00154 
00156   bool setSRDFFile( const std::string& srdf_string );
00157 
00159   bool extractPackageNameFromPath();
00160 
00162   bool createFullURDFPath();
00163 
00165   bool createFullSRDFPath( const std::string& package_path );
00166 
00168   bool createFullPackagePath();
00169 };
00170 
00171 // ******************************************************************************************
00172 // ******************************************************************************************
00173 // Class for selecting which mode
00174 // ******************************************************************************************
00175 // ******************************************************************************************
00176 
00177 class SelectModeWidget : public QFrame
00178 {
00179   Q_OBJECT
00180 
00181   private:
00182 
00183     private Q_SLOTS:
00184 
00185   public:
00186 
00187   SelectModeWidget( QWidget * parent );
00188 
00189   // Load file button
00190   QPushButton *btn_new_;
00191   QPushButton *btn_exist_;
00192 
00193 };
00194 
00195 }
00196 
00197 #endif


moveit_setup_assistant
Author(s): Dave Coleman
autogenerated on Mon Oct 6 2014 02:32:27