cloud_mesh_item.cpp
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Point Cloud Library (PCL) - www.pointclouds.org
00005  *  Copyright (c) 2012, Willow Garage, Inc.
00006  *  All rights reserved.
00007  *
00008  *  Redistribution and use in source and binary forms, with or without
00009  *  modification, are permitted provided that the following conditions
00010  *  are met:
00011  *
00012  *   * Redistributions of source code must retain the above copyright
00013  *     notice, this list of conditions and the following disclaimer.
00014  *   * Redistributions in binary form must reproduce the above
00015  *     copyright notice, this list of conditions and the following
00016  *     disclaimer in the documentation and/or other materials provided
00017  *     with the distribution.
00018  *   * Neither the name of Willow Garage, Inc. nor the names of its
00019  *     contributors may be used to endorse or promote products derived
00020  *     from this software without specific prior written permission.
00021  *
00022  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00023  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00024  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00025  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00026  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00027  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00028  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00029  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00030  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00031  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00032  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00033  *  POSSIBILITY OF SUCH DAMAGE.
00034  *
00035  */
00036 
00037 #include <pcl/apps/modeler/cloud_mesh_item.h>
00038 #include <pcl/apps/modeler/render_window.h>
00039 #include <pcl/apps/modeler/render_window_item.h>
00040 #include <pcl/apps/modeler/points_actor_item.h>
00041 #include <pcl/apps/modeler/normals_actor_item.h>
00042 #include <pcl/apps/modeler/surface_actor_item.h>
00043 #include <pcl/apps/modeler/cloud_mesh.h>
00044 #include <pcl/apps/modeler/main_window.h>
00045 #include <pcl/apps/modeler/parameter.h>
00046 #include <pcl/apps/modeler/parameter_dialog.h>
00047 #include <pcl/common/common.h>
00048 #include <vtkRenderWindow.h>
00049 
00050 
00052 pcl::modeler::CloudMeshItem::CloudMeshItem (QTreeWidgetItem* parent, const std::string& filename)
00053   :QTreeWidgetItem(parent),
00054   AbstractItem(),
00055   filename_(filename),
00056   cloud_mesh_(boost::shared_ptr<CloudMesh>(new CloudMesh())),
00057   translation_x_(new DoubleParameter("Translation X", "Translation X", 0.0, -1.0, 1.0)),
00058   translation_y_(new DoubleParameter("Translation Y", "Translation Y", 0.0, -1.0, 1.0)),
00059   translation_z_(new DoubleParameter("Translation Z", "Translation Z", 0.0, -1.0, 1.0)),
00060   rotation_x_(new DoubleParameter("Rotation X", "Rotation X", 0.0, -180.0, 180.0)),
00061   rotation_y_(new DoubleParameter("Rotation Y", "Rotation Y", 0.0, -180.0, 180.0)),
00062   rotation_z_(new DoubleParameter("Rotation Z", "Rotation Z", 0.0, -180.0, 180.0))
00063 {
00064   setFlags(flags()&(~Qt::ItemIsDropEnabled));
00065   setText(0, QString(filename.c_str()));
00066 }
00067 
00069 pcl::modeler::CloudMeshItem::CloudMeshItem (QTreeWidgetItem* parent, CloudMesh::PointCloudPtr cloud)
00070   :QTreeWidgetItem(parent),
00071   AbstractItem(),
00072   filename_("unnamed point cloud"),
00073   cloud_mesh_(boost::shared_ptr<CloudMesh>(new CloudMesh(cloud))),
00074   translation_x_(new DoubleParameter("Translation X", "Translation X", 0.0, -1.0, 1.0)),
00075   translation_y_(new DoubleParameter("Translation Y", "Translation Y", 0.0, -1.0, 1.0)),
00076   translation_z_(new DoubleParameter("Translation Z", "Translation Z", 0.0, -1.0, 1.0)),
00077   rotation_x_(new DoubleParameter("Rotation X", "Rotation X", 0.0, -180.0, 180.0)),
00078   rotation_y_(new DoubleParameter("Rotation Y", "Rotation Y", 0.0, -180.0, 180.0)),
00079   rotation_z_(new DoubleParameter("Rotation Z", "Rotation Z", 0.0, -180.0, 180.0))
00080 {
00081   setFlags(flags()&(~Qt::ItemIsDropEnabled));
00082   setText(0, QString(filename_.c_str()));
00083 
00084   createChannels();
00085 
00086   treeWidget()->expandItem(this);
00087 }
00088 
00090 pcl::modeler::CloudMeshItem::CloudMeshItem(QTreeWidgetItem* parent,  const CloudMeshItem& cloud_mesh_item)
00091   :QTreeWidgetItem(parent),
00092   AbstractItem(),
00093   filename_(cloud_mesh_item.filename_),
00094   cloud_mesh_(cloud_mesh_item.cloud_mesh_),
00095   translation_x_(new DoubleParameter("Translation X", "Translation X", 0.0, -1.0, 1.0)),
00096   translation_y_(new DoubleParameter("Translation Y", "Translation Y", 0.0, -1.0, 1.0)),
00097   translation_z_(new DoubleParameter("Translation Z", "Translation Z", 0.0, -1.0, 1.0)),
00098   rotation_x_(new DoubleParameter("Rotation X", "Rotation X", 0.0, -180.0, 180.0)),
00099   rotation_y_(new DoubleParameter("Rotation Y", "Rotation Y", 0.0, -180.0, 180.0)),
00100   rotation_z_(new DoubleParameter("Rotation Z", "Rotation Z", 0.0, -180.0, 180.0))
00101 {
00102   setFlags(flags()&(~Qt::ItemIsDropEnabled));
00103   setText(0, QString(filename_.c_str()));
00104 
00105   createChannels();
00106 
00107   treeWidget()->expandItem(this);
00108 }
00109 
00111 pcl::modeler::CloudMeshItem::~CloudMeshItem ()
00112 {
00113 }
00114 
00116 bool
00117 pcl::modeler::CloudMeshItem::savePointCloud(const QList<CloudMeshItem*>& items, const QString& filename)
00118 {
00119   if (items.size() == 1)
00120     return (items.first()->getCloudMesh()->save(filename.toStdString()));
00121 
00122   std::vector<const CloudMesh*> cloud_meshes;
00123   for (QList<CloudMeshItem*>::const_iterator items_it = items.begin();
00124     items_it != items.end();
00125     ++ items_it)
00126   {
00127     cloud_meshes.push_back((*items_it)->getCloudMesh().get());
00128   }
00129 
00130   return (CloudMesh::save(cloud_meshes, filename.toStdString()));
00131 }
00132 
00134 bool
00135 pcl::modeler::CloudMeshItem::open()
00136 {
00137   if(!cloud_mesh_->open(filename_))
00138     return (false);
00139 
00140   createChannels();
00141 
00142   treeWidget()->expandItem(this);
00143 
00144   return (true);
00145 }
00146 
00148 void
00149 pcl::modeler::CloudMeshItem::prepareContextMenu(QMenu* menu) const
00150 {
00151   menu->addMenu(ui()->menuFilters);
00152   menu->addMenu(ui()->menuRegistration);
00153   menu->addMenu(ui()->menuSurfaceReconstruction);
00154   menu->addAction(ui()->actionSavePointCloud);
00155   menu->addAction(ui()->actionClosePointCloud);
00156 }
00157 
00159 void
00160 pcl::modeler::CloudMeshItem::createChannels()
00161 {
00162   RenderWindowItem* render_window_item = dynamic_cast<RenderWindowItem*>(parent());
00163   addChild(new PointsActorItem(this, cloud_mesh_, render_window_item->getRenderWindow()->GetRenderWindow()));
00164   addChild(new NormalsActorItem(this, cloud_mesh_, render_window_item->getRenderWindow()->GetRenderWindow()));
00165   addChild(new SurfaceActorItem(this, cloud_mesh_, render_window_item->getRenderWindow()->GetRenderWindow()));
00166   for (int i = 0, i_end = childCount(); i < i_end; ++ i)
00167   {
00168     ChannelActorItem* child_item = dynamic_cast<ChannelActorItem*>(child(i));
00169     child_item->init();
00170   }
00171 
00172   render_window_item->getRenderWindow()->updateAxes();
00173   render_window_item->getRenderWindow()->resetCamera();
00174 
00175   return;
00176 }
00177 
00178 
00180 void
00181 pcl::modeler::CloudMeshItem::updateChannels()
00182 {
00183   cloud_mesh_->updateVtkPoints();
00184   cloud_mesh_->updateVtkPolygons();
00185 
00186   for (int i = 0, i_end = childCount(); i < i_end; ++ i)
00187   {
00188     ChannelActorItem* child_item = dynamic_cast<ChannelActorItem*>(child(i));
00189     child_item->update();
00190   }
00191 
00192   RenderWindowItem* render_window_item = dynamic_cast<RenderWindowItem*>(parent());
00193   render_window_item->getRenderWindow()->updateAxes();
00194 
00195   return;
00196 }
00197 
00199 void
00200 pcl::modeler::CloudMeshItem::prepareProperties(ParameterDialog* parameter_dialog)
00201 {
00202   translation_x_->reset();
00203   translation_y_->reset();
00204   translation_z_->reset();
00205   rotation_x_->reset();
00206   rotation_y_->reset();
00207   rotation_z_->reset();
00208   parameter_dialog->addParameter(translation_x_);
00209   parameter_dialog->addParameter(translation_y_);
00210   parameter_dialog->addParameter(translation_z_);
00211   parameter_dialog->addParameter(rotation_x_);
00212   parameter_dialog->addParameter(rotation_y_);
00213   parameter_dialog->addParameter(rotation_z_);
00214 
00215   Eigen::Vector4f min_pt, max_pt;
00216   pcl::getMinMax3D(*(cloud_mesh_->getCloud()), min_pt, max_pt);
00217   double x_range = max_pt.x() - min_pt.x();
00218   double y_range = max_pt.y() - min_pt.y();
00219   double z_range = max_pt.z() - min_pt.z();
00220   translation_x_->setLow(-x_range/2);
00221   translation_x_->setHigh(x_range/2);
00222   translation_x_->setStep(x_range/1000);
00223   translation_y_->setLow(-y_range/2);
00224   translation_y_->setHigh(y_range/2);
00225   translation_y_->setStep(y_range/1000);
00226   translation_z_->setLow(-z_range/2);
00227   translation_z_->setHigh(z_range/2);
00228   translation_z_->setStep(z_range/1000);
00229 }
00230 
00232 void
00233 pcl::modeler::CloudMeshItem::setProperties()
00234 {
00235   cloud_mesh_->transform(*translation_x_, *translation_y_, *translation_z_,
00236     *rotation_x_, *rotation_y_, *rotation_z_);
00237 
00238   updateChannels();
00239 }
00240 
00242 void
00243 pcl::modeler::CloudMeshItem::updateRenderWindow()
00244 {
00245   RenderWindowItem* render_window_item = dynamic_cast<RenderWindowItem*>(parent());
00246   for (int i = 0, i_end = childCount(); i < i_end; ++ i)
00247   {
00248     ChannelActorItem* child_item = dynamic_cast<ChannelActorItem*>(child(i));
00249     child_item->switchRenderWindow(render_window_item->getRenderWindow()->GetRenderWindow());
00250   }
00251 
00252   render_window_item->getRenderWindow()->updateAxes();
00253   render_window_item->getRenderWindow()->resetCamera();
00254 
00255   return;
00256 }


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:22:46