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> 49 "rtabmap-exportCloud [options] database.db\n" 51 " --mesh Create a mesh.\n" 52 " --texture Create a mesh with texture.\n" 57 int main(
int argc,
char * argv[])
69 for(
int i=1; i<argc-1; ++i)
71 if(std::strcmp(argv[i],
"--mesh") == 0)
75 else if(std::strcmp(argv[i],
"--texture") == 0)
81 std::string dbPath = argv[argc-1];
93 UERROR(
"Cannot open database %s!", dbPath.c_str());
99 rtabmap.
init(parameters, dbPath);
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);
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)
113 Signature node = nodes.find(iter->first)->second;
120 pcl::IndicesPtr indices(
new std::vector<int>);
128 pcl::PointCloud<pcl::PointXYZRGB>::Ptr transformedCloud(
new pcl::PointCloud<pcl::PointXYZRGB>);
132 Eigen::Vector3f viewpoint( iter->second.x(), iter->second.y(), iter->second.z());
135 pcl::PointCloud<pcl::PointXYZRGBNormal>::Ptr cloudWithNormals(
new pcl::PointCloud<pcl::PointXYZRGBNormal>);
136 pcl::concatenateFields(*transformedCloud, *normals, *cloudWithNormals);
138 if(mergedClouds->size() == 0)
140 *mergedClouds = *cloudWithNormals;
144 *mergedClouds += *cloudWithNormals;
147 cameraPoses.insert(std::make_pair(iter->first, iter->second));
150 cameraModels.insert(std::make_pair(iter->first, models));
154 cameraDepths.insert(std::make_pair(iter->first, depth));
157 if(mergedClouds->size())
159 if(!(mesh || texture))
161 printf(
"Voxel grid filtering of the assembled cloud (voxel=%f, %d points)\n", 0.01
f, (
int)mergedClouds->size());
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");
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)
176 if(mapLength/
float(1<<i) < 0.03
f)
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);
190 poisson.reconstruct(*mesh);
191 printf(
"Mesh reconstruction... done! %fs (%d polygons)\n", timer.
ticks(), (int)mesh->polygons.size());
193 if(mesh->polygons.size())
195 rtabmap::util3d::denseMeshPostProcessing<pcl::PointXYZRGBNormal>(
205 printf(
"Saving mesh.ply...\n");
206 pcl::io::savePLYFile(
"mesh.ply", *mesh);
207 printf(
"Saving mesh.ply... done!\n");
211 printf(
"Texturing... cameraPoses=%d, cameraDepths=%d\n", (
int)cameraPoses.size(), (int)cameraDepths.size());
212 std::vector<std::map<int, pcl::PointXY> > vertexToPixels;
222 std::vector<float>(),
225 printf(
"Texturing... done! %fs\n", timer.
ticks());
228 if(textureMesh->tex_coordinates.size())
230 printf(
"Cleanup mesh...\n");
232 printf(
"Cleanup mesh... done! %fs\n", timer.
ticks());
235 if(textureMesh->tex_materials.size())
237 printf(
"Merging %d textures...\n", (
int)textureMesh->tex_materials.size());
240 std::map<int, cv::Mat>(),
241 std::map<
int, std::vector<rtabmap::CameraModel> >(),
247 true, 10.0f,
true ,
true, 0, 0, 0,
false);
251 bool success =
false;
253 UASSERT(textureMesh->tex_materials.size() == 1);
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);
261 UERROR(
"Failed saving %s!", filePath.c_str());
265 printf(
"Saved %s.\n", filePath.c_str());
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;
277 printf(
"Saved obj to %s!\n", filePath.c_str());
281 UERROR(
"Failed saving obj to %s!", filePath.c_str());
291 printf(
"Export failed! The cloud is empty.\n");
void get3DMap(std::map< int, Signature > &signatures, std::map< int, Transform > &poses, std::multimap< int, Link > &constraints, bool optimized, bool global) const
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)
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)
std::map< std::string, std::string > ParametersMap
Basic mathematics functions.
static void setLevel(ULogger::Level level)
bool openConnection(const std::string &url, bool overwritten=false)
#define UASSERT(condition)
T uMax3(const T &a, const T &b, const T &c)
void closeConnection(bool save=true, const std::string &outputUrl="")
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 >())
static void setType(Type type, const std::string &fileName=kDefaultLogFileName, bool append=true)
cv::Mat RTABMAP_EXP computeNormals(const cv::Mat &laserScan, int searchK, float searchRadius)
void init(const ParametersMap ¶meters, const std::string &databasePath="")
static DBDriver * create(const ParametersMap ¶meters=ParametersMap())
const std::vector< CameraModel > & cameraModels() const
GLM_FUNC_DECL genType max(genType const &x, genType const &y)
SensorData & sensorData()
void RTABMAP_EXP cleanTextureMesh(pcl::TextureMesh &textureMesh, int minClusterSize)
ParametersMap getLastParameters() const
const Memory * getMemory() const
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[])