project_model.cpp
Go to the documentation of this file.
00001 #include <pcl/apps/cloud_composer/qt.h>
00002 #include <pcl/apps/cloud_composer/project_model.h>
00003 #include <pcl/apps/cloud_composer/tool_interface/abstract_tool.h>
00004 #include <pcl/apps/cloud_composer/commands.h>
00005 #include <pcl/apps/cloud_composer/work_queue.h>
00006 #include <pcl/apps/cloud_composer/items/cloud_item.h>
00007 #include <pcl/apps/cloud_composer/cloud_view.h>
00008 #include <pcl/apps/cloud_composer/merge_selection.h>
00009 #include <pcl/apps/cloud_composer/transform_clouds.h>
00010 
00011 
00012 pcl::cloud_composer::ProjectModel::ProjectModel (QObject* parent)
00013   : QStandardItemModel (parent)
00014 {
00015   
00016   last_directory_ = QDir (".");
00017     
00018   selection_model_ = new QItemSelectionModel (this);
00019   
00020   undo_stack_ = new QUndoStack (this);
00021   undo_stack_->setUndoLimit (10);
00022   
00023   work_thread_ = new QThread();
00024   work_queue_ = new WorkQueue ();
00025   work_queue_->moveToThread (work_thread_);
00026   
00027   connect (this, SIGNAL (enqueueNewAction (AbstractTool*, ConstItemList)),
00028            work_queue_, SLOT (enqueueNewAction (AbstractTool*, ConstItemList)));
00029   connect (work_queue_, SIGNAL (commandComplete (CloudCommand*)),
00030            this, SLOT (commandCompleted (CloudCommand*)));
00031   work_thread_->start ();
00032   
00033   connect (this, SIGNAL (rowsInserted ( const QModelIndex, int, int)),
00034            this, SIGNAL (modelChanged ()));
00035   connect (this, SIGNAL (rowsRemoved  ( const QModelIndex, int, int)),
00036            this, SIGNAL (modelChanged ()));
00037   
00038   connect (this, SIGNAL (rowsAboutToBeRemoved  ( const QModelIndex, int, int)),
00039            this, SLOT (clearSelection()));
00040   connect (selection_model_, SIGNAL (selectionChanged(QItemSelection,QItemSelection)),
00041            this, SLOT (emitAllStateSignals ()));
00042   connect (selection_model_, SIGNAL (selectionChanged(QItemSelection,QItemSelection)),
00043            this, SLOT (itemSelectionChanged (QItemSelection,QItemSelection)));
00044   
00045   selected_style_map_.insert (interactor_styles::PCL_VISUALIZER, true);
00046   selected_style_map_.insert (interactor_styles::CLICK_TRACKBALL, false);
00047   selected_style_map_.insert (interactor_styles::RECTANGULAR_FRUSTUM, false);
00048   selected_style_map_.insert (interactor_styles::SELECTED_TRACKBALL, false);
00049 }
00050 
00051 pcl::cloud_composer::ProjectModel::ProjectModel (const ProjectModel&)
00052   : QStandardItemModel ()
00053 {
00054 }
00055 
00056 pcl::cloud_composer::ProjectModel::~ProjectModel ()
00057 {
00058   work_thread_->quit ();
00059   work_thread_->deleteLater ();
00060   work_queue_->deleteLater ();
00061 }
00062 
00063 pcl::cloud_composer::ProjectModel::ProjectModel (QString project_name, QObject* parent)
00064 : QStandardItemModel (parent)
00065 {
00066   selection_model_ = new QItemSelectionModel(this);
00067   setName (project_name);
00068 }
00069 
00070 void 
00071 pcl::cloud_composer::ProjectModel::setName (QString new_name)
00072 { 
00073   //If it hasn't been set yet
00074   if (!horizontalHeaderItem (0))
00075     setHorizontalHeaderItem (0, new QStandardItem (new_name));
00076   else
00077   {
00078     QStandardItem* header = horizontalHeaderItem (0);  
00079     header->setText(new_name);
00080   }
00081 }
00082 
00083 void
00084 pcl::cloud_composer::ProjectModel::setCloudView (CloudView* view)
00085 {
00086   cloud_view_ = view;
00087   // Initialize status variables tied to the view
00088   setAxisVisibility (true);
00089    
00090 }
00091 
00092 void
00093 pcl::cloud_composer::ProjectModel::setPointSelection (boost::shared_ptr<SelectionEvent> selected_event)
00094 {
00095   selection_event_ = selected_event;
00096   //Get all the items in this project that are clouds
00097   QList <CloudItem*> project_clouds;
00098   for (int i = 0; i < this->rowCount (); ++i)
00099   {
00100     CloudItem* cloud_item = dynamic_cast <CloudItem*> (this->item (i));
00101     if ( cloud_item )
00102       project_clouds.append ( cloud_item );
00103   }
00104   
00105   selected_item_index_map_.clear ();
00106   // Find all indices in the selected points which are present in the clouds
00107   foreach (CloudItem* cloud_item, project_clouds)
00108   {
00109     pcl::PointIndices::Ptr found_indices = boost::make_shared<pcl::PointIndices>();
00110     selected_event->findIndicesInItem (cloud_item, found_indices);
00111     if (found_indices->indices.size () > 0)
00112     {
00113       qDebug () << "Found "<<found_indices->indices.size ()<<" points in "<<cloud_item->text ();
00114       selected_item_index_map_. insert (cloud_item, found_indices);
00115       cloud_item->setForeground (QBrush (Qt::green));
00116     }
00117   }
00118   setSelectedStyle (interactor_styles::PCL_VISUALIZER);
00119   emit mouseStyleState (interactor_styles::PCL_VISUALIZER);
00120 }
00121 
00122 void
00123 pcl::cloud_composer::ProjectModel::manipulateClouds (boost::shared_ptr<ManipulationEvent> manip_event)
00124 {
00125   
00126   //Get all the items in this project that are clouds
00127   QList <CloudItem*> project_clouds;
00128   for (int i = 0; i < this->rowCount (); ++i)
00129   {
00130     CloudItem* cloud_item = dynamic_cast <CloudItem*> (this->item (i));
00131     if ( cloud_item )
00132       project_clouds.append ( cloud_item );
00133   }
00134   
00135   QMap <QString, vtkSmartPointer<vtkMatrix4x4> > transform_map = manip_event->getEndMap ();
00136   QList <QString> ids = transform_map.keys ();
00137   ConstItemList input_data;
00138   
00139   TransformClouds* transform_tool = new TransformClouds (transform_map);
00140   foreach (CloudItem* cloud_item, project_clouds)
00141   {
00142     if (ids.contains (cloud_item->getId ()))
00143     {
00144       qDebug () << "Found matching item for actor "<<cloud_item->getId ();
00145       input_data.append (cloud_item);
00146     }
00147   }
00148   
00149   //Move the tool object to the work queue thread
00150   transform_tool->moveToThread (work_thread_);
00151   //Emit signal which tells work queue to enqueue this new action
00152   emit enqueueNewAction (transform_tool, input_data);
00153   
00154 
00155 }
00156 
00157 void
00158 pcl::cloud_composer::ProjectModel::insertNewCloudFromFile ()
00159 {
00160   qDebug () << "Inserting cloud from file...";
00161   QString filename = QFileDialog::getOpenFileName (0,tr ("Select cloud to open"), last_directory_.absolutePath (), tr ("PointCloud(*.pcd)"));
00162   if ( filename.isNull ())
00163   {
00164     qWarning () << "No file selected, no cloud loaded";
00165     return;
00166   }
00167   else
00168   {
00169     QFileInfo file_info (filename);
00170     last_directory_ = file_info.absoluteDir ();
00171   }
00172     
00173   pcl::PCLPointCloud2::Ptr cloud_blob (new pcl::PCLPointCloud2);
00174   Eigen::Vector4f origin;
00175   Eigen::Quaternionf orientation;
00176   int version;
00177   
00178   pcl::PCDReader pcd;
00179   if (pcd.read (filename.toStdString (), *cloud_blob, origin, orientation, version) < 0)
00180   {
00181     qDebug () << "Failed to read cloud from file";
00182     return;
00183   }
00184   if (cloud_blob->width * cloud_blob->height == 0)
00185   {
00186     qDebug () << "Cloud read has zero size!";
00187     return;
00188   }
00189   
00190   QFileInfo file_info (filename);
00191   QString short_filename = file_info.baseName ();
00192   //Check if this name already exists in the project - if so, append digit
00193   QList <QStandardItem*> items = findItems (short_filename);
00194   if (items.size () > 0)
00195   {
00196     int k = 2;
00197     items = findItems (short_filename+ tr ("-%1").arg (k));
00198     while (items.size () > 0)
00199     {  
00200       ++k;
00201       items = findItems (short_filename+ tr ("-%1").arg (k));
00202     }
00203     short_filename = short_filename+ tr ("-%1").arg (k);
00204   }
00205   CloudItem* new_item = new CloudItem (short_filename, cloud_blob, origin, orientation, true);
00206    
00207   insertNewCloudComposerItem (new_item, invisibleRootItem());
00208   
00209 }
00210 
00211 void
00212 pcl::cloud_composer::ProjectModel::insertNewCloudFromRGBandDepth ()
00213 {
00214   qDebug () << "Inserting cloud from RGB and Depth files...";
00215   QString rgb_filename = QFileDialog::getOpenFileName (0,tr ("Select rgb image file to open"), last_directory_.absolutePath (), tr ("Images(*.png *.bmp *.tif *.ppm)"));
00216   QString depth_filename;
00217   if ( rgb_filename.isNull ())
00218   {
00219     qWarning () << "No file selected, no cloud loaded";
00220     return;
00221   }
00222   else
00223   {
00224     QFileInfo file_info (rgb_filename);
00225     last_directory_ = file_info.absoluteDir ();
00226     QString base_name = file_info.baseName ();
00227     QStringList depth_filter;
00228     depth_filter << base_name.split("_").at(0) + "_depth.*";
00229     last_directory_.setNameFilters (depth_filter);
00230     QFileInfoList depth_info_list = last_directory_.entryInfoList ();
00231     if (depth_info_list.size () == 0)
00232     {
00233       qCritical () << "Could not find depth file in format (rgb file base name)_depth.*";
00234       return;
00235     }
00236     else if (depth_info_list.size () > 1)
00237     {
00238       qWarning () << "Found more than one file which matches depth naming format, using first one!";
00239     }
00240     depth_filename = depth_info_list.at (0).absoluteFilePath ();
00241   }
00242   
00243   //Read the images
00244   vtkSmartPointer<vtkImageReader2Factory> reader_factory = vtkSmartPointer<vtkImageReader2Factory>::New ();
00245   vtkImageReader2* rgb_reader = reader_factory->CreateImageReader2 (rgb_filename.toStdString ().c_str ());
00246   qDebug () << "RGB File="<<rgb_filename;
00247   if ( ! rgb_reader->CanReadFile (rgb_filename.toStdString ().c_str ()))
00248   {
00249     qCritical () << "Cannot read rgb image file!";
00250     return;
00251   }
00252   rgb_reader->SetFileName (rgb_filename.toStdString ().c_str ());
00253   rgb_reader->Update ();
00254   qDebug () << "Depth File="<<depth_filename;
00255   vtkImageReader2* depth_reader = reader_factory->CreateImageReader2 (depth_filename.toStdString ().c_str ());
00256   if ( ! depth_reader->CanReadFile (depth_filename.toStdString ().c_str ()))
00257   {
00258     qCritical () << "Cannot read depth image file!";
00259     return;
00260   }
00261   depth_reader->SetFileName (depth_filename.toStdString ().c_str ());
00262   depth_reader->Update ();
00263 
00264   vtkSmartPointer<vtkImageData> rgb_image = rgb_reader->GetOutput ();
00265   int *rgb_dims = rgb_image->GetDimensions ();
00266   vtkSmartPointer<vtkImageData> depth_image = depth_reader->GetOutput ();
00267   int *depth_dims = depth_image->GetDimensions ();
00268   
00269   if (rgb_dims[0] != depth_dims[0] || rgb_dims[1] != depth_dims[1])
00270   {
00271     qCritical () << "Depth and RGB dimensions to not match!";
00272     qDebug () << "RGB Image is of size "<<rgb_dims[0] << " by "<<rgb_dims[1];
00273     qDebug () << "Depth Image is of size "<<depth_dims[0] << " by "<<depth_dims[1];
00274     return;
00275   }
00276   qDebug () << "Images loaded, making cloud";
00277   PointCloud<PointXYZRGB>::Ptr cloud = boost::make_shared <PointCloud<PointXYZRGB> >();
00278   cloud->points.reserve (depth_dims[0] * depth_dims[1]);
00279   cloud->width = depth_dims[0];
00280   cloud->height = depth_dims[1];
00281   cloud->is_dense = false;
00282  
00283 
00284   // Fill in image data
00285   int centerX = static_cast<int>(cloud->width / 2.0);
00286   int centerY = static_cast<int>(cloud->height / 2.0);
00287   unsigned short* depth_pixel;
00288   unsigned char* color_pixel;
00289   float scale = 1.0f/1000.0f;
00290   float focal_length = 525.0f;
00291   float fl_const = 1.0f / focal_length;
00292   depth_pixel = static_cast<unsigned short*>(depth_image->GetScalarPointer (depth_dims[0]-1,depth_dims[1]-1,0));
00293   color_pixel = static_cast<unsigned char*> (rgb_image->GetScalarPointer (depth_dims[0]-1,depth_dims[1]-1,0));
00294   
00295   for (int y=0; y<cloud->height; ++y)
00296   {
00297     for (int x=0; x<cloud->width; ++x, --depth_pixel, color_pixel-=3)
00298     {
00299       PointXYZRGB new_point;
00300       //  uint8_t* p_i = &(cloud_blob->data[y * cloud_blob->row_step + x * cloud_blob->point_step]);
00301       float depth = (float)(*depth_pixel) * scale;
00302     //  qDebug () << "Depth = "<<depth;
00303       if (depth == 0.0f)
00304       {
00305         new_point.x = new_point.y = new_point.z = std::numeric_limits<float>::quiet_NaN ();
00306       }
00307       else
00308       {
00309         new_point.x = ((float)(x - centerX)) * depth * fl_const;
00310         new_point.y = ((float)(centerY - y)) * depth * fl_const; // vtk seems to start at the bottom left image corner
00311         new_point.z = depth;
00312       }
00313       
00314       uint32_t rgb = (uint32_t)color_pixel[0] << 16 | (uint32_t)color_pixel[1] << 8 | (uint32_t)color_pixel[2];
00315       new_point.rgb = *reinterpret_cast<float*> (&rgb);
00316       cloud->points.push_back (new_point);
00317       //   qDebug () << "depth = "<<depth << "x,y,z="<<data[0]<<","<<data[1]<<","<<data[2];
00318       //qDebug() << "r ="<<color_pixel[0]<<" g="<<color_pixel[1]<<" b="<<color_pixel[2];
00319       
00320     }
00321   }
00322   qDebug () << "Done making cloud!";
00323   QFileInfo file_info (rgb_filename);
00324   QString short_filename = file_info.baseName ();
00325   //Check if this name already exists in the project - if so, append digit
00326   QList <QStandardItem*> items = findItems (short_filename);
00327   if (items.size () > 0)
00328   {
00329     int k = 2;
00330     items = findItems (short_filename+ tr ("-%1").arg (k));
00331     while (items.size () > 0)
00332     {  
00333       ++k;
00334       items = findItems (short_filename+ tr ("-%1").arg (k));
00335     }
00336     short_filename = short_filename+ tr ("-%1").arg (k);
00337   }
00338 
00339   CloudItem* new_item = CloudItem::createCloudItemFromTemplate<PointXYZRGB> (short_filename,cloud);
00340   
00341   insertNewCloudComposerItem (new_item, invisibleRootItem());
00342   
00343 }
00344 void
00345 pcl::cloud_composer::ProjectModel::saveSelectedCloudToFile ()
00346 {
00347   qDebug () << "Saving cloud to file...";
00348   QModelIndexList selected_indexes = selection_model_->selectedIndexes ();
00349   if (selected_indexes.size () == 0)
00350   {
00351     QMessageBox::warning (qobject_cast<QWidget *>(this->parent ()), "No Cloud Selected", "Cannot save, no cloud is selected in the browser or cloud view");
00352     return;
00353   }
00354   else if (selected_indexes.size () > 1)
00355   {
00356     QMessageBox::warning (qobject_cast<QWidget *>(this->parent ()), "Too many clouds Selected", "Cannot save, currently only support saving one cloud at a time");
00357     return;
00358   }
00359   
00360   QStandardItem* item = this->itemFromIndex (selected_indexes.value (0));
00361   CloudItem* cloud_to_save = dynamic_cast <CloudItem*> (item); 
00362   if (!cloud_to_save )
00363   {
00364     QMessageBox::warning (qobject_cast<QWidget *>(this->parent ()), "Not a Cloud!", "Selected item is not a cloud, not saving!");
00365     return;
00366   }
00367   
00368   QString filename = QFileDialog::getSaveFileName (0,tr ("Save Cloud"), last_directory_.absolutePath (), tr ("PointCloud(*.pcd)"));
00369   if ( filename.isNull ())
00370   {
00371     qWarning () << "No file selected, not saving";
00372     return;
00373   }
00374   else
00375   {
00376     QFileInfo file_info (filename);
00377     last_directory_ = file_info.absoluteDir ();
00378   }
00379   
00380   pcl::PCLPointCloud2::ConstPtr cloud = cloud_to_save->data (ItemDataRole::CLOUD_BLOB).value <pcl::PCLPointCloud2::ConstPtr> ();
00381   Eigen::Vector4f origin = cloud_to_save->data (ItemDataRole::ORIGIN).value <Eigen::Vector4f> ();
00382   Eigen::Quaternionf orientation = cloud_to_save->data (ItemDataRole::ORIENTATION).value <Eigen::Quaternionf> ();
00383   int result = pcl::io::savePCDFile (filename.toStdString (), *cloud, origin, orientation );
00384   
00385 }
00386 
00387 void 
00388 pcl::cloud_composer::ProjectModel::enqueueToolAction (AbstractTool* tool)
00389 {
00390   qDebug () << "Enqueuing tool action "<<tool->getToolName ()<<" in project model "<<this->getName ();
00391   //Get the currently selected item(s), put them in a list, and create the command
00392   ConstItemList input_data;
00393   QModelIndexList selected_indexes = selection_model_->selectedIndexes ();
00394   if (selected_indexes.size () == 0)
00395   {
00396     QMessageBox::warning (qobject_cast<QWidget *>(this->parent ()), "No Items Selected", "Cannot use tool, no item is selected in the browser or cloud view");
00397     return;
00398   }
00399   foreach (QModelIndex index, selected_indexes)
00400   {
00401     QStandardItem* item = this->itemFromIndex (index);
00402     if ( dynamic_cast <CloudComposerItem*> (item))
00403       input_data.append (dynamic_cast <CloudComposerItem*> (item));
00404   }
00405   qDebug () << "Input for tool is "<<input_data.size () << " element(s)";
00406  
00407   //Move the tool object to the work queue thread
00408   tool->moveToThread (work_thread_);
00409   //Emit signal which tells work queue to enqueue this new action
00410   emit enqueueNewAction (tool, input_data);
00411 }
00412 
00413 
00414 void
00415 pcl::cloud_composer::ProjectModel::commandCompleted (CloudCommand* command)
00416 {
00417   //We set the project model here - this wasn't done earlier so model is never exposed to plugins
00418   command->setProjectModel (this);
00419   qDebug () << "Applying command changes to model and pushing onto undo stack";
00420   //command->redo ();
00421   undo_stack_->push (command);
00422   
00423 }
00424 
00425 void
00426 pcl::cloud_composer::ProjectModel::insertNewCloudComposerItem (CloudComposerItem* new_item, QStandardItem* parent_item)
00427 {
00428   parent_item->appendRow (new_item);  
00429 }
00430 
00432 //Slots for commands arriving from GUI
00434 void
00435 pcl::cloud_composer::ProjectModel::clearSelection ()
00436 {
00437   getSelectionModel ()->clearSelection ();
00438   
00439   //Clear the point selector as well if it has an active selection
00440   if (selection_event_)
00441     selection_event_.reset ();
00442   
00443   foreach (CloudItem* selected_item, selected_item_index_map_.keys())
00444   {
00445     qDebug () << "Setting item color back to black";
00446     selected_item->setForeground (QBrush (Qt::black));;
00447   }
00448   
00449   selected_item_index_map_.clear ();
00450 }
00451 
00452 void
00453 pcl::cloud_composer::ProjectModel::deleteSelectedItems ()
00454 {
00455   
00456   QModelIndexList selected_indexes = selection_model_->selectedIndexes ();
00457   if (selected_indexes.size () == 0)
00458   {
00459     QMessageBox::warning (qobject_cast<QWidget *>(this->parent ()), "No Items Selected", "Cannot execute delete command, no item is selected in the browser or cloud view");
00460     return;
00461   }    
00462   
00463   ConstItemList input_data;
00464   foreach (QModelIndex index, selected_indexes)
00465   {
00466     QStandardItem* item = this->itemFromIndex (index);
00467     //qDebug () << item->text () << " selected!";
00468     if ( dynamic_cast <CloudComposerItem*> (item))
00469       input_data.append (dynamic_cast <CloudComposerItem*> (item));
00470   }
00471  // qDebug () << "Input for command is "<<input_data.size () << " element(s)";
00472   DeleteItemCommand* delete_command = new DeleteItemCommand (ConstItemList ());
00473   delete_command->setInputData (input_data);
00474   if (delete_command->runCommand (0))
00475     commandCompleted(delete_command);
00476   else
00477     qCritical () << "Execution of delete command failed!";
00478 }
00479 
00480 void
00481 pcl::cloud_composer::ProjectModel::setAxisVisibility (bool visible)
00482 {
00483   //qDebug () << "Setting axis visibility to "<<visible;
00484   axis_visible_ = visible;
00485   cloud_view_->setAxisVisibility (axis_visible_);
00486 }
00487 
00488 void
00489 pcl::cloud_composer::ProjectModel::mouseStyleChanged (QAction* new_style_action)
00490 {
00491   interactor_styles::INTERACTOR_STYLES selected_style = new_style_action->data ().value<interactor_styles::INTERACTOR_STYLES> ();
00492   qDebug () << "Selected style ="<<selected_style;
00493   setSelectedStyle (selected_style);  
00494   
00495   // Now set the correct interactor
00496   if (cloud_view_)
00497     cloud_view_->setInteractorStyle (selected_style);
00498   else
00499     qWarning () << "No Cloud View active, can't change interactor style!";
00500 
00501     
00502 }
00503 
00504 void
00505 pcl::cloud_composer::ProjectModel::createNewCloudFromSelection ()
00506 {
00507   // We need only clouds to be selected
00508   if (!onlyCloudItemsSelected ())
00509   {
00510     qCritical () << "Only Clouds Selected = False -- Cannot create a new cloud from non-cloud selection";
00511     return;
00512   }
00513   //Add selected items into input data list
00514   QModelIndexList selected_indexes = selection_model_->selectedIndexes ();
00515   ConstItemList input_data;
00516   foreach (QModelIndex index, selected_indexes)
00517   {
00518     QStandardItem* item = this->itemFromIndex (index);
00519     //qDebug () << item->text () << " selected!";
00520     if ( dynamic_cast <CloudComposerItem*> (item))
00521       input_data.append (dynamic_cast <CloudComposerItem*> (item));
00522   }
00523  
00524   QMap <const CloudItem*, pcl::PointIndices::ConstPtr> selected_const_map;
00525   foreach ( CloudItem* item, selected_item_index_map_.keys ())
00526     selected_const_map.insert (item, selected_item_index_map_.value (item));
00527   MergeSelection* merge_tool = new MergeSelection (selected_const_map);
00528   
00529   //We don't call the enqueueToolAction function since that would abort if we only have a green selection
00530   //Move the tool object to the work queue thread
00531   merge_tool->moveToThread (work_thread_);
00532   //Emit signal which tells work queue to enqueue this new action
00533   emit enqueueNewAction (merge_tool, input_data);
00534   
00535   
00536 }
00537 
00538 void
00539 pcl::cloud_composer::ProjectModel::selectAllItems (QStandardItem* item)
00540 {
00541  
00542   int num_rows;
00543   if (!item)
00544     item = this->invisibleRootItem ();
00545   else
00546    selection_model_->select (item->index (), QItemSelectionModel::Select);
00547   //qDebug () << "Select all!"<< item->rowCount();
00548   for (int i = 0; i < item->rowCount (); ++i)
00549   {
00550     if (item->child (i))
00551       selectAllItems(item->child (i));
00552   }
00553   
00554 }
00555 
00557 //Slots for Model State
00559 void
00560 pcl::cloud_composer::ProjectModel::emitAllStateSignals ()
00561 {
00562   emit axisVisible (axis_visible_);
00563   emit deleteAvailable (selection_model_->hasSelection ());
00564   emit newCloudFromSelectionAvailable (onlyCloudItemsSelected ());  
00565   
00566   //Find out which style is active, emit the signal 
00567   QMap<interactor_styles::INTERACTOR_STYLES, bool>::iterator itr = selected_style_map_.begin();
00568   foreach (interactor_styles::INTERACTOR_STYLES style, selected_style_map_.keys())
00569   {
00570     if (selected_style_map_.value (style))
00571     {
00572       emit mouseStyleState (style);
00573       break;
00574     }
00575   }
00576   
00577   
00578 }
00579 
00580 void
00581 pcl::cloud_composer::ProjectModel::itemSelectionChanged ( const QItemSelection & selected, const QItemSelection & deselected )
00582 {
00583   //qDebug () << "Item selection changed!";
00584   //Set all point selected cloud items back to green text, since if they are selected they get changed to white
00585   foreach (CloudItem* selected_item, selected_item_index_map_.keys())
00586   {
00587     selected_item->setForeground (QBrush (Qt::green));;
00588   }
00589 }
00590 
00591 
00593 //  Private Support Functions
00595 
00596 
00597 bool
00598 pcl::cloud_composer::ProjectModel::onlyCloudItemsSelected ()
00599 {
00600   QModelIndexList selected_indexes = selection_model_->selectedIndexes();
00601   foreach (QModelIndex model_index, selected_indexes)
00602   {
00603     if (this->itemFromIndex (model_index)->type () != CloudComposerItem::CLOUD_ITEM )
00604     {
00605       return false;
00606     }
00607   }
00608   return true;
00609 }
00610 
00611 void 
00612 pcl::cloud_composer::ProjectModel::setSelectedStyle (interactor_styles::INTERACTOR_STYLES style)
00613 {
00614   QMap<interactor_styles::INTERACTOR_STYLES, bool>::iterator itr = selected_style_map_.begin();
00615   while (itr != selected_style_map_.end ())
00616   {
00617     itr.value() = false;
00618     ++itr;
00619   }
00620   selected_style_map_[style] = true;
00621   
00622 }
00623 
00624 


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:31:34