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


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