configuration_files_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_ROS_MOVEIT_SETUP_ASSISTANT_WIDGETS_CONFIGURATION_FILES_WIDGET_
00038 #define MOVEIT_ROS_MOVEIT_SETUP_ASSISTANT_WIDGETS_CONFIGURATION_FILES_WIDGET_
00039 
00040 #include <QWidget>
00041 #include <QPushButton>
00042 #include <QString>
00043 #include <QProgressBar>
00044 #include <QLabel>
00045 #include <QListWidget>
00046 #include <QList>
00047 
00048 #ifndef Q_MOC_RUN
00049 #include <moveit/setup_assistant/tools/moveit_config_data.h>
00050 #endif
00051 
00052 #include "header_widget.h"
00053 #include "setup_screen_widget.h" // a base class for screens in the setup assistant
00054 
00055 namespace moveit_setup_assistant
00056 {
00057 
00058 // Struct for storing all the file operations
00059 struct GenerateFile
00060 {
00061   GenerateFile() :
00062     generate_(true)
00063   {}
00064   std::string file_name_;
00065   std::string rel_path_;
00066   std::string description_;
00067   bool generate_;
00068   boost::function<bool(std::string)> gen_func_;
00069 };
00070 
00071 // Typedef for storing template string replacement pairs
00072 typedef std::vector< std::pair<std::string, std::string> > StringPairVector;
00073 
00074 // Class
00075 class ConfigurationFilesWidget : public SetupScreenWidget
00076 {
00077   Q_OBJECT
00078 
00079   public:
00080   // ******************************************************************************************
00081   // Public Functions
00082   // ******************************************************************************************
00083 
00084   ConfigurationFilesWidget( QWidget *parent, moveit_setup_assistant::MoveItConfigDataPtr config_data );
00085 
00087   virtual void focusGiven();
00088 
00089   // ******************************************************************************************
00090   // Qt Components
00091   // ******************************************************************************************
00092   QPushButton *btn_save_;
00093   LoadPathWidget *stack_path_;
00094   QProgressBar *progress_bar_;
00095   QListWidget *action_list_;
00096   QLabel *action_label_;
00097   QLabel *success_label_;
00098   QList<QString> action_desc_; // Holds the descriptions explaining all performed actions
00099 
00100 private Q_SLOTS:
00101 
00102   // ******************************************************************************************
00103   // Slot Event Functions
00104   // ******************************************************************************************
00105 
00107   void savePackage();
00108 
00110   bool generatePackage();
00111 
00113   void exitSetupAssistant();
00114 
00116   void changeActionDesc(int id);
00117 
00119   void changeCheckedState(QListWidgetItem* item);
00120 
00121 private:
00122 
00123 
00124   // ******************************************************************************************
00125   // Variables
00126   // ******************************************************************************************
00127 
00129   moveit_setup_assistant::MoveItConfigDataPtr config_data_;
00130 
00132   std::string new_package_name_;
00133 
00135   unsigned int action_num_;
00136 
00138   bool has_generated_pkg_;
00139 
00141   bool first_focusGiven_;
00142 
00144   std::vector<GenerateFile> gen_files_;
00145 
00147   StringPairVector template_strings_;
00148 
00149   // ******************************************************************************************
00150   // Private Functions
00151   // ******************************************************************************************
00152 
00154   bool loadGenFiles();
00155 
00158   bool checkGenFiles();
00159 
00161   void showGenFiles();
00162 
00164   bool checkDependencies();
00165 
00167   void updateProgress();
00168 
00170   const std::string getPackageName( std::string package_path );
00171 
00173   bool noGroupsEmpty();
00174 
00179   void loadTemplateStrings();
00180 
00187   bool addTemplateString( const std::string& key, const std::string& value );
00188 
00198   bool copyTemplate(const std::string& template_path, const std::string& output_path );
00199 
00205   bool createFolder(const std::string& output_path);
00206 
00207 };
00208 
00209 } //namespace moveit_setup_assistant
00210 
00211 #endif


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