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 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 GroupEditWidget::GroupEditWidget(QWidget* parent, moveit_setup_assistant::MoveItConfigDataPtr config_data)
00051   : QWidget(parent), config_data_(config_data)
00052 {
00053   // Basic widget container
00054   QVBoxLayout* layout = new QVBoxLayout();
00055 
00056   // Label ------------------------------------------------
00057   title_ = new QLabel(this);  // specify the title from the parent widget
00058   QFont group_title_font("Arial", 12, QFont::Bold);
00059   title_->setFont(group_title_font);
00060   layout->addWidget(title_);
00061 
00062   // Simple form -------------------------------------------
00063   QFormLayout* form_layout = new QFormLayout();
00064   form_layout->setContentsMargins(0, 15, 0, 15);
00065 
00066   // Name input
00067   group_name_field_ = new QLineEdit(this);
00068   group_name_field_->setMaximumWidth(400);
00069   form_layout->addRow("Group Name:", group_name_field_);
00070 
00071   // Kinematic solver
00072   kinematics_solver_field_ = new QComboBox(this);
00073   kinematics_solver_field_->setEditable(false);
00074   kinematics_solver_field_->setMaximumWidth(400);
00075   form_layout->addRow("Kinematic Solver:", kinematics_solver_field_);
00076 
00077   // resolution to use with solver
00078   kinematics_resolution_field_ = new QLineEdit(this);
00079   kinematics_resolution_field_->setMaximumWidth(400);
00080   form_layout->addRow("Kin. Search Resolution:", kinematics_resolution_field_);
00081 
00082   // resolution to use with solver
00083   kinematics_timeout_field_ = new QLineEdit(this);
00084   kinematics_timeout_field_->setMaximumWidth(400);
00085   form_layout->addRow("Kin. Search Timeout (sec):", kinematics_timeout_field_);
00086 
00087   // number of IK attempts
00088   kinematics_attempts_field_ = new QLineEdit(this);
00089   kinematics_attempts_field_->setMaximumWidth(400);
00090   form_layout->addRow("Kin. Solver Attempts:", kinematics_attempts_field_);
00091 
00092   layout->addLayout(form_layout);
00093   layout->setAlignment(Qt::AlignTop);
00094 
00095   // New Group Options  ---------------------------------------------------------
00096   new_buttons_widget_ = new QWidget();
00097   QVBoxLayout* new_buttons_layout = new QVBoxLayout();
00098 
00099   QLabel* save_and_add = new QLabel("Next, Add Components To Group:", this);
00100   QFont save_and_add_font("Arial", 12, QFont::Bold);
00101   save_and_add->setFont(save_and_add_font);
00102   new_buttons_layout->addWidget(save_and_add);
00103 
00104   QLabel* add_subtitle = new QLabel("Recommended: ", this);
00105   QFont add_subtitle_font("Arial", 10, QFont::Bold);
00106   add_subtitle->setFont(add_subtitle_font);
00107   new_buttons_layout->addWidget(add_subtitle);
00108 
00109   // Save and add joints
00110   QPushButton* btn_save_joints = new QPushButton("Add Joints", this);
00111   btn_save_joints->setMaximumWidth(200);
00112   connect(btn_save_joints, SIGNAL(clicked()), this, SIGNAL(saveJoints()));
00113   new_buttons_layout->addWidget(btn_save_joints);
00114 
00115   QLabel* add_subtitle2 = new QLabel("Advanced Options:", this);
00116   add_subtitle2->setFont(add_subtitle_font);
00117   new_buttons_layout->addWidget(add_subtitle2);
00118 
00119   // Save and add links
00120   QPushButton* btn_save_links = new QPushButton("Add Links", this);
00121   btn_save_links->setMaximumWidth(200);
00122   connect(btn_save_links, SIGNAL(clicked()), this, SIGNAL(saveLinks()));
00123   new_buttons_layout->addWidget(btn_save_links);
00124 
00125   // Save and add chain
00126   QPushButton* btn_save_chain = new QPushButton("Add Kin. Chain", this);
00127   btn_save_chain->setMaximumWidth(200);
00128   connect(btn_save_chain, SIGNAL(clicked()), this, SIGNAL(saveChain()));
00129   new_buttons_layout->addWidget(btn_save_chain);
00130 
00131   // Save and add subgroups
00132   QPushButton* btn_save_subgroups = new QPushButton("Add Subgroups", this);
00133   btn_save_subgroups->setMaximumWidth(200);
00134   connect(btn_save_subgroups, SIGNAL(clicked()), this, SIGNAL(saveSubgroups()));
00135   new_buttons_layout->addWidget(btn_save_subgroups);
00136 
00137   // Create widget and add to main layout
00138   new_buttons_widget_->setLayout(new_buttons_layout);
00139   layout->addWidget(new_buttons_widget_);
00140 
00141   // Verticle Spacer -----------------------------------------------------
00142   QWidget* vspacer = new QWidget(this);
00143   vspacer->setSizePolicy(QSizePolicy::Preferred, QSizePolicy::Expanding);
00144   layout->addWidget(vspacer);
00145 
00146   // Bottom Controls ---------------------------------------------------------
00147   QHBoxLayout* controls_layout = new QHBoxLayout();
00148 
00149   // Delete
00150   btn_delete_ = new QPushButton("&Delete Group", this);
00151   btn_delete_->setMaximumWidth(200);
00152   connect(btn_delete_, SIGNAL(clicked()), this, SIGNAL(deleteGroup()));
00153   controls_layout->addWidget(btn_delete_);
00154   controls_layout->setAlignment(btn_delete_, Qt::AlignRight);
00155 
00156   // Horizontal Spacer
00157   QWidget* spacer = new QWidget(this);
00158   spacer->setSizePolicy(QSizePolicy::Expanding, QSizePolicy::Preferred);
00159   controls_layout->addWidget(spacer);
00160 
00161   // Save
00162   btn_save_ = new QPushButton("&Save", this);
00163   btn_save_->setMaximumWidth(200);
00164   connect(btn_save_, SIGNAL(clicked()), this, SIGNAL(save()));
00165   controls_layout->addWidget(btn_save_);
00166   controls_layout->setAlignment(btn_save_, Qt::AlignRight);
00167 
00168   // Cancel
00169   QPushButton* btn_cancel = new QPushButton("&Cancel", this);
00170   btn_cancel->setMaximumWidth(200);
00171   connect(btn_cancel, SIGNAL(clicked()), this, SIGNAL(cancelEditing()));
00172   controls_layout->addWidget(btn_cancel);
00173   controls_layout->setAlignment(btn_cancel, Qt::AlignRight);
00174 
00175   // Add layout
00176   layout->addLayout(controls_layout);
00177 
00178   // Finish Layout --------------------------------------------------
00179   this->setLayout(layout);
00180 }
00181 
00182 // ******************************************************************************************
00183 // Set the link field with previous value
00184 // ******************************************************************************************
00185 void GroupEditWidget::setSelected(const std::string& group_name)
00186 {
00187   group_name_field_->setText(QString(group_name.c_str()));
00188 
00189   // Load properties from moveit_config_data.cpp ----------------------------------------------
00190 
00191   // Load resolution
00192   double* resolution = &config_data_->group_meta_data_[group_name].kinematics_solver_search_resolution_;
00193   if (*resolution == 0)
00194   {
00195     // Set default value
00196     *resolution = DEFAULT_KIN_SOLVER_SEARCH_RESOLUTION_;
00197   }
00198   kinematics_resolution_field_->setText(QString::number(*resolution));
00199 
00200   // Load timeout
00201   double* timeout = &config_data_->group_meta_data_[group_name].kinematics_solver_timeout_;
00202   if (*timeout == 0)
00203   {
00204     // Set default value
00205     *timeout = DEFAULT_KIN_SOLVER_TIMEOUT_;
00206   }
00207   kinematics_timeout_field_->setText(QString::number(*timeout));
00208 
00209   // Load attempts
00210   int* attempts = &config_data_->group_meta_data_[group_name].kinematics_solver_attempts_;
00211   if (*attempts == 0)
00212   {
00213     // Set default value
00214     *attempts = DEFAULT_KIN_SOLVER_ATTEMPTS_;
00215   }
00216   kinematics_attempts_field_->setText(QString::number(*attempts));
00217 
00218   // Set kin solver
00219   std::string kin_solver = config_data_->group_meta_data_[group_name].kinematics_solver_;
00220 
00221   // If this group doesn't have a solver, reset it to 'None'
00222   if (kin_solver.empty())
00223   {
00224     kin_solver = "None";
00225   }
00226 
00227   // Set the kin solver combo box
00228   int index = kinematics_solver_field_->findText(kin_solver.c_str());
00229   if (index == -1)
00230   {
00231     QMessageBox::warning(this, "Missing Kinematic Solvers",
00232                          QString("Unable to find the kinematic solver '")
00233                              .append(kin_solver.c_str())
00234                              .append("'. Trying running rosmake for this package. Until fixed, this setting will be "
00235                                      "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 "
00272                                                             "solver plugins");
00273     ROS_ERROR_STREAM(ex.what());
00274     return;
00275   }
00276 
00277   // Get classes
00278   const std::vector<std::string>& classes = loader->getDeclaredClasses();
00279 
00280   // Warn if no plugins are found
00281   if (classes.empty())
00282   {
00283     QMessageBox::warning(this, "Missing Kinematic Solvers", "No MoveIt!-compatible kinematics solvers found. Try "
00284                                                             "installing moveit_kinematics (sudo apt-get install "
00285                                                             "ros-${ROS_DISTRO}-moveit-kinematics)");
00286     return;
00287   }
00288 
00289   // Loop through all planners and add to combo box
00290   for (std::vector<std::string>::const_iterator plugin_it = classes.begin(); plugin_it != classes.end(); ++plugin_it)
00291   {
00292     kinematics_solver_field_->addItem(plugin_it->c_str());
00293   }
00294 }
00295 
00296 }  // namespace


moveit_setup_assistant
Author(s): Dave Coleman
autogenerated on Wed Jun 19 2019 19:25:13