virtual_joints_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 // SA
00038 #include "virtual_joints_widget.h"
00039 // Qt
00040 #include <QFormLayout>
00041 #include <QMessageBox>
00042 #include <QApplication>
00043 
00044 namespace moveit_setup_assistant
00045 {
00046 // ******************************************************************************************
00047 // Constructor
00048 // ******************************************************************************************
00049 VirtualJointsWidget::VirtualJointsWidget(QWidget* parent, moveit_setup_assistant::MoveItConfigDataPtr config_data)
00050   : SetupScreenWidget(parent), config_data_(config_data)
00051 {
00052   // Basic widget container
00053   QVBoxLayout* layout = new QVBoxLayout();
00054 
00055   // Top Header Area ------------------------------------------------
00056 
00057   HeaderWidget* header =
00058       new HeaderWidget("Virtual Joints", "Define a virtual joint between a robot link and an external frame of "
00059                                          "reference (considered fixed with respect to the robot).",
00060                        this);
00061   layout->addWidget(header);
00062 
00063   // Create contents screens ---------------------------------------
00064 
00065   vjoint_list_widget_ = createContentsWidget();
00066   vjoint_edit_widget_ = createEditWidget();
00067 
00068   // Create stacked layout -----------------------------------------
00069   stacked_layout_ = new QStackedLayout(this);
00070   stacked_layout_->addWidget(vjoint_list_widget_);  // screen index 0
00071   stacked_layout_->addWidget(vjoint_edit_widget_);  // screen index 1
00072 
00073   // Create Widget wrapper for layout
00074   QWidget* stacked_layout_widget = new QWidget(this);
00075   stacked_layout_widget->setLayout(stacked_layout_);
00076 
00077   layout->addWidget(stacked_layout_widget);
00078 
00079   // Finish Layout --------------------------------------------------
00080   this->setLayout(layout);
00081 }
00082 
00083 // ******************************************************************************************
00084 // Create the main content widget
00085 // ******************************************************************************************
00086 QWidget* VirtualJointsWidget::createContentsWidget()
00087 {
00088   // Main widget
00089   QWidget* content_widget = new QWidget(this);
00090 
00091   // Basic widget container
00092   QVBoxLayout* layout = new QVBoxLayout(this);
00093 
00094   // Table ------------ ------------------------------------------------
00095 
00096   data_table_ = new QTableWidget(this);
00097   data_table_->setColumnCount(4);
00098   data_table_->setSortingEnabled(true);
00099   data_table_->setSelectionBehavior(QAbstractItemView::SelectRows);
00100   connect(data_table_, SIGNAL(cellDoubleClicked(int, int)), this, SLOT(editDoubleClicked(int, int)));
00101   connect(data_table_, SIGNAL(cellClicked(int, int)), this, SLOT(previewClicked(int, int)));
00102   layout->addWidget(data_table_);
00103 
00104   // Set header labels
00105   QStringList header_list;
00106   header_list.append("Virtual Joint Name");
00107   header_list.append("Child Link");
00108   header_list.append("Parent Frame");
00109   header_list.append("Type");
00110   data_table_->setHorizontalHeaderLabels(header_list);
00111 
00112   // Bottom Buttons --------------------------------------------------
00113 
00114   QHBoxLayout* controls_layout = new QHBoxLayout();
00115 
00116   // Spacer
00117   QWidget* spacer = new QWidget(this);
00118   spacer->setSizePolicy(QSizePolicy::Expanding, QSizePolicy::Preferred);
00119   controls_layout->addWidget(spacer);
00120 
00121   // Edit Selected Button
00122   btn_edit_ = new QPushButton("&Edit Selected", this);
00123   btn_edit_->setSizePolicy(QSizePolicy::Expanding, QSizePolicy::Preferred);
00124   btn_edit_->setMaximumWidth(300);
00125   btn_edit_->hide();  // show once we know if there are existing poses
00126   connect(btn_edit_, SIGNAL(clicked()), this, SLOT(editSelected()));
00127   controls_layout->addWidget(btn_edit_);
00128   controls_layout->setAlignment(btn_edit_, Qt::AlignRight);
00129 
00130   // Delete Selected Button
00131   btn_delete_ = new QPushButton("&Delete Selected", this);
00132   connect(btn_delete_, SIGNAL(clicked()), this, SLOT(deleteSelected()));
00133   controls_layout->addWidget(btn_delete_);
00134   controls_layout->setAlignment(btn_delete_, Qt::AlignRight);
00135 
00136   // Add VJoint Button
00137   QPushButton* btn_add = new QPushButton("&Add Virtual Joint", this);
00138   btn_add->setSizePolicy(QSizePolicy::Expanding, QSizePolicy::Preferred);
00139   btn_add->setMaximumWidth(300);
00140   connect(btn_add, SIGNAL(clicked()), this, SLOT(showNewScreen()));
00141   controls_layout->addWidget(btn_add);
00142   controls_layout->setAlignment(btn_add, Qt::AlignRight);
00143 
00144   // Add layout
00145   layout->addLayout(controls_layout);
00146 
00147   // Set layout -----------------------------------------------------
00148   content_widget->setLayout(layout);
00149 
00150   return content_widget;
00151 }
00152 
00153 // ******************************************************************************************
00154 // Create the edit widget
00155 // ******************************************************************************************
00156 QWidget* VirtualJointsWidget::createEditWidget()
00157 {
00158   // Main widget
00159   QWidget* edit_widget = new QWidget(this);
00160   // Layout
00161   QVBoxLayout* layout = new QVBoxLayout();
00162 
00163   // Simple form -------------------------------------------
00164   QFormLayout* form_layout = new QFormLayout();
00165   // form_layout->setContentsMargins( 0, 15, 0, 15 );
00166   form_layout->setRowWrapPolicy(QFormLayout::WrapAllRows);
00167 
00168   // Name input
00169   vjoint_name_field_ = new QLineEdit(this);
00170   form_layout->addRow("Virtual Joint Name:", vjoint_name_field_);
00171 
00172   // Child Link input
00173   child_link_field_ = new QComboBox(this);
00174   child_link_field_->setEditable(false);
00175   form_layout->addRow("Child Link:", child_link_field_);
00176 
00177   // Parent frame name input
00178   parent_name_field_ = new QLineEdit(this);
00179   form_layout->addRow("Parent Frame Name:", parent_name_field_);
00180 
00181   // Type input
00182   joint_type_field_ = new QComboBox(this);
00183   joint_type_field_->setEditable(false);
00184   loadJointTypesComboBox();  // only do this once
00185   // connect( joint_type_field_, SIGNAL( currentIndexChanged( const QString & ) ),
00186   //         this, SLOT( loadJoinSliders( const QString & ) ) );
00187   form_layout->addRow("Joint Type:", joint_type_field_);
00188 
00189   layout->addLayout(form_layout);
00190 
00191   // Bottom Buttons --------------------------------------------------
00192 
00193   QHBoxLayout* controls_layout = new QHBoxLayout();
00194   controls_layout->setContentsMargins(0, 25, 0, 15);
00195 
00196   // Spacer
00197   QWidget* spacer = new QWidget(this);
00198   spacer->setSizePolicy(QSizePolicy::Expanding, QSizePolicy::Preferred);
00199   controls_layout->addWidget(spacer);
00200 
00201   // Save
00202   QPushButton* btn_save_ = new QPushButton("&Save", this);
00203   btn_save_->setMaximumWidth(200);
00204   connect(btn_save_, SIGNAL(clicked()), this, SLOT(doneEditing()));
00205   controls_layout->addWidget(btn_save_);
00206   controls_layout->setAlignment(btn_save_, Qt::AlignRight);
00207 
00208   // Cancel
00209   QPushButton* btn_cancel_ = new QPushButton("&Cancel", this);
00210   btn_cancel_->setMaximumWidth(200);
00211   connect(btn_cancel_, SIGNAL(clicked()), this, SLOT(cancelEditing()));
00212   controls_layout->addWidget(btn_cancel_);
00213   controls_layout->setAlignment(btn_cancel_, Qt::AlignRight);
00214 
00215   // Add layout
00216   layout->addLayout(controls_layout);
00217 
00218   // Set layout -----------------------------------------------------
00219   edit_widget->setLayout(layout);
00220 
00221   return edit_widget;
00222 }
00223 
00224 // ******************************************************************************************
00225 // Show edit screen for creating a new vjoint
00226 // ******************************************************************************************
00227 void VirtualJointsWidget::showNewScreen()
00228 {
00229   // Remember that this is a new vjoint
00230   current_edit_vjoint_.clear();
00231 
00232   // Clear previous data
00233   vjoint_name_field_->setText("");
00234   parent_name_field_->setText("");
00235   child_link_field_->clearEditText();
00236   joint_type_field_->clearEditText();  // actually this just chooses first option
00237 
00238   // Switch to screen
00239   stacked_layout_->setCurrentIndex(1);
00240 
00241   // Announce that this widget is in modal mode
00242   Q_EMIT isModal(true);
00243 }
00244 
00245 // ******************************************************************************************
00246 // Edit whatever element is selected
00247 // ******************************************************************************************
00248 void VirtualJointsWidget::editDoubleClicked(int row, int column)
00249 {
00250   editSelected();
00251 }
00252 
00253 // ******************************************************************************************
00254 // Preview whatever element is selected
00255 // ******************************************************************************************
00256 void VirtualJointsWidget::previewClicked(int row, int column)
00257 {
00258   // TODO: highlight the virtual joint?
00259 
00260   /*  // Get list of all selected items
00261   QList<QTableWidgetItem*> selected = data_table_->selectedItems();
00262 
00263   // Check that an element was selected
00264   if( !selected.size() )
00265     return;
00266 
00267   // Find the selected in datastructure
00268   srdf::Model::GroupState *vjoint = findVjointByName( selected[0]->text().toStdString() );
00269 
00270   // Set vjoint joint values by adding them to the local joint state map
00271   for( std::map<std::string, std::vector<double> >::const_iterator value_it = vjoint->joint_values_.begin();
00272        value_it != vjoint->joint_values_.end(); ++value_it )
00273   {
00274     // Only copy the first joint value
00275     joint_state_map_[ value_it->first ] = value_it->second[0];
00276   }
00277 
00278   // Update the joints
00279   publishJoints();
00280   */
00281 }
00282 
00283 // ******************************************************************************************
00284 // Edit whatever element is selected
00285 // ******************************************************************************************
00286 void VirtualJointsWidget::editSelected()
00287 {
00288   // Get list of all selected items
00289   QList<QTableWidgetItem*> selected = data_table_->selectedItems();
00290 
00291   // Check that an element was selected
00292   if (!selected.size())
00293     return;
00294 
00295   // Get selected name and edit it
00296   edit(selected[0]->text().toStdString());
00297 }
00298 
00299 // ******************************************************************************************
00300 // Edit vjoint
00301 // ******************************************************************************************
00302 void VirtualJointsWidget::edit(const std::string& name)
00303 {
00304   // Remember what we are editing
00305   current_edit_vjoint_ = name;
00306 
00307   // Find the selected in datastruture
00308   srdf::Model::VirtualJoint* vjoint = findVJointByName(name);
00309 
00310   // Set vjoint name
00311   vjoint_name_field_->setText(vjoint->name_.c_str());
00312   parent_name_field_->setText(vjoint->parent_frame_.c_str());
00313 
00314   // Set vjoint child link
00315   int index = child_link_field_->findText(vjoint->child_link_.c_str());
00316   if (index == -1)
00317   {
00318     QMessageBox::critical(this, "Error Loading", "Unable to find child link in drop down box");
00319     return;
00320   }
00321   child_link_field_->setCurrentIndex(index);
00322 
00323   // Set joint type
00324   index = joint_type_field_->findText(vjoint->type_.c_str());
00325   if (index == -1)
00326   {
00327     QMessageBox::critical(this, "Error Loading", "Unable to find joint type in drop down box");
00328     return;
00329   }
00330   joint_type_field_->setCurrentIndex(index);
00331 
00332   // Switch to screen
00333   stacked_layout_->setCurrentIndex(1);
00334 
00335   // Announce that this widget is in modal mode
00336   Q_EMIT isModal(true);
00337 }
00338 
00339 // ******************************************************************************************
00340 // Populate the combo dropdown box with joint types
00341 // ******************************************************************************************
00342 void VirtualJointsWidget::loadJointTypesComboBox()
00343 {
00344   // Remove all old items
00345   joint_type_field_->clear();
00346 
00347   // joint types (hard coded)
00348   joint_type_field_->addItem("fixed");
00349   joint_type_field_->addItem("floating");
00350   joint_type_field_->addItem("planar");
00351 }
00352 
00353 // ******************************************************************************************
00354 // Populate the combo dropdown box with avail child links
00355 // ******************************************************************************************
00356 void VirtualJointsWidget::loadChildLinksComboBox()
00357 {
00358   // Remove all old links
00359   child_link_field_->clear();
00360 
00361   // Get all links in robot model
00362   std::vector<const robot_model::LinkModel*> link_models = config_data_->getRobotModel()->getLinkModels();
00363 
00364   // Add all links to combo box
00365   for (std::vector<const robot_model::LinkModel*>::const_iterator link_it = link_models.begin();
00366        link_it < link_models.end(); ++link_it)
00367   {
00368     child_link_field_->addItem((*link_it)->getName().c_str());
00369   }
00370 }
00371 
00372 // ******************************************************************************************
00373 // Find the associated data by name
00374 // ******************************************************************************************
00375 srdf::Model::VirtualJoint* VirtualJointsWidget::findVJointByName(const std::string& name)
00376 {
00377   // Find the group state we are editing based on the vjoint name
00378   srdf::Model::VirtualJoint* searched_group = NULL;  // used for holding our search results
00379 
00380   for (std::vector<srdf::Model::VirtualJoint>::iterator vjoint_it = config_data_->srdf_->virtual_joints_.begin();
00381        vjoint_it != config_data_->srdf_->virtual_joints_.end(); ++vjoint_it)
00382   {
00383     if (vjoint_it->name_ == name)  // string match
00384     {
00385       searched_group = &(*vjoint_it);  // convert to pointer from iterator
00386       break;                           // we are done searching
00387     }
00388   }
00389 
00390   // Check if vjoint was found
00391   if (searched_group == NULL)  // not found
00392   {
00393     QMessageBox::critical(this, "Error Saving", "An internal error has occured while saving. Quitting.");
00394     QApplication::quit();
00395   }
00396 
00397   return searched_group;
00398 }
00399 
00400 // ******************************************************************************************
00401 // Delete currently editing item
00402 // ******************************************************************************************
00403 void VirtualJointsWidget::deleteSelected()
00404 {
00405   // Get list of all selected items
00406   QList<QTableWidgetItem*> selected = data_table_->selectedItems();
00407 
00408   // Check that an element was selected
00409   if (!selected.size())
00410     return;
00411 
00412   // Get selected name and edit it
00413   current_edit_vjoint_ = selected[0]->text().toStdString();
00414 
00415   // Confirm user wants to delete group
00416   if (QMessageBox::question(this, "Confirm Virtual Joint Deletion",
00417                             QString("Are you sure you want to delete the virtual joint '")
00418                                 .append(current_edit_vjoint_.c_str())
00419                                 .append("'?"),
00420                             QMessageBox::Ok | QMessageBox::Cancel) == QMessageBox::Cancel)
00421   {
00422     return;
00423   }
00424 
00425   // Delete vjoint from vector
00426   for (std::vector<srdf::Model::VirtualJoint>::iterator vjoint_it = config_data_->srdf_->virtual_joints_.begin();
00427        vjoint_it != config_data_->srdf_->virtual_joints_.end(); ++vjoint_it)
00428   {
00429     // check if this is the group we want to delete
00430     if (vjoint_it->name_ == current_edit_vjoint_)  // string match
00431     {
00432       config_data_->srdf_->virtual_joints_.erase(vjoint_it);
00433       break;
00434     }
00435   }
00436 
00437   // Reload main screen table
00438   loadDataTable();
00439   config_data_->changes |= MoveItConfigData::VIRTUAL_JOINTS;
00440 }
00441 
00442 // ******************************************************************************************
00443 // Save editing changes
00444 // ******************************************************************************************
00445 void VirtualJointsWidget::doneEditing()
00446 {
00447   // Get a reference to the supplied strings
00448   const std::string vjoint_name = vjoint_name_field_->text().toStdString();
00449   const std::string parent_name = parent_name_field_->text().toStdString();
00450 
00451   // Used for editing existing groups
00452   srdf::Model::VirtualJoint* searched_data = NULL;
00453 
00454   // Check that name field is not empty
00455   if (vjoint_name.empty())
00456   {
00457     QMessageBox::warning(this, "Error Saving", "A name must be given for the virtual joint!");
00458     return;
00459   }
00460 
00461   // Check that parent frame name field is not empty
00462   if (parent_name.empty())
00463   {
00464     QMessageBox::warning(this, "Error Saving", "A name must be given for the parent frame");
00465     return;
00466   }
00467 
00468   // Check if this is an existing vjoint
00469   if (!current_edit_vjoint_.empty())
00470   {
00471     // Find the group we are editing based on the goup name string
00472     searched_data = findVJointByName(current_edit_vjoint_);
00473   }
00474 
00475   // Check that the vjoint name is unique
00476   for (std::vector<srdf::Model::VirtualJoint>::const_iterator data_it = config_data_->srdf_->virtual_joints_.begin();
00477        data_it != config_data_->srdf_->virtual_joints_.end(); ++data_it)
00478   {
00479     if (data_it->name_.compare(vjoint_name) == 0)  // the names are the same
00480     {
00481       // is this our existing vjoint? check if vjoint pointers are same
00482       if (&(*data_it) != searched_data)
00483       {
00484         QMessageBox::warning(this, "Error Saving", "A virtual joint already exists with that name!");
00485         return;
00486       }
00487     }
00488   }
00489 
00490   // Check that a joint type was selected
00491   if (joint_type_field_->currentText().isEmpty())
00492   {
00493     QMessageBox::warning(this, "Error Saving", "A joint type must be chosen!");
00494     return;
00495   }
00496 
00497   // Check that a child link was selected
00498   if (child_link_field_->currentText().isEmpty())
00499   {
00500     QMessageBox::warning(this, "Error Saving", "A child link must be chosen!");
00501     return;
00502   }
00503 
00504   config_data_->changes |= MoveItConfigData::VIRTUAL_JOINTS;
00505 
00506   // Save the new vjoint name or create the new vjoint ----------------------------
00507   bool isNew = false;
00508 
00509   if (searched_data == NULL)  // create new
00510   {
00511     isNew = true;
00512 
00513     searched_data = new srdf::Model::VirtualJoint();
00514   }
00515 
00516   // Copy name data ----------------------------------------------------
00517   searched_data->name_ = vjoint_name;
00518   searched_data->parent_frame_ = parent_name;
00519   searched_data->child_link_ = child_link_field_->currentText().toStdString();
00520   searched_data->type_ = joint_type_field_->currentText().toStdString();
00521 
00522   bool emit_frame_notice = false;
00523 
00524   // Insert new vjoints into group state vector --------------------------
00525   if (isNew)
00526   {
00527     if (searched_data->child_link_ == config_data_->getRobotModel()->getRootLinkName())
00528       emit_frame_notice = true;
00529     config_data_->srdf_->virtual_joints_.push_back(*searched_data);
00530     config_data_->updateRobotModel();
00531   }
00532 
00533   // Finish up ------------------------------------------------------
00534 
00535   // Reload main screen table
00536   loadDataTable();
00537 
00538   // Switch to screen
00539   stacked_layout_->setCurrentIndex(0);
00540 
00541   // Announce that this widget is not in modal mode
00542   Q_EMIT isModal(false);
00543 
00544   // if the root frame changed for the robot, emit the signal
00545   if (emit_frame_notice)
00546   {
00547     Q_EMIT referenceFrameChanged();
00548   }
00549 }
00550 
00551 // ******************************************************************************************
00552 // Cancel changes
00553 // ******************************************************************************************
00554 void VirtualJointsWidget::cancelEditing()
00555 {
00556   // Switch to screen
00557   stacked_layout_->setCurrentIndex(0);
00558 
00559   // Announce that this widget is not in modal mode
00560   Q_EMIT isModal(false);
00561 }
00562 
00563 // ******************************************************************************************
00564 // Load the virtual joints into the table
00565 // ******************************************************************************************
00566 void VirtualJointsWidget::loadDataTable()
00567 {
00568   // Disable Table
00569   data_table_->setUpdatesEnabled(false);  // prevent table from updating until we are completely done
00570   data_table_->setDisabled(true);         // make sure we disable it so that the cellChanged event is not called
00571   data_table_->clearContents();
00572 
00573   // Set size of datatable
00574   data_table_->setRowCount(config_data_->srdf_->virtual_joints_.size());
00575 
00576   // Loop through every virtual joint
00577   int row = 0;
00578   for (std::vector<srdf::Model::VirtualJoint>::const_iterator data_it = config_data_->srdf_->virtual_joints_.begin();
00579        data_it != config_data_->srdf_->virtual_joints_.end(); ++data_it)
00580   {
00581     // Create row elements
00582     QTableWidgetItem* data_name = new QTableWidgetItem(data_it->name_.c_str());
00583     data_name->setFlags(Qt::ItemIsEnabled | Qt::ItemIsSelectable);
00584     QTableWidgetItem* child_link_name = new QTableWidgetItem(data_it->child_link_.c_str());
00585     child_link_name->setFlags(Qt::ItemIsEnabled | Qt::ItemIsSelectable);
00586     QTableWidgetItem* parent_frame_name = new QTableWidgetItem(data_it->parent_frame_.c_str());
00587     parent_frame_name->setFlags(Qt::ItemIsEnabled | Qt::ItemIsSelectable);
00588     QTableWidgetItem* type_name = new QTableWidgetItem(data_it->type_.c_str());
00589     type_name->setFlags(Qt::ItemIsEnabled | Qt::ItemIsSelectable);
00590 
00591     // Add to table
00592     data_table_->setItem(row, 0, data_name);
00593     data_table_->setItem(row, 1, child_link_name);
00594     data_table_->setItem(row, 2, parent_frame_name);
00595     data_table_->setItem(row, 3, type_name);
00596 
00597     // Increment counter
00598     ++row;
00599   }
00600 
00601   // Reenable
00602   data_table_->setUpdatesEnabled(true);  // prevent table from updating until we are completely done
00603   data_table_->setDisabled(false);       // make sure we disable it so that the cellChanged event is not called
00604 
00605   // Resize header
00606   data_table_->resizeColumnToContents(0);
00607   data_table_->resizeColumnToContents(1);
00608   data_table_->resizeColumnToContents(2);
00609   data_table_->resizeColumnToContents(3);
00610 
00611   // Show edit button if applicable
00612   if (config_data_->srdf_->virtual_joints_.size())
00613     btn_edit_->show();
00614 }
00615 
00616 // ******************************************************************************************
00617 // Called when setup assistant navigation switches to this screen
00618 // ******************************************************************************************
00619 void VirtualJointsWidget::focusGiven()
00620 {
00621   // Show the current vjoints screen
00622   stacked_layout_->setCurrentIndex(0);
00623 
00624   // Load the data to the tree
00625   loadDataTable();
00626 
00627   // Load the avail groups to the combo box
00628   loadChildLinksComboBox();
00629 }
00630 
00631 }  // namespace


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