examples/Export/main.cpp
Go to the documentation of this file.
1 /*
2 Copyright (c) 2010-2016, Mathieu Labbe - IntRoLab - Universite de Sherbrooke
3 All rights reserved.
4 
5 Redistribution and use in source and binary forms, with or without
6 modification, are permitted provided that the following conditions are met:
7  * Redistributions of source code must retain the above copyright
8  notice, this list of conditions and the following disclaimer.
9  * Redistributions in binary form must reproduce the above copyright
10  notice, this list of conditions and the following disclaimer in the
11  documentation and/or other materials provided with the distribution.
12  * Neither the name of the Universite de Sherbrooke nor the
13  names of its contributors may be used to endorse or promote products
14  derived from this software without specific prior written permission.
15 
16 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
17 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
18 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
19 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY
20 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
21 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
22 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
23 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
24 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
25 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
26 */
27 
28 #include <rtabmap/core/DBDriver.h>
29 #include <rtabmap/core/Rtabmap.h>
30 #include <rtabmap/core/util3d.h>
34 #include <rtabmap/utilite/UMath.h>
35 #include <rtabmap/utilite/UTimer.h>
36 #include <rtabmap/utilite/UFile.h>
37 #include <pcl/filters/filter.h>
38 #include <pcl/io/ply_io.h>
39 #include <pcl/io/obj_io.h>
40 #include <pcl/common/common.h>
41 #include <pcl/surface/poisson.h>
42 #include <stdio.h>
43 
44 using namespace rtabmap;
45 
46 void showUsage()
47 {
48  printf("\nUsage:\n"
49  "rtabmap-exportCloud [options] database.db\n"
50  "Options:\n"
51  " --mesh Create a mesh.\n"
52  " --texture Create a mesh with texture.\n"
53  "\n");
54  exit(1);
55 }
56 
57 int main(int argc, char * argv[])
58 {
61 
62  if(argc < 2)
63  {
64  showUsage();
65  }
66 
67  bool mesh = false;
68  bool texture = false;
69  for(int i=1; i<argc-1; ++i)
70  {
71  if(std::strcmp(argv[i], "--mesh") == 0)
72  {
73  mesh = true;
74  }
75  else if(std::strcmp(argv[i], "--texture") == 0)
76  {
77  texture = true;
78  }
79  }
80 
81  std::string dbPath = argv[argc-1];
82 
83  // Get parameters
84  ParametersMap parameters;
85  DBDriver * driver = DBDriver::create();
86  if(driver->openConnection(dbPath))
87  {
88  parameters = driver->getLastParameters();
89  driver->closeConnection(false);
90  }
91  else
92  {
93  UERROR("Cannot open database %s!", dbPath.c_str());
94  }
95  delete driver;
96 
97  // Get the global optimized map
99  rtabmap.init(parameters, dbPath);
100 
101  std::map<int, Signature> nodes;
102  std::map<int, Transform> optimizedPoses;
103  std::multimap<int, Link> links;
104  rtabmap.get3DMap(nodes, optimizedPoses, links, true, true);
105 
106  // Construct the cloud
107  pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr mergedClouds(new pcl::PointCloud<pcl::PointXYZRGBNormal>);
108  std::map<int, rtabmap::Transform> cameraPoses;
109  std::map<int, std::vector<rtabmap::CameraModel> > cameraModels;
110  std::map<int, cv::Mat> cameraDepths;
111  for(std::map<int, Transform>::iterator iter=optimizedPoses.begin(); iter!=optimizedPoses.end(); ++iter)
112  {
113  Signature node = nodes.find(iter->first)->second;
114 
115  // uncompress data
116  node.sensorData().uncompressData();
117  std::vector<CameraModel> models = node.sensorData().cameraModels();
118  cv::Mat depth = node.sensorData().depthRaw();
119 
120  pcl::IndicesPtr indices(new std::vector<int>);
121  pcl::PointCloud<pcl::PointXYZRGB>::Ptr cloud = util3d::cloudRGBFromSensorData(
122  node.sensorData(),
123  4, // image decimation before creating the clouds
124  4.0f, // maximum depth of the cloud
125  0.0f,
126  indices.get());
127 
128  pcl::PointCloud<pcl::PointXYZRGB>::Ptr transformedCloud(new pcl::PointCloud<pcl::PointXYZRGB>);
129  transformedCloud = rtabmap::util3d::voxelize(cloud, indices, 0.01);
130  transformedCloud = rtabmap::util3d::transformPointCloud(transformedCloud, iter->second);
131 
132  Eigen::Vector3f viewpoint( iter->second.x(), iter->second.y(), iter->second.z());
133  pcl::PointCloud<pcl::Normal>::Ptr normals = rtabmap::util3d::computeNormals(transformedCloud, 10, 0.0f, viewpoint);
134 
135  pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr cloudWithNormals(new pcl::PointCloud<pcl::PointXYZRGBNormal>);
136  pcl::concatenateFields(*transformedCloud, *normals, *cloudWithNormals);
137 
138  if(mergedClouds->size() == 0)
139  {
140  *mergedClouds = *cloudWithNormals;
141  }
142  else
143  {
144  *mergedClouds += *cloudWithNormals;
145  }
146 
147  cameraPoses.insert(std::make_pair(iter->first, iter->second));
148  if(!models.empty())
149  {
150  cameraModels.insert(std::make_pair(iter->first, models));
151  }
152  if(!depth.empty())
153  {
154  cameraDepths.insert(std::make_pair(iter->first, depth));
155  }
156  }
157  if(mergedClouds->size())
158  {
159  if(!(mesh || texture))
160  {
161  printf("Voxel grid filtering of the assembled cloud (voxel=%f, %d points)\n", 0.01f, (int)mergedClouds->size());
162  mergedClouds = util3d::voxelize(mergedClouds, 0.01f);
163 
164  printf("Saving cloud.ply... (%d points)\n", (int)mergedClouds->size());
165  pcl::io::savePLYFile("cloud.ply", *mergedClouds);
166  printf("Saving cloud.ply... done!\n");
167  }
168  else
169  {
170  Eigen::Vector4f min,max;
171  pcl::getMinMax3D(*mergedClouds, min, max);
172  float mapLength = uMax3(max[0]-min[0], max[1]-min[1], max[2]-min[2]);
173  int optimizedDepth = 12;
174  for(int i=6; i<12; ++i)
175  {
176  if(mapLength/float(1<<i) < 0.03f)
177  {
178  optimizedDepth = i;
179  break;
180  }
181  }
182 
183  // Mesh reconstruction
184  printf("Mesh reconstruction...\n");
185  pcl::PolygonMesh::Ptr mesh(new pcl::PolygonMesh);
186  pcl::Poisson<pcl::PointXYZRGBNormal> poisson;
187  poisson.setDepth(optimizedDepth);
188  poisson.setInputCloud(mergedClouds);
189  UTimer timer;
190  poisson.reconstruct(*mesh);
191  printf("Mesh reconstruction... done! %fs (%d polygons)\n", timer.ticks(), (int)mesh->polygons.size());
192 
193  if(mesh->polygons.size())
194  {
195  rtabmap::util3d::denseMeshPostProcessing<pcl::PointXYZRGBNormal>(
196  mesh,
197  0.0f,
198  0,
199  mergedClouds,
200  0.05,
201  !texture);
202 
203  if(!texture)
204  {
205  printf("Saving mesh.ply...\n");
206  pcl::io::savePLYFile("mesh.ply", *mesh);
207  printf("Saving mesh.ply... done!\n");
208  }
209  else
210  {
211  printf("Texturing... cameraPoses=%d, cameraDepths=%d\n", (int)cameraPoses.size(), (int)cameraDepths.size());
212  std::vector<std::map<int, pcl::PointXY> > vertexToPixels;
213  pcl::TextureMeshPtr textureMesh = rtabmap::util3d::createTextureMesh(
214  mesh,
215  cameraPoses,
216  cameraModels,
217  cameraDepths,
218  3,
219  0.0f,
220  0.0f,
221  50,
222  std::vector<float>(),
223  0,
224  &vertexToPixels);
225  printf("Texturing... done! %fs\n", timer.ticks());
226 
227  // Remove occluded polygons (polygons with no texture)
228  if(textureMesh->tex_coordinates.size())
229  {
230  printf("Cleanup mesh...\n");
231  rtabmap::util3d::cleanTextureMesh(*textureMesh, 0);
232  printf("Cleanup mesh... done! %fs\n", timer.ticks());
233  }
234 
235  if(textureMesh->tex_materials.size())
236  {
237  printf("Merging %d textures...\n", (int)textureMesh->tex_materials.size());
238  cv::Mat textures = rtabmap::util3d::mergeTextures(
239  *textureMesh,
240  std::map<int, cv::Mat>(),
241  std::map<int, std::vector<rtabmap::CameraModel> >(),
242  rtabmap.getMemory(),
243  0,
244  4096,
245  1,
246  vertexToPixels,
247  true, 10.0f, true ,true, 0, 0, 0, false);
248 
249 
250  // TextureMesh OBJ
251  bool success = false;
252  UASSERT(!textures.empty());
253  UASSERT(textureMesh->tex_materials.size() == 1);
254 
255  std::string filePath = "mesh.jpg";
256  textureMesh->tex_materials[0].tex_file = filePath;
257  printf("Saving texture to %s.\n", filePath.c_str());
258  success = cv::imwrite(filePath, textures);
259  if(!success)
260  {
261  UERROR("Failed saving %s!", filePath.c_str());
262  }
263  else
264  {
265  printf("Saved %s.\n", filePath.c_str());
266  }
267 
268  if(success)
269  {
270 
271  std::string filePath = "mesh.obj";
272  printf("Saving obj (%d vertices) to %s.\n", (int)textureMesh->cloud.data.size()/textureMesh->cloud.point_step, filePath.c_str());
273  success = pcl::io::saveOBJFile(filePath, *textureMesh) == 0;
274 
275  if(success)
276  {
277  printf("Saved obj to %s!\n", filePath.c_str());
278  }
279  else
280  {
281  UERROR("Failed saving obj to %s!", filePath.c_str());
282  }
283  }
284  }
285  }
286  }
287  }
288  }
289  else
290  {
291  printf("Export failed! The cloud is empty.\n");
292  }
293 
294  return 0;
295 }
void get3DMap(std::map< int, Signature > &signatures, std::map< int, Transform > &poses, std::multimap< int, Link > &constraints, bool optimized, bool global) const
Definition: Rtabmap.cpp:3670
cv::Mat RTABMAP_EXP mergeTextures(pcl::TextureMesh &mesh, const std::map< int, cv::Mat > &images, const std::map< int, CameraModel > &calibrations, const Memory *memory=0, const DBDriver *dbDriver=0, int textureSize=4096, int textureCount=1, const std::vector< std::map< int, pcl::PointXY > > &vertexToPixels=std::vector< std::map< int, pcl::PointXY > >(), bool gainCompensation=true, float gainBeta=10.0f, bool gainRGB=true, bool blending=true, int blendingDecimation=0, int brightnessContrastRatioLow=0, int brightnessContrastRatioHigh=0, bool exposureFusion=false, const ProgressState *state=0)
Definition: UTimer.h:46
GLM_FUNC_DECL genType min(genType const &x, genType const &y)
pcl::PointCloud< pcl::PointXYZ >::Ptr RTABMAP_EXP transformPointCloud(const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, const Transform &transform)
pcl::TextureMesh::Ptr RTABMAP_EXP createTextureMesh(const pcl::PolygonMesh::Ptr &mesh, const std::map< int, Transform > &poses, const std::map< int, CameraModel > &cameraModels, const std::map< int, cv::Mat > &cameraDepths, float maxDistance=0.0f, float maxDepthError=0.0f, float maxAngle=0.0f, int minClusterSize=50, const std::vector< float > &roiRatios=std::vector< float >(), const ProgressState *state=0, std::vector< std::map< int, pcl::PointXY > > *vertexToPixels=0)
void RTABMAP_EXP getMinMax3D(const cv::Mat &laserScan, cv::Point3f &min, cv::Point3f &max)
Definition: util3d.cpp:2593
f
std::map< std::string, std::string > ParametersMap
Definition: Parameters.h:41
Basic mathematics functions.
static void setLevel(ULogger::Level level)
Definition: ULogger.h:339
bool openConnection(const std::string &url, bool overwritten=false)
Definition: DBDriver.cpp:86
#define UASSERT(condition)
#define true
Definition: ConvertUTF.c:57
T uMax3(const T &a, const T &b, const T &c)
Definition: UMath.h:80
void showUsage()
void closeConnection(bool save=true, const std::string &outputUrl="")
Definition: DBDriver.cpp:64
pcl::PointCloud< pcl::PointXYZRGB >::Ptr RTABMAP_EXP cloudRGBFromSensorData(const SensorData &sensorData, int decimation=1, float maxDepth=0.0f, float minDepth=0.0f, std::vector< int > *validIndices=0, const ParametersMap &stereoParameters=ParametersMap(), const std::vector< float > &roiRatios=std::vector< float >())
Definition: util3d.cpp:1031
static void setType(Type type, const std::string &fileName=kDefaultLogFileName, bool append=true)
Definition: ULogger.cpp:176
cv::Mat RTABMAP_EXP computeNormals(const cv::Mat &laserScan, int searchK, float searchRadius)
void init(const ParametersMap &parameters, const std::string &databasePath="")
Definition: Rtabmap.cpp:282
static DBDriver * create(const ParametersMap &parameters=ParametersMap())
Definition: DBDriver.cpp:41
const std::vector< CameraModel > & cameraModels() const
Definition: SensorData.h:193
GLM_FUNC_DECL genType max(genType const &x, genType const &y)
SensorData & sensorData()
Definition: Signature.h:134
void RTABMAP_EXP cleanTextureMesh(pcl::TextureMesh &textureMesh, int minClusterSize)
#define UERROR(...)
ParametersMap getLastParameters() const
Definition: DBDriver.cpp:239
const Memory * getMemory() const
Definition: Rtabmap.h:124
double ticks()
Definition: UTimer.cpp:110
pcl::PointCloud< pcl::PointXYZ >::Ptr RTABMAP_EXP voxelize(const pcl::PointCloud< pcl::PointXYZ >::Ptr &cloud, const pcl::IndicesPtr &indices, float voxelSize)
int main(int argc, char *argv[])
cv::Mat depthRaw() const
Definition: SensorData.h:172


rtabmap
Author(s): Mathieu Labbe
autogenerated on Wed Jun 5 2019 22:41:31