group_edit_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 #include <QVBoxLayout>
00038 #include <QHBoxLayout>
00039 #include <QMessageBox>
00040 #include <QFormLayout>
00041 #include <QString>
00042 #include "group_edit_widget.h"
00043 #include <pluginlib/class_loader.h> // for loading all avail kinematic planners
00044 
00045 namespace moveit_setup_assistant
00046 {
00047 
00048 // ******************************************************************************************
00049 //
00050 // ******************************************************************************************
00051 GroupEditWidget::GroupEditWidget( QWidget *parent, moveit_setup_assistant::MoveItConfigDataPtr config_data )
00052   :  QWidget( parent ), config_data_( config_data )
00053 {
00054   // Basic widget container
00055   QVBoxLayout *layout = new QVBoxLayout( );
00056 
00057   // Label ------------------------------------------------
00058   title_ = new QLabel( this ); // specify the title from the parent widget
00059   QFont group_title_font( "Arial", 12, QFont::Bold );
00060   title_->setFont(group_title_font);
00061   layout->addWidget( title_ );
00062 
00063   // Simple form -------------------------------------------
00064   QFormLayout *form_layout = new QFormLayout();
00065   form_layout->setContentsMargins( 0, 15, 0, 15 );
00066 
00067   // Name input
00068   group_name_field_ = new QLineEdit( this );
00069   group_name_field_->setMaximumWidth( 400 );
00070   form_layout->addRow( "Group Name:", group_name_field_ );
00071 
00072   // Kinematic solver
00073   kinematics_solver_field_ = new QComboBox( this );
00074   kinematics_solver_field_->setEditable( false );
00075   kinematics_solver_field_->setMaximumWidth( 400 );
00076   form_layout->addRow( "Kinematic Solver:", kinematics_solver_field_ );
00077 
00078   // resolution to use with solver
00079   kinematics_resolution_field_ = new QLineEdit( this );
00080   kinematics_resolution_field_->setMaximumWidth( 400 );
00081   form_layout->addRow( "Kin. Search Resolution:", kinematics_resolution_field_ );
00082 
00083   // resolution to use with solver
00084   kinematics_timeout_field_ = new QLineEdit( this );
00085   kinematics_timeout_field_->setMaximumWidth( 400 );
00086   form_layout->addRow( "Kin. Search Timeout (sec):", kinematics_timeout_field_ );
00087 
00088   // number of IK attempts
00089   kinematics_attempts_field_ = new QLineEdit( this );
00090   kinematics_attempts_field_->setMaximumWidth( 400 );
00091   form_layout->addRow( "Kin. Solver Attempts:", kinematics_attempts_field_ );
00092 
00093   layout->addLayout( form_layout );
00094   layout->setAlignment( Qt::AlignTop );
00095 
00096   // New Group Options  ---------------------------------------------------------
00097   new_buttons_widget_ = new QWidget();
00098   QVBoxLayout *new_buttons_layout = new QVBoxLayout();
00099 
00100   QLabel *save_and_add = new QLabel( "Next, Add Components To Group:", this );
00101   QFont save_and_add_font( "Arial", 12, QFont::Bold );
00102   save_and_add->setFont( save_and_add_font );
00103   new_buttons_layout->addWidget( save_and_add );
00104 
00105   QLabel *add_subtitle = new QLabel( "Recommended: ", this );
00106   QFont add_subtitle_font( "Arial", 10, QFont::Bold );
00107   add_subtitle->setFont( add_subtitle_font );
00108   new_buttons_layout->addWidget( add_subtitle );
00109 
00110   // Save and add joints
00111   QPushButton *btn_save_joints = new QPushButton( "Add Joints", this );
00112   btn_save_joints->setMaximumWidth( 200 );
00113   connect( btn_save_joints, SIGNAL(clicked()), this, SIGNAL( saveJoints() ) );
00114   new_buttons_layout->addWidget( btn_save_joints );
00115 
00116   QLabel *add_subtitle2 = new QLabel( "Advanced Options:", this );
00117   add_subtitle2->setFont( add_subtitle_font );
00118   new_buttons_layout->addWidget( add_subtitle2 );
00119 
00120   // Save and add links
00121   QPushButton *btn_save_links = new QPushButton( "Add Links", this );
00122   btn_save_links->setMaximumWidth( 200 );
00123   connect( btn_save_links, SIGNAL(clicked()), this, SIGNAL( saveLinks() ) );
00124   new_buttons_layout->addWidget( btn_save_links );
00125 
00126   // Save and add chain
00127   QPushButton *btn_save_chain = new QPushButton( "Add Kin. Chain", this );
00128   btn_save_chain->setMaximumWidth( 200 );
00129   connect( btn_save_chain, SIGNAL(clicked()), this, SIGNAL( saveChain() ) );
00130   new_buttons_layout->addWidget( btn_save_chain );
00131 
00132   // Save and add subgroups
00133   QPushButton *btn_save_subgroups = new QPushButton( "Add Subgroups", this );
00134   btn_save_subgroups->setMaximumWidth( 200 );
00135   connect( btn_save_subgroups, SIGNAL(clicked()), this, SIGNAL( saveSubgroups() ) );
00136   new_buttons_layout->addWidget( btn_save_subgroups );
00137 
00138   // Create widget and add to main layout
00139   new_buttons_widget_->setLayout( new_buttons_layout );
00140   layout->addWidget( new_buttons_widget_ );
00141 
00142   // Verticle Spacer -----------------------------------------------------
00143   QWidget *vspacer = new QWidget( this );
00144   vspacer->setSizePolicy( QSizePolicy::Preferred, QSizePolicy::Expanding );
00145   layout->addWidget( vspacer );
00146 
00147   // Bottom Controls ---------------------------------------------------------
00148   QHBoxLayout *controls_layout = new QHBoxLayout();
00149 
00150   // Delete
00151   btn_delete_ = new QPushButton( "&Delete Group", this );
00152   btn_delete_->setMaximumWidth( 200 );
00153   connect( btn_delete_, SIGNAL(clicked()), this, SIGNAL( deleteGroup() ) );
00154   controls_layout->addWidget( btn_delete_ );
00155   controls_layout->setAlignment(btn_delete_, Qt::AlignRight);
00156 
00157   // Horizontal Spacer
00158   QWidget *spacer = new QWidget( this );
00159   spacer->setSizePolicy( QSizePolicy::Expanding, QSizePolicy::Preferred );
00160   controls_layout->addWidget( spacer );
00161 
00162   // Save
00163   btn_save_ = new QPushButton( "&Save", this );
00164   btn_save_->setMaximumWidth( 200 );
00165   connect( btn_save_, SIGNAL(clicked()), this, SIGNAL( save() ) );
00166   controls_layout->addWidget( btn_save_ );
00167   controls_layout->setAlignment(btn_save_, Qt::AlignRight);
00168 
00169   // Cancel
00170   QPushButton *btn_cancel = new QPushButton( "&Cancel", this );
00171   btn_cancel->setMaximumWidth( 200 );
00172   connect( btn_cancel, SIGNAL(clicked()), this, SIGNAL( cancelEditing() ) );
00173   controls_layout->addWidget( btn_cancel );
00174   controls_layout->setAlignment(btn_cancel, Qt::AlignRight);
00175 
00176   // Add layout
00177   layout->addLayout( controls_layout );
00178 
00179   // Finish Layout --------------------------------------------------
00180   this->setLayout(layout);
00181 
00182 }
00183 
00184 // ******************************************************************************************
00185 // Set the link field with previous value
00186 // ******************************************************************************************
00187 void GroupEditWidget::setSelected( const std::string &group_name )
00188 {
00189   group_name_field_->setText( QString( group_name.c_str() ) );
00190 
00191   // Load properties from moveit_config_data.cpp ----------------------------------------------
00192 
00193   // Load resolution
00194   double *resolution = &config_data_->group_meta_data_[ group_name ].kinematics_solver_search_resolution_;
00195   if( *resolution == 0 )
00196   {
00197     // Set default value
00198     *resolution = DEFAULT_KIN_SOLVER_SEARCH_RESOLUTION_;
00199   }
00200   kinematics_resolution_field_->setText( QString::number( *resolution ) );
00201 
00202   // Load timeout
00203   double *timeout = &config_data_->group_meta_data_[ group_name ].kinematics_solver_timeout_;
00204   if( *timeout == 0 )
00205   {
00206     // Set default value
00207     *timeout = DEFAULT_KIN_SOLVER_TIMEOUT_;
00208   }
00209   kinematics_timeout_field_->setText( QString::number( *timeout ) );
00210 
00211   // Load attempts
00212   int *attempts = &config_data_->group_meta_data_[ group_name ].kinematics_solver_attempts_;
00213   if( *attempts == 0 )
00214   {
00215     // Set default value
00216     *attempts = DEFAULT_KIN_SOLVER_ATTEMPTS_;
00217   }
00218   kinematics_attempts_field_->setText( QString::number( *attempts ) );
00219 
00220   // Set kin solver
00221   std::string kin_solver = config_data_->group_meta_data_[ group_name ].kinematics_solver_;
00222 
00223   // If this group doesn't have a solver, reset it to 'None'
00224   if( kin_solver.empty() )
00225   {
00226     kin_solver = "None";
00227   }
00228 
00229   // Set the kin solver combo box
00230   int index = kinematics_solver_field_->findText( kin_solver.c_str() );
00231   if( index == -1 )
00232   {
00233     QMessageBox::warning( this, "Missing Kinematic Solvers",
00234                           QString( "Unable to find the kinematic solver '").append( kin_solver.c_str() )
00235                           .append( "'. Trying running rosmake for this package. Until fixed, this setting will be lost the next time the MoveIt configuration files are generated" ));
00236     return;
00237   }
00238   else
00239   {
00240     kinematics_solver_field_->setCurrentIndex( index );
00241   }
00242 
00243   // Set default
00244 }
00245 
00246 // ******************************************************************************************
00247 // Populate the combo dropdown box with kinematic planners
00248 // ******************************************************************************************
00249 void GroupEditWidget::loadKinematicPlannersComboBox()
00250 {
00251   // Only load this combo box once
00252   static bool hasLoaded = false;
00253   if( hasLoaded )
00254     return;
00255   hasLoaded = true;
00256 
00257   // Remove all old items
00258   kinematics_solver_field_->clear();
00259 
00260   // Add none option, the default
00261   kinematics_solver_field_->addItem( "None" );
00262 
00263   // load all avail kin planners
00264   boost::scoped_ptr<pluginlib::ClassLoader<kinematics::KinematicsBase> > loader;
00265   try
00266   {
00267     loader.reset(new pluginlib::ClassLoader<kinematics::KinematicsBase>("moveit_core", "kinematics::KinematicsBase"));
00268   }
00269   catch(pluginlib::PluginlibException& ex)
00270   {
00271     QMessageBox::warning( this, "Missing Kinematic Solvers", "Exception while creating class loader for kinematic solver plugins");
00272     ROS_ERROR_STREAM( ex.what() );
00273     return;
00274   }
00275 
00276   // Get classes
00277   const std::vector<std::string> &classes = loader->getDeclaredClasses();
00278 
00279   // Loop through all planners and add to combo box
00280   for( std::vector<std::string>::const_iterator plugin_it = classes.begin();
00281        plugin_it != classes.end(); ++plugin_it )
00282   {
00283     kinematics_solver_field_->addItem( plugin_it->c_str() );
00284   }
00285 
00286 
00287 
00288 }
00289 
00290 } // namespace


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