0
点赞
收藏
分享

微信扫一扫

【三维重建】OpenMVS代码解析——点云稠密化:详细过程(2)

东林梁 2022-02-02 阅读 601

上一节内容过了一遍DensifyPointCloud.cpp中的main()函数,其中的每一步的具体操作在本篇文章中进行介绍。

1. 功能一:在曲面上进行点云采样的功能

  //option1:  enable uniformly samples points on a mesh 
	Scene scene(OPT::nMaxThreads);
	if (OPT::fSampleMesh != 0) {
		// sample input mesh and export the obtained point-cloud
		//load .ply of .obj pointcloud
		if (!scene.mesh.Load(MAKE_PATH_SAFE(OPT::strInputFileName))) 
			return EXIT_FAILURE;
		TD_TIMER_START();

		PointCloud pointcloud;
		if (OPT::fSampleMesh > 0)   // set points density
			scene.mesh.SamplePoints(OPT::fSampleMesh, 0, pointcloud);
		else                                        // set points number
			scene.mesh.SamplePoints((unsigned)ROUND2INT(-OPT::fSampleMesh), pointcloud);

		VERBOSE("Sample mesh completed: %u points (%s)", pointcloud.GetSize(), TD_TIMER_GET_FMT().c_str());
		pointcloud.Save(MAKE_PATH_SAFE(Util::getFileFullName(OPT::strOutputFileName))+_T(".ply"));
		Finalize();
		return EXIT_SUCCESS;
	}

OPT::fSampleMesh是进行点云采样的操作指令,OPT::fSampleMesh != 0意味着要进行这部分功能,return EXIT_SUCCESS意味着进行完这部分内容后不再执行后面的代码了。这一大段代码里,核心内容就两句话,scene.mesh.Load(MAKE_PATH_SAFE(OPT::strInputFileName))和scene.mesh.SamplePoints((unsigned)ROUND2INT(-OPT::fSampleMesh), pointcloud)。

1.1 导入数据

Load()函数在libs/MVS/Mesh.cpp下,这部分代码很直观,从这里可以看出来,OpenMVS的作者他是自己去实现输入输出,点云,octotree,甚至数据类型都是自定义的,而不是调库。

站在代码阅读的角度来看,读到这里已经可以了,如果感兴趣的话可以进一步读到LoadOBJ()和LoadPLY()里面去,可以帮助理解.obj和.ply文件是怎么描述mesh的,这里就不展开介绍了。这两个函数的作用是读取对应的mesh模型文件,并把对应的数据保存到内存中去。

// import the mesh from the given file
bool Mesh::Load(const String& fileName)
{
	TD_TIMER_STARTD();
	const String ext(Util::getFileExt(fileName).ToLower());
	bool ret;
	if (ext == _T(".obj"))
		ret = LoadOBJ(fileName);
	else
		ret = LoadPLY(fileName);
	if (!ret)
		return false;
	DEBUG_EXTRA("Mesh loaded: %u vertices, %u faces (%s)", vertices.GetSize(), faces.GetSize(), TD_TIMER_GET_FMT().c_str());
	return true;
}

1.2 在mesh上进行点云采样

SamplePoints()函数也是在libs/MVS/Mesh.cpp下,

void Mesh::SamplePoints(REAL samplingDensity, unsigned mumPointsTheoretic, PointCloud& pointcloud) const
{
    //allocate memory
	ASSERT(!IsEmpty());
	pointcloud.Release();
	if (mumPointsTheoretic > 0) {
		pointcloud.points.reserve(mumPointsTheoretic); 
		if (HasTexture())
			pointcloud.colors.reserve(mumPointsTheoretic);
	}

	// for each triangle
	std::mt19937 rnd((std::random_device())()); //generate random number
	std::uniform_real_distribution<REAL> dist(0,1);
	FOREACH(idxFace, faces) {
		const Face& face = faces[idxFace];

		// vertices (OAB)
		const Vertex& O = vertices[face[0]];
		const Vertex& A = vertices[face[1]];
		const Vertex& B = vertices[face[2]];

		// edges (OA and OB)
		const Vertex u(A - O);
		const Vertex v(B - O);

		// compute triangle area
		const REAL area(norm(u.cross(v)) * REAL(0.5));

		// deduce the number of points to generate on this face
		const REAL fPointsToAdd(area*samplingDensity);
		unsigned pointsToAdd(static_cast<unsigned>(fPointsToAdd));

		// take care of the remaining fractional part;
		// add a point with the same probability as its (relative) area
		const REAL fracPart(fPointsToAdd - static_cast<REAL>(pointsToAdd));
		if (dist(rnd) <= fracPart)
			pointsToAdd++;

		for (unsigned i = 0; i < pointsToAdd; ++i) {
			// generate random points as in:
			// "Generating random points in triangles", Greg Turk;
			// in A. S. Glassner, editor, Graphics Gems, pages 24-28. Academic Press, 1990
			REAL x(dist(rnd));
			REAL y(dist(rnd));

			// test if the generated point lies on the right side of (AB)
			if (x + y > REAL(1)) {
				x = REAL(1) - x;
				y = REAL(1) - y;
			}

			// compute position
			pointcloud.points.emplace_back(O + static_cast<Vertex::Type>(x)*u + static_cast<Vertex::Type>(y)*v);

			if (HasTexture()) {
				// compute color
				const FIndex idxTexCoord(idxFace*3);
				const TexCoord& TO = faceTexcoords[idxTexCoord+0];
				const TexCoord& TA = faceTexcoords[idxTexCoord+1];
				const TexCoord& TB = faceTexcoords[idxTexCoord+2];
				const TexCoord xt(TO + static_cast<TexCoord::Type>(x)*(TA - TO) + static_cast<TexCoord::Type>(y)*(TB - TO));
				pointcloud.colors.emplace_back(textureDiffuse.sampleSafe(Point2f(xt.x*textureDiffuse.width(), (1.f-xt.y)*textureDiffuse.height())));
			}
		}
	}
}

首先给点云开辟内存空间,再遍历每一个mesh,根据采样分辨率和计算在当前的mesh上应该采样多少个点。这里计算的点数可能是小数,比如说100.6个点,此时随机数函数就排上了用场,在0-1之间创建一个随机数,如果这个随机数小于那个0.6,那么就创建101个点,否则就创建100个点。然后假设当前mesh有三个顶点OAB,那么采样获得的点就在这三个点围成的三角形上,颜色取该位置到三个点的距离作为权值,融合颜色给到当前的采样点上。

2. 导入数据

这部分内容是导入输入数据,

	// load and estimate a dense point-cloud
	// input images and poses
	if (!scene.Load(MAKE_PATH_SAFE(OPT::strInputFileName)))
		return EXIT_FAILURE;
    //  input mesh
	if (!OPT::strMeshFileName.empty())
		scene.mesh.Load(MAKE_PATH_SAFE(OPT::strMeshFileName));
	if (scene.pointcloud.IsEmpty() && OPT::strViewNeighborsFileName.empty() && scene.mesh.IsEmpty()) {
		VERBOSE("error: empty initial point-cloud");
		return EXIT_FAILURE;
	}

scene.Load(MAKE_PATH_SAFE(OPT::strInputFileName))导入的是相机里程计和图片,scene.mesh.Load(MAKE_PATH_SAFE(OPT::strMeshFileName))导入的是经过SfM获得的mesh模型,对于后面的内容,以上数据缺一不可。

2.1 导入相机数据

Load()函数在libs/MVS/Scene.cpp下,

bool Scene::Load(const String& fileName, bool bImport)
{
	TD_TIMER_STARTD();
	Release();

	#ifdef _USE_BOOST
	// open the input stream
	std::ifstream fs(fileName, std::ios::in | std::ios::binary);
	if (!fs.is_open())
		return false;
	// load project header ID
	char szHeader[4];
	fs.read(szHeader, 4);
	if (!fs || _tcsncmp(szHeader, PROJECT_ID, 4) != 0) {
		fs.close();
		if (bImport && Import(fileName))
			return true;
		if (LoadInterface(fileName))
			return true;
		VERBOSE("error: invalid project");
		return false;
	}
	// load project version
	uint32_t nVer;
	fs.read((char*)&nVer, sizeof(uint32_t));
	if (!fs || nVer != PROJECT_VER) {
		VERBOSE("error: different project version");
		return false;
	}

	// load stream type
	uint32_t nType;
	fs.read((char*)&nType, sizeof(uint32_t));

	// skip reserved bytes
	uint64_t nReserved;
	fs.read((char*)&nReserved, sizeof(uint64_t));

	// serialize in the current state
	if (!SerializeLoad(*this, fs, (ARCHIVE_TYPE)nType))
		return false;

	// init images
	nCalibratedImages = 0;
	size_t nTotalPixels(0);
	FOREACH(ID, images) {
		Image& imageData = images[ID];
		if (imageData.poseID == NO_ID)
			continue;
		imageData.UpdateCamera(platforms);
		++nCalibratedImages;
		nTotalPixels += imageData.width * imageData.height;
	}
	DEBUG_EXTRA("Scene loaded (%s):\n"
				"\t%u images (%u calibrated) with a total of %.2f MPixels (%.2f MPixels/image)\n"
				"\t%u points, %u vertices, %u faces",
				TD_TIMER_GET_FMT().c_str(),
				images.GetSize(), nCalibratedImages, (double)nTotalPixels/(1024.0*1024.0), (double)nTotalPixels/(1024.0*1024.0*nCalibratedImages),
				pointcloud.points.GetSize(), mesh.vertices.GetSize(), mesh.faces.GetSize());
	return true;
	#else
	return false;
	#endif
} // Load

3.功能二:降采样

	//option2:  split the scene in sub-scenes such that each sub-scene surface does not exceed the given maximum sampling area (0 - disabled)
	if (OPT::fMaxSubsceneArea > 0) {
		// split the scene in sub-scenes by maximum sampling area
		Scene::ImagesChunkArr chunks;
		// downsampling depth pixels and images and get pintcloud
		scene.Split(chunks, OPT::fMaxSubsceneArea);
		//  save each chunk as a .mvs
		scene.ExportChunks(chunks, Util::getFilePath(MAKE_PATH_SAFE(OPT::strOutputFileName)), (ARCHIVE_TYPE)OPT::nArchiveType);
		Finalize();
		return EXIT_SUCCESS;
	}

OPT::fMaxSubsceneArea是执行降采样的操作指令,>0意味着执行这部分代码。scene.Split()是降采样的操作过程,scene.ExportChunks()是输出结果。

3.1 降采样

Split()函数在libs/MVS/Scene.cpp下,这一长串原生注释介绍了这个函数是干什么用的:限制读取到内存里的照片数量和照片分辨率,目的就是让内存一次就能把当前的数据都加载了。

// split the scene in sub-scenes such that each sub-scene surface does not exceed the given
// maximum sampling area; the area is composed of overlapping samples from different cameras
// taking into account the footprint of each sample (pixels/unit-length, GSD inverse),
// including overlapping samples;
// the indirect goals this method tries to achieve are:
//  - limit the maximum number of images in each sub-scene such that the depth-map fusion
//    can load all sub-scene's depth-maps into memory at once
//  - limit in the same time maximum accumulated images resolution (total number of pixels)
//    per sub-scene in order to allow all images to be loaded and processed during mesh refinement
unsigned Scene::Split(ImagesChunkArr& chunks, float maxArea, int depthMapStep) const {}

3.1.1 定义一些变量

	const float areaScale(0.01f);//resolution
	typedef cList<Point3f::EVec,const Point3f::EVec&,0,4096,uint32_t> Samples;            
	typedef TOctree<Samples,float,3> Octree;                                                                    
	Octree octree;//octotree in world
	FloatArr areas(0, images.size()*4192);//area of each surface piece
	IIndexArr visibility(0, (IIndex)areas.capacity());//for each points in Samples, the idx of image it belongs to
	Unsigned32Arr imageAreas(images.size());//for each image, how many points can be observed on it
    Samples samples(0, (uint32_t)areas.capacity());//pointcloud in world

3.1.2 对每一张image进行降采样

		FOREACH(idxImage, images) {
			const Image& imageData = images[idxImage];
			if (!imageData.IsValid())
				continue;
			DepthData depthData;
			depthData.Load(ComposeDepthFilePath(imageData.ID, "dmap"));
			if (depthData.IsEmpty())
				continue;
            
             //1.  limit maximum accumulated images resolution per sub-scene
			const IIndex numPointsBegin(visibility.size());
			const Camera camera(imageData.GetCamera(platforms, depthData.depthMap.size()));
			for (int r=(depthData.depthMap.rows%depthMapStep)/2; r<depthData.depthMap.rows; r+=depthMapStep) {
				for (int c=(depthData.depthMap.cols%depthMapStep)/2; c<depthData.depthMap.cols; c+=depthMapStep) {
					const Depth depth = depthData.depthMap(r,c);
					if (depth <= 0)
						continue;
					const Point3f& X = samples.emplace_back(Cast<float>(camera.TransformPointI2W(Point3(c,r,depth))));
					areas.emplace_back(Footprint(camera, X)*areaScale);
					visibility.emplace_back(idxImage);
				}
			}
			imageAreas[idxImage] = visibility.size()-numPointsBegin;
		}

3.1.3 构造八叉树

		#if 0
		const AABB3f aabb(samples.data(), samples.size());
		#else
		// try to find a dominant plane, and set the bounding-box center on the plane bottom
		OBB3f obb(samples.data(), samples.size());
		obb.m_ext(0) *= 2;
		#if 1
		// dump box for visualization
		OBB3f::POINT pts[8];
		obb.GetCorners(pts);
		PointCloud pc;
		for (int i=0; i<8; ++i)
			pc.points.emplace_back(pts[i]);
		pc.Save(MAKE_PATH("scene_obb.ply"));
		#endif
		const AABB3f aabb(obb.GetAABB());
		#endif
		octree.Insert(samples, aabb, [](Octree::IDX_TYPE size, Octree::Type /*radius*/) {return size > 128;});
		#if 0 && !defined(_RELEASE)
		Octree::DEBUGINFO_TYPE info;
		octree.GetDebugInfo(&info);
		Octree::LogDebugInfo(info);
		#endif
		octree.ResetItems();

利用上一步获取的点云构造八叉树。

3.1.4 删除一些区别不大的照片

这部分说实话没有看的特别懂,首先它定义了两个结构体,AreaInserter和ChunkInserter,分别用于帮助计算累加的面积和往chunk里面加image.

	struct AreaInserter {
		const FloatArr& areas;
		float area;
		inline void operator() (const Octree::IDX_TYPE* indices, Octree::SIZE_TYPE size) {
			FOREACHRAWPTR(pIdx, indices, size)
				area += areas[*pIdx];
		}
		inline float PopArea() {
			const float a(area);
			area = 0;
			return a;
		}
	} areaEstimator{areas, 0.f};
    
	struct ChunkInserter {
		const IIndex numImages;
		const Octree& octree;
		const IIndexArr& visibility;
		ImagesChunkArr& chunks;
		CLISTDEF2(Unsigned32Arr) imagesAreas;

		void operator() (const Octree::CELL_TYPE& parentCell, Octree::Type parentRadius, const UnsignedArr& children) {
			ASSERT(!children.empty());
			ImagesChunk& chunk = chunks.AddEmpty();
			Unsigned32Arr& imageAreas = imagesAreas.AddEmpty();
			imageAreas.resize(numImages);
			imageAreas.Memset(0);

			struct Inserter {
				const IIndexArr& visibility;
				std::unordered_set<IIndex>& images;
				Unsigned32Arr& imageAreas;
				inline void operator() (const Octree::IDX_TYPE* indices, Octree::SIZE_TYPE size) {
					FOREACHRAWPTR(pIdx, indices, size) {
						const IIndex idxImage(visibility[*pIdx]);
						images.emplace(idxImage);
						++imageAreas[idxImage];
					}
				}
			} inserter{visibility, chunk.images, imageAreas};

			if (children.size() == 1) {
				octree.CollectCells(parentCell.GetChild(children.front()), inserter);
				chunk.aabb = parentCell.GetChildAabb(children.front(), parentRadius);
			} else {
				chunk.aabb.Reset();
				for (unsigned c: children) {
					octree.CollectCells(parentCell.GetChild(c), inserter);
					chunk.aabb.Insert(parentCell.GetChildAabb(c, parentRadius));
				}
			}
			if (chunk.images.empty()) {
				chunks.RemoveLast();
				imagesAreas.RemoveLast();
			}
		}
	} chunkInserter{images.size(), octree, visibility, chunks};

然后,把这两个结构体传入到八叉树里,

    //TODO I do not what actually done here, but I know it does something to downsampling images
	octree.SplitVolume(maxArea, areaEstimator, chunkInserter);
	if (chunks.size() < 2)
		return 0;

根据照片本身是否有足够的贡献度进行过滤,

	//2.1 remove images with very little contribution
	const float minImageContributionRatio(0.3f);
	FOREACH(c, chunks) {
		ImagesChunk& chunk = chunks[c];
		const Unsigned32Arr& chunkImageAreas = chunkInserter.imagesAreas[c];
		float maxAreaRatio = 0;
		for (const IIndex idxImage : chunk.images) {
			const float areaRatio(static_cast<float>(chunkImageAreas[idxImage])/static_cast<float>(imageAreas[idxImage]));
			if (maxAreaRatio < areaRatio)
				maxAreaRatio = areaRatio;
		}
		const float minImageContributionRatioChunk(maxAreaRatio * minImageContributionRatio);
		for (auto it = chunk.images.begin(); it != chunk.images.end(); ) {
			const IIndex idxImage(*it);
			if (static_cast<float>(chunkImageAreas[idxImage])/static_cast<float>(imageAreas[idxImage]) < minImageContributionRatioChunk)
				it = chunk.images.erase(it);
			else
				++it;
		}
	}

对于描述了重复三位空间的chunk,删掉小的那个chunk,

	//2.2 remove images already completely contained by a larger chunk
	const float minImageContributionRatioLargerChunk(0.9f);
	FOREACH(cSmall, chunks) {
		ImagesChunk& chunkSmall = chunks[cSmall];
		const Unsigned32Arr& chunkSmallImageAreas = chunkInserter.imagesAreas[cSmall];
		FOREACH(cLarge, chunks) {
			const ImagesChunk& chunkLarge = chunks[cLarge];
			if (chunkLarge.images.size() <= chunkSmall.images.size())
				continue;
			const Unsigned32Arr& chunkLargeImageAreas = chunkInserter.imagesAreas[cLarge];
			for (auto it = chunkSmall.images.begin(); it != chunkSmall.images.end(); ) {
				const IIndex idxImage(*it);
				if (chunkSmallImageAreas[idxImage] < chunkLargeImageAreas[idxImage] &&
					static_cast<float>(chunkLargeImageAreas[idxImage])/static_cast<float>(imageAreas[idxImage]) > minImageContributionRatioLargerChunk)
					it = chunkSmall.images.erase(it);
				else
					++it;
			}
		}
	}

把小chunk合并到相邻的大chunk里。

	//2.3 merge small chunks into larger chunk neighbors
	// TODO: better manage the bounding-box merge
	const unsigned minNumImagesPerChunk(4);
	RFOREACH(cSmall, chunks) {
		ImagesChunk& chunkSmall = chunks[cSmall];
		if (chunkSmall.images.size() > minNumImagesPerChunk)
			continue;
		// find the chunk having the most images in common
		IIndex idxBestChunk;
		unsigned numLargestCommonImages(0);
		FOREACH(cLarge, chunks) {
			if (cSmall == cLarge)
				continue;
			const ImagesChunk& chunkLarge = chunks[cLarge];
			unsigned numCommonImages(0);
			for (const IIndex idxImage: chunkSmall.images)
				if (chunkLarge.images.find(idxImage) != chunkLarge.images.end())
					++numCommonImages;
			if (numCommonImages == 0)
				continue;
			if (numLargestCommonImages < numCommonImages ||
				(numLargestCommonImages == numCommonImages && chunks[idxBestChunk].images.size() < chunkLarge.images.size()))
			{
				numLargestCommonImages = numCommonImages;
				idxBestChunk = cLarge;
			}
		}
		if (numLargestCommonImages == 0) {
			DEBUG_ULTIMATE("warning: small chunk can not be merged (%u chunk, %u images)",
				cSmall, chunkSmall.images.size());
			continue;
		}
		// merge the small chunk and remove it
		ImagesChunk& chunkLarge = chunks[idxBestChunk];
		DEBUG_ULTIMATE("Small chunk merged: %u chunk (%u images) -> %u chunk (%u images)",
			cSmall, chunkSmall.images.size(), idxBestChunk, chunkLarge.images.size());
		chunkLarge.aabb.Insert(chunkSmall.aabb);
		chunkLarge.images.insert(chunkSmall.images.begin(), chunkSmall.images.end());
		chunks.RemoveAt(cSmall);
	}

3.2 保存模型

ExportChunks()在libs/MVS/Scene.cpp下,

// split the scene in sub-scenes according to the given chunks array, and save them to disk
bool Scene::ExportChunks(const ImagesChunkArr& chunks, const String& path, ARCHIVE_TYPE type) const
{
    // visit each chunck
	FOREACH(chunkID, chunks) {
		const ImagesChunk& chunk = chunks[chunkID];
		Scene subset;
		subset.nCalibratedImages = (IIndex)chunk.images.size();
        
		//1. visit each image in current chunk: extract chunk images
		typedef std::unordered_map<IIndex,IIndex> MapIIndex;
		MapIIndex mapPlatforms(platforms.size());
		MapIIndex mapImages(images.size());
		FOREACH(idxImage, images) {
			if (chunk.images.find(idxImage) == chunk.images.end())
				continue;
			const Image& image = images[idxImage];
			if (!image.IsValid())
				continue;
			//1.1 copy platform: put these information into subset
			const Platform& platform = platforms[image.platformID];
			MapIIndex::iterator itSubPlatformMVS = mapPlatforms.find(image.platformID);
			uint32_t subPlatformID;
			if (itSubPlatformMVS == mapPlatforms.end()) {
				ASSERT(subset.platforms.size() == mapPlatforms.size());
				subPlatformID = subset.platforms.size();
				mapPlatforms.emplace(image.platformID, subPlatformID);
				Platform subPlatform;
				subPlatform.name = platform.name;
				subPlatform.cameras = platform.cameras;
				subset.platforms.emplace_back(std::move(subPlatform));
			} else {
				subPlatformID = itSubPlatformMVS->second;
			}
			Platform& subPlatform = subset.platforms[subPlatformID];
			//1.2 copy image
			const IIndex idxImageNew((IIndex)mapImages.size());
			mapImages[idxImage] = idxImageNew;
			Image subImage(image);
			subImage.platformID = subPlatformID;
			subImage.poseID = subPlatform.poses.size();
			subImage.ID = idxImage;
			subset.images.emplace_back(std::move(subImage));
			//1.3 copy pose
			subPlatform.poses.emplace_back(platform.poses[image.poseID]);
		}

		//2. map image IDs from global to local
		for (Image& image: subset.images) {
			RFOREACH(i, image.neighbors) {
				ViewScore& neighbor = image.neighbors[i];
				const auto itImage(mapImages.find(neighbor.idx.ID));
				if (itImage == mapImages.end()) {
					image.neighbors.RemoveAtMove(i);
					continue;
				}
				ASSERT(itImage->second < subset.images.size());
				neighbor.idx.ID = itImage->second;
			}
		}

		//3. extract point-cloud
		FOREACH(idxPoint, pointcloud.points) {
			PointCloud::ViewArr subViews;
			PointCloud::WeightArr subWeights;
			const PointCloud::ViewArr& views = pointcloud.pointViews[idxPoint];
			FOREACH(i, views) {
				const IIndex idxImage(views[i]);
				const auto itImage(mapImages.find(idxImage));
				if (itImage == mapImages.end())
					continue;
				subViews.emplace_back(itImage->second);
				if (!pointcloud.pointWeights.empty())
					subWeights.emplace_back(pointcloud.pointWeights[idxPoint][i]);
			}
			if (subViews.size() < 2)
				continue;
			subset.pointcloud.points.emplace_back(pointcloud.points[idxPoint]);
			subset.pointcloud.pointViews.emplace_back(std::move(subViews));
			if (!pointcloud.pointWeights.empty())
				subset.pointcloud.pointWeights.emplace_back(std::move(subWeights));
			if (!pointcloud.colors.empty())
				subset.pointcloud.colors.emplace_back(pointcloud.colors[idxPoint]);
		}

		//4. set scene ROI
		subset.obb.Set(OBB3f::MATRIX::Identity(), chunk.aabb.ptMin, chunk.aabb.ptMax);
		// serialize out the current state
		if (!subset.Save(String::FormatString("%s" PATH_SEPARATOR_STR "scene_%04u.mvs", path.c_str(), chunkID), type))
			return false;
	}
	return true;
} // ExportChunks

4. 功能三:根据能否被看到进行点云过滤

	//option3: filter dense point-cloud based on visibility (0 - disabled)
	if (OPT::thFilterPointCloud < 0) {
		// filter point-cloud based on camera-point visibility intersections
		scene.PointCloudFilter(OPT::thFilterPointCloud);
		// save
		const String baseFileName(MAKE_PATH_SAFE(Util::getFileFullName(OPT::strOutputFileName))+_T("_filtered"));
		scene.Save(baseFileName+_T(".mvs"), (ARCHIVE_TYPE)OPT::nArchiveType);
		scene.pointcloud.Save(baseFileName+_T(".ply"));
		Finalize();
		return EXIT_SUCCESS;
	}

PointCloudFilter()定义在libs/MVS/SceneDensify.cpp下。

4.1 Collector结构体的定义

首先,定义了一些用到的变量和构造函数,包括序号,相机在某一个位置时的pose,这个pose附近的一个球体,和ConeIntersect,帮助判断某一个点云是否能被看到。

	struct Collector {
		typedef Octree::IDX_TYPE IDX; // idx
		typedef PointCloud::Point::Type Real; // something like float or double
		typedef TCone<Real,3> Cone; // Basic cone: I think it is ray center
		typedef TSphere<Real,3> Sphere; // Basic sphere class
		typedef TConeIntersect<Real,3> ConeIntersect; // Structure used to compute the intersection between a cone and the given sphere/point

		Cone                                             cone;
		const ConeIntersect                              coneIntersect;
		const PointCloud&                                pointcloud;
		IntArr&                                          visibility;
		PointCloud::Index                                idxPoint;
		Real                                             distance;
		int                                              weight;
		#ifdef DENSE_USE_OPENMP
		uint8_t                                          pcs[sizeof(CriticalSection)];
		#endif

		Collector(const Cone::RAY& ray, Real angle, const PointCloud& _pointcloud, IntArr& _visibility)
			: cone(ray, angle), coneIntersect(cone), pointcloud(_pointcloud), visibility(_visibility)
		#ifdef DENSE_USE_OPENMP
		{ new(pcs) CriticalSection; }
		~Collector() { reinterpret_cast<CriticalSection*>(pcs)->~CriticalSection(); }
		inline CriticalSection& GetCS() { return *reinterpret_cast<CriticalSection*>(pcs); }
		#else
		{}
		#endif

初始化函数,记录某一个点云和相机中心的空间关系,

		inline void Init(PointCloud::Index _idxPoint, const PointCloud::Point& X, int _weight) {
			const Real thMaxDepth(1.02f);// something like a factor, ratio, coefficient
			idxPoint =_idxPoint;// idx of point x
			const PointCloud::Point::EVec D((PointCloud::Point::EVec&)X-cone.ray.m_pOrig);// direction vector cone -> X
			distance = D.norm();// distance cone -> X
			cone.ray.m_vDir = D/distance;// uniformed direction vetor cone -> X (length is 1)
			cone.maxHeight = MaxDepthDifference(distance, thMaxDepth);// distance * thMaxDepth
			weight = _weight;// weight
		}

判断来自相机中心的射线是否与当前点云相交,

		// judge whether the cone is intersected with the sphere
		inline bool Intersects(const Octree::POINT_TYPE& center, Octree::Type radius) const {
			return coneIntersect(Sphere(center, radius*Real(SQRT_3)));                                              
		}

其中coneIntersect()定义在libs/Common/Ray.inl下,如果sphere和cone的中心的足够近,那么就true。

template <typename TYPE, int DIMS>
bool TConeIntersect<TYPE,DIMS>::operator()(const SPHERE& sphere) const
{
	const VECTOR CmV(sphere.center - cone.ray.m_pOrig);
	const VECTOR D(CmV + cone.ray.m_vDir * (sphere.radius*invSinAngle));
	TYPE e = D.dot(cone.ray.m_vDir);
	if (e <= TYPE(0) || e*e < D.squaredNorm()*cosAngleSq)
		return false;
	e = CmV.dot(cone.ray.m_vDir);
	if (e-sphere.radius > cone.maxHeight)
		return false;
	if (e < cone.minHeight) {
		const TYPE lenSq = CmV.squaredNorm();
		if (e*e >= lenSq*sinAngleSq)
			return lenSq <= SQUARE(sphere.radius);
	}
	return true;
} // Intersect

然后计算每一个点的visibility,

		// find the visibility of each point
		inline void operator () (const IDX* idices, IDX size) {
			const Real thSimilar(0.01f);
			Real dist;
			FOREACHRAWPTR(pIdx, idices, size) {
				const PointCloud::Index idx(*pIdx);
                // if the point is visible and depth is different with existing points, add this visibility
				if (coneIntersect.Classify(pointcloud.points[idx], dist) == VISIBLE && !IsDepthSimilar(distance, dist, thSimilar)) {
					if (dist > distance)
						visibility[idx] += pointcloud.pointViews[idx].size();
					else
						visibility[idx] -= weight;
				}
			}
		}

其中Classify()也是定义在libs/Common/Ray.inl下,同样保留与cone中心近的点,

// Classify point to cone.
template <typename TYPE, int DIMS>
GCLASS TConeIntersect<TYPE,DIMS>::Classify(const POINT& p, TYPE& t) const
{
	ASSERT(ISEQUAL(cone.ray.m_vDir.norm(), TYPE(1)));
	const VECTOR D(p - cone.ray.m_pOrig);
	t = cone.ray.m_vDir.dot(D);

	if (ISZERO(t))           return PLANAR;
	if (t < cone.minHeight)  return BACK;
	if (t > cone.maxHeight)  return FRONT;

	ASSERT(!ISZERO(D.norm()));
	const TYPE tSq(SQUARE(t));
	const TYPE dSq(cosAngleSq*D.squaredNorm());
	if (tSq < dSq)                return CULLED;
	if (tSq > dSq)                return VISIBLE;

	return PLANAR;
} // Classify

4.2 准备用于判断intersect的容器和数据

	// create octree to speed-up search
	Octree octree(pointcloud.points, [](Octree::IDX_TYPE size, Octree::Type /*radius*/) {return size > 128;});
    
    // build a collector for each image, and put into collectors
	IntArr visibility(pointcloud.GetSize());       visibility.Memset(0);
	Collectors collectors;                                  collectors.reserve(images.size());
	FOREACH(idxView, images) {
		const Image& image = images[idxView];
		const Ray3f ray(Cast<float>(image.camera.C), Cast<float>(image.camera.Direction()));
		const float angle(float(image.ComputeFOV(0)/image.width));
		collectors.emplace_back(ray, angle, pointcloud, visibility);
	}

4.3 计算visibility

	// run all camera-point visibility intersections
	Util::Progress progress(_T("Point visibility checks"), pointcloud.GetSize());
	#ifdef DENSE_USE_OPENMP
	#pragma omp parallel for //schedule(dynamic)
	for (int64_t i=0; i<(int64_t)pointcloud.GetSize(); ++i) {
		const PointCloud::Index idxPoint((PointCloud::Index)i);
	#else
	FOREACH(idxPoint, pointcloud.points) {
	#endif
		const PointCloud::Point&     X        = pointcloud.points[idxPoint];
		const PointCloud::ViewArr& views = pointcloud.pointViews[idxPoint];
		for (PointCloud::View idxView: views) {
			Collector& collector = collectors[idxView];
			#ifdef DENSE_USE_OPENMP
			Lock l(collector.GetCS());
			#endif
			collector.Init(idxPoint, X, (int)views.size());
			octree.Collect(collector, collector);
		}
		++progress;
	}
	progress.close();

4.4 保留visibility符合条件的点

	// filter points
	const size_t numInitPoints(pointcloud.GetSize());
	RFOREACH(idxPoint, pointcloud.points) {
		if (visibility[idxPoint] <= thRemove)
			pointcloud.RemovePoint(idxPoint);
	}

5. 根据被观测到的次数过滤点云

	//option4: export points with >= number of views (0 - disabled)
	if (OPT::nExportNumViews && scene.pointcloud.IsValid()) {
		// export point-cloud containing only points with N+ views
		const String baseFileName(MAKE_PATH_SAFE(Util::getFileFullName(OPT::strOutputFileName)));
		scene.pointcloud.SaveNViews(baseFileName+String::FormatString(_T("_%dviews.ply"), OPT::nExportNumViews), (IIndex)OPT::nExportNumViews);
		Finalize();
		return EXIT_SUCCESS;
	}

SaveNViews()定义在libs/MVS/PointCloud.cpp下,

// save the dense point cloud having >=N views as PLY file
bool PointCloud::SaveNViews(const String& fileName, uint32_t minViews, bool bLegacyTypes) const
{
	if (points.IsEmpty())
		return false;
	TD_TIMER_STARTD();

	// create PLY object
	ASSERT(!fileName.IsEmpty());
	Util::ensureFolder(fileName);
	PLY ply;
	if (bLegacyTypes)
		ply.set_legacy_type_names();
	if (!ply.write(fileName, 1, BasicPLY::elem_names, PLY::BINARY_LE, 64*1024))
		return false;

	if (normals.IsEmpty()) {
		// describe what properties go into the vertex elements
		ply.describe_property(BasicPLY::elem_names[0], 6, BasicPLY::vert_props);

		// export the array of 3D points
		BasicPLY::PointColNormal vertex;
		FOREACH(i, points) {
            // save the dense point cloud having >=N views as PLY file
			if (pointViews[i].size() < minViews)
				continue;
			// export the vertex position, normal and color
			vertex.p = points[i];
			vertex.c = (!colors.IsEmpty() ? colors[i] : Color::WHITE);
            // save
			ply.put_element(&vertex);
		}
	} else {
		// describe what properties go into the vertex elements
		ply.describe_property(BasicPLY::elem_names[0], 9, BasicPLY::vert_props);

		// export the array of 3D points
		BasicPLY::PointColNormal vertex;
		FOREACH(i, points) {
            // save the dense point cloud having >=N views as PLY file
			if (pointViews[i].size() < minViews)
				continue;
			// export the vertex position, normal and color
			vertex.p = points[i];
			vertex.n = normals[i];
			vertex.c = (!colors.IsEmpty() ? colors[i] : Color::WHITE);
            // save
			ply.put_element(&vertex);
		}
	}
	const int numPoints(ply.get_current_element_count());

	// write the header
	if (!ply.header_complete())
		return false;

	DEBUG_EXTRA("Point-cloud saved: %u points with at least %u views each (%s)", numPoints, minViews, TD_TIMER_GET_FMT().c_str());
	return true;
} // SaveNViews
举报

相关推荐

0 条评论