configuration_files_widget.cpp
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 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 // Qt
00038 #include <QVBoxLayout>
00039 #include <QPushButton>
00040 #include <QMessageBox>
00041 #include <QApplication>
00042 #include <QSplitter>
00043 #include <QRegExp>
00044 // ROS
00045 #include "configuration_files_widget.h"
00046 #include <srdfdom/model.h>  // use their struct datastructures
00047 #include <ros/ros.h>
00048 // Boost
00049 #include <boost/algorithm/string.hpp>  // for trimming whitespace from user input
00050 #include <boost/filesystem.hpp>        // for creating folders/files
00051 // Read write files
00052 #include <iostream>  // For writing yaml and launch files
00053 #include <fstream>
00054 
00055 namespace moveit_setup_assistant
00056 {
00057 // Boost file system
00058 namespace fs = boost::filesystem;
00059 
00060 const std::string SETUP_ASSISTANT_FILE = ".setup_assistant";
00061 
00062 // ******************************************************************************************
00063 // Outer User Interface for MoveIt Configuration Assistant
00064 // ******************************************************************************************
00065 ConfigurationFilesWidget::ConfigurationFilesWidget(QWidget* parent,
00066                                                    moveit_setup_assistant::MoveItConfigDataPtr config_data)
00067   : SetupScreenWidget(parent), config_data_(config_data), has_generated_pkg_(false), first_focusGiven_(true)
00068 {
00069   // Basic widget container
00070   QVBoxLayout* layout = new QVBoxLayout();
00071 
00072   // Top Header Area ------------------------------------------------
00073 
00074   HeaderWidget* header =
00075       new HeaderWidget("Generate Configuration Files",
00076                        "Create or update the configuration files package needed to run your robot with MoveIt. Uncheck "
00077                        "files to disable them from being generated - this is useful if you have made custom changes to "
00078                        "them. Files in orange have been automatically detected as changed.",
00079                        this);
00080   layout->addWidget(header);
00081 
00082   // Path Widget ----------------------------------------------------
00083 
00084   // Stack Path Dialog
00085   stack_path_ = new LoadPathWidget("Configuration Package Save Path",
00086                                    "Specify the desired directory for the MoveIt configuration package to be "
00087                                    "generated. Overwriting an existing configuration package directory is acceptable. "
00088                                    "Example: <i>/u/robot/ros/pr2_moveit_config</i>",
00089                                    true, this);  // is directory
00090   layout->addWidget(stack_path_);
00091 
00092   // Pass the package path from start screen to configuration files screen
00093   stack_path_->setPath(config_data_->config_pkg_path_);
00094 
00095   // Generated Files List -------------------------------------------
00096   QLabel* generated_list = new QLabel("Files to be generated: (checked)", this);
00097   layout->addWidget(generated_list);
00098 
00099   QSplitter* splitter = new QSplitter(Qt::Horizontal, this);
00100   splitter->setSizePolicy(QSizePolicy::Expanding, QSizePolicy::Expanding);
00101 
00102   // List Box
00103   action_list_ = new QListWidget(this);
00104   action_list_->setSizePolicy(QSizePolicy::Expanding, QSizePolicy::Expanding);
00105   connect(action_list_, SIGNAL(currentRowChanged(int)), this, SLOT(changeActionDesc(int)));
00106 
00107   // Description
00108   action_label_ = new QLabel(this);
00109   action_label_->setFrameShape(QFrame::StyledPanel);
00110   action_label_->setFrameShadow(QFrame::Raised);
00111   action_label_->setLineWidth(1);
00112   action_label_->setMidLineWidth(0);
00113   action_label_->setWordWrap(true);
00114   action_label_->setSizePolicy(QSizePolicy::Preferred, QSizePolicy::Expanding);
00115   action_label_->setMinimumWidth(100);
00116   action_label_->setAlignment(Qt::AlignTop);
00117   action_label_->setOpenExternalLinks(true);  // open with web browser
00118 
00119   // Add to splitter
00120   splitter->addWidget(action_list_);
00121   splitter->addWidget(action_label_);
00122 
00123   // Add Layout
00124   layout->addWidget(splitter);
00125 
00126   // Progress bar and generate buttons ---------------------------------------------------
00127   QHBoxLayout* hlayout1 = new QHBoxLayout();
00128 
00129   // Progress Bar
00130   progress_bar_ = new QProgressBar(this);
00131   progress_bar_->setMaximum(100);
00132   progress_bar_->setMinimum(0);
00133   hlayout1->addWidget(progress_bar_);
00134   // hlayout1->setContentsMargins( 20, 30, 20, 30 );
00135 
00136   // Generate Package Button
00137   btn_save_ = new QPushButton("&Generate Package", this);
00138   // btn_save_->setMinimumWidth(180);
00139   btn_save_->setMinimumHeight(40);
00140   connect(btn_save_, SIGNAL(clicked()), this, SLOT(savePackage()));
00141   hlayout1->addWidget(btn_save_);
00142 
00143   // Add Layout
00144   layout->addLayout(hlayout1);
00145 
00146   // Bottom row --------------------------------------------------
00147 
00148   QHBoxLayout* hlayout3 = new QHBoxLayout();
00149 
00150   // Success label
00151   success_label_ = new QLabel(this);
00152   QFont success_label_font("Arial", 12, QFont::Bold);
00153   success_label_->setFont(success_label_font);
00154   success_label_->hide();  // only show once the files have been generated
00155   success_label_->setText("Configuration package generated successfully!");
00156   hlayout3->addWidget(success_label_);
00157   hlayout3->setAlignment(success_label_, Qt::AlignRight);
00158 
00159   // Exit button
00160   QPushButton* btn_exit = new QPushButton("E&xit Setup Assistant", this);
00161   btn_exit->setMinimumWidth(180);
00162   connect(btn_exit, SIGNAL(clicked()), this, SLOT(exitSetupAssistant()));
00163   hlayout3->addWidget(btn_exit);
00164   hlayout3->setAlignment(btn_exit, Qt::AlignRight);
00165 
00166   layout->addLayout(hlayout3);
00167 
00168   // Finish Layout --------------------------------------------------
00169   this->setLayout(layout);
00170 }
00171 
00172 // ******************************************************************************************
00173 // Populate the 'Files to be generated' list
00174 // ******************************************************************************************
00175 bool ConfigurationFilesWidget::loadGenFiles()
00176 {
00177   GenerateFile file;          // re-used
00178   std::string template_path;  // re-used
00179   const std::string robot_name = config_data_->srdf_->robot_name_;
00180 
00181   gen_files_.clear();  // reset vector
00182 
00183   // Get template package location ----------------------------------------------------------------------
00184   fs::path template_package_path = config_data_->setup_assistant_path_;
00185   template_package_path /= "templates";
00186   template_package_path /= "moveit_config_pkg_template";
00187   config_data_->template_package_path_ = template_package_path.make_preferred().native().c_str();
00188 
00189   if (!fs::is_directory(config_data_->template_package_path_))
00190   {
00191     QMessageBox::critical(
00192         this, "Error Generating",
00193         QString("Unable to find package template directory: ").append(config_data_->template_package_path_.c_str()));
00194     return false;
00195   }
00196 
00197   // -------------------------------------------------------------------------------------------------------------------
00198   // ROS PACKAGE FILES AND FOLDERS ----------------------------------------------------------------------------
00199   // -------------------------------------------------------------------------------------------------------------------
00200 
00201   // package.xml --------------------------------------------------------------------------------------
00202   // Note: we call the file package.xml.template so that it isn't automatically indexed by rosprofile
00203   // in the scenario where we want to disabled the setup_assistant by renaming its root package.xml
00204   file.file_name_ = "package.xml";
00205   file.rel_path_ = file.file_name_;
00206   template_path = config_data_->appendPaths(config_data_->template_package_path_, "package.xml.template");
00207   file.description_ = "Defines a ROS package";
00208   file.gen_func_ = boost::bind(&ConfigurationFilesWidget::copyTemplate, this, template_path, _1);
00209   file.write_on_changes = MoveItConfigData::AUTHOR_INFO;
00210   gen_files_.push_back(file);
00211 
00212   // CMakeLists.txt --------------------------------------------------------------------------------------
00213   file.file_name_ = "CMakeLists.txt";
00214   file.rel_path_ = file.file_name_;
00215   template_path = config_data_->appendPaths(config_data_->template_package_path_, file.file_name_);
00216   file.description_ = "CMake build system configuration file";
00217   file.gen_func_ = boost::bind(&ConfigurationFilesWidget::copyTemplate, this, template_path, _1);
00218   file.write_on_changes = 0;
00219   gen_files_.push_back(file);
00220 
00221   // -------------------------------------------------------------------------------------------------------------------
00222   // CONIG FILES -------------------------------------------------------------------------------------------------------
00223   // -------------------------------------------------------------------------------------------------------------------
00224   std::string config_path = "config";
00225 
00226   // config/ --------------------------------------------------------------------------------------
00227   file.file_name_ = "config/";
00228   file.rel_path_ = file.file_name_;
00229   file.description_ = "Folder containing all MoveIt configuration files for your robot. This folder is required and "
00230                       "cannot be disabled.";
00231   file.gen_func_ = boost::bind(&ConfigurationFilesWidget::createFolder, this, _1);
00232   file.write_on_changes = 0;
00233   gen_files_.push_back(file);
00234 
00235   // robot.srdf ----------------------------------------------------------------------------------------------
00236   file.file_name_ = config_data_->srdf_pkg_relative_path_.empty() ? config_data_->urdf_model_->getName() + ".srdf" :
00237                                                                     config_data_->srdf_pkg_relative_path_;
00238   file.rel_path_ = config_data_->srdf_pkg_relative_path_.empty() ?
00239                        config_data_->appendPaths(config_path, file.file_name_) :
00240                        config_data_->srdf_pkg_relative_path_;
00241   file.description_ = "SRDF (<a href='http://www.ros.org/wiki/srdf'>Semantic Robot Description Format</a>) is a "
00242                       "representation of semantic information about robots. This format is intended to represent "
00243                       "information about the robot that is not in the URDF file, but it is useful for a variety of "
00244                       "applications. The intention is to include information that has a semantic aspect to it.";
00245   file.gen_func_ = boost::bind(&srdf::SRDFWriter::writeSRDF, config_data_->srdf_, _1);
00246   file.write_on_changes = MoveItConfigData::SRDF;
00247   gen_files_.push_back(file);
00248   // special step required so the generated .setup_assistant yaml has this value
00249   config_data_->srdf_pkg_relative_path_ = file.rel_path_;
00250 
00251   // ompl_planning.yaml --------------------------------------------------------------------------------------
00252   file.file_name_ = "ompl_planning.yaml";
00253   file.rel_path_ = config_data_->appendPaths(config_path, file.file_name_);
00254   file.description_ = "Configures the OMPL (<a href='http://ompl.kavrakilab.org/'>Open Motion Planning Library</a>) "
00255                       "planning plugin. For every planning group defined in the SRDF, a number of planning "
00256                       "configurations are specified (under planner_configs). Additionally, default settings for the "
00257                       "state space to plan in for a particular group can be specified, such as the collision checking "
00258                       "resolution. Each planning configuration specified for a group must be defined under the "
00259                       "planner_configs tag. While defining a planner configuration, the only mandatory parameter is "
00260                       "'type', which is the name of the motion planner to be used. Any other planner-specific "
00261                       "parameters can be defined but are optional.";
00262   file.gen_func_ = boost::bind(&MoveItConfigData::outputOMPLPlanningYAML, config_data_, _1);
00263   file.write_on_changes = MoveItConfigData::GROUPS;
00264   gen_files_.push_back(file);
00265 
00266   // kinematics.yaml  --------------------------------------------------------------------------------------
00267   file.file_name_ = "kinematics.yaml";
00268   file.rel_path_ = config_data_->appendPaths(config_path, file.file_name_);
00269   file.description_ = "Specifies which kinematic solver plugin to use for each planning group in the SRDF, as well as "
00270                       "the kinematic solver search resolution.";
00271   file.gen_func_ = boost::bind(&MoveItConfigData::outputKinematicsYAML, config_data_, _1);
00272   file.write_on_changes = MoveItConfigData::GROUPS | MoveItConfigData::GROUP_KINEMATICS;
00273   gen_files_.push_back(file);
00274 
00275   // joint_limits.yaml --------------------------------------------------------------------------------------
00276   file.file_name_ = "joint_limits.yaml";
00277   file.rel_path_ = config_data_->appendPaths(config_path, file.file_name_);
00278   file.description_ = "Contains additional information about joints that appear in your planning groups that is not "
00279                       "contained in the URDF, as well as allowing you to set maximum and minimum limits for velocity "
00280                       "and acceleration than those contained in your URDF. This information is used by our trajectory "
00281                       "filtering system to assign reasonable velocities and timing for the trajectory before it is "
00282                       "passed to the robots controllers.";
00283   file.gen_func_ = boost::bind(&MoveItConfigData::outputJointLimitsYAML, config_data_, _1);
00284   file.write_on_changes = 0;  // Can they be changed?
00285   gen_files_.push_back(file);
00286 
00287   // fake_controllers.yaml --------------------------------------------------------------------------------------
00288   file.file_name_ = "fake_controllers.yaml";
00289   file.rel_path_ = config_data_->appendPaths(config_path, file.file_name_);
00290   file.description_ = "Creates dummy configurations for controllers that correspond to defined groups. This is mostly "
00291                       "useful for testing.";
00292   file.gen_func_ = boost::bind(&MoveItConfigData::outputFakeControllersYAML, config_data_, _1);
00293   file.write_on_changes = MoveItConfigData::GROUPS;
00294   gen_files_.push_back(file);
00295 
00296   // -------------------------------------------------------------------------------------------------------------------
00297   // LAUNCH FILES ------------------------------------------------------------------------------------------------------
00298   // -------------------------------------------------------------------------------------------------------------------
00299   std::string launch_path = "launch";
00300   const std::string template_launch_path = config_data_->appendPaths(config_data_->template_package_path_, launch_path);
00301 
00302   // launch/ --------------------------------------------------------------------------------------
00303   file.file_name_ = "launch/";
00304   file.rel_path_ = file.file_name_;
00305   file.description_ = "Folder containing all MoveIt launch files for your robot. This folder is required and cannot be "
00306                       "disabled.";
00307   file.gen_func_ = boost::bind(&ConfigurationFilesWidget::createFolder, this, _1);
00308   file.write_on_changes = 0;
00309   gen_files_.push_back(file);
00310 
00311   // move_group.launch --------------------------------------------------------------------------------------
00312   file.file_name_ = "move_group.launch";
00313   file.rel_path_ = config_data_->appendPaths(launch_path, file.file_name_);
00314   template_path = config_data_->appendPaths(template_launch_path, file.file_name_);
00315   file.description_ = "Launches the move_group node that provides the MoveGroup action and other parameters <a "
00316                       "href='http://moveit.ros.org/doxygen/"
00317                       "classmoveit_1_1planning__interface_1_1MoveGroup.html#details'>MoveGroup action</a>";
00318   file.gen_func_ = boost::bind(&ConfigurationFilesWidget::copyTemplate, this, template_path, _1);
00319   file.write_on_changes = 0;
00320   gen_files_.push_back(file);
00321 
00322   // planning_context.launch --------------------------------------------------------------------------------------
00323   file.file_name_ = "planning_context.launch";
00324   file.rel_path_ = config_data_->appendPaths(launch_path, file.file_name_);
00325   template_path = config_data_->appendPaths(template_launch_path, file.file_name_);
00326   file.description_ = "Loads settings for the ROS parameter server, required for running MoveIt. This includes the "
00327                       "SRDF, joints_limits.yaml file, ompl_planning.yaml file, optionally the URDF, etc";
00328   file.gen_func_ = boost::bind(&ConfigurationFilesWidget::copyTemplate, this, template_path, _1);
00329   file.write_on_changes = 0;
00330   gen_files_.push_back(file);
00331 
00332   // moveit_rviz.launch --------------------------------------------------------------------------------------
00333   file.file_name_ = "moveit_rviz.launch";
00334   file.rel_path_ = config_data_->appendPaths(launch_path, file.file_name_);
00335   template_path = config_data_->appendPaths(template_launch_path, file.file_name_);
00336   file.description_ = "Visualize in Rviz the robot's planning groups running with interactive markers that allow goal "
00337                       "states to be set.";
00338   file.gen_func_ = boost::bind(&ConfigurationFilesWidget::copyTemplate, this, template_path, _1);
00339   file.write_on_changes = 0;
00340   gen_files_.push_back(file);
00341 
00342   // ompl_planning_pipeline.launch
00343   // --------------------------------------------------------------------------------------
00344   file.file_name_ = "ompl_planning_pipeline.launch.xml";
00345   file.rel_path_ = config_data_->appendPaths(launch_path, file.file_name_);
00346   template_path = config_data_->appendPaths(template_launch_path, file.file_name_);
00347   file.description_ = "Intended to be included in other launch files that require the OMPL planning plugin. Defines "
00348                       "the proper plugin name on the parameter server and a default selection of planning request "
00349                       "adapters.";
00350   file.gen_func_ = boost::bind(&ConfigurationFilesWidget::copyTemplate, this, template_path, _1);
00351   file.write_on_changes = 0;
00352   gen_files_.push_back(file);
00353 
00354   // planning_pipeline.launch --------------------------------------------------------------------------------------
00355   file.file_name_ = "planning_pipeline.launch.xml";
00356   file.rel_path_ = config_data_->appendPaths(launch_path, file.file_name_);
00357   template_path = config_data_->appendPaths(template_launch_path, file.file_name_);
00358   file.description_ = "Helper launch file that can choose between different planning pipelines to be loaded.";
00359   file.gen_func_ = boost::bind(&ConfigurationFilesWidget::copyTemplate, this, template_path, _1);
00360   file.write_on_changes = 0;
00361   gen_files_.push_back(file);
00362 
00363   // warehouse_settings.launch --------------------------------------------------------------------------------------
00364   file.file_name_ = "warehouse_settings.launch.xml";
00365   file.rel_path_ = config_data_->appendPaths(launch_path, file.file_name_);
00366   template_path = config_data_->appendPaths(template_launch_path, file.file_name_);
00367   file.description_ = "Helper launch file that specifies default settings for MongoDB.";
00368   file.gen_func_ = boost::bind(&ConfigurationFilesWidget::copyTemplate, this, template_path, _1);
00369   file.write_on_changes = 0;
00370   gen_files_.push_back(file);
00371 
00372   // warehouse.launch --------------------------------------------------------------------------------------
00373   file.file_name_ = "warehouse.launch";
00374   file.rel_path_ = config_data_->appendPaths(launch_path, file.file_name_);
00375   template_path = config_data_->appendPaths(template_launch_path, file.file_name_);
00376   file.description_ = "Launch file for starting MongoDB.";
00377   file.gen_func_ = boost::bind(&ConfigurationFilesWidget::copyTemplate, this, template_path, _1);
00378   file.write_on_changes = 0;
00379   gen_files_.push_back(file);
00380 
00381   // default_warehouse_db.launch --------------------------------------------------------------------------------------
00382   file.file_name_ = "default_warehouse_db.launch";
00383   file.rel_path_ = config_data_->appendPaths(launch_path, file.file_name_);
00384   template_path = config_data_->appendPaths(template_launch_path, file.file_name_);
00385   file.description_ = "Launch file for starting the warehouse with a default MongoDB.";
00386   file.gen_func_ = boost::bind(&ConfigurationFilesWidget::copyTemplate, this, template_path, _1);
00387   file.write_on_changes = 0;
00388   gen_files_.push_back(file);
00389 
00390   // run_benchmark_ompl.launch --------------------------------------------------------------------------------------
00391   file.file_name_ = "run_benchmark_ompl.launch";
00392   file.rel_path_ = config_data_->appendPaths(launch_path, file.file_name_);
00393   template_path = config_data_->appendPaths(template_launch_path, file.file_name_);
00394   file.description_ = "Launch file for benchmarking OMPL planners";
00395   file.gen_func_ = boost::bind(&ConfigurationFilesWidget::copyTemplate, this, template_path, _1);
00396   file.write_on_changes = 0;
00397   gen_files_.push_back(file);
00398 
00399   // sensor_manager.launch --------------------------------------------------------------------------------------
00400   file.file_name_ = "sensor_manager.launch.xml";
00401   file.rel_path_ = config_data_->appendPaths(launch_path, file.file_name_);
00402   template_path = config_data_->appendPaths(template_launch_path, file.file_name_);
00403   file.description_ = "Helper launch file that can choose between different sensor managers to be loaded.";
00404   file.gen_func_ = boost::bind(&ConfigurationFilesWidget::copyTemplate, this, template_path, _1);
00405   file.write_on_changes = 0;
00406   gen_files_.push_back(file);
00407 
00408   // robot_moveit_controller_manager.launch ------------------------------------------------------------------
00409   file.file_name_ = robot_name + "_moveit_controller_manager.launch.xml";
00410   file.rel_path_ = config_data_->appendPaths(launch_path, file.file_name_);
00411   template_path = config_data_->appendPaths(template_launch_path, "moveit_controller_manager.launch.xml");
00412   file.description_ = "Placeholder for settings specific to the MoveIt controller manager implemented for you robot.";
00413   file.gen_func_ = boost::bind(&ConfigurationFilesWidget::copyTemplate, this, template_path, _1);
00414   file.write_on_changes = 0;
00415   gen_files_.push_back(file);
00416 
00417   // robot_moveit_sensor_manager.launch ------------------------------------------------------------------
00418   file.file_name_ = robot_name + "_moveit_sensor_manager.launch.xml";
00419   file.rel_path_ = config_data_->appendPaths(launch_path, file.file_name_);
00420   template_path = config_data_->appendPaths(template_launch_path, "moveit_sensor_manager.launch.xml");
00421   file.description_ = "Placeholder for settings specific to the MoveIt sensor manager implemented for you robot.";
00422   file.gen_func_ = boost::bind(&ConfigurationFilesWidget::copyTemplate, this, template_path, _1);
00423   file.write_on_changes = 0;
00424   gen_files_.push_back(file);
00425 
00426   // trajectory_execution.launch ------------------------------------------------------------------
00427   file.file_name_ = "trajectory_execution.launch.xml";
00428   file.rel_path_ = config_data_->appendPaths(launch_path, file.file_name_);
00429   template_path = config_data_->appendPaths(template_launch_path, file.file_name_);
00430   file.description_ = "Loads settings for the ROS parameter server required for executing trajectories using the "
00431                       "trajectory_execution_manager::TrajectoryExecutionManager.";
00432   file.gen_func_ = boost::bind(&ConfigurationFilesWidget::copyTemplate, this, template_path, _1);
00433   file.write_on_changes = 0;
00434   gen_files_.push_back(
00435       file);  // trajectory_execution.launch ------------------------------------------------------------------
00436 
00437   file.file_name_ = "fake_moveit_controller_manager.launch.xml";
00438   file.rel_path_ = config_data_->appendPaths(launch_path, file.file_name_);
00439   template_path = config_data_->appendPaths(template_launch_path, file.file_name_);
00440   file.description_ = "Loads a fake controller plugin.";
00441   file.gen_func_ = boost::bind(&ConfigurationFilesWidget::copyTemplate, this, template_path, _1);
00442   file.write_on_changes = 0;
00443   gen_files_.push_back(file);
00444 
00445   // demo.launch ------------------------------------------------------------------
00446   file.file_name_ = "demo.launch";
00447   file.rel_path_ = config_data_->appendPaths(launch_path, file.file_name_);
00448   template_path = config_data_->appendPaths(template_launch_path, file.file_name_);
00449   file.description_ = "Run a demo of MoveIt.";
00450   file.gen_func_ = boost::bind(&ConfigurationFilesWidget::copyTemplate, this, template_path, _1);
00451   file.write_on_changes = 0;
00452   gen_files_.push_back(file);
00453 
00454   // joystick_control.launch ------------------------------------------------------------------
00455   file.file_name_ = "joystick_control.launch";
00456   file.rel_path_ = config_data_->appendPaths(launch_path, file.file_name_);
00457   template_path = config_data_->appendPaths(template_launch_path, file.file_name_);
00458   file.description_ = "Control the Rviz Motion Planning Plugin with a joystick";
00459   file.gen_func_ = boost::bind(&ConfigurationFilesWidget::copyTemplate, this, template_path, _1);
00460   file.write_on_changes = 0;
00461   gen_files_.push_back(file);
00462 
00463   // setup_assistant.launch ------------------------------------------------------------------
00464   file.file_name_ = "setup_assistant.launch";
00465   file.rel_path_ = config_data_->appendPaths(launch_path, file.file_name_);
00466   template_path = config_data_->appendPaths(
00467       template_launch_path, "edit_configuration_package.launch");  // named this so that this launch file is not mixed
00468                                                                    // up with the SA's real launch file
00469   file.description_ = "Launch file for easily re-starting the MoveIt Setup Assistant to edit this robot's generated "
00470                       "configuration package.";
00471   file.gen_func_ = boost::bind(&ConfigurationFilesWidget::copyTemplate, this, template_path, _1);
00472   file.write_on_changes = 0;
00473   gen_files_.push_back(file);
00474 
00475   // moveit.rviz ------------------------------------------------------------------
00476   file.file_name_ = "moveit.rviz";
00477   file.rel_path_ = config_data_->appendPaths(launch_path, file.file_name_);
00478   template_path = config_data_->appendPaths(template_launch_path, "moveit.rviz");
00479   file.description_ = "Configuration file for Rviz with the Motion Planning Plugin already setup. Used by passing "
00480                       "roslaunch moveit_rviz.launch config:=true";
00481   file.gen_func_ = boost::bind(&ConfigurationFilesWidget::copyTemplate, this, template_path, _1);
00482   file.write_on_changes = 0;
00483   gen_files_.push_back(file);
00484 
00485   // -------------------------------------------------------------------------------------------------------------------
00486   // OTHER FILES -------------------------------------------------------------------------------------------------------
00487   // -------------------------------------------------------------------------------------------------------------------
00488 
00489   // .setup_assistant ------------------------------------------------------------------
00490   file.file_name_ = SETUP_ASSISTANT_FILE;
00491   file.rel_path_ = file.file_name_;
00492   file.description_ = "MoveIt Setup Assistant's hidden settings file. You should not need to edit this file.";
00493   file.gen_func_ = boost::bind(&MoveItConfigData::outputSetupAssistantFile, config_data_, _1);
00494   file.write_on_changes = -1;  // write on any changes
00495   gen_files_.push_back(file);
00496 
00497   return true;
00498 }
00499 
00500 // ******************************************************************************************
00501 // Verify with user if certain screens have not been completed
00502 // ******************************************************************************************
00503 bool ConfigurationFilesWidget::checkDependencies()
00504 {
00505   QStringList dependencies;
00506   bool requiredActions = false;
00507 
00508   // Check that at least 1 planning group exists
00509   if (!config_data_->srdf_->groups_.size())
00510   {
00511     dependencies << "No robot model planning groups have been created";
00512   }
00513 
00514   // Check that at least 1 link pair is disabled from collision checking
00515   if (!config_data_->srdf_->disabled_collisions_.size())
00516   {
00517     dependencies << "No self-collisions have been disabled";
00518   }
00519 
00520   // Check that there is at least 1 end effector added
00521   if (!config_data_->srdf_->end_effectors_.size())
00522   {
00523     dependencies << "No end effectors have been added";
00524   }
00525 
00526   // Check that there is at least 1 virtual joint added
00527   if (!config_data_->srdf_->virtual_joints_.size())
00528   {
00529     dependencies << "No virtual joints have been added";
00530   }
00531 
00532   // Check that there is a author name
00533   if (config_data_->author_name_.find_first_not_of(' ') == std::string::npos)
00534   {
00535     // There is no name or it consists of whitespaces only
00536     dependencies << "<b>No author name added</b>";
00537     requiredActions = true;
00538   }
00539 
00540   // Check that email information is filled
00541   QRegExp mailRegex("\\b[A-Z0-9._%+-]+@[A-Z0-9.-]+\\.[A-Z]{2,4}\\b");
00542   mailRegex.setCaseSensitivity(Qt::CaseInsensitive);
00543   mailRegex.setPatternSyntax(QRegExp::RegExp);
00544   QString testEmail = QString::fromStdString(config_data_->author_email_);
00545   if (!mailRegex.exactMatch(testEmail))
00546   {
00547     dependencies << "<b>No valid email address added</b>";
00548     requiredActions = true;
00549   }
00550 
00551   // Display all accumumlated errors:
00552   if (dependencies.size())
00553   {
00554     // Create a dependency message
00555     QString dep_message;
00556     if (!requiredActions)
00557     {
00558       dep_message = "Some setup steps have not been completed. None of the steps are required, but here is a reminder "
00559                     "of what was not filled in, just in case something was forgotten:<br /><ul>";
00560     }
00561     else
00562     {
00563       dep_message = "Some setup steps have not been completed. Please fix the required steps (printed in bold), "
00564                     "otherwise the setup cannot be completed:<br /><ul>";
00565     }
00566 
00567     for (int i = 0; i < dependencies.size(); ++i)
00568     {
00569       dep_message.append("<li>").append(dependencies.at(i)).append("</li>");
00570     }
00571 
00572     if (!requiredActions)
00573     {
00574       dep_message.append("</ul><br/>Press Ok to continue generating files.");
00575       if (QMessageBox::question(this, "Incomplete MoveIt Setup Assistant Steps", dep_message,
00576                                 QMessageBox::Ok | QMessageBox::Cancel) == QMessageBox::Cancel)
00577       {
00578         return false;  // abort
00579       }
00580     }
00581     else
00582     {
00583       QMessageBox::warning(this, "Incomplete MoveIt Setup Assistant Steps", dep_message);
00584       return false;
00585     }
00586   }
00587 
00588   return true;
00589 }
00590 
00591 // ******************************************************************************************
00592 // A function for showing progress and user feedback about what happened
00593 // ******************************************************************************************
00594 void ConfigurationFilesWidget::updateProgress()
00595 {
00596   action_num_++;
00597 
00598   // Calc percentage
00599   progress_bar_->setValue(double(action_num_) / gen_files_.size() * 100);
00600 
00601   // allow the progress bar to be shown
00602   QApplication::processEvents();
00603 }
00604 
00605 // ******************************************************************************************
00606 // Display the selected action in the desc box
00607 // ******************************************************************************************
00608 void ConfigurationFilesWidget::changeActionDesc(int id)
00609 {
00610   // Only allow event if list is not empty
00611   if (id >= 0)
00612   {
00613     // Show the selected text
00614     action_label_->setText(action_desc_.at(id));
00615   }
00616 }
00617 
00618 // ******************************************************************************************
00619 // Disable or enable item in gen_files_ array
00620 // ******************************************************************************************
00621 void ConfigurationFilesWidget::changeCheckedState(QListWidgetItem* item)
00622 {
00623   std::size_t index = item->data(Qt::UserRole).toUInt();
00624   bool generate = (item->checkState() == Qt::Checked);
00625 
00626   if (!generate && (gen_files_[index].write_on_changes & config_data_->changes))
00627   {
00628     QMessageBox::warning(this, "Package Generation", "You should generate this file to ensure your changes will take "
00629                                                      "effect.");
00630   }
00631 
00632   // Enable/disable file
00633   gen_files_[index].generate_ = generate;
00634 }
00635 
00636 // ******************************************************************************************
00637 // Called when setup assistant navigation switches to this screen
00638 // ******************************************************************************************
00639 void ConfigurationFilesWidget::focusGiven()
00640 {
00641   if (first_focusGiven_)
00642   {
00643     // only generate list once
00644     first_focusGiven_ = false;
00645 
00646     // Load this list of all files to be generated
00647     loadGenFiles();
00648   }
00649 
00650   // Which files have been modified outside the Setup Assistant?
00651   bool files_already_modified = checkGenFiles();
00652 
00653   // disable reaction to checkbox changes
00654   disconnect(action_list_, SIGNAL(itemChanged(QListWidgetItem*)), this, SLOT(changeCheckedState(QListWidgetItem*)));
00655 
00656   // Show files in GUI
00657   bool have_conflicting_changes = showGenFiles();
00658 
00659   // react to manual changes only (not programmatic ones)
00660   connect(action_list_, SIGNAL(itemChanged(QListWidgetItem*)), this, SLOT(changeCheckedState(QListWidgetItem*)));
00661 
00662   // Allow list box to populate
00663   QApplication::processEvents();
00664 
00665   if (files_already_modified)
00666   {
00667     // Some were found to be modified
00668     QString msg("Some files have been modified outside of the Setup Assistant (according to timestamp). "
00669                 "The Setup Assistant will not overwrite these changes by default because often changing configuration "
00670                 "files manually is necessary, "
00671                 "but we recommend you check the list and enable the checkbox next to files you would like to "
00672                 "overwrite. ");
00673     if (have_conflicting_changes)
00674       msg += "<br/><font color='red'>Attention:</font> Some files (<font color='red'>marked red</font>) are changed "
00675              "both, externally and in Setup Assistant.";
00676     QMessageBox::information(this, "Files Modified", msg);
00677   }
00678 }
00679 
00680 // ******************************************************************************************
00681 // Check the list of files to be generated for modification
00682 // Returns true if files were detected as modified
00683 // ******************************************************************************************
00684 bool ConfigurationFilesWidget::checkGenFiles()
00685 {
00686   // Check if we are 'editing' a prev generated config pkg
00687   if (config_data_->config_pkg_path_.empty())
00688     return false;  // this is a new package
00689 
00690   // Check if we have the previous modification timestamp to compare agains
00691   if (config_data_->config_pkg_generated_timestamp_ == 0)
00692     return false;  // this package has not been generated with a timestamp, backwards compatible.
00693 
00694   static const std::time_t TIME_MOD_TOLERANCE = 10;
00695 
00696   // Check all old file's modification time
00697   bool found_modified = false;
00698   for (int i = 0; i < gen_files_.size(); ++i)
00699   {
00700     GenerateFile* file = &gen_files_[i];
00701 
00702     fs::path file_path = config_data_->appendPaths(config_data_->config_pkg_path_, file->rel_path_);
00703 
00704     // Don't disable folders from being generated
00705     if (fs::is_directory(file_path))
00706       continue;
00707 
00708     if (fs::is_regular_file(file_path))
00709     {
00710       std::time_t mod_time = fs::last_write_time(file_path);
00711 
00712       // ROS_DEBUG_STREAM("File " << file->file_name_ << " file modified " << mod_time << " pkg modified " <<
00713       // config_data_->config_pkg_generated_timestamp_);
00714 
00715       if (mod_time > config_data_->config_pkg_generated_timestamp_ + TIME_MOD_TOLERANCE ||
00716           mod_time < config_data_->config_pkg_generated_timestamp_ - TIME_MOD_TOLERANCE)
00717       {
00718         ROS_INFO_STREAM("Manual editing detected: not over-writing by default file " << file->file_name_);
00719 
00720         if (file->write_on_changes & config_data_->changes)
00721           ROS_WARN_STREAM("Editing in Setup Assistant conflicts with external editing of file " << file->file_name_);
00722 
00723         file->generate_ = false;  // do not overwrite by default
00724         file->modified_ = true;
00725         found_modified = true;
00726       }
00727       else
00728       {
00729         file->modified_ = false;
00730       }
00731     }
00732   }
00733 
00734   // Warn user if files have been modified outside Setup Assistant
00735   return found_modified;
00736 }
00737 
00738 // ******************************************************************************************
00739 // Show the list of files to be generated
00740 // ******************************************************************************************
00741 bool ConfigurationFilesWidget::showGenFiles()
00742 {
00743   bool have_conflicting_changes = false;
00744   action_list_->clear();
00745 
00746   // Display this list in the GUI
00747   for (std::size_t i = 0; i < gen_files_.size(); ++i)
00748   {
00749     GenerateFile* file = &gen_files_[i];
00750 
00751     // Create a formatted row
00752     QListWidgetItem* item = new QListWidgetItem(QString(file->rel_path_.c_str()), action_list_, 0);
00753 
00754     fs::path file_path = config_data_->appendPaths(config_data_->config_pkg_path_, file->rel_path_);
00755 
00756     // Checkbox
00757     item->setCheckState(file->generate_ ? Qt::Checked : Qt::Unchecked);
00758     // externally modified?
00759     if (file->modified_)
00760     {
00761       if (file->write_on_changes & config_data_->changes)
00762       {
00763         have_conflicting_changes = true;
00764         item->setForeground(QBrush(QColor(255, 0, 0)));
00765       }
00766       else
00767         item->setForeground(QBrush(QColor(255, 135, 0)));
00768     }
00769 
00770     // Don't allow folders to be disabled
00771     if (fs::is_directory(file_path))
00772     {
00773       item->setFlags(Qt::ItemIsSelectable | Qt::ItemIsEnabled);
00774     }
00775 
00776     // Link the gen_files_ index to this item
00777     item->setData(Qt::UserRole, QVariant(static_cast<qulonglong>(i)));
00778 
00779     // Add actions to list
00780     action_list_->addItem(item);
00781     action_desc_.append(QString(file->description_.c_str()));
00782   }
00783 
00784   // Select the first item in the list so that a description is visible
00785   action_list_->setCurrentRow(0);
00786   return have_conflicting_changes;
00787 }
00788 
00789 // ******************************************************************************************
00790 // Save configuration click event
00791 // ******************************************************************************************
00792 void ConfigurationFilesWidget::savePackage()
00793 {
00794   // Feedback
00795   success_label_->hide();
00796 
00797   // Reset the progress bar counter and GUI stuff
00798   action_num_ = 0;
00799   progress_bar_->setValue(0);
00800 
00801   if (!generatePackage())
00802   {
00803     ROS_ERROR_STREAM("Failed to generate entire configuration package");
00804     return;
00805   }
00806 
00807   // Alert user it completed successfully --------------------------------------------------
00808   progress_bar_->setValue(100);
00809   success_label_->show();
00810   has_generated_pkg_ = true;
00811 }
00812 
00813 // ******************************************************************************************
00814 // Save package using default path
00815 // ******************************************************************************************
00816 bool ConfigurationFilesWidget::generatePackage()
00817 {
00818   // Get path name
00819   std::string new_package_path = stack_path_->getPath();
00820 
00821   // Check that a valid stack package name has been given
00822   if (new_package_path.empty())
00823   {
00824     QMessageBox::warning(this, "Error Generating", "No package path provided. Please choose a directory location to "
00825                                                    "generate the MoveIt configuration files.");
00826     return false;
00827   }
00828 
00829   // Check setup assist deps
00830   if (!checkDependencies())
00831     return false;  // canceled
00832 
00833   // Check that all groups have components
00834   if (!noGroupsEmpty())
00835     return false;  // not ready
00836 
00837   // Trim whitespace from user input
00838   boost::trim(new_package_path);
00839 
00840   // Get the package name ---------------------------------------------------------------------------------
00841   new_package_name_ = getPackageName(new_package_path);
00842 
00843   const std::string setup_assistant_file = config_data_->appendPaths(new_package_path, SETUP_ASSISTANT_FILE);
00844 
00845   // Make sure old package is correct package type and verify over write
00846   if (fs::is_directory(new_package_path) && !fs::is_empty(new_package_path))
00847   {
00848     // Check if the old package is a setup assistant package. If it is not, quit
00849     if (!fs::is_regular_file(setup_assistant_file))
00850     {
00851       QMessageBox::warning(
00852           this, "Incorrect Folder/Package",
00853           QString("The chosen package location already exists but was not previously created using this MoveIt Setup "
00854                   "Assistant. "
00855                   "If this is a mistake, add the missing file: ")
00856               .append(setup_assistant_file.c_str()));
00857       return false;
00858     }
00859 
00860     // Confirm overwrite
00861     if (QMessageBox::question(
00862             this, "Confirm Package Update",
00863             QString("Are you sure you want to overwrite this existing package with updated configurations?<br /><i>")
00864                 .append(new_package_path.c_str())
00865                 .append("</i>"),
00866             QMessageBox::Ok | QMessageBox::Cancel) == QMessageBox::Cancel)
00867     {
00868       return false;  // abort
00869     }
00870   }
00871   else  // this is a new package (but maybe the folder already exists)
00872   {
00873     // Create new directory ------------------------------------------------------------------
00874     try
00875     {
00876       fs::create_directory(new_package_path) && !fs::is_directory(new_package_path);
00877     }
00878     catch (...)
00879     {
00880       QMessageBox::critical(this, "Error Generating Files",
00881                             QString("Unable to create directory ").append(new_package_path.c_str()));
00882       return false;
00883     }
00884   }
00885 
00886   // Begin to create files and folders ----------------------------------------------------------------------
00887   std::string absolute_path;
00888 
00889   for (int i = 0; i < gen_files_.size(); ++i)
00890   {
00891     GenerateFile* file = &gen_files_[i];
00892 
00893     // Check if we should skip this file
00894     if (!file->generate_)
00895     {
00896       continue;
00897     }
00898 
00899     // Create the absolute path
00900     absolute_path = config_data_->appendPaths(new_package_path, file->rel_path_);
00901     ROS_DEBUG_STREAM("Creating file " << absolute_path);
00902 
00903     // Run the generate function
00904     if (!file->gen_func_(absolute_path))
00905     {
00906       // Error occured
00907       QMessageBox::critical(this, "Error Generating File", QString("Failed to generate folder or file: '")
00908                                                                .append(file->rel_path_.c_str())
00909                                                                .append("' at location:\n")
00910                                                                .append(absolute_path.c_str()));
00911       return false;
00912     }
00913     updateProgress();  // Increment and update GUI
00914   }
00915 
00916   return true;
00917 }
00918 
00919 // ******************************************************************************************
00920 // Quit the program because we are done
00921 // ******************************************************************************************
00922 void ConfigurationFilesWidget::exitSetupAssistant()
00923 {
00924   if (has_generated_pkg_ ||
00925       QMessageBox::question(this, "Exit Setup Assistant",
00926                             QString("Are you sure you want to exit the MoveIt Setup Assistant?"),
00927                             QMessageBox::Ok | QMessageBox::Cancel) == QMessageBox::Ok)
00928   {
00929     QApplication::quit();
00930   }
00931 }
00932 
00933 // ******************************************************************************************
00934 // Get the last folder name in a directory path
00935 // ******************************************************************************************
00936 const std::string ConfigurationFilesWidget::getPackageName(std::string package_path)
00937 {
00938   // Remove end slash if there is one
00939   if (!package_path.compare(package_path.size() - 1, 1, "/"))
00940   {
00941     package_path = package_path.substr(0, package_path.size() - 1);
00942   }
00943 
00944   // Get the last directory name
00945   std::string package_name;
00946   fs::path fs_package_path = package_path;
00947 
00948   package_name = fs_package_path.filename().c_str();
00949 
00950   // check for empty
00951   if (package_name.empty())
00952     package_name = "unknown";
00953 
00954   return package_name;
00955 }
00956 
00957 // ******************************************************************************************
00958 // Check that no group is empty (without links/joints/etc)
00959 // ******************************************************************************************
00960 bool ConfigurationFilesWidget::noGroupsEmpty()
00961 {
00962   // Loop through all groups
00963   for (std::vector<srdf::Model::Group>::const_iterator group_it = config_data_->srdf_->groups_.begin();
00964        group_it != config_data_->srdf_->groups_.end(); ++group_it)
00965   {
00966     // Whenever 1 of the 4 component types are found, stop checking this group
00967     if (group_it->joints_.size())
00968       continue;
00969     if (group_it->links_.size())
00970       continue;
00971     if (group_it->chains_.size())
00972       continue;
00973     if (group_it->subgroups_.size())
00974       continue;
00975 
00976     // This group has no contents, bad
00977     QMessageBox::warning(
00978         this, "Empty Group",
00979         QString("The planning group '")
00980             .append(group_it->name_.c_str())
00981             .append("' is empty and has no subcomponents associated with it (joints/links/chains/subgroups). You must "
00982                     "edit or remove this planning group before this configuration package can be saved."));
00983     return false;
00984   }
00985 
00986   return true;  // good
00987 }
00988 
00989 // ******************************************************************************************
00990 // Load the strings that will be replaced in all templates
00991 // ******************************************************************************************
00992 void ConfigurationFilesWidget::loadTemplateStrings()
00993 {
00994   // Pair 1
00995   addTemplateString("[GENERATED_PACKAGE_NAME]", new_package_name_);
00996 
00997   // Pair 2
00998   std::string urdf_location = config_data_->urdf_pkg_name_.empty() ? config_data_->urdf_path_ :
00999                                                                      "$(find " + config_data_->urdf_pkg_name_ + ")/" +
01000                                                                          config_data_->urdf_pkg_relative_path_;
01001   addTemplateString("[URDF_LOCATION]", urdf_location);
01002 
01003   // Pair 3
01004   if (config_data_->urdf_from_xacro_)
01005     addTemplateString("[URDF_LOAD_ATTRIBUTE]", "command=\"$(find xacro)/xacro.py '" + urdf_location + "'\"");
01006   else
01007     addTemplateString("[URDF_LOAD_ATTRIBUTE]", "textfile=\"" + urdf_location + "\"");
01008 
01009   // Pair 4
01010   addTemplateString("[ROBOT_NAME]", config_data_->srdf_->robot_name_);
01011 
01012   // Pair 5
01013   addTemplateString("[ROBOT_ROOT_LINK]", config_data_->getRobotModel()->getRootLinkName());
01014 
01015   // Pair 6
01016   addTemplateString("[PLANNING_FRAME]", config_data_->getRobotModel()->getModelFrame());
01017 
01018   // Pair 7
01019   std::stringstream vjb;
01020   for (std::size_t i = 0; i < config_data_->srdf_->virtual_joints_.size(); ++i)
01021   {
01022     const srdf::Model::VirtualJoint& vj = config_data_->srdf_->virtual_joints_[i];
01023     if (vj.type_ != "fixed")
01024       vjb << "  <node pkg=\"tf\" type=\"static_transform_publisher\" name=\"virtual_joint_broadcaster_" << i
01025           << "\" args=\"0 0 0 0 0 0 " << vj.parent_frame_ << " " << vj.child_link_ << " 100\" />" << std::endl;
01026   }
01027   addTemplateString("[VIRTUAL_JOINT_BROADCASTER]", vjb.str());
01028 
01029   // Pair 8 - Add dependencies to package.xml if the robot.urdf file is relative to a ROS package
01030   if (config_data_->urdf_pkg_name_.empty())
01031   {
01032     addTemplateString("[OTHER_DEPENDENCIES", "");  // not relative to a ROS package
01033   }
01034   else
01035   {
01036     std::stringstream deps;
01037     deps << "<build_depend>" << config_data_->urdf_pkg_name_ << "</build_depend>\n";
01038     deps << "  <run_depend>" << config_data_->urdf_pkg_name_ << "</run_depend>\n";
01039     addTemplateString("[OTHER_DEPENDENCIES]", deps.str());  // not relative to a ROS package
01040   }
01041 
01042   addTemplateString("[AUTHOR_NAME]", config_data_->author_name_);
01043   addTemplateString("[AUTHOR_EMAIL]", config_data_->author_email_);
01044 }
01045 
01046 // ******************************************************************************************
01047 // Insert a string pair into the template_strings_ datastructure
01048 // ******************************************************************************************
01049 bool ConfigurationFilesWidget::addTemplateString(const std::string& key, const std::string& value)
01050 {
01051   template_strings_.push_back(std::pair<std::string, std::string>(key, value));
01052 
01053   return true;
01054 }
01055 
01056 // ******************************************************************************************
01057 // Copy a template from location <template_path> to location <output_path> and replace package name
01058 // ******************************************************************************************
01059 bool ConfigurationFilesWidget::copyTemplate(const std::string& template_path, const std::string& output_path)
01060 {
01061   // Check if template strings have been loaded yet
01062   if (template_strings_.empty())
01063   {
01064     loadTemplateStrings();
01065   }
01066 
01067   // Error check file
01068   if (!fs::is_regular_file(template_path))
01069   {
01070     ROS_ERROR_STREAM("Unable to find template file " << template_path);
01071     return false;
01072   }
01073 
01074   // Load file
01075   std::ifstream template_stream(template_path.c_str());
01076   if (!template_stream.good())  // File not found
01077   {
01078     ROS_ERROR_STREAM("Unable to load file " << template_path);
01079     return false;
01080   }
01081 
01082   // Load the file to a string using an efficient memory allocation technique
01083   std::string template_string;
01084   template_stream.seekg(0, std::ios::end);
01085   template_string.reserve(template_stream.tellg());
01086   template_stream.seekg(0, std::ios::beg);
01087   template_string.assign((std::istreambuf_iterator<char>(template_stream)), std::istreambuf_iterator<char>());
01088   template_stream.close();
01089 
01090   // Replace keywords in string ------------------------------------------------------------
01091   for (int i = 0; i < template_strings_.size(); ++i)
01092   {
01093     boost::replace_all(template_string, template_strings_[i].first, template_strings_[i].second);
01094   }
01095 
01096   // Save string to new location -----------------------------------------------------------
01097   std::ofstream output_stream(output_path.c_str(), std::ios_base::trunc);
01098   if (!output_stream.good())
01099   {
01100     ROS_ERROR_STREAM("Unable to open file for writing " << output_path);
01101     return false;
01102   }
01103 
01104   output_stream << template_string.c_str();
01105   output_stream.close();
01106 
01107   return true;  // file created successfully
01108 }
01109 
01110 // ******************************************************************************************
01111 // Create a folder
01112 // ******************************************************************************************
01113 bool ConfigurationFilesWidget::createFolder(const std::string& output_path)
01114 {
01115   if (!fs::is_directory(output_path))
01116   {
01117     if (!fs::create_directory(output_path))
01118     {
01119       QMessageBox::critical(this, "Error Generating Files",
01120                             QString("Unable to create directory ").append(output_path.c_str()));
01121       return false;
01122     }
01123   }
01124   return true;
01125 }
01126 
01127 }  // namespace


moveit_setup_assistant
Author(s): Dave Coleman
autogenerated on Mon Jul 24 2017 02:22:29