start_screen_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 <QLabel>
00039 #include <QTimer>
00040 #include <QVBoxLayout>
00041 #include <QHBoxLayout>
00042 #include <QMessageBox>
00043 #include <QString>
00044 #include <QApplication>
00045 #include <QFont>
00046 #include <QFileDialog>
00047 // ROS
00048 #include <ros/ros.h>
00049 #include <ros/package.h> // for getting file path for loadng images
00050 // SA
00051 #include "header_widget.h" // title and instructions
00052 #include "start_screen_widget.h"
00053 // C
00054 #include <fstream>  // for reading in urdf
00055 #include <streambuf>
00056 // Boost
00057 #include <boost/algorithm/string.hpp> // for trimming whitespace from user input
00058 #include <boost/filesystem.hpp>  // for reading folders/files
00059 #include <boost/algorithm/string.hpp> // for string find and replace in paths
00060 
00061 namespace moveit_setup_assistant
00062 {
00063 
00064 // Boost file system
00065 namespace fs = boost::filesystem;
00066 
00067 // ******************************************************************************************
00068 // Start screen user interface for MoveIt Configuration Assistant
00069 // ******************************************************************************************
00070 StartScreenWidget::StartScreenWidget( QWidget* parent, moveit_setup_assistant::MoveItConfigDataPtr config_data )
00071   :  SetupScreenWidget( parent ), config_data_( config_data )
00072 {
00073 
00074 
00075   // Basic widget container
00076   QVBoxLayout *layout = new QVBoxLayout( this );
00077 
00078   // Horizontal layout splitter
00079   QHBoxLayout *hlayout = new QHBoxLayout( );
00080   // Left side of screen
00081   QVBoxLayout *left_layout = new QVBoxLayout( );
00082   // Right side of screen
00083   QVBoxLayout *right_layout = new QVBoxLayout( );
00084 
00085 
00086   // Right Image Area ----------------------------------------------
00087   right_image_ = new QImage();
00088   right_image_label_ = new QLabel( this );
00089   std::string image_path = "./resources/MoveIt_Setup_Asst_xSm.png";
00090   if(chdir(config_data_->setup_assistant_path_.c_str()) != 0)
00091   {
00092     ROS_ERROR("FAILED TO CHANGE PACKAGE TO moveit_setup_assistant");
00093   }
00094 
00095   if (right_image_->load( image_path.c_str() ))
00096   {
00097     right_image_label_->setPixmap(QPixmap::fromImage( *right_image_));
00098     right_image_label_->setMinimumHeight(384);  // size of right_image_label_
00099     //right_image_label_->setMinimumWidth(450);
00100   }
00101   else
00102   {
00103     ROS_ERROR_STREAM("FAILED TO LOAD " << image_path );
00104   }
00105 
00106   logo_image_ = new QImage();
00107   logo_image_label_ = new QLabel( this );
00108   image_path = "./resources/moveit_logo.png";
00109 
00110   if (logo_image_->load( image_path.c_str() ))
00111   {
00112     logo_image_label_->setPixmap(QPixmap::fromImage( *logo_image_));
00113     logo_image_label_->setMinimumWidth(96);
00114   }
00115   else
00116   {
00117     ROS_ERROR_STREAM("FAILED TO LOAD " << image_path );
00118   }
00119 
00120 
00121   // Top Label Area ---------------------------------------------------
00122   HeaderWidget *header = new HeaderWidget( "MoveIt Setup Assistant",
00123                                            "Welcome to the MoveIt Setup Assistant! These tools will assist you in creating a MoveIt configuration package that is required to run MoveIt. This includes generating a Semantic Robot Description Format (SRDF) file, kinematics configuration file and OMPL planning configuration file. It also involves creating launch files for move groups, OMPL planner, planning contexts and the planning warehouse.",
00124                                            this);
00125   layout->addWidget( header );
00126 
00127   left_layout->addWidget(logo_image_label_);
00128   left_layout->setAlignment(logo_image_label_, Qt::AlignLeft | Qt::AlignTop);
00129 
00130   // Select Mode Area -------------------------------------------------
00131   select_mode_ = new SelectModeWidget( this );
00132   connect( select_mode_->btn_new_, SIGNAL( clicked() ), this, SLOT( showNewOptions() ) );
00133   connect( select_mode_->btn_exist_, SIGNAL( clicked() ), this, SLOT( showExistingOptions() ) );
00134   left_layout->addWidget( select_mode_ );
00135 
00136   // Path Box Area ----------------------------------------------------
00137 
00138   // Stack Path Dialog
00139   stack_path_ = new LoadPathWidget("Load MoveIt Configuration Package Path",
00140                                    "Specify the package name or path of an existing MoveIt configuration package to be edited for your robot. Example package name: <i>pr2_moveit_config</i>",
00141                                    true, this); // is directory
00142   stack_path_->hide(); // user needs to select option before this is shown
00143   left_layout->addWidget( stack_path_ );
00144 
00145   // URDF File Dialog
00146   urdf_file_ = new LoadPathWidget("Load a URDF or COLLADA Robot Model",
00147                                   "Specify the location of an existing Universal Robot Description Format or COLLADA file for your robot. The robot model will be loaded to the parameter server for you.",
00148                                   false, true, this); // no directory, load only
00149   urdf_file_->hide(); // user needs to select option before this is shown
00150   left_layout->addWidget( urdf_file_ );
00151 
00152   // Load settings box ---------------------------------------------
00153   QHBoxLayout *load_files_layout = new QHBoxLayout();
00154 
00155   progress_bar_ = new QProgressBar( this );
00156   progress_bar_->setMaximum(100);
00157   progress_bar_->setMinimum(0);
00158   progress_bar_->hide();
00159   load_files_layout->addWidget( progress_bar_ );
00160   //load_files_layout->setContentsMargins( 20, 30, 20, 30 );
00161 
00162   btn_load_ = new QPushButton("&Load Files", this);
00163   btn_load_->setMinimumWidth(180);
00164   btn_load_->setMinimumHeight(40);
00165   btn_load_->hide();
00166   load_files_layout->addWidget( btn_load_ );
00167   load_files_layout->setAlignment( btn_load_, Qt::AlignRight );
00168   connect( btn_load_, SIGNAL( clicked() ), this, SLOT( loadFilesClick() ) );
00169 
00170   // Next step instructions
00171   next_label_ = new QLabel( this );
00172   QFont next_label_font( "Arial", 11, QFont::Bold );
00173   next_label_->setFont( next_label_font );
00174   //next_label_->setWordWrap(true);
00175   next_label_->setText( "Success! Use the left navigation pane to continue." );
00176   //  next_label_->setSizePolicy( QSizePolicy::Expanding, QSizePolicy::Preferred );
00177   next_label_->hide(); // only show once the files have been loaded.
00178 
00179   right_layout->addWidget(right_image_label_);
00180   right_layout->setAlignment(right_image_label_, Qt::AlignRight | Qt::AlignTop);
00181 
00182   // Final Layout Setup ---------------------------------------------
00183   // Alignment
00184   layout->setAlignment( Qt::AlignTop );
00185   hlayout->setAlignment( Qt::AlignTop );
00186   left_layout->setAlignment( Qt::AlignTop );
00187   right_layout->setAlignment( Qt::AlignTop );
00188 
00189   // Stretch
00190   left_layout->setSpacing( 30 );
00191   //hlayout->setContentsMargins( 0, 20, 0, 0);
00192 
00193   // Attach Layouts
00194   hlayout->addLayout( left_layout );
00195   hlayout->addLayout( right_layout );
00196   layout->addLayout( hlayout );
00197 
00198   // Verticle Spacer
00199   QWidget *vspacer = new QWidget( this );
00200   vspacer->setSizePolicy( QSizePolicy::Preferred, QSizePolicy::Expanding );
00201   layout->addWidget( vspacer );
00202 
00203   // Attach bottom layout
00204   layout->addWidget( next_label_);
00205   layout->setAlignment( next_label_, Qt::AlignRight );
00206   layout->addLayout( load_files_layout );
00207 
00208   this->setLayout(layout);
00209   //  this->setSizePolicy(QSizePolicy::Expanding, QSizePolicy::Expanding);
00210 
00211 
00212   // Debug mode: auto load the configuration file by clicking button after a timeout
00213   if( config_data_->debug_ )
00214   {
00215     //select_mode_->btn_exist_->click();
00216 
00217     QTimer *update_timer = new QTimer( this );
00218     update_timer->setSingleShot( true ); // only run once
00219     connect( update_timer, SIGNAL( timeout() ), btn_load_, SLOT( click() ));
00220     update_timer->start( 100 );
00221   }
00222 
00223 
00224 }
00225 
00226 // ******************************************************************************************
00227 // Destructor
00228 // ******************************************************************************************
00229 StartScreenWidget::~StartScreenWidget()
00230 {
00231   delete right_image_; // does not have a parent passed to it
00232   delete logo_image_;
00233 }
00234 
00235 // ******************************************************************************************
00236 // Show options for creating a new configuration package
00237 // ******************************************************************************************
00238 void StartScreenWidget::showNewOptions()
00239 {
00240   // Do GUI stuff
00241   select_mode_->btn_exist_->setFlat( false );
00242   select_mode_->btn_new_->setFlat( true );
00243   urdf_file_->show();
00244   //  srdf_file_->show();
00245   stack_path_->hide();
00246   btn_load_->show();
00247 
00248   // Remember choice
00249   create_new_package_ = true;
00250 }
00251 
00252 // ******************************************************************************************
00253 // Show options for editing an existing configuration package
00254 // ******************************************************************************************
00255 void StartScreenWidget::showExistingOptions()
00256 {
00257   // Do GUI stuff
00258   select_mode_->btn_exist_->setFlat( true );
00259   select_mode_->btn_new_->setFlat( false );
00260   urdf_file_->hide();
00261   //srdf_file_->hide();
00262   stack_path_->show();
00263   btn_load_->show();
00264 
00265   // Remember choice
00266   create_new_package_ = false;
00267 }
00268 
00269 // ******************************************************************************************
00270 // Load files to parameter server - CLICK
00271 // ******************************************************************************************
00272 void StartScreenWidget::loadFilesClick()
00273 {
00274   // Disable start screen GUI components from being changed
00275   urdf_file_->setDisabled(true);
00276   //srdf_file_->setDisabled(true);
00277   stack_path_->setDisabled(true);
00278   select_mode_->setDisabled(true);
00279   btn_load_->setDisabled(true);
00280   progress_bar_->show();
00281 
00282   bool result;
00283 
00284   // Decide if this is a new config package, or loading an old one
00285   if( create_new_package_ )
00286   {
00287     result = loadNewFiles();
00288   }
00289   else
00290   {
00291     result = loadExistingFiles();
00292   }
00293 
00294   // Check if there was a failure loading files
00295   if( !result )
00296   {
00297     // Renable components
00298     urdf_file_->setDisabled(false);
00299     //srdf_file_->setDisabled(false);
00300     stack_path_->setDisabled(false);
00301     select_mode_->setDisabled(false);
00302     btn_load_->setDisabled(false);
00303     progress_bar_->hide();
00304   }
00305   else
00306   {
00307     // Hide the logo image so that other screens can resize the rviz thing properly
00308     right_image_label_->hide();
00309   }
00310 
00311 }
00312 
00313 // ******************************************************************************************
00314 // Load exisiting package files
00315 // ******************************************************************************************
00316 bool StartScreenWidget::loadExistingFiles()
00317 {
00318   // Progress Indicator
00319   progress_bar_->setValue( 10 );
00320   QApplication::processEvents();
00321 
00322   // Get the package path
00323   if( !createFullPackagePath() )
00324     return false; // error occured
00325 
00326   // Path of .setup_assistant file
00327   fs::path setup_assistant_file = config_data_->config_pkg_path_;
00328   setup_assistant_file /= ".setup_assistant";
00329 
00330   // Check if the old package is a setup assistant package. If it is not, quit
00331   if( ! fs::is_regular_file( setup_assistant_file ) )
00332   {
00333     QMessageBox::warning( this, "Incorrect Directory/Package",
00334                           QString("The chosen package location exists but was not previously created using this MoveIt Setup Assistant. If this is a mistake, replace the missing file: ")
00335                           .append( setup_assistant_file.make_preferred().native().c_str() ) );
00336     return false;
00337   }
00338 
00339   // Get setup assistant data
00340   if( !config_data_->inputSetupAssistantYAML( setup_assistant_file.make_preferred().native().c_str() ) )
00341   {
00342     QMessageBox::warning( this, "Setup Assistant File Error",
00343                           QString("Unable to correctly parse the setup assistant configuration file: " )
00344                           .append( setup_assistant_file.make_preferred().native().c_str() ) );
00345     return false;
00346   }
00347 
00348   // Progress Indicator
00349   progress_bar_->setValue( 30 );
00350   QApplication::processEvents();
00351 
00352   // Get the URDF path using the loaded .setup_assistant data and check it
00353   if( !createFullURDFPath() )
00354     return false; // error occured
00355 
00356   // Load the URDF
00357   if( !loadURDFFile( config_data_->urdf_path_ ) )
00358     return false; // error occured
00359 
00360   // Get the SRDF path using the loaded .setup_assistant data and check it
00361   if( !createFullSRDFPath( config_data_->config_pkg_path_ ) )
00362     return false; // error occured
00363 
00364   // Progress Indicator
00365   progress_bar_->setValue( 50 );
00366   QApplication::processEvents();
00367 
00368   // Load the SRDF
00369   if( !loadSRDFFile( config_data_->srdf_path_ ) )
00370     return false; // error occured
00371 
00372   // Progress Indicator
00373   progress_bar_->setValue( 60 );
00374   QApplication::processEvents();
00375 
00376   // Load the allowed collision matrix
00377   config_data_->loadAllowedCollisionMatrix();
00378 
00379   // Load kinematics yaml file if available --------------------------------------------------
00380   fs::path kinematics_yaml_path = config_data_->config_pkg_path_;
00381   kinematics_yaml_path /= "config/kinematics.yaml";
00382 
00383   if( !config_data_->inputKinematicsYAML( kinematics_yaml_path.make_preferred().native().c_str() ) )
00384   {
00385     QMessageBox::warning( this, "No Kinematic YAML File",
00386                           QString("Failed to parse kinematics yaml file. This file is not critical but any previous kinematic solver settings have been lost. To re-populate this file edit each existing planning group and choose a solver, then save each change. \n\nFile error at location ").append( kinematics_yaml_path.make_preferred().native().c_str() ) );
00387   }
00388 
00389   // DONE LOADING --------------------------------------------------------------------------
00390 
00391   // Call a function that enables navigation
00392   Q_EMIT readyToProgress();
00393 
00394   // Progress Indicator
00395   progress_bar_->setValue( 70 );
00396   QApplication::processEvents();
00397 
00398   // Load Rviz
00399   Q_EMIT loadRviz();
00400 
00401   // Progress Indicator
00402   progress_bar_->setValue( 100 );
00403   QApplication::processEvents();
00404 
00405   next_label_->show(); // only show once the files have been loaded
00406 
00407   ROS_INFO( "Loading Setup Assistant Complete" );
00408   return true; // success!
00409 }
00410 
00411 // ******************************************************************************************
00412 // Load chosen files for creating new package
00413 // ******************************************************************************************
00414 bool StartScreenWidget::loadNewFiles()
00415 {
00416   // Get URDF file path
00417   config_data_->urdf_path_ = urdf_file_->getPath();
00418 
00419   // Check that box is filled out
00420   if( config_data_->urdf_path_.empty() )
00421   {
00422     QMessageBox::warning( this, "Error Loading Files", "No robot model file specefied" );
00423     return false;
00424   }
00425 
00426   // Check that this file exits
00427   if( ! fs::is_regular_file( config_data_->urdf_path_ ) )
00428   {
00429     QMessageBox::warning( this, "Error Loading Files",
00430                           QString("Unable to locate the URDF file: " )
00431                           .append( config_data_->urdf_path_.c_str() ) );
00432     return false;
00433   }
00434 
00435   // Attempt to get the ROS package from the path
00436   if( !extractPackageNameFromPath() )
00437   {
00438     return false; // An error occurred
00439   }
00440 
00441   // Progress Indicator
00442   progress_bar_->setValue( 20 );
00443   QApplication::processEvents();
00444 
00445   // Load the URDF to the parameter server and check that it is correct format
00446   if( !loadURDFFile( config_data_->urdf_path_ ) )
00447     return false; // error occurred
00448 
00449   // Progress Indicator
00450   progress_bar_->setValue( 50 );
00451   QApplication::processEvents();
00452 
00453   // Create blank SRDF file
00454   const std::string blank_srdf =
00455     "<?xml version='1.0'?><robot name='" + config_data_->urdf_model_->getName() + "'></robot>";
00456 
00457   // Load a blank SRDF file to the parameter server
00458   if( !setSRDFFile( blank_srdf ))
00459   {
00460     QMessageBox::warning( this, "Error Loading Files", "Failure loading blank SRDF file." );
00461     return false;
00462   }
00463 
00464   // Progress Indicator
00465   progress_bar_->setValue( 60 );
00466   QApplication::processEvents();
00467 
00468   // DONE LOADING --------------------------------------------------------------------------
00469 
00470   // Call a function that enables navigation
00471   Q_EMIT readyToProgress();
00472 
00473   // Progress Indicator
00474   progress_bar_->setValue( 70 );
00475   QApplication::processEvents();
00476 
00477   // Load Rviz
00478   Q_EMIT loadRviz();
00479 
00480   // Progress Indicator
00481   progress_bar_->setValue( 100 );
00482   QApplication::processEvents();
00483 
00484   next_label_->show(); // only show once the files have been loaded
00485 
00486   ROS_INFO( "Loading Setup Assistant Complete" );
00487   return true; // success!
00488 }
00489 
00490 // ******************************************************************************************
00491 // Load URDF File to Parameter Server
00492 // ******************************************************************************************
00493 bool StartScreenWidget::loadURDFFile( const std::string& urdf_file_path )
00494 {
00495   // check that URDF can be loaded
00496   std::ifstream urdf_stream( urdf_file_path.c_str() );
00497   if( !urdf_stream.good() ) // File not found
00498   {
00499     QMessageBox::warning( this, "Error Loading Files", QString( "URDF/COLLADA file not found: " ).append( urdf_file_path.c_str() ) );
00500     return false;
00501   }
00502   std::string urdf_string;
00503   bool xacro = false;
00504 
00505   if (urdf_file_path.find(".xacro") != std::string::npos)
00506   {
00507     std::string cmd("rosrun xacro xacro.py ");
00508     cmd += urdf_file_path;
00509     ROS_INFO( "Running '%s'...", cmd.c_str() );
00510 
00511     FILE* pipe = popen(cmd.c_str(), "r");
00512     if (!pipe)
00513     {
00514       QMessageBox::warning( this, "Error Loading Files", QString( "XACRO file or parser not found: " ).append( urdf_file_path.c_str() ) );
00515       return false;
00516     }
00517     char buffer[128] = {0};
00518     while (!feof(pipe))
00519     {
00520       if (fgets(buffer, sizeof(buffer), pipe) != NULL)
00521         urdf_string += buffer;
00522     }
00523     pclose(pipe);
00524     
00525     if (urdf_string.empty())
00526     {
00527       QMessageBox::warning( this, "Error Loading Files", QString( "Unable to parse XACRO file: " ).append( urdf_file_path.c_str() ) );
00528       return false;
00529     }
00530     xacro = true;
00531   }
00532   else
00533   {
00534     // Load the file to a string using an efficient memory allocation technique
00535     urdf_stream.seekg(0, std::ios::end);
00536     urdf_string.reserve(urdf_stream.tellg());
00537     urdf_stream.seekg(0, std::ios::beg);
00538     urdf_string.assign( (std::istreambuf_iterator<char>(urdf_stream)), std::istreambuf_iterator<char>() );
00539     urdf_stream.close();
00540   }
00541   // Verify that file is in correct format / not an XACRO by loading into robot model
00542   if( !config_data_->urdf_model_->initString( urdf_string ) )
00543   {
00544     QMessageBox::warning( this, "Error Loading Files",
00545                           "URDF/COLLADA file is not a valid robot model." );
00546     return false;
00547   }
00548   config_data_->urdf_from_xacro_ = xacro;
00549 
00550   ROS_INFO_STREAM( "Loaded " << config_data_->urdf_model_->getName() << " robot model." );
00551 
00552   // Load the robot model to the parameter server
00553   ros::NodeHandle nh;
00554   int steps = 0;
00555   while (!nh.ok() && steps < 4)
00556   {
00557     ROS_WARN("Waiting for node handle");
00558     sleep(1);
00559     steps++;
00560     ros::spinOnce();
00561   }
00562 
00563   ROS_INFO("Setting Param Server with Robot Description");
00564   //ROS_WARN("Ignore the following error message 'Failed to contact master'. This is a known issue.");
00565   nh.setParam("/robot_description", urdf_string);
00566 
00567   return true;
00568 }
00569 
00570 // ******************************************************************************************
00571 // Load SRDF File to Parameter Server
00572 // ******************************************************************************************
00573 bool StartScreenWidget::loadSRDFFile( const std::string& srdf_file_path )
00574 {
00575   // check that SRDF can be loaded
00576   std::ifstream srdf_stream( srdf_file_path.c_str() );
00577   if( !srdf_stream.good() ) // File not found
00578   {
00579     QMessageBox::warning( this, "Error Loading Files", QString( "SRDF file not found: " ).append( config_data_->srdf_path_.c_str() ) );
00580     return false;
00581   }
00582 
00583   // Load the file to a string using an efficient memory allocation technique
00584   std::string srdf_string;
00585   srdf_stream.seekg(0, std::ios::end);
00586   srdf_string.reserve(srdf_stream.tellg());
00587   srdf_stream.seekg(0, std::ios::beg);
00588   srdf_string.assign( (std::istreambuf_iterator<char>(srdf_stream)), std::istreambuf_iterator<char>() );
00589   srdf_stream.close();
00590 
00591   // Put on param server
00592   return setSRDFFile( srdf_string );
00593 }
00594 
00595 // ******************************************************************************************
00596 // Put SRDF File on Parameter Server
00597 // ******************************************************************************************
00598 bool StartScreenWidget::setSRDFFile( const std::string& srdf_string )
00599 {
00600   // Verify that file is in correct format / not an XACRO by loading into robot model
00601   if( !config_data_->srdf_->initString( *config_data_->urdf_model_, srdf_string ) )
00602   {
00603     QMessageBox::warning( this, "Error Loading Files",
00604                           "SRDF file not a valid semantic robot description model." );
00605     return false;
00606   }
00607   ROS_INFO_STREAM( "Robot semantic model successfully loaded." );
00608 
00609   // Load to param server
00610   ros::NodeHandle nh;
00611   int steps = 0;
00612   while (!nh.ok() && steps < 4)
00613   {
00614     ROS_WARN("Waiting for node handle");
00615     sleep(1);
00616     steps++;
00617     ros::spinOnce();
00618   }
00619 
00620   ROS_INFO("Setting Param Server with Robot Semantic Description");
00621   nh.setParam("/robot_description_semantic", srdf_string);
00622 
00623   return true;
00624 }
00625 
00626 // ******************************************************************************************
00627 // Extract the package/stack name and relative path to urdf from an absolute path name
00628 // Input:  cofig_data_->urdf_path_
00629 // Output: cofig_data_->urdf_pkg_name_
00630 //         cofig_data_->urdf_pkg_relative_path_
00631 // ******************************************************************************************
00632 bool StartScreenWidget::extractPackageNameFromPath()
00633 {
00634   // Get the path to urdf, save filename
00635   fs::path urdf_path = config_data_->urdf_path_;
00636   fs::path urdf_directory = urdf_path;
00637   urdf_directory.remove_filename();
00638 
00639   fs::path sub_path; // holds the directory less one folder
00640   fs::path relative_path; // holds the path after the sub_path
00641   std::string package_name; // result
00642 
00643   // Paths for testing if files exist
00644   fs::path package_path;
00645 
00646   std::vector<std::string> path_parts; // holds each folder name in vector
00647 
00648   // Copy path into vector of parts
00649   for (fs::path::iterator it = urdf_directory.begin(); it != urdf_directory.end(); ++it)
00650     path_parts.push_back( it->native() );
00651   
00652   bool packageFound = false;
00653 
00654   // reduce the generated directoy path's folder count by 1 each loop
00655   for( int segment_length = path_parts.size(); segment_length > 0; --segment_length )
00656   {
00657     // Reset the sub_path
00658     sub_path.clear();
00659 
00660     // Create a subpath based on the outer loops length
00661     for( int segment_count = 0; segment_count < segment_length; ++segment_count )
00662     {
00663       sub_path /= path_parts[ segment_count ];
00664 
00665       // decide if we should remember this directory name because it is topmost, in case it is the package/stack name
00666       if( segment_count == segment_length - 1)
00667       {
00668         package_name = path_parts[ segment_count ];
00669       }
00670     }
00671 
00672     // check if this directory has a package.xml
00673     package_path = sub_path;
00674     package_path /= "package.xml";
00675     ROS_DEBUG_STREAM("Checking for " << package_path.make_preferred().native());
00676 
00677     // Check if the files exist
00678     if( fs::is_regular_file( package_path ) || fs::is_regular_file( sub_path / "manifest.xml" ))
00679     {
00680       // now generate the relative path
00681       for( size_t relative_count = segment_length; relative_count < path_parts.size(); ++relative_count )
00682         relative_path /= path_parts[ relative_count ];
00683 
00684       // add the URDF filename at end of relative path
00685       relative_path /= urdf_path.filename();
00686 
00687       // end the search
00688       segment_length = 0;
00689       packageFound = true;
00690       break;
00691     }
00692 
00693   }
00694 
00695   // Assign data to moveit_config_data
00696   if( !packageFound )
00697   {
00698     // No package name found, we must be outside ROS
00699     config_data_->urdf_pkg_name_ = "";
00700     config_data_->urdf_pkg_relative_path_ = config_data_->urdf_path_; // just the absolute path
00701   }
00702   else
00703   {
00704     // Check that ROS can find the package
00705     const std::string robot_desc_pkg_path = ros::package::getPath( config_data_->urdf_pkg_name_ ) + "/";
00706 
00707     if( robot_desc_pkg_path.empty() )
00708     {
00709       QMessageBox::warning( this, "Package Not Found In ROS Workspace", QString("ROS was unable to find the package name '")
00710                             .append( config_data_->urdf_pkg_name_.c_str() )
00711                             .append("' within the ROS workspace. This may cause issues later.") );
00712     }
00713 
00714     // Success
00715     config_data_->urdf_pkg_name_ = package_name;
00716     config_data_->urdf_pkg_relative_path_ = relative_path.make_preferred().native();
00717   }
00718 
00719   ROS_DEBUG_STREAM( "URDF Package Name: " << config_data_->urdf_pkg_name_ );
00720   ROS_DEBUG_STREAM( "URDF Package Path: " << config_data_->urdf_pkg_relative_path_ );
00721 
00722   return true; // success
00723 }
00724 
00725 // ******************************************************************************************
00726 // Make the full URDF path using the loaded .setup_assistant data
00727 // ******************************************************************************************
00728 bool StartScreenWidget::createFullURDFPath()
00729 {
00730   fs::path urdf_path;
00731 
00732   // Check if a package name was provided
00733   if( config_data_->urdf_pkg_name_.empty() || config_data_->urdf_pkg_name_ == "\"\"" )
00734   {
00735     urdf_path = config_data_->urdf_pkg_relative_path_;
00736     ROS_WARN("The URDF path is absolute to the filesystem and not relative to a ROS package/stack");
00737   }
00738   else
00739   {
00740 
00741     // Check that ROS can find the package
00742     fs::path robot_desc_pkg_path = ros::package::getPath( config_data_->urdf_pkg_name_ );
00743 
00744     if( robot_desc_pkg_path.empty() )
00745     {
00746       QMessageBox::warning( this, "Error Loading Files", QString("ROS was unable to find the package name '")
00747                             .append( config_data_->urdf_pkg_name_.c_str() )
00748                             .append("'. Verify this package is inside your ROS workspace and is a proper ROS package.") );
00749       return false;
00750     }
00751 
00752     // Append the relative URDF url path
00753     urdf_path = robot_desc_pkg_path;
00754     urdf_path /= config_data_->urdf_pkg_relative_path_;
00755   }
00756 
00757 
00758   // Check that this file exits -------------------------------------------------
00759   if( ! fs::is_regular_file( urdf_path ) )
00760   {
00761     QMessageBox::warning( this, "Error Loading Files",
00762                           QString( "Unable to locate the URDF file in package. File: " )
00763                           .append( urdf_path.make_preferred().native().c_str() ) );
00764     return false;
00765   }
00766 
00767   // Remember the path
00768   config_data_->urdf_path_ = urdf_path.make_preferred().native();
00769 
00770   return true; // success
00771 }
00772 
00773 // ******************************************************************************************
00774 // Make the full SRDF path using the loaded .setup_assistant data
00775 // ******************************************************************************************
00776 bool StartScreenWidget::createFullSRDFPath( const std::string& package_path )
00777 {
00778   // Append the relative SRDF url path
00779   fs::path srdf_path = package_path;
00780   srdf_path /= config_data_->srdf_pkg_relative_path_;
00781   config_data_->srdf_path_ = srdf_path.make_preferred().native();
00782 
00783   // Check that this file exits
00784   if( ! fs::is_regular_file( config_data_->srdf_path_ ) )
00785   {
00786     QMessageBox::warning( this, "Error Loading Files",
00787                           QString("Unable to locate the SRDF file: " )
00788                           .append( config_data_->srdf_path_.c_str() ) );
00789     return false;
00790   }
00791 
00792   return true; // success
00793 }
00794 
00795 // ******************************************************************************************
00796 // Get the full package path for editing an existing package
00797 // ******************************************************************************************
00798 bool StartScreenWidget::createFullPackagePath()
00799 {
00800   // Get package path
00801   std::string package_path_input = stack_path_->getPath();
00802   std::string full_package_path;
00803 
00804   // Trim whitespace from user input
00805   boost::trim( package_path_input );
00806 
00807   // check that input is provided
00808   if( package_path_input.empty() )
00809   {
00810     QMessageBox::warning( this, "Error Loading Files", "Please specify a configuration package path to load." );
00811     return false;
00812   }
00813 
00814   // Decide if this is a package name or a full path ----------------------------------------------
00815 
00816   // check that the folder exists
00817   if( !fs::is_directory( package_path_input ) )
00818   {
00819     // does not exist, check if its a package
00820     full_package_path = ros::package::getPath( package_path_input );
00821 
00822     // check that the folder exists
00823     if( !fs::is_directory( full_package_path ) )
00824     {
00825       // error
00826       QMessageBox::critical( this, "Error Loading Files", "The specified path is not a directory or is not accessable" );
00827       return false;
00828     }
00829   }
00830   else
00831   {
00832     // they inputted a full path
00833     full_package_path = package_path_input;
00834   }
00835 
00836   config_data_->config_pkg_path_ = full_package_path;
00837 
00838   return true;
00839 }
00840 
00841 
00842 // ******************************************************************************************
00843 // ******************************************************************************************
00844 // Class for selecting which mode
00845 // ******************************************************************************************
00846 // ******************************************************************************************
00847 
00848 // ******************************************************************************************
00849 // Create the widget
00850 // ******************************************************************************************
00851 SelectModeWidget::SelectModeWidget( QWidget* parent )
00852   : QFrame(parent)
00853 {
00854   // Set frame graphics
00855   setFrameShape(QFrame::StyledPanel);
00856   setFrameShadow(QFrame::Raised);
00857   setLineWidth(1);
00858   setMidLineWidth(0);
00859 
00860   // Basic widget container
00861   QVBoxLayout *layout = new QVBoxLayout(this);
00862 
00863   // Horizontal layout splitter
00864   QHBoxLayout *hlayout = new QHBoxLayout();
00865 
00866   // Widget Title
00867   QLabel * widget_title = new QLabel(this);
00868   widget_title->setText( "Choose mode:" );
00869   QFont widget_title_font( "Arial", 12, QFont::Bold );
00870   widget_title->setFont(widget_title_font);
00871   layout->addWidget( widget_title);
00872   layout->setAlignment( widget_title, Qt::AlignTop);
00873 
00874   // Widget Instructions
00875   QLabel * widget_instructions = new QLabel(this);
00876   widget_instructions->setText( "All settings for MoveIt are stored in a Moveit configuration package. Here you have the option to create a new configuration package, or load an existing one. Note: any changes to a MoveIt configuration package outside this setup assistant will likely be overwritten by this tool." );
00877   widget_instructions->setWordWrap(true);
00878   //widget_instructions->setMinimumWidth(1);
00879   widget_instructions->setSizePolicy( QSizePolicy::Preferred, QSizePolicy::Preferred );
00880   layout->addWidget( widget_instructions);
00881   layout->setAlignment( widget_instructions, Qt::AlignTop);
00882 
00883   // New Button
00884   btn_new_ = new QPushButton(this);
00885   btn_new_->setText("Create &New MoveIt\nConfiguration Package");
00886   hlayout->addWidget( btn_new_ );
00887 
00888   // Exist Button
00889   btn_exist_ = new QPushButton(this);
00890   btn_exist_->setText("&Edit Existing MoveIt\nConfiguration Package");
00891   hlayout->addWidget( btn_exist_ );
00892 
00893   // Add horizontal layer to verticle layer
00894   layout->addLayout(hlayout);
00895   setLayout(layout);
00896 }
00897 
00898 
00899 } // namespace


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