Merged add-poissonrecon, cleaned up old config params

pull/889/head
Piero Toffanin 2018-07-06 10:29:55 -04:00
commit 6b537945a2
13 zmienionych plików z 61 dodań i 689 usunięć

Wyświetl plik

@ -131,6 +131,7 @@ endforeach()
externalproject_add(mve
GIT_REPOSITORY https://github.com/simonfuhrmann/mve.git
GIT_TAG 2106a5b0aef61a7f744551510b1b4c5d8e3be594
UPDATE_COMMAND ""
SOURCE_DIR ${SB_SOURCE_DIR}/elibs/mve
CONFIGURE_COMMAND ""
@ -142,6 +143,7 @@ externalproject_add(mve
externalproject_add(smvs
DEPENDS mve
GIT_REPOSITORY https://github.com/flanggut/smvs.git
GIT_TAG 6a7d0c095aa66ab98c5b285c2bc04e34d8993353
UPDATE_COMMAND ""
SOURCE_DIR ${SB_SOURCE_DIR}/elibs/smvs
CONFIGURE_COMMAND ""
@ -150,3 +152,13 @@ externalproject_add(smvs
INSTALL_COMMAND ""
)
externalproject_add(poissonrecon
GIT_REPOSITORY https://github.com/mkazhdan/PoissonRecon.git
GIT_TAG ce5005ae3094d902d551a65a8b3131e06f45e7cf
SOURCE_DIR ${SB_SOURCE_DIR}/PoissonRecon
UPDATE_COMMAND ""
CONFIGURE_COMMAND ""
BUILD_IN_SOURCE 1
BUILD_COMMAND make poissonrecon
INSTALL_COMMAND ""
)

Wyświetl plik

@ -6,7 +6,6 @@ endif()
# Add ODM sub-modules
add_subdirectory(odm_extract_utm)
add_subdirectory(odm_georef)
add_subdirectory(odm_meshing)
add_subdirectory(odm_orthophoto)
add_subdirectory(odm_cleanmesh)
if (ODM_BUILD_SLAM)

Wyświetl plik

@ -1,26 +0,0 @@
project(odm_meshing)
cmake_minimum_required(VERSION 2.8)
# Set pcl dir to the input spedified with option -DPCL_DIR="path"
set(PCL_DIR "PCL_DIR-NOTFOUND" CACHE "PCL_DIR" "Path to the pcl installation directory")
# Add compiler options.
add_definitions(-Wall -Wextra)
# Find pcl at the location specified by PCL_DIR
find_package(PCL 1.8 HINTS "${PCL_DIR}/share/pcl-1.8")
# Add the PCL and Eigen include dirs.
# Necessary since the PCL_INCLUDE_DIR variable set by find_package is broken.)
include_directories(${PCL_ROOT}/include/pcl-${PCL_VERSION_MAJOR}.${PCL_VERSION_MINOR})
include_directories(${EIGEN_ROOT})
# Add source directory
aux_source_directory("./src" SRC_LIST)
# Add exectuteable
add_executable(${PROJECT_NAME} ${SRC_LIST})
# Link
target_link_libraries(odm_meshing ${PCL_COMMON_LIBRARIES} ${PCL_IO_LIBRARIES} ${PCL_SURFACE_LIBRARIES})

Wyświetl plik

@ -1,31 +0,0 @@
#include "Logger.hpp"
Logger::Logger(bool isPrintingInCout) : isPrintingInCout_(isPrintingInCout)
{
}
Logger::~Logger()
{
}
void Logger::printToFile(std::string filePath)
{
std::ofstream file(filePath.c_str(), std::ios::binary);
file << logStream_.str();
file.close();
}
bool Logger::isPrintingInCout() const
{
return isPrintingInCout_;
}
void Logger::setIsPrintingInCout(bool isPrintingInCout)
{
isPrintingInCout_ = isPrintingInCout;
}

Wyświetl plik

@ -1,68 +0,0 @@
#pragma once
// STL
#include <string>
#include <sstream>
#include <fstream>
#include <iostream>
/*!
* \brief The Logger class is used to store program messages in a log file.
* \details By using the << operator while printInCout is set, the class writes both to
* cout and to file, if the flag is not set, output is written to file only.
*/
class Logger
{
public:
/*!
* \brief Logger Contains functionality for printing and displaying log information.
* \param printInCout Flag toggling if operator << also writes to cout.
*/
Logger(bool isPrintingInCout = true);
/*!
* \brief Destructor.
*/
~Logger();
/*!
* \brief print Prints the contents of the log to file.
* \param filePath Path specifying where to write the log.
*/
void printToFile(std::string filePath);
/*!
* \brief isPrintingInCout Check if console printing flag is set.
* \return Console printing flag.
*/
bool isPrintingInCout() const;
/*!
* \brief setIsPrintingInCout Set console printing flag.
* \param isPrintingInCout Value, if true, messages added to the log are also printed in cout.
*/
void setIsPrintingInCout(bool isPrintingInCout);
/*!
* Operator for printing messages to log and in the standard output stream if desired.
*/
template<class T>
friend Logger& operator<< (Logger &log, T t)
{
// If console printing is enabled.
if (log.isPrintingInCout_)
{
std::cout << t;
std::cout.flush();
}
// Write to log.
log.logStream_ << t;
return log;
}
private:
bool isPrintingInCout_; /*!< If flag is set, log is printed in cout and written to the log. */
std::stringstream logStream_; /*!< Stream for storing the log. */
};

Wyświetl plik

@ -1,361 +0,0 @@
#include "OdmMeshing.hpp"
OdmMeshing::OdmMeshing() : log_(false)
{
meshCreator_ = pcl::Poisson<pcl::PointNormal>::Ptr(new pcl::Poisson<pcl::PointNormal>());
points_ = pcl::PointCloud<pcl::PointNormal>::Ptr(new pcl::PointCloud<pcl::PointNormal>());
mesh_ = pcl::PolygonMeshPtr(new pcl::PolygonMesh);
decimatedMesh_ = pcl::PolygonMeshPtr(new pcl::PolygonMesh);
// Set default values
outputFile_ = "";
logFilePath_ = "";
maxVertexCount_ = 0;
treeDepth_ = 0;
solverDivide_ = 9.0;
samplesPerNode_ = 1.0;
decimationFactor_ = 0.0;
logFilePath_ = "odm_meshing_log.txt";
log_ << logFilePath_ << "\n";
}
OdmMeshing::~OdmMeshing()
{
}
int OdmMeshing::run(int argc, char **argv)
{
// If no arguments were passed, print help and return early.
if (argc <= 1)
{
printHelp();
return EXIT_SUCCESS;
}
try
{
parseArguments(argc, argv);
loadPoints();
createMesh();
decimateMesh();
writePlyFile();
}
catch (const OdmMeshingException& e)
{
log_.setIsPrintingInCout(true);
log_ << e.what() << "\n";
log_.printToFile(logFilePath_);
log_ << "For more detailed information, see log file." << "\n";
return EXIT_FAILURE;
}
catch (const std::exception& e)
{
log_.setIsPrintingInCout(true);
log_ << "Error in OdmMeshing:\n";
log_ << e.what() << "\n";
log_.printToFile(logFilePath_);
log_ << "For more detailed information, see log file." << "\n";
return EXIT_FAILURE;
}
catch (...)
{
log_.setIsPrintingInCout(true);
log_ << "Unknwon error in OdmMeshing:\n";
log_.printToFile(logFilePath_);
log_ << "For more detailed information, see log file." << "\n";
return EXIT_FAILURE;
}
log_.printToFile(logFilePath_);
return EXIT_SUCCESS;
}
void OdmMeshing::parseArguments(int argc, char **argv)
{
for(int argIndex = 1; argIndex < argc; ++argIndex)
{
// The argument to be parsed.
std::string argument = std::string(argv[argIndex]);
if(argument == "-help")
{
printHelp();
}
else if(argument == "-verbose")
{
log_.setIsPrintingInCout(true);
}
else if(argument == "-maxVertexCount" && argIndex < argc)
{
++argIndex;
if (argIndex >= argc)
{
throw OdmMeshingException("Argument '" + argument + "' expects 1 more input following it, but no more inputs were provided.");
}
std::stringstream ss(argv[argIndex]);
ss >> maxVertexCount_;
if (ss.bad())
{
throw OdmMeshingException("Argument '" + argument + "' has a bad value (wrong type).");
}
log_ << "Vertex count was manually set to: " << maxVertexCount_ << "\n";
}
else if(argument == "-octreeDepth" && argIndex < argc)
{
++argIndex;
if (argIndex >= argc)
{
throw OdmMeshingException("Argument '" + argument + "' expects 1 more input following it, but no more inputs were provided.");
}
std::stringstream ss(argv[argIndex]);
ss >> treeDepth_;
if (ss.bad())
{
throw OdmMeshingException("Argument '" + argument + "' has a bad value (wrong type).");
}
log_ << "Octree depth was manually set to: " << treeDepth_ << "\n";
}
else if(argument == "-solverDivide" && argIndex < argc)
{
++argIndex;
if (argIndex >= argc)
{
throw OdmMeshingException("Argument '" + argument + "' expects 1 more input following it, but no more inputs were provided.");
}
std::stringstream ss(argv[argIndex]);
ss >> solverDivide_;
if (ss.bad())
{
throw OdmMeshingException("Argument '" + argument + "' has a bad value (wrong type).");
}
log_ << "Numerical solver divisions was manually set to: " << treeDepth_ << "\n";
}
else if(argument == "-samplesPerNode" && argIndex < argc)
{
++argIndex;
if (argIndex >= argc)
{
throw OdmMeshingException("Argument '" + argument + "' expects 1 more input following it, but no more inputs were provided.");
}
std::stringstream ss(argv[argIndex]);
ss >> samplesPerNode_;
if (ss.bad())
{
throw OdmMeshingException("Argument '" + argument + "' has a bad value (wrong type).");
}
log_ << "The number of samples per octree node was manually set to: " << samplesPerNode_ << "\n";
}
else if(argument == "-inputFile" && argIndex < argc)
{
++argIndex;
if (argIndex >= argc)
{
throw OdmMeshingException("Argument '" + argument + "' expects 1 more input following it, but no more inputs were provided.");
}
inputFile_ = std::string(argv[argIndex]);
std::ifstream testFile(inputFile_.c_str(), std::ios::binary);
if (!testFile.is_open())
{
throw OdmMeshingException("Argument '" + argument + "' has a bad value. (file not accessible)");
}
testFile.close();
log_ << "Reading point cloud at: " << inputFile_ << "\n";
}
else if(argument == "-outputFile" && argIndex < argc)
{
++argIndex;
if (argIndex >= argc)
{
throw OdmMeshingException("Argument '" + argument + "' expects 1 more input following it, but no more inputs were provided.");
}
outputFile_ = std::string(argv[argIndex]);
std::ofstream testFile(outputFile_.c_str());
if (!testFile.is_open())
{
throw OdmMeshingException("Argument '" + argument + "' has a bad value.");
}
testFile.close();
log_ << "Writing output to: " << outputFile_ << "\n";
}
else if(argument == "-logFile" && argIndex < argc)
{
++argIndex;
if (argIndex >= argc)
{
throw OdmMeshingException("Argument '" + argument + "' expects 1 more input following it, but no more inputs were provided.");
}
logFilePath_ = std::string(argv[argIndex]);
std::ofstream testFile(outputFile_.c_str());
if (!testFile.is_open())
{
throw OdmMeshingException("Argument '" + argument + "' has a bad value.");
}
testFile.close();
log_ << "Writing log information to: " << logFilePath_ << "\n";
}
else
{
printHelp();
throw OdmMeshingException("Unrecognised argument '" + argument + "'");
}
}
}
void OdmMeshing::loadPoints()
{
if(pcl::io::loadPLYFile<pcl::PointNormal> (inputFile_.c_str(), *points_.get()) == -1) {
throw OdmMeshingException("Error when reading points and normals from:\n" + inputFile_ + "\n");
}
else
{
log_ << "Successfully loaded " << points_->size() << " points with corresponding normals from file.\n";
}
}
void OdmMeshing::printHelp()
{
bool printInCoutPop = log_.isPrintingInCout();
log_.setIsPrintingInCout(true);
log_ << "OpenDroneMapMeshing.exe\n\n";
log_ << "Purpose:" << "\n";
log_ << "Create a mesh from an oriented point cloud (points with normals) using the Poisson surface reconstruction method." << "\n";
log_ << "Usage:" << "\n";
log_ << "The program requires a path to an input PLY point cloud file, all other input parameters are optional." << "\n\n";
log_ << "The following flags are available\n";
log_ << "Call the program with flag \"-help\", or without parameters to print this message, or check any generated log file.\n";
log_ << "Call the program with flag \"-verbose\", to print log messages in the standard output stream as well as in the log file.\n\n";
log_ << "Parameters are specified as: \"-<argument name> <argument>\", (without <>), and the following parameters are configureable: " << "\n";
log_ << "\"-inputFile <path>\" (mandatory)" << "\n";
log_ << "\"Input ascii ply file that must contain a point cloud with normals.\n\n";
log_ << "\"-outputFile <path>\" (optional, default: odm_mesh.ply)" << "\n";
log_ << "\"Target file in which the mesh is saved.\n\n";
log_ << "\"-logFile <path>\" (optional, default: odm_meshing_log.txt)" << "\n";
log_ << "\"Target file in which the mesh is saved.\n\n";
log_ << "\"-maxVertexCount <integer>\" (optional, default: 100,000)" << "\n";
log_ << "Desired final vertex count (after decimation), set to 0 to disable decimation.\n\n";
log_ << "\"-treeDepth <integer>\" (optional, default: 0 (automatic))" << "\n";
log_ << "Controls octree depth used for poisson reconstruction. Recommended values (9-11).\n"
<< "Increasing the value on this parameter will raise initial vertex count."
<< "If omitted or zero, the depth is calculated automatically from the input point count.\n\n";
log_ << "\"-samplesPerNode <float>\" (optional, default: 1)" << "\n";
log_ << "Average number of samples (points) per octree node. Increasing this value might help if data is very noisy.\n\n";
log_ << "\"-solverDivide <integer>\" (optional, default: 9)" << "\n";
log_ << "Ocree depth at which the Laplacian equation is solved in the surface reconstruction step.\n";
log_ << "Increasing this value increases computation times slightly but helps reduce memory usage.\n\n";
log_.setIsPrintingInCout(printInCoutPop);
}
void OdmMeshing::createMesh()
{
// Attempt to calculate the depth of the tree if unspecified
if (treeDepth_ == 0)
{
treeDepth_ = calcTreeDepth(points_->size());
}
log_ << "Octree depth used for reconstruction is: " << treeDepth_ << "\n";
log_ << "Estimated initial vertex count: " << pow(4, treeDepth_) << "\n\n";
meshCreator_->setDepth(treeDepth_);
meshCreator_->setSamplesPerNode(samplesPerNode_);
meshCreator_->setInputCloud(points_);
// Guarantee manifold mesh.
meshCreator_->setManifold(true);
// Begin reconstruction
meshCreator_->reconstruct(*mesh_.get());
log_ << "Reconstruction complete:\n";
log_ << "Vertex count: " << mesh_->cloud.width << "\n";
log_ << "Triangle count: " << mesh_->polygons.size() << "\n\n";
}
void OdmMeshing::decimateMesh()
{
if (maxVertexCount_ <= 0)
{
log_ << "Vertex count not specified, decimation cancelled.\n";
return;
}
if (maxVertexCount_ > mesh_->cloud.height*mesh_->cloud.width)
{
log_ << "Vertex count in mesh lower than initially generated mesh, unable to decimate.\n";
return;
}
else
{
decimatedMesh_ = pcl::PolygonMeshPtr(new pcl::PolygonMesh);
double reductionFactor = 1.0 - double(maxVertexCount_)/double(mesh_->cloud.height*mesh_->cloud.width);
log_ << "Decimating mesh, removing " << reductionFactor*100 << " percent of vertices.\n";
pcl::MeshQuadricDecimationVTK decimator;
decimator.setInputMesh(mesh_);
decimator.setTargetReductionFactor(reductionFactor);
decimator.process(*decimatedMesh_.get());
log_ << "Decimation complete.\n";
log_ << "Decimated vertex count: " << decimatedMesh_->cloud.width << "\n";
log_ << "Decimated triangle count: " << decimatedMesh_->polygons.size() << "\n\n";
mesh_ = decimatedMesh_;
}
}
int OdmMeshing::calcTreeDepth(size_t nPoints)
{
// Assume points are located (roughly) in a plane.
double squareSide = std::sqrt(double(nPoints));
// Calculate octree depth such that if points were equally distributed in
// a quadratic plane, there would be at least 1 point per octree node.
int depth = 0;
while(std::pow<double>(2,depth) < squareSide/2)
{
depth++;
}
return depth;
}
void OdmMeshing::writePlyFile()
{
log_ << "Saving mesh to file.\n";
if (pcl::io::savePLYFile(outputFile_.c_str(), *mesh_.get()) == -1) {
throw OdmMeshingException("Error when saving mesh to file:\n" + outputFile_ + "\n");
}
else
{
log_ << "Successfully wrote mesh to:\n"
<< outputFile_ << "\n";
}
}

Wyświetl plik

@ -1,117 +0,0 @@
#pragma once
// STL
#include <string>
#include <iostream>
// PCL
#include <pcl/io/ply_io.h>
#include <pcl/surface/poisson.h>
#include <pcl/surface/vtk_smoothing/vtk_mesh_quadric_decimation.h>
// Logging
#include "Logger.hpp"
/*!
* \brief The OdmMeshing class is used to create a triangulated mesh using the Poisson method.
* The class reads an oriented point cloud (coordinates and normals) from a PLY ascii
* file and outputs the resulting welded manifold mesh on the form of an ASCII PLY-file.
* The class uses file read and write functions from pcl.
*/
class OdmMeshing
{
public:
OdmMeshing();
~OdmMeshing();
/*!
* \brief run Runs the meshing functionality using the provided input arguments.
* For a list of accepted arguments, please see the main page documentation or
* call the program with parameter "-help".
* \param argc Application argument count.
* \param argv Argument values.
* \return 0 If successful.
*/
int run(int argc, char **argv);
private:
/*!
* \brief parseArguments Parses command line arguments.
* \param argc Application argument count.
* \param argv Argument values.
*/
void parseArguments(int argc, char** argv);
/*!
* \brief createMesh Sets up the pcl::Poisson meshing class using provided arguments and calls
* it to start the meshing.
*/
void createMesh();
/*!
* \brief loadPoints Loads a PLY ascii file with points and normals from file.
*/
void loadPoints();
/*!
* \brief decimateMesh Performs post-processing on the form of quadric decimation to generate a mesh
* that has a higher density in areas with a lot of structure.
*/
void decimateMesh();
/*!
* \brief writePlyFile Writes the mesh to file on the Ply format.
*/
void writePlyFile();
/*!
* \brief printHelp Prints help, explaining usage. Can be shown by calling the program with argument: "-help".
*/
void printHelp();
/*!
* \brief calcTreeDepth Attepts to calculate the depth of the tree using the point cloud.
* The function makes the assumption points are located roughly in a plane
* (fairly reasonable for ortho-terrain photos) and tries to generate a mesh using
* an octree with an appropriate resolution.
* \param nPoints The total number of points in the input point cloud.
* \return The calcualated octree depth.
*/
int calcTreeDepth(size_t nPoints);
Logger log_; /**< Logging object. */
pcl::Poisson<pcl::PointNormal>::Ptr meshCreator_; /**< PCL poisson meshing class. */
pcl::PointCloud<pcl::PointNormal>::Ptr points_; /**< Input point and normals. */
pcl::PolygonMeshPtr mesh_; /**< PCL polygon mesh. */
pcl::PolygonMeshPtr decimatedMesh_; /**< Decimated polygon mesh. */
std::string inputFile_; /**< Path to a file containing points and normals. */
std::string outputFile_; /**< Path to the destination file. */
std::string logFilePath_; /**< Path to the log file. */
unsigned int maxVertexCount_; /**< Desired output vertex count. */
unsigned int treeDepth_; /**< Depth of octree used for reconstruction. */
double samplesPerNode_; /**< Samples per octree node.*/
double solverDivide_; /**< Depth at which the Laplacian equation solver is run during surface estimation.*/
double decimationFactor_; /**< Percentage of points to remove when decimating the mesh. */
};
/*!
* \brief The OdmMeshingException class
*/
class OdmMeshingException : public std::exception
{
public:
OdmMeshingException() : message("Error in OdmMeshing") {}
OdmMeshingException(std::string msgInit) : message("Error in OdmMeshing:\n" + msgInit) {}
~OdmMeshingException() throw() {}
virtual const char* what() const throw() {return message.c_str(); }
private:
std::string message; /**< The error message **/
};

Wyświetl plik

@ -1,20 +0,0 @@
// Insert license here.
// Include meshing source code.
#include "OdmMeshing.hpp"
/*!
* \mainpage main OpenDroneMap Meshing Module
*
* The OpenDroneMap Meshing Module generates a welded, manifold mesh using the Poisson
* surface reconstruction algorithm from any oriented point cloud (points with corresponding normals).
*
*/
int main(int argc, char** argv)
{
OdmMeshing meshCreator;
return meshCreator.run(argc, argv);
}

Wyświetl plik

@ -242,7 +242,7 @@ def config():
metavar='<positive integer>',
default=100000,
type=int,
help=('The maximum vertex count of the output mesh '
help=('The maximum vertex count of the output mesh. '
'Default: %(default)s'))
parser.add_argument('--mesh-octree-depth',
@ -255,40 +255,21 @@ def config():
parser.add_argument('--mesh-samples',
metavar='<float >= 1.0>',
default=1.0,
default=2.0,
type=float,
help=('Number of points per octree node, recommended '
'and default value: %(default)s'))
parser.add_argument('--mesh-solver-divide',
metavar='<positive integer>',
default=9,
type=int,
help=('Oct-tree depth at which the Laplacian equation '
'is solved in the surface reconstruction step. '
'Increasing this value increases computation '
'times slightly but helps reduce memory usage. '
'Default: %(default)s'))
parser.add_argument('--mesh-neighbors',
metavar='<positive integer>',
default=24,
type=int,
help=('Number of neighbors to select when estimating the surface model used to compute the mesh and for statistical outlier removal. Higher values lead to smoother meshes but take longer to process. '
'Applies to 2.5D mesh only. '
'Default: %(default)s'))
parser.add_argument('--mesh-resolution',
metavar='<positive float>',
default=0,
parser.add_argument('--mesh-point-weight',
metavar='<interpolation weight>',
default=4,
type=float,
help=('Size of the interpolated surface model used for deriving the 2.5D mesh, expressed in pixels per meter. '
'Higher values work better for complex or urban terrains. '
'Lower values work better on flat areas. '
'Resolution has no effect on the number of vertices, but high values can severely impact runtime speed and memory usage. '
'When set to zero, the program automatically attempts to find a good value based on the point cloud extent and target vertex count. '
'Applies to 2.5D mesh only. '
'Default: %(default)s'))
help=('This floating point value specifies the importance'
' that interpolation of the point samples is given in the '
'formulation of the screened Poisson equation. The results '
'of the original (unscreened) Poisson Reconstruction can '
'be obtained by setting this value to 0.'
'Default= %(default)s'))
parser.add_argument('--fast-orthophoto',
action='store_true',

Wyświetl plik

@ -27,6 +27,8 @@ orb_slam2_path = os.path.join(superbuild_path, "src/orb_slam2")
makescene_path = os.path.join(superbuild_path, 'src', 'elibs', 'mve', 'apps', 'makescene', 'makescene') #TODO: don't install in source
smvs_path = os.path.join(superbuild_path, 'src', 'elibs', 'smvs', 'app', 'smvsrecon')
poisson_recon_path = os.path.join(superbuild_path, 'src', 'PoissonRecon', 'Bin', 'Linux', 'PoissonRecon')
# define mvstex path
mvstex_path = os.path.join(superbuild_path, "install/bin/texrecon")

Wyświetl plik

@ -37,8 +37,12 @@ def create_25dmesh(inPointCloud, outMesh, dsm_resolution=0.05, depth=8, samples=
)
dsm_points = dem_to_points(os.path.join(tmp_directory, 'mesh_dsm.tif'), os.path.join(tmp_directory, 'dsm_points.ply'))
mesh = screened_poisson_reconstruction(dsm_points, outMesh, depth=depth, samples=samples, maxVertexCount=maxVertexCount, verbose=verbose)
mesh = screened_poisson_reconstruction(dsm_points, outMesh, depth=depth,
samples=samples,
maxVertexCount=maxVertexCount,
threads=max_workers,
verbose=verbose)
# Cleanup tmp
if os.path.exists(tmp_directory):
shutil.rmtree(tmp_directory)
@ -71,7 +75,7 @@ def dem_to_points(inGeotiff, outPointCloud):
tx = xmin + (float(x) / float(arr_width)) * ext_width
ty = ymax - (float(y) / float(arr_height)) * ext_height
mem_file.write(struct.pack('ffffff', tx, ty, z, 0, 0, 1))
# Skirting
for (nx, ny) in ((x, y + 1), (x, y - 1), (x + 1, y), (x - 1, y)):
current_z = z
@ -85,11 +89,11 @@ def dem_to_points(inGeotiff, outPointCloud):
mem_file.write(struct.pack('ffffff', tx, ty, neighbor_z, 0, 0, 1))
skirt_points += 1
with open(outPointCloud, "wb") as f:
f.write("ply\n")
f.write("format binary_%s_endian 1.0\n" % sys.byteorder)
f.write("format binary_%s_endian 1.0\n" % sys.byteorder)
f.write("element vertex %s\n" % (vertex_count + skirt_points))
f.write("property float x\n")
f.write("property float y\n")
@ -108,7 +112,7 @@ def dem_to_points(inGeotiff, outPointCloud):
return outPointCloud
def screened_poisson_reconstruction(inPointCloud, outMesh, depth = 8, samples = 1, maxVertexCount=100000, verbose=False):
def screened_poisson_reconstruction(inPointCloud, outMesh, depth = 8, samples = 1, maxVertexCount=100000, pointWeight=4, threads=context.num_cores, verbose=False):
mesh_path, mesh_filename = os.path.split(outMesh)
# mesh_path = path/to
@ -121,28 +125,25 @@ def screened_poisson_reconstruction(inPointCloud, outMesh, depth = 8, samples =
outMeshDirty = os.path.join(mesh_path, "{}.dirty{}".format(basename, ext))
poissonReconArgs = {
#TODO: @dakotabenjamin adjust path to PoissonRecon program
# 'bin': '/PoissonRecon/Bin/Linux/PoissonRecon',
'bin': context.odm_modules_path,
'bin': context.poisson_recon_path,
'outfile': outMeshDirty,
'infile': inPointCloud,
'depth': depth,
'samples': samples,
'pointWeight': pointWeight,
'threads': threads,
'verbose': '--verbose' if verbose else ''
}
# Run PoissonRecon (new)
# system.run('{bin} --in {infile} '
# '--out {outfile} '
# '--depth {depth} '
# '--linearFit '
# '{verbose}'.format(**kwargs))
# TODO: remove odm_meshing in favor of above
system.run('{bin}/odm_meshing -inputFile {infile} '
'-outputFile {outfile} '
'-octreeDepth {depth} -verbose '
'-samplesPerNode {samples} -solverDivide 9'.format(**poissonReconArgs))
# Run PoissonRecon
system.run('{bin} --in {infile} '
'--out {outfile} '
'--depth {depth} '
'--pointWeight {pointWeight} '
'--samplesPerNode {samples} '
'--threads {threads} '
'--linearFit '
'{verbose}'.format(**poissonReconArgs))
# Cleanup and reduce vertex count if necessary
cleanupArgs = {

Wyświetl plik

@ -59,7 +59,8 @@ class ODMApp(ecto.BlackBox):
'meshing': ODMeshingCell(max_vertex=p.args.mesh_size,
oct_tree=p.args.mesh_octree_depth,
samples=p.args.mesh_samples,
solver=p.args.mesh_solver_divide,
point_weight=p.args.mesh_point_weight,
max_concurrency=p.args.max_concurrency,
verbose=p.args.verbose),
'texturing': ODMMvsTexCell(data_term=p.args.texturing_data_term,
outlier_rem_type=p.args.texturing_outlier_removal_type,

Wyświetl plik

@ -16,10 +16,8 @@ class ODMeshingCell(ecto.Cell):
'values are 8-12', 9)
params.declare("samples", 'Number of points per octree node, recommended '
'value: 1.0', 1)
params.declare("solver", 'Oct-tree depth at which the Laplacian equation '
'is solved in the surface reconstruction step. '
'Increasing this value increases computation '
'times slightly but helps reduce memory usage.', 9)
params.declare("point_weight", "specifies the importance that interpolation of the point samples is given in the formulation of the screened Poisson equation.", 4)
params.declare("max_concurrency", 'max threads', context.num_cores)
params.declare("verbose", 'print additional messages to console', False)
def declare_io(self, params, inputs, outputs):
@ -39,7 +37,6 @@ class ODMeshingCell(ecto.Cell):
args = inputs.args
tree = inputs.tree
reconstruction = inputs.reconstruction
verbose = '-verbose' if self.params.verbose else ''
# define paths and create working directories
system.mkdir_p(tree.odm_meshing)
@ -62,12 +59,14 @@ class ODMeshingCell(ecto.Cell):
if not io.file_exists(tree.odm_mesh) or rerun_cell:
log.ODM_DEBUG('Writing ODM Mesh file in: %s' % tree.odm_mesh)
mesh.screened_poisson_reconstruction(infile,
mesh.screened_poisson_reconstruction(infile,
tree.odm_mesh,
depth=self.params.oct_tree,
samples=self.params.samples,
maxVertexCount=self.params.max_vertex,
verbose=verbose)
depth=self.params.oct_tree,
samples=self.params.samples,
maxVertexCount=self.params.max_vertex,
pointWeight=self.params.point_weight,
threads=self.params.max_concurrency,
verbose=self.params.verbose)
else:
log.ODM_WARNING('Found a valid ODM Mesh file in: %s' %
@ -83,14 +82,14 @@ class ODMeshingCell(ecto.Cell):
# Create reference DSM at half ortho resolution
dsm_resolution *= 2
# Sparse point clouds benefits from using
# a larger resolution value (more radius interolation, less holes)
if args.fast_orthophoto:
dsm_resolution *= 2
mesh.create_25dmesh(infile, tree.odm_25dmesh,
dsm_resolution=dsm_resolution,
mesh.create_25dmesh(infile, tree.odm_25dmesh,
dsm_resolution=dsm_resolution,
depth=self.params.oct_tree,
maxVertexCount=self.params.max_vertex,
verbose=self.params.verbose,