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


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