OptimizeStage.cpp
Go to the documentation of this file.
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Redistribution and use in source and binary forms, with or without
5  * modification, are permitted provided that the following conditions
6  * are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above
11  * copyright notice, this list of conditions and the following
12  * disclaimer in the documentation and/or other materials provided
13  * with the distribution.
14  * * Neither the name of Willow Garage, Inc. nor the names of its
15  * contributors may be used to endorse or promote products derived
16  * from this software without specific prior written permission.
17  *
18  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
19  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
20  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
21  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
22  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
23  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
24  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
25  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
26  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
27  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
28  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
29  * POSSIBILITY OF SUCH DAMAGE.
30  *
31  */
32 /*
33  * OptimizeStage.cpp
34  *
35  * @date 13.11.2015
36  * @author Tristan Igelbrink (Tristan@Igelbrink.com)
37  */
38 
40 
41 // default constructor
43  ,mesh_count_(0), options_(options), bounding_counter(0),texture_counter(0),pic_count_(0)
44 {
45  optiMesh_ = NULL;
47 }
48 
50 
52 {
53  auto mesh_work = boost::any_cast<pair<pair<MeshPtr, bool>, vector<kfusion::ImgPose*> > >(getInQueue()->Take());
54  bool last_shift = mesh_work.first.second;
55  MeshPtr act_mesh = mesh_work.first.first;
56  string mesh_notice = ("#### C: Mesh Optimization " + to_string(mesh_count_) + " ####");
57  ScopeTime* opti_time = new ScopeTime(mesh_notice.c_str());
58  act_mesh->fillHoles(options_->getFillHoles());
59  if(optiMesh_ == NULL)
60  optiMesh_ = act_mesh;
61  else
62  optiMesh_->addMesh(act_mesh, options_->textures());
63  std::vector<kfusion::ImgPose*> image_poses_buffer = mesh_work.second;
64  //std::cout << "Loaded " << image_poses_buffer.size() << " Images. " << std::endl;
65  // Set recursion depth for region growing
66  if(options_->getDepth())
67  {
68  optiMesh_->setDepth(options_->getDepth());
69  }
70  optiMesh_->setClassifier(options_->getClassifier());
71  optiMesh_->optimizePlanes(options_->getPlaneIterations(),
75  MeshPtr tmp_pointer = optiMesh_->retesselateInHalfEdge(options_->getLineFusionThreshold(), options_->textures(), texture_counter);
76  if(tmp_pointer == NULL)
77  return;
78  optiMesh_->restorePlanes(options_->getMinPlaneSize());
79  delete opti_time;
80  mesh_count_++;
81 
83  if(options_->textures())
84  {
85  int counter=0;
86  int i;
87  int progress = 0, j;
88 
89 
90  for(i=0;i<image_poses_buffer.size();i++){
91  counter = tmp_pointer->projectAndMapNewImage(*(image_poses_buffer[i]));
92  }
93 
94  pic_count_+=i;
95 
96  texture_counter += tmp_pointer->textures.size();
97 
98  meshBufferPtr = tmp_pointer->meshBuffer();
99 
100  }
101  image_poses_buffer.resize(0);
102  getOutQueue()->Add(pair<pair<MeshPtr, bool>, vector<ImgPose*> >(
103  pair<MeshPtr, bool>(tmp_pointer, last_shift), mesh_work.second));
104  if(last_shift)
105  done(true);
106 }
108 {
109  delete optiMesh_;
110 }
OptimizeStage::optiMesh_
MeshPtr optiMesh_
Definition: OptimizeStage.hpp:77
OptimizeStage::firstStep
virtual void firstStep()
Definition: OptimizeStage.cpp:49
kfusion::ScopeTime
Definition: types.hpp:103
kfusion::Options::getFillHoles
int getFillHoles() const
Returns the region threshold for hole filling.
Definition: ext/kintinuous/kfusion/src/app/Options.cpp:115
OptimizeStage::OptimizeStage
OptimizeStage(Options *options)
Definition: OptimizeStage.cpp:42
AbstractStage::done
bool done() const
Definition: AbstractStage.hpp:91
kfusion::Options::getMinPlaneSize
int getMinPlaneSize() const
Minimum value for plane optimzation.
Definition: ext/kintinuous/kfusion/src/app/Options.cpp:120
kfusion::Options::getDepth
int getDepth() const
Returns the maximum recursion depth for region growing.
Definition: ext/kintinuous/kfusion/src/app/Options.cpp:192
kfusion::Options::getSmallRegionThreshold
int getSmallRegionThreshold() const
Returns the threshold for the size of small region deletion after plane optimization.
Definition: ext/kintinuous/kfusion/src/app/Options.cpp:181
NULL
#define NULL
Definition: mydefs.hpp:141
OptimizeStage.hpp
kfusion::Options::textures
bool textures() const
Definition: ext/kintinuous/kfusion/src/app/Options.cpp:143
OptimizeStage::lastStep
virtual void lastStep()
Definition: OptimizeStage.cpp:107
OptimizeStage::pic_count_
size_t pic_count_
Definition: OptimizeStage.hpp:81
options
const kaboom::Options * options
Definition: src/tools/lvr2_kaboom/Main.cpp:45
kfusion::Options::verbose
bool verbose() const
Definition: ext/kintinuous/kfusion/src/app/Options.cpp:160
AbstractStage
Definition: AbstractStage.hpp:49
OptimizeStage::texture_counter
size_t texture_counter
Definition: OptimizeStage.hpp:81
OptimizeStage::step
virtual void step()
Definition: OptimizeStage.cpp:51
OptimizeStage::meshBufferPtr
MeshBufferPtr meshBufferPtr
Definition: OptimizeStage.hpp:80
lvr2::timestamp
static Timestamp timestamp
A global time stamp object for program runtime measurement.
Definition: Timestamp.hpp:116
lvr2::Timestamp::setQuiet
void setQuiet(bool quiet)
Definition: Timestamp.hpp:87
MeshPtr
HMesh * MeshPtr
Definition: FusionStage.hpp:63
kfusion::Options::getNormalThreshold
float getNormalThreshold() const
Returns the normal threshold for plane optimization.
Definition: ext/kintinuous/kfusion/src/app/Options.cpp:176
OptimizeStage::mesh_count_
size_t mesh_count_
Definition: OptimizeStage.hpp:76
kfusion::Options::getPlaneIterations
int getPlaneIterations() const
Returns to number plane optimization iterations.
Definition: ext/kintinuous/kfusion/src/app/Options.cpp:80
kfusion::Options::getClassifier
string getClassifier() const
Returns the name of the classifier used to color the mesh.
Definition: ext/kintinuous/kfusion/src/app/Options.cpp:95
kfusion::Options
A class to parse the program options for the reconstruction executable.
Definition: ext/kintinuous/kfusion/include/kfusion/Options.hpp:51
AbstractStage::getOutQueue
boost::shared_ptr< BlockingQueue > getOutQueue() const
Definition: AbstractStage.hpp:89
AbstractStage::getInQueue
boost::shared_ptr< BlockingQueue > getInQueue() const
Definition: AbstractStage.hpp:88
kfusion::Options::getLineFusionThreshold
float getLineFusionThreshold() const
Returns the fusion threshold for tesselation.
Definition: ext/kintinuous/kfusion/src/app/Options.cpp:197
OptimizeStage::options_
Options * options_
Definition: OptimizeStage.hpp:78


lvr2
Author(s): Thomas Wiemann , Sebastian Pütz , Alexander Mock , Lars Kiesow , Lukas Kalbertodt , Tristan Igelbrink , Johan M. von Behren , Dominik Feldschnieders , Alexander Löhr
autogenerated on Wed Mar 2 2022 00:37:24