Update clang-format style: 100 columns, and forbid one-line braces

This commit is contained in:
Jose Luis Blanco-Claraco
2025-12-22 17:16:23 +01:00
parent 6ac7fa078e
commit 2a42d1bac2
20 changed files with 397 additions and 681 deletions

View File

@@ -1,83 +1,22 @@
Language: Cpp
Language: Cpp
BasedOnStyle: Google
# ---
#AccessModifierOffset: -4
AlignAfterOpenBracket: AlwaysBreak # Values: Align, DontAlign, AlwaysBreak
AlignConsecutiveAssignments: true
AlignConsecutiveDeclarations: true
#AlignEscapedNewlinesLeft: true
#AlignOperands: false
AlignTrailingComments: false # Should be off, causes many dummy problems!!
#AllowAllParametersOfDeclarationOnNextLine: true
AllowShortBlocksOnASingleLine: true
#AllowShortCaseLabelsOnASingleLine: false
#AllowShortFunctionsOnASingleLine: Empty
#AllowShortIfStatementsOnASingleLine: false
#AllowShortLoopsOnASingleLine: false
#AlwaysBreakAfterDefinitionReturnType: None
#AlwaysBreakAfterReturnType: None
#AlwaysBreakBeforeMultilineStrings: true
#AlwaysBreakTemplateDeclarations: true
#BinPackArguments: false
#BinPackParameters: false
#BraceWrapping:
#AfterClass: false
#AfterControlStatement: false
#AfterEnum: false
#AfterFunction: false
#AfterNamespace: false
#AfterObjCDeclaration: false
#AfterStruct: false
#AfterUnion: false
#BeforeCatch: false
#BeforeElse: true
#IndentBraces: false
#BreakBeforeBinaryOperators: None
AllowShortBlocksOnASingleLine: false
BreakBeforeBraces: Allman
#BreakBeforeTernaryOperators: true
#BreakConstructorInitializersBeforeComma: false
ColumnLimit: 80
#CommentPragmas: ''
#ConstructorInitializerAllOnOneLineOrOnePerLine: true
#ConstructorInitializerIndentWidth: 4
#ContinuationIndentWidth: 4
#Cpp11BracedListStyle: true
#DerivePointerAlignment: false
#DisableFormat: false
#ExperimentalAutoDetectBinPacking: false
##FixNamespaceComments: true # Not applicable in 3.8
#ForEachMacros: [ foreach, Q_FOREACH, BOOST_FOREACH ]
#IncludeCategories:
#- Regex: '.*'
#Priority: 1
ColumnLimit: 100
IndentCaseLabels: true
IndentWidth: 4
IndentWidth: 4
IndentWrappedFunctionNames: true
#KeepEmptyLinesAtTheStartOfBlocks: true
#MacroBlockBegin: ''
#MacroBlockEnd: ''
MaxEmptyLinesToKeep: 1
NamespaceIndentation: None
#PenaltyBreakBeforeFirstCallParameter: 19
#PenaltyBreakComment: 300
#PenaltyBreakFirstLessLess: 120
#PenaltyBreakString: 1000
#PenaltyExcessCharacter: 1000000
#PenaltyReturnTypeOnItsOwnLine: 200
DerivePointerAlignment: false
#PointerAlignment: Left
ReflowComments: true # Should be true, otherwise clang-format doesn't touch comments
SortIncludes: true
#SpaceAfterCStyleCast: false
ReflowComments: true # Should be true, otherwise clang-format doesn't touch comments
SortIncludes: true
SpaceBeforeAssignmentOperators: true
#SpaceBeforeParens: ControlStatements
#SpaceInEmptyParentheses: false
#SpacesBeforeTrailingComments: 2
#SpacesInAngles: false
#SpacesInContainerLiterals: true
#SpacesInCStyleCastParentheses: false
#SpacesInParentheses: false
#SpacesInSquareBrackets: false
Standard: Cpp11
TabWidth: 4
UseTab: Never # Available options are Never, Always, ForIndentation
Standard: Cpp11
TabWidth: 4
UseTab: Never # Available options are Never, Always, ForIndentation

View File

@@ -54,12 +54,10 @@ template <
class Distance = nanoflann::metric_L2, typename IndexType = size_t>
struct KDTreeVectorOfVectorsAdaptor
{
using self_t = KDTreeVectorOfVectorsAdaptor<
VectorOfVectorsType, num_t, DIM, Distance, IndexType>;
using metric_t =
typename Distance::template traits<num_t, self_t>::distance_t;
using index_t =
nanoflann::KDTreeSingleIndexAdaptor<metric_t, self_t, DIM, IndexType>;
using self_t =
KDTreeVectorOfVectorsAdaptor<VectorOfVectorsType, num_t, DIM, Distance, IndexType>;
using metric_t = typename Distance::template traits<num_t, self_t>::distance_t;
using index_t = nanoflann::KDTreeSingleIndexAdaptor<metric_t, self_t, DIM, IndexType>;
/** The kd-tree index for the user to call its methods as usual with any
* other FLANN index */
@@ -81,8 +79,7 @@ struct KDTreeVectorOfVectorsAdaptor
index = new index_t(
static_cast<int>(dims), *this /* adaptor */,
nanoflann::KDTreeSingleIndexAdaptorParams(
leaf_max_size, nanoflann::KDTreeSingleIndexAdaptorFlags::None,
n_thread_build));
leaf_max_size, nanoflann::KDTreeSingleIndexAdaptorFlags::None, n_thread_build));
}
~KDTreeVectorOfVectorsAdaptor() { delete index; }
@@ -95,8 +92,8 @@ struct KDTreeVectorOfVectorsAdaptor
* The user can also call index->... methods as desired.
*/
inline void query(
const num_t* query_point, const size_t num_closest,
IndexType* out_indices, num_t* out_distances_sq) const
const num_t* query_point, const size_t num_closest, IndexType* out_indices,
num_t* out_distances_sq) const
{
nanoflann::KNNResultSet<num_t, IndexType> resultSet(num_closest);
resultSet.init(out_indices, out_distances_sq);

View File

@@ -45,8 +45,8 @@ void kdtree_demo(const size_t N)
// construct a kd-tree index:
using my_kd_tree_t = nanoflann::KDTreeSingleIndexAdaptor<
nanoflann::SO2_Adaptor<num_t, PointCloud_Orient<num_t>>,
PointCloud_Orient<num_t>, 1 /* dim */
nanoflann::SO2_Adaptor<num_t, PointCloud_Orient<num_t>>, PointCloud_Orient<num_t>,
1 /* dim */
>;
dump_mem_usage();
@@ -64,8 +64,7 @@ void kdtree_demo(const size_t N)
index.findNeighbors(resultSet, &query_pt[0]);
std::cout << "knnSearch(nn=" << num_results << "): \n";
std::cout << "ret_index=" << ret_index
<< " out_dist_sqr=" << out_dist_sqr << std::endl;
std::cout << "ret_index=" << ret_index << " out_dist_sqr=" << out_dist_sqr << std::endl;
}
}

View File

@@ -45,8 +45,7 @@ void kdtree_demo(const size_t N)
// construct a kd-tree index:
using my_kd_tree_t = nanoflann::KDTreeSingleIndexAdaptor<
nanoflann::SO3_Adaptor<num_t, PointCloud_Quat<num_t>>,
PointCloud_Quat<num_t>, 4 /* dim */
nanoflann::SO3_Adaptor<num_t, PointCloud_Quat<num_t>>, PointCloud_Quat<num_t>, 4 /* dim */
>;
dump_mem_usage();
@@ -64,8 +63,7 @@ void kdtree_demo(const size_t N)
index.findNeighbors(resultSet, &query_pt[0]);
std::cout << "knnSearch(nn=" << num_results << "): \n";
std::cout << "ret_index=" << ret_index
<< " out_dist_sqr=" << out_dist_sqr << std::endl;
std::cout << "ret_index=" << ret_index << " out_dist_sqr=" << out_dist_sqr << std::endl;
}
}

View File

@@ -40,8 +40,7 @@ void kdtree_demo(const size_t N)
// construct a kd-tree index:
using my_kd_tree_t = nanoflann::KDTreeSingleIndexDynamicAdaptor<
nanoflann::L2_Simple_Adaptor<num_t, PointCloud<num_t>>,
PointCloud<num_t>, 3 /* dim */
nanoflann::L2_Simple_Adaptor<num_t, PointCloud<num_t>>, PointCloud<num_t>, 3 /* dim */
>;
dump_mem_usage();
@@ -78,19 +77,16 @@ void kdtree_demo(const size_t N)
index.findNeighbors(resultSet, query_pt, {10});
std::cout << "knnSearch(nn=" << num_results << "): \n";
std::cout << "ret_index=" << ret_index
<< " out_dist_sqr=" << out_dist_sqr << std::endl;
std::cout << "ret_index=" << ret_index << " out_dist_sqr=" << out_dist_sqr << std::endl;
std::cout << "point: ("
<< "point: (" << cloud.pts[ret_index].x << ", "
<< cloud.pts[ret_index].y << ", " << cloud.pts[ret_index].z
<< ")" << std::endl;
<< "point: (" << cloud.pts[ret_index].x << ", " << cloud.pts[ret_index].y << ", "
<< cloud.pts[ret_index].z << ")" << std::endl;
std::cout << std::endl;
}
{
// do a knn search searching for more than one result
const size_t num_results = 5;
std::cout << "Searching for " << num_results << " elements"
<< std::endl;
std::cout << "Searching for " << num_results << " elements" << std::endl;
size_t ret_index[num_results];
num_t out_dist_sqr[num_results];
nanoflann::KNNResultSet<num_t> resultSet(num_results);
@@ -105,8 +101,8 @@ void kdtree_demo(const size_t N)
<< "index: " << ret_index[i] << ",\t"
<< "dist: " << out_dist_sqr[i] << ",\t"
<< "point: (" << cloud.pts[ret_index[i]].x << ", "
<< cloud.pts[ret_index[i]].y << ", "
<< cloud.pts[ret_index[i]].z << ")" << std::endl;
<< cloud.pts[ret_index[i]].y << ", " << cloud.pts[ret_index[i]].z << ")"
<< std::endl;
}
std::cout << std::endl;
}
@@ -115,18 +111,16 @@ void kdtree_demo(const size_t N)
std::cout << "Unsorted radius search" << std::endl;
const num_t radiusSqr = 1;
std::vector<nanoflann::ResultItem<size_t, num_t>> indices_dists;
nanoflann::RadiusResultSet<num_t, size_t> resultSet(
radiusSqr, indices_dists);
nanoflann::RadiusResultSet<num_t, size_t> resultSet(radiusSqr, indices_dists);
index.findNeighbors(resultSet, query_pt);
nanoflann::ResultItem<size_t, num_t> worst_pair =
resultSet.worst_item();
std::cout << "Worst pair: idx=" << worst_pair.first
<< " dist=" << worst_pair.second << std::endl;
nanoflann::ResultItem<size_t, num_t> worst_pair = resultSet.worst_item();
std::cout << "Worst pair: idx=" << worst_pair.first << " dist=" << worst_pair.second
<< std::endl;
std::cout << "point: (" << cloud.pts[worst_pair.first].x << ", "
<< cloud.pts[worst_pair.first].y << ", "
<< cloud.pts[worst_pair.first].z << ")" << std::endl;
<< cloud.pts[worst_pair.first].y << ", " << cloud.pts[worst_pair.first].z << ")"
<< std::endl;
std::cout << std::endl;
}
}

View File

@@ -45,8 +45,7 @@ void kdtree_demo(const size_t N)
// construct a kd-tree index:
using my_kd_tree_t = nanoflann::KDTreeSingleIndexAdaptor<
nanoflann::L2_Simple_Adaptor<num_t, PointCloud<num_t>>,
PointCloud<num_t>, 3 /* dim */
nanoflann::L2_Simple_Adaptor<num_t, PointCloud<num_t>>, PointCloud<num_t>, 3 /* dim */
>;
dump_mem_usage();
@@ -61,26 +60,23 @@ void kdtree_demo(const size_t N)
num_t out_dist_sqr;
nanoflann::KNNResultSet<num_t> resultSet(num_results);
resultSet.init(&ret_index, &out_dist_sqr);
index.findNeighbors(
resultSet, &query_pt[0], nanoflann::SearchParams(10));
index.findNeighbors(resultSet, &query_pt[0], nanoflann::SearchParams(10));
std::cout << "knnSearch(nn=" << num_results << "): \n";
std::cout << "ret_index=" << ret_index
<< " out_dist_sqr=" << out_dist_sqr << std::endl;
std::cout << "ret_index=" << ret_index << " out_dist_sqr=" << out_dist_sqr << std::endl;
}
{
// Unsorted radius search:
const num_t radius = 1;
std::vector<std::pair<size_t, num_t>> indices_dists;
nanoflann::RadiusResultSet<num_t, size_t> resultSet(
radius, indices_dists);
nanoflann::RadiusResultSet<num_t, size_t> resultSet(radius, indices_dists);
index.findNeighbors(resultSet, query_pt, nanoflann::SearchParams());
// Get worst (furthest) point, without sorting:
std::pair<size_t, num_t> worst_pair = resultSet.worst_item();
std::cout << "Worst pair: idx=" << worst_pair.first
<< " dist=" << worst_pair.second << std::endl;
std::cout << "Worst pair: idx=" << worst_pair.first << " dist=" << worst_pair.second
<< std::endl;
}
}

View File

@@ -45,8 +45,7 @@ void kdtree_demo(const size_t N)
// construct a kd-tree index:
using my_kd_tree_t = nanoflann::KDTreeSingleIndexAdaptor<
nanoflann::L2_Simple_Adaptor<num_t, PointCloud<num_t>>,
PointCloud<num_t>, 3 /* dim */
nanoflann::L2_Simple_Adaptor<num_t, PointCloud<num_t>>, PointCloud<num_t>, 3 /* dim */
>;
dump_mem_usage();
@@ -61,26 +60,23 @@ void kdtree_demo(const size_t N)
num_t out_dist_sqr;
nanoflann::KNNResultSet<num_t> resultSet(num_results);
resultSet.init(&ret_index, &out_dist_sqr);
index.findNeighbors(
resultSet, &query_pt[0], nanoflann::SearchParams(10));
index.findNeighbors(resultSet, &query_pt[0], nanoflann::SearchParams(10));
std::cout << "knnSearch(nn=" << num_results << "): \n";
std::cout << "ret_index=" << ret_index
<< " out_dist_sqr=" << out_dist_sqr << std::endl;
std::cout << "ret_index=" << ret_index << " out_dist_sqr=" << out_dist_sqr << std::endl;
}
{
// Unsorted radius search:
const num_t radius = 1;
std::vector<std::pair<size_t, num_t>> indices_dists;
nanoflann::RadiusResultSet<num_t, size_t> resultSet(
radius, indices_dists);
nanoflann::RadiusResultSet<num_t, size_t> resultSet(radius, indices_dists);
index.findNeighbors(resultSet, query_pt, nanoflann::SearchParams());
// Get worst (furthest) point, without sorting:
std::pair<size_t, num_t> worst_pair = resultSet.worst_item();
std::cout << "Worst pair: idx=" << worst_pair.first
<< " dist=" << worst_pair.second << std::endl;
std::cout << "Worst pair: idx=" << worst_pair.first << " dist=" << worst_pair.second
<< std::endl;
}
}

View File

@@ -44,7 +44,10 @@
mrpt::opengl::CPointCloud::Ptr pc_to_viz(const PointCloud<double>& pc)
{
auto gl = mrpt::opengl::CPointCloud::Create();
for (const auto pt : pc.pts) { gl->insertPoint(pt.x, pt.y, pt.z); }
for (const auto pt : pc.pts)
{
gl->insertPoint(pt.x, pt.y, pt.z);
}
gl->setPointSize(3.0f);
return gl;
}
@@ -91,8 +94,7 @@ void kdtree_demo(const size_t N)
// construct a kd-tree index:
using my_kd_tree_t = nanoflann::KDTreeSingleIndexAdaptor<
nanoflann::L2_Simple_Adaptor<double, PointCloud<double>>,
PointCloud<double>, 3 /* dim */
nanoflann::L2_Simple_Adaptor<double, PointCloud<double>>, PointCloud<double>, 3 /* dim */
>;
mrpt::system::CTimeLogger profiler;
@@ -127,22 +129,19 @@ void kdtree_demo(const size_t N)
const size_t nnToSearch = (rng.drawUniform32bit() % 10) + 1;
#endif
const double queryPt[3] = {
rng.drawUniform(-0.3, maxRangeXY + 0.3),
rng.drawUniform(-0.3, maxRangeXY + 0.3),
rng.drawUniform(-0.3, maxRangeXY + 0.3), rng.drawUniform(-0.3, maxRangeXY + 0.3),
rng.drawUniform(-0.3, maxRangeZ + 0.3)};
mrpt::system::CTimeLoggerEntry tle2(profiler, "query");
#if defined(USE_RADIUS_SEARCH)
indicesDists.clear();
nanoflann::RadiusResultSet<double, size_t> resultSet(
sqRadius, indicesDists);
nanoflann::RadiusResultSet<double, size_t> resultSet(sqRadius, indicesDists);
index.findNeighbors(resultSet, queryPt);
#else
#if defined(USE_RKNN_SEARCH)
nanoflann::RKNNResultSet<double, size_t> resultSet(
nnToSearch, sqRadius);
nanoflann::RKNNResultSet<double, size_t> resultSet(nnToSearch, sqRadius);
#elif defined(USE_KNN_SEARCH)
nanoflann::KNNResultSet<double, size_t> resultSet(nnToSearch);
#else
@@ -162,20 +161,17 @@ void kdtree_demo(const size_t N)
#endif
tle2.stop();
std::cout << "\nQuery point: (" << queryPt[0] << "," << queryPt[1]
<< "," << queryPt[2] << ") => " << resultSet.size()
<< " results.\n";
std::cout << "\nQuery point: (" << queryPt[0] << "," << queryPt[1] << "," << queryPt[2]
<< ") => " << resultSet.size() << " results.\n";
if (!resultSet.empty())
{
#if defined(USE_RADIUS_SEARCH)
nanoflann::ResultItem<size_t, double> worstPair =
resultSet.worst_item();
nanoflann::ResultItem<size_t, double> worstPair = resultSet.worst_item();
std::cout << "Worst pair: idx=" << worstPair.first
<< " dist=" << std::sqrt(worstPair.second) << std::endl;
#else
std::cout << "nnToSearch=" << nnToSearch
<< " actual found=" << indices.size()
std::cout << "nnToSearch=" << nnToSearch << " actual found=" << indices.size()
<< " Worst found dist=" << worstDist << std::endl;
#endif
}

View File

@@ -79,8 +79,7 @@ struct Bearing
mrpt::math::TPoint3D bearing_to_point(const Bearing& b)
{
const auto R =
mrpt::poses::CPose3D::FromYawPitchRoll(b.yaw, b.pitch, 0.0 /*roll*/)
.getRotationMatrix();
mrpt::poses::CPose3D::FromYawPitchRoll(b.yaw, b.pitch, 0.0 /*roll*/).getRotationMatrix();
return {R(0, 0), R(1, 0), R(2, 0)};
}
#endif
@@ -175,9 +174,7 @@ inline T my_angDistance(T from, T to)
//
// ********************************* IMPORTANT ********************************
//
template <
class T, class DataSource, typename _DistanceType = T,
typename IndexType = uint32_t>
template <class T, class DataSource, typename _DistanceType = T, typename IndexType = uint32_t>
struct ThetaPhiMetric_Adaptor
{
using ElementType = T;
@@ -185,17 +182,12 @@ struct ThetaPhiMetric_Adaptor
const DataSource& data_source;
ThetaPhiMetric_Adaptor(const DataSource& _data_source)
: data_source(_data_source)
{
}
ThetaPhiMetric_Adaptor(const DataSource& _data_source) : data_source(_data_source) {}
DistanceType evalMetric(
const T* a, const IndexType b_idx, size_t /*size = 2*/) const
DistanceType evalMetric(const T* a, const IndexType b_idx, size_t /*size = 2*/) const
{
DistanceType result =
mrpt::square(
my_angDistance(a[0], data_source.kdtree_get_pt(b_idx, 0))) +
mrpt::square(my_angDistance(a[0], data_source.kdtree_get_pt(b_idx, 0))) +
mrpt::square(a[1] - data_source.kdtree_get_pt(b_idx, 1));
return result;
@@ -217,8 +209,7 @@ struct ThetaPhiMetric_Adaptor
};
using my_kd_tree_t = nanoflann::KDTreeSingleIndexAdaptor<
ThetaPhiMetric_Adaptor<double, BearingsDataset>, BearingsDataset,
2 /* dim */
ThetaPhiMetric_Adaptor<double, BearingsDataset>, BearingsDataset, 2 /* dim */
>;
void kdtree_demo(const size_t N)
@@ -241,8 +232,7 @@ void kdtree_demo(const size_t N)
auto glPts = pc_to_viz(data);
scene->insert(glPts);
scene->insert(mrpt::opengl::stock_objects::CornerXYZSimple());
auto glAxis =
mrpt::opengl::CAxis::Create(-1.0, -1.0, -1.0, 1.0, 1.0, 1.0, 0.25);
auto glAxis = mrpt::opengl::CAxis::Create(-1.0, -1.0, -1.0, 1.0, 1.0, 1.0, 0.25);
glAxis->setTextScale(0.1);
scene->insert(glAxis);
@@ -276,18 +266,17 @@ void kdtree_demo(const size_t N)
for (size_t i = 0; i < N; i++)
#endif
{
const double queryPt[2] = {
data.kdtree_get_pt(i, 0), data.kdtree_get_pt(i, 1)};
const double queryPt[2] = {data.kdtree_get_pt(i, 0), data.kdtree_get_pt(i, 1)};
mrpt::system::CTimeLoggerEntry tle2(profiler, "query");
const auto numNN = index.knnSearch(
queryPt, NUM_NEIGHBORS, nn_indices.data(), nn_distances.data());
const auto numNN =
index.knnSearch(queryPt, NUM_NEIGHBORS, nn_indices.data(), nn_distances.data());
tle2.stop();
std::cout << "\nQuery point: (" << queryPt[0] << "," << queryPt[1]
<< ") => " << numNN << " results.\n";
std::cout << "\nQuery point: (" << queryPt[0] << "," << queryPt[1] << ") => " << numNN
<< " results.\n";
#ifdef SHOW_GUI
bool stop = false;
@@ -305,8 +294,7 @@ void kdtree_demo(const size_t N)
glFoundPts->clear();
for (size_t j = 0; j < numNN; j++)
{
const auto pt =
bearing_to_point(data.samples.at(nn_indices[j]));
const auto pt = bearing_to_point(data.samples.at(nn_indices[j]));
glFoundPts->insertPoint(pt.x, pt.y, pt.z);
}
@@ -324,10 +312,8 @@ void kdtree_demo(const size_t N)
int main()
{
std::cout << my_angDistance(mrpt::DEG2RAD(179.0), mrpt::DEG2RAD(-179.0))
<< std::endl;
std::cout << my_angDistance(mrpt::DEG2RAD(-179.0), mrpt::DEG2RAD(179.0))
<< std::endl;
std::cout << my_angDistance(mrpt::DEG2RAD(179.0), mrpt::DEG2RAD(-179.0)) << std::endl;
std::cout << my_angDistance(mrpt::DEG2RAD(-179.0), mrpt::DEG2RAD(179.0)) << std::endl;
kdtree_demo(NUM_SAMPLES);
return 0;

View File

@@ -43,8 +43,7 @@ void generateRandomPointCloud(
mat.resize(N, dim);
for (size_t i = 0; i < N; i++)
for (size_t d = 0; d < dim; d++)
mat(i, d) =
max_range * (rand() % 1000) / typename Der::Scalar(1000);
mat(i, d) = max_range * (rand() % 1000) / typename Der::Scalar(1000);
std::cout << "done\n";
}
@@ -64,8 +63,7 @@ void kdtree_demo(const size_t nSamples, const size_t dim)
// Query point:
std::vector<num_t> query_pt(dim);
for (size_t d = 0; d < dim; d++)
query_pt[d] = max_range * (rand() % 1000) / num_t(1000);
for (size_t d = 0; d < dim; d++) query_pt[d] = max_range * (rand() % 1000) / num_t(1000);
// ------------------------------------------------------------
// construct a kd-tree index:

View File

@@ -51,10 +51,7 @@ struct PointCloudAdaptor
inline const Derived& derived() const { return obj; }
// Must return the number of data points
inline size_t kdtree_get_point_count() const
{
return derived().pts.size();
}
inline size_t kdtree_get_point_count() const { return derived().pts.size(); }
// Returns the dim'th component of the idx'th point in the class:
// Since this is inlined and the "dim" argument is typically an immediate
@@ -114,8 +111,7 @@ void kdtree_demo(const size_t N)
index.findNeighbors(resultSet, &query_pt[0]);
std::cout << "knnSearch(nn=" << num_results << "): \n";
std::cout << "ret_index=" << ret_index
<< " out_dist_sqr=" << out_dist_sqr << std::endl;
std::cout << "ret_index=" << ret_index << " out_dist_sqr=" << out_dist_sqr << std::endl;
};
my_kd_tree_t index1(3 /*dim*/, pc2kd, {10 /* max leaf */});

View File

@@ -40,9 +40,7 @@ using namespace nanoflann;
// the metric class My_Custom_Metric_Adaptor, whose constructor accepts
// arbitrary parameters:
template <
class T, class DataSource, typename _DistanceType = T,
typename IndexType = uint32_t>
template <class T, class DataSource, typename _DistanceType = T, typename IndexType = uint32_t>
struct My_Custom_Metric_Adaptor
{
using ElementType = T;
@@ -57,14 +55,12 @@ struct My_Custom_Metric_Adaptor
{
}
inline DistanceType evalMetric(
const T* a, const IndexType b_idx, size_t size) const
inline DistanceType evalMetric(const T* a, const IndexType b_idx, size_t size) const
{
DistanceType result = DistanceType();
for (size_t i = 0; i < size; ++i)
{
const DistanceType diff =
a[i] - data_source.kdtree_get_pt(b_idx, i);
const DistanceType diff = a[i] - data_source.kdtree_get_pt(b_idx, i);
result += std::pow(diff, _myParam);
}
return result;
@@ -90,8 +86,7 @@ static void kdtree_custom_metric_demo(const size_t N)
// construct a kd-tree index:
using my_kd_tree_t = KDTreeSingleIndexAdaptor<
My_Custom_Metric_Adaptor<num_t, PointCloud<num_t>>, PointCloud<num_t>,
3 /* dim */
My_Custom_Metric_Adaptor<num_t, PointCloud<num_t>>, PointCloud<num_t>, 3 /* dim */
>;
dump_mem_usage();
@@ -112,22 +107,19 @@ static void kdtree_custom_metric_demo(const size_t N)
index.findNeighbors(resultSet, &query_pt[0]);
std::cout << "knnSearch(nn=" << num_results << "\n";
std::cout << "ret_index=" << ret_index
<< " out_dist_sqr=" << out_dist_sqr << endl;
std::cout << "ret_index=" << ret_index << " out_dist_sqr=" << out_dist_sqr << endl;
}
{
// Unsorted radius search:
const num_t radius = 1;
std::vector<nanoflann::ResultItem<size_t, num_t>> indices_dists;
RadiusResultSet<num_t, size_t> resultSet(radius, indices_dists);
RadiusResultSet<num_t, size_t> resultSet(radius, indices_dists);
index.findNeighbors(resultSet, query_pt);
// Get worst (furthest) point, without sorting:
nanoflann::ResultItem<size_t, num_t> worst_pair =
resultSet.worst_item();
cout << "Worst pair: idx=" << worst_pair.first
<< " dist=" << worst_pair.second << endl;
nanoflann::ResultItem<size_t, num_t> worst_pair = resultSet.worst_item();
cout << "Worst pair: idx=" << worst_pair.first << " dist=" << worst_pair.second << endl;
}
}

View File

@@ -46,13 +46,11 @@ class MyCustomResultSet
public:
const DistanceType radius;
std::vector<nanoflann::ResultItem<IndexType, DistanceType>>&
m_indices_dists;
std::vector<nanoflann::ResultItem<IndexType, DistanceType>>& m_indices_dists;
explicit MyCustomResultSet(
DistanceType radius_,
std::vector<nanoflann::ResultItem<IndexType, DistanceType>>&
indices_dists)
DistanceType radius_,
std::vector<nanoflann::ResultItem<IndexType, DistanceType>>& indices_dists)
: radius(radius_), m_indices_dists(indices_dists)
{
init();
@@ -73,9 +71,7 @@ class MyCustomResultSet
*/
bool addPoint(DistanceType dist, IndexType index)
{
printf(
"addPoint() called: dist=%f index=%u\n", dist,
static_cast<unsigned int>(index));
printf("addPoint() called: dist=%f index=%u\n", dist, static_cast<unsigned int>(index));
if (dist < radius) m_indices_dists.emplace_back(index, dist);
return true;
@@ -85,9 +81,7 @@ class MyCustomResultSet
void sort()
{
std::sort(
m_indices_dists.begin(), m_indices_dists.end(),
nanoflann::IndexDist_Sorter());
std::sort(m_indices_dists.begin(), m_indices_dists.end(), nanoflann::IndexDist_Sorter());
}
};
@@ -102,8 +96,7 @@ void kdtree_demo(const size_t N)
// construct a kd-tree index:
using my_kd_tree_t = nanoflann::KDTreeSingleIndexAdaptor<
nanoflann::L2_Simple_Adaptor<num_t, PointCloud<num_t>>,
PointCloud<num_t>, 3 /* dim */
nanoflann::L2_Simple_Adaptor<num_t, PointCloud<num_t>>, PointCloud<num_t>, 3 /* dim */
>;
my_kd_tree_t index(3 /*dim*/, cloud, {10 /* max leaf */});
@@ -113,13 +106,11 @@ void kdtree_demo(const size_t N)
const num_t squaredRadius = 1;
std::vector<nanoflann::ResultItem<size_t, num_t>> indices_dists;
MyCustomResultSet<num_t, size_t> resultSet(
squaredRadius, indices_dists);
MyCustomResultSet<num_t, size_t> resultSet(squaredRadius, indices_dists);
index.findNeighbors(resultSet, query_pt);
std::cout << "Found: " << indices_dists.size() << " NN points."
<< std::endl;
std::cout << "Found: " << indices_dists.size() << " NN points." << std::endl;
}
}

View File

@@ -50,8 +50,7 @@ void kdtree_demo(const size_t N)
// construct a kd-tree index:
using my_kd_tree_t = nanoflann::KDTreeSingleIndexAdaptor<
nanoflann::L2_Simple_Adaptor<num_t, PointCloud<num_t>>,
PointCloud<num_t>, 3 /* dim */
nanoflann::L2_Simple_Adaptor<num_t, PointCloud<num_t>>, PointCloud<num_t>, 3 /* dim */
>;
dump_mem_usage();
@@ -69,24 +68,21 @@ void kdtree_demo(const size_t N)
index.findNeighbors(resultSet, &query_pt[0]);
std::cout << "knnSearch(nn=" << num_results << "): \n";
std::cout << "ret_index=" << ret_index
<< " out_dist_sqr=" << out_dist_sqr << std::endl;
std::cout << "ret_index=" << ret_index << " out_dist_sqr=" << out_dist_sqr << std::endl;
}
{
// radius search:
const num_t squaredRadius = 1;
std::vector<nanoflann::ResultItem<size_t, num_t>> indices_dists;
nanoflann::RadiusResultSet<num_t, size_t> resultSet(
squaredRadius, indices_dists);
nanoflann::RadiusResultSet<num_t, size_t> resultSet(squaredRadius, indices_dists);
index.findNeighbors(resultSet, query_pt);
// Get worst (furthest) point, without sorting:
nanoflann::ResultItem<size_t, num_t> worst_pair =
resultSet.worst_item();
std::cout << "Worst pair: idx=" << worst_pair.first
<< " squaredDist=" << worst_pair.second << std::endl;
nanoflann::ResultItem<size_t, num_t> worst_pair = resultSet.worst_item();
std::cout << "Worst pair: idx=" << worst_pair.first << " squaredDist=" << worst_pair.second
<< std::endl;
}
}

View File

@@ -46,8 +46,7 @@ void kdtree_demo(const size_t N)
// construct a kd-tree index:
using my_kd_tree_t = nanoflann::KDTreeSingleIndexAdaptor<
nanoflann::L2_Simple_Adaptor<num_t, PointCloud<num_t>>,
PointCloud<num_t>, 3 /* dim */
nanoflann::L2_Simple_Adaptor<num_t, PointCloud<num_t>>, PointCloud<num_t>, 3 /* dim */
>;
my_kd_tree_t index(3 /*dim*/, cloud, {10 /* max leaf */});
@@ -68,8 +67,7 @@ void kdtree_demo(const size_t N)
std::vector<uint32_t> ret_index(num_results);
std::vector<num_t> out_dist_sqr(num_results);
num_results = index.knnSearch(
&query_pt[0], num_results, &ret_index[0], &out_dist_sqr[0]);
num_results = index.knnSearch(&query_pt[0], num_results, &ret_index[0], &out_dist_sqr[0]);
// In case of less points in the tree than requested:
ret_index.resize(num_results);
@@ -77,8 +75,8 @@ void kdtree_demo(const size_t N)
cout << "knnSearch(): num_results=" << num_results << "\n";
for (size_t i = 0; i < num_results; i++)
cout << "idx[" << i << "]=" << ret_index[i] << " dist[" << i
<< "]=" << out_dist_sqr[i] << endl;
cout << "idx[" << i << "]=" << ret_index[i] << " dist[" << i << "]=" << out_dist_sqr[i]
<< endl;
cout << "\n";
}
@@ -86,17 +84,15 @@ void kdtree_demo(const size_t N)
// radiusSearch(): Perform a search for the points within search_radius
// ----------------------------------------------------------------
{
const num_t search_radius = static_cast<num_t>(0.1);
const num_t search_radius = static_cast<num_t>(0.1);
std::vector<nanoflann::ResultItem<uint32_t, num_t>> ret_matches;
// nanoflanSearchParamsameters params;
// params.sorted = false;
const size_t nMatches =
index.radiusSearch(&query_pt[0], search_radius, ret_matches);
const size_t nMatches = index.radiusSearch(&query_pt[0], search_radius, ret_matches);
cout << "radiusSearch(): radius=" << search_radius << " -> " << nMatches
<< " matches\n";
cout << "radiusSearch(): radius=" << search_radius << " -> " << nMatches << " matches\n";
for (size_t i = 0; i < nMatches; i++)
cout << "idx[" << i << "]=" << ret_matches[i].first << " dist[" << i
<< "]=" << ret_matches[i].second << endl;

View File

@@ -45,16 +45,14 @@ void kdtree_save_load_demo(const size_t N)
// construct a kd-tree index:
using my_kd_tree_t = nanoflann::KDTreeSingleIndexAdaptor<
nanoflann::L2_Simple_Adaptor<double, PointCloud<double>>,
PointCloud<double>, 3 /* dim */
nanoflann::L2_Simple_Adaptor<double, PointCloud<double>>, PointCloud<double>, 3 /* dim */
>;
// Construct the index and save it:
// --------------------------------------------
{
my_kd_tree_t index(
3 /*dim*/, cloud,
nanoflann::KDTreeSingleIndexAdaptorParams(10 /* max leaf */));
3 /*dim*/, cloud, nanoflann::KDTreeSingleIndexAdaptorParams(10 /* max leaf */));
std::ofstream f("index.bin", std::ofstream::binary);
@@ -74,8 +72,8 @@ void kdtree_save_load_demo(const size_t N)
my_kd_tree_t index(
3 /*dim*/, cloud,
nanoflann::KDTreeSingleIndexAdaptorParams(
10 /* max leaf */, nanoflann::KDTreeSingleIndexAdaptorFlags::
SkipInitialBuildIndex));
10 /* max leaf */,
nanoflann::KDTreeSingleIndexAdaptorFlags::SkipInitialBuildIndex));
std::ifstream f("index.bin", std::ofstream::binary);
@@ -93,8 +91,7 @@ void kdtree_save_load_demo(const size_t N)
index.findNeighbors(resultSet, &query_pt[0]);
std::cout << "knnSearch(nn=" << num_results << "): \n";
std::cout << "ret_index=" << ret_index
<< " out_dist_sqr=" << out_dist_sqr << std::endl;
std::cout << "ret_index=" << ret_index << " out_dist_sqr=" << out_dist_sqr << std::endl;
}
// Stress test: try to save an empty index

View File

@@ -87,8 +87,7 @@ void generateRandomPointCloudRanges(
}
template <typename T>
void generateRandomPointCloud(
PointCloud<T>& pc, const size_t N, const T max_range = 10)
void generateRandomPointCloud(PointCloud<T>& pc, const size_t N, const T max_range = 10)
{
generateRandomPointCloudRanges(pc, N, max_range, max_range, max_range);
}
@@ -143,8 +142,7 @@ void generateRandomPointCloud_Quat(PointCloud_Quat<T>& point, const size_t N)
T theta, X, Y, Z, sinAng, cosAng, mag;
for (size_t i = 0; i < N; i++)
{
theta = static_cast<T>(
nanoflann::pi_const<double>() * (((double)rand()) / RAND_MAX));
theta = static_cast<T>(nanoflann::pi_const<double>() * (((double)rand()) / RAND_MAX));
// Generate random value in [-1, 1]
X = static_cast<T>(2 * (((double)rand()) / RAND_MAX) - 1);
Y = static_cast<T>(2 * (((double)rand()) / RAND_MAX) - 1);
@@ -199,16 +197,14 @@ struct PointCloud_Orient
};
template <typename T>
void generateRandomPointCloud_Orient(
PointCloud_Orient<T>& point, const size_t N)
void generateRandomPointCloud_Orient(PointCloud_Orient<T>& point, const size_t N)
{
// Generating Random Orientations
point.pts.resize(N);
for (size_t i = 0; i < N; i++)
{
point.pts[i].theta = static_cast<T>(
(2 * nanoflann::pi_const<double>() *
(((double)rand()) / RAND_MAX)) -
(2 * nanoflann::pi_const<double>() * (((double)rand()) / RAND_MAX)) -
nanoflann::pi_const<double>());
}
}

View File

@@ -48,8 +48,7 @@ void generateRandomPointCloud(
for (size_t i = 0; i < N; i++)
{
samples[i].resize(dim);
for (size_t d = 0; d < dim; d++)
samples[i][d] = max_range * (rand() % 1000) / (1000.0);
for (size_t d = 0; d < dim; d++) samples[i][d] = max_range * (rand() % 1000) / (1000.0);
}
std::cout << "done\n";
}
@@ -65,14 +64,12 @@ void kdtree_demo(const size_t nSamples, const size_t dim)
// Query point:
std::vector<double> query_pt(dim);
for (size_t d = 0; d < dim; d++)
query_pt[d] = max_range * (rand() % 1000) / (1000.0);
for (size_t d = 0; d < dim; d++) query_pt[d] = max_range * (rand() % 1000) / (1000.0);
// construct a kd-tree index:
// Dimensionality set at run-time (default: L2)
// ------------------------------------------------------------
typedef KDTreeVectorOfVectorsAdaptor<my_vector_of_vectors_t, double>
my_kd_tree_t;
typedef KDTreeVectorOfVectorsAdaptor<my_vector_of_vectors_t, double> my_kd_tree_t;
my_kd_tree_t mat_index(dim /*dim*/, samples, 10 /* max leaf */);

File diff suppressed because it is too large Load Diff

View File

@@ -60,19 +60,16 @@ void L2_vs_L2_simple_test(const size_t N, const size_t num_results)
// construct a kd-tree index:
using my_kd_tree_simple_t = KDTreeSingleIndexAdaptor<
L2_Simple_Adaptor<num_t, PointCloud<num_t>>, PointCloud<num_t>,
3 /* dim */
L2_Simple_Adaptor<num_t, PointCloud<num_t>>, PointCloud<num_t>, 3 /* dim */
>;
using my_kd_tree_t = KDTreeSingleIndexAdaptor<
L2_Adaptor<num_t, PointCloud<num_t>>, PointCloud<num_t>, 3 /* dim */
>;
my_kd_tree_simple_t index1(
3 /*dim*/, cloud, KDTreeSingleIndexAdaptorParams(10 /* max leaf */));
my_kd_tree_simple_t index1(3 /*dim*/, cloud, KDTreeSingleIndexAdaptorParams(10 /* max leaf */));
my_kd_tree_t index2(
3 /*dim*/, cloud, KDTreeSingleIndexAdaptorParams(10 /* max leaf */));
my_kd_tree_t index2(3 /*dim*/, cloud, KDTreeSingleIndexAdaptorParams(10 /* max leaf */));
// do a knn search
std::vector<size_t> ret_index(num_results);
@@ -88,8 +85,14 @@ void L2_vs_L2_simple_test(const size_t N, const size_t num_results)
index2.findNeighbors(resultSet, &query_pt[0]);
if (N >= num_results) { EXPECT_EQ(resultSet.size(), num_results); }
else { EXPECT_EQ(resultSet.size(), N); }
if (N >= num_results)
{
EXPECT_EQ(resultSet.size(), num_results);
}
else
{
EXPECT_EQ(resultSet.size(), N);
}
for (size_t i = 0; i < resultSet.size(); i++)
{
@@ -109,12 +112,11 @@ void L2_vs_L2_simple_test(const size_t N, const size_t num_results)
const num_t maxRadiusSqrSearch = 10.0 * 10.0;
std::vector<nanoflann::ResultItem<
typename my_kd_tree_simple_t::IndexType,
typename my_kd_tree_simple_t::DistanceType>>
typename my_kd_tree_simple_t::IndexType, typename my_kd_tree_simple_t::DistanceType>>
radiusIdxs;
nanoflann::RadiusResultSet<num_t, typename my_kd_tree_simple_t::IndexType>
radiusResults(maxRadiusSqrSearch, radiusIdxs);
nanoflann::RadiusResultSet<num_t, typename my_kd_tree_simple_t::IndexType> radiusResults(
maxRadiusSqrSearch, radiusIdxs);
radiusResults.init();
nanoflann::SearchParameters searchParams;
searchParams.sorted = true;
@@ -135,21 +137,18 @@ using namespace nanoflann;
template <typename NUM>
void generateRandomPointCloud(
std::vector<std::vector<NUM>>& samples, const size_t N, const size_t dim,
const NUM max_range)
std::vector<std::vector<NUM>>& samples, const size_t N, const size_t dim, const NUM max_range)
{
samples.resize(N);
for (size_t i = 0; i < N; i++)
{
samples[i].resize(dim);
for (size_t d = 0; d < dim; d++)
samples[i][d] = max_range * (rand() % 1000) / NUM(1000.0);
for (size_t d = 0; d < dim; d++) samples[i][d] = max_range * (rand() % 1000) / NUM(1000.0);
}
}
template <typename NUM>
void L1_vs_bruteforce_test(
const size_t nSamples, const size_t DIM, const size_t numToSearch)
void L1_vs_bruteforce_test(const size_t nSamples, const size_t DIM, const size_t numToSearch)
{
std::vector<std::vector<NUM>> samples;
@@ -196,8 +195,7 @@ void L1_vs_bruteforce_test(
for (size_t i = 0; i < nSamples; i++)
{
double dist = 0.0;
for (size_t d = 0; d < DIM; d++)
dist += std::abs(query_pt[d] - samples[i][d]);
for (size_t d = 0; d < DIM; d++) dist += std::abs(query_pt[d] - samples[i][d]);
bf_nn.emplace(dist, i);
}
}
@@ -218,16 +216,15 @@ void L1_vs_bruteforce_test(
// indices may be not in the (rare) case of a tie:
EXPECT_NEAR(bf_idx2dist.at(ret_indexes[i]), out_dists_sqr[i], 1e-3)
<< "For: numToSearch=" << numToSearch
<< " out_dists_sqr[i]=" << out_dists_sqr[i] << "\n";
<< "For: numToSearch=" << numToSearch << " out_dists_sqr[i]=" << out_dists_sqr[i]
<< "\n";
}
}
}
template <typename NUM>
void rknn_L1_vs_bruteforce_test(
const size_t nSamples, const size_t DIM, const size_t numToSearch,
const NUM maxRadiusSqr)
const size_t nSamples, const size_t DIM, const size_t numToSearch, const NUM maxRadiusSqr)
{
std::vector<std::vector<NUM>> samples;
@@ -273,8 +270,7 @@ void rknn_L1_vs_bruteforce_test(
for (size_t i = 0; i < nSamples; i++)
{
double dist = 0.0;
for (size_t d = 0; d < DIM; d++)
dist += std::abs(query_pt[d] - samples[i][d]);
for (size_t d = 0; d < DIM; d++) dist += std::abs(query_pt[d] - samples[i][d]);
if (dist <= maxRadiusSqr) bf_nn.emplace(dist, i);
}
@@ -293,20 +289,19 @@ void rknn_L1_vs_bruteforce_test(
{
// Distances must be in exact order:
EXPECT_NEAR(it->first, out_dists_sqr[i], 1e-3)
<< "For: numToSearch=" << numToSearch
<< " out_dists_sqr[i]=" << out_dists_sqr[i] << "\n";
<< "For: numToSearch=" << numToSearch << " out_dists_sqr[i]=" << out_dists_sqr[i]
<< "\n";
// indices may be not in the (rare) case of a tie:
EXPECT_NEAR(bf_idx2dist.at(ret_indexes[i]), out_dists_sqr[i], 1e-3)
<< "For: numToSearch=" << numToSearch
<< " out_dists_sqr[i]=" << out_dists_sqr[i] << "\n";
<< "For: numToSearch=" << numToSearch << " out_dists_sqr[i]=" << out_dists_sqr[i]
<< "\n";
}
}
}
template <typename NUM>
void L2_vs_bruteforce_test(
const size_t nSamples, const size_t DIM, const size_t numToSearch)
void L2_vs_bruteforce_test(const size_t nSamples, const size_t DIM, const size_t numToSearch)
{
std::vector<std::vector<NUM>> samples;
@@ -323,8 +318,7 @@ void L2_vs_bruteforce_test(
// construct a kd-tree index:
// Dimensionality set at run-time (default: L2)
// ------------------------------------------------------------
typedef KDTreeVectorOfVectorsAdaptor<std::vector<std::vector<NUM>>, NUM>
my_kd_tree_t;
typedef KDTreeVectorOfVectorsAdaptor<std::vector<std::vector<NUM>>, NUM> my_kd_tree_t;
my_kd_tree_t mat_index(DIM /*dim*/, samples, 10 /* max leaf */);
@@ -353,8 +347,7 @@ void L2_vs_bruteforce_test(
{
double dist = 0.0;
for (size_t d = 0; d < DIM; d++)
dist += (query_pt[d] - samples[i][d]) *
(query_pt[d] - samples[i][d]);
dist += (query_pt[d] - samples[i][d]) * (query_pt[d] - samples[i][d]);
bf_nn.emplace(dist, i);
}
}
@@ -375,8 +368,8 @@ void L2_vs_bruteforce_test(
// indices may be not in the (rare) case of a tie:
EXPECT_NEAR(bf_idx2dist.at(ret_indexes[i]), out_dists_sqr[i], 1e-3)
<< "For: numToSearch=" << numToSearch
<< " out_dists_sqr[i]=" << out_dists_sqr[i] << "\n";
<< "For: numToSearch=" << numToSearch << " out_dists_sqr[i]=" << out_dists_sqr[i]
<< "\n";
}
}
}
@@ -391,19 +384,15 @@ void box_L2_vs_bruteforce_test(const size_t nSamples, const size_t DIM)
// Generate points:
generateRandomPointCloud(samples, nSamples, DIM, max_range);
typedef KDTreeVectorOfVectorsAdaptor<std::vector<std::vector<NUM>>, NUM>
my_kd_tree_t;
typedef KDTreeVectorOfVectorsAdaptor<std::vector<std::vector<NUM>>, NUM> my_kd_tree_t;
// Query box:
typename my_kd_tree_t::index_t::BoundingBox query_box(DIM);
for (size_t d = 0; d < DIM; d++)
{
query_box[d].low =
static_cast<NUM>(max_range * (rand() % 1000) / (1000.0));
query_box[d].high =
static_cast<NUM>(max_range * (rand() % 1000) / (1000.0));
if (query_box[d].low > query_box[d].high)
std::swap(query_box[d].low, query_box[d].high);
query_box[d].low = static_cast<NUM>(max_range * (rand() % 1000) / (1000.0));
query_box[d].high = static_cast<NUM>(max_range * (rand() % 1000) / (1000.0));
if (query_box[d].low > query_box[d].high) std::swap(query_box[d].low, query_box[d].high);
}
// construct a kd-tree index:
@@ -438,8 +427,7 @@ void box_L2_vs_bruteforce_test(const size_t nSamples, const size_t DIM)
template <typename NUM>
void rknn_L2_vs_bruteforce_test(
const size_t nSamples, const size_t DIM, const size_t numToSearch,
const NUM maxRadiusSqr)
const size_t nSamples, const size_t DIM, const size_t numToSearch, const NUM maxRadiusSqr)
{
std::vector<std::vector<NUM>> samples;
@@ -456,8 +444,7 @@ void rknn_L2_vs_bruteforce_test(
// construct a kd-tree index:
// Dimensionality set at run-time (default: L2)
// ------------------------------------------------------------
typedef KDTreeVectorOfVectorsAdaptor<std::vector<std::vector<NUM>>, NUM>
my_kd_tree_t;
typedef KDTreeVectorOfVectorsAdaptor<std::vector<std::vector<NUM>>, NUM> my_kd_tree_t;
my_kd_tree_t mat_index(DIM /*dim*/, samples, 10 /* max leaf */);
@@ -485,8 +472,7 @@ void rknn_L2_vs_bruteforce_test(
{
double dist = 0.0;
for (size_t d = 0; d < DIM; d++)
dist += (query_pt[d] - samples[i][d]) *
(query_pt[d] - samples[i][d]);
dist += (query_pt[d] - samples[i][d]) * (query_pt[d] - samples[i][d]);
if (dist <= maxRadiusSqr) bf_nn.emplace(dist, i);
}
@@ -505,13 +491,13 @@ void rknn_L2_vs_bruteforce_test(
{
// Distances must be in exact order:
EXPECT_NEAR(it->first, out_dists_sqr[i], 1e-3)
<< "For: numToSearch=" << numToSearch
<< " out_dists_sqr[i]=" << out_dists_sqr[i] << "\n";
<< "For: numToSearch=" << numToSearch << " out_dists_sqr[i]=" << out_dists_sqr[i]
<< "\n";
// indices may be not in the (rare) case of a tie:
EXPECT_NEAR(bf_idx2dist.at(ret_indexes[i]), out_dists_sqr[i], 1e-3)
<< "For: numToSearch=" << numToSearch
<< " out_dists_sqr[i]=" << out_dists_sqr[i] << "\n";
<< "For: numToSearch=" << numToSearch << " out_dists_sqr[i]=" << out_dists_sqr[i]
<< "\n";
}
}
}
@@ -528,13 +514,11 @@ void SO3_vs_bruteforce_test(const size_t nSamples)
// construct a kd-tree index:
typedef KDTreeSingleIndexAdaptor<
SO3_Adaptor<NUM, PointCloud_Quat<NUM>>, PointCloud_Quat<NUM>,
4 /* dim */
SO3_Adaptor<NUM, PointCloud_Quat<NUM>>, PointCloud_Quat<NUM>, 4 /* dim */
>
my_kd_tree_t;
my_kd_tree_t index(
4 /*dim*/, cloud, KDTreeSingleIndexAdaptorParams(10 /* max leaf */));
my_kd_tree_t index(4 /*dim*/, cloud, KDTreeSingleIndexAdaptorParams(10 /* max leaf */));
// do a knn search
const size_t num_results = 1;
std::vector<size_t> ret_indexes(num_results);
@@ -581,13 +565,11 @@ void SO2_vs_bruteforce_test(const size_t nSamples)
// construct a kd-tree index:
typedef KDTreeSingleIndexAdaptor<
SO2_Adaptor<NUM, PointCloud_Orient<NUM>>, PointCloud_Orient<NUM>,
1 /* dim */
SO2_Adaptor<NUM, PointCloud_Orient<NUM>>, PointCloud_Orient<NUM>, 1 /* dim */
>
my_kd_tree_t;
my_kd_tree_t index(
1 /*dim*/, cloud, KDTreeSingleIndexAdaptorParams(10 /* max leaf */));
my_kd_tree_t index(1 /*dim*/, cloud, KDTreeSingleIndexAdaptorParams(10 /* max leaf */));
// do a knn search
const size_t num_results = 1;
std::vector<size_t> ret_indexes(num_results);
@@ -639,8 +621,7 @@ void L2_dynamic_vs_bruteforce_test(const size_t nSamples)
>
my_kd_tree_t;
my_kd_tree_t index(
3 /*dim*/, cloud, KDTreeSingleIndexAdaptorParams(10 /* max leaf */));
my_kd_tree_t index(3 /*dim*/, cloud, KDTreeSingleIndexAdaptorParams(10 /* max leaf */));
// Generate points:
generateRandomPointCloud(cloud, nSamples, max_range);
@@ -731,8 +712,7 @@ void L2_dynamic_vs_bruteforce_test(const size_t nSamples)
}
template <typename NUM>
void L2_concurrent_build_vs_bruteforce_test(
const size_t nSamples, const size_t DIM)
void L2_concurrent_build_vs_bruteforce_test(const size_t nSamples, const size_t DIM)
{
std::vector<std::vector<NUM>> samples;
@@ -749,11 +729,9 @@ void L2_concurrent_build_vs_bruteforce_test(
// construct a kd-tree index:
// Dimensionality set at run-time (default: L2)
// ------------------------------------------------------------
typedef KDTreeVectorOfVectorsAdaptor<std::vector<std::vector<NUM>>, NUM>
my_kd_tree_t;
typedef KDTreeVectorOfVectorsAdaptor<std::vector<std::vector<NUM>>, NUM> my_kd_tree_t;
my_kd_tree_t mat_index(
DIM /*dim*/, samples, 10 /* max leaf */, 0 /* concurrent build */);
my_kd_tree_t mat_index(DIM /*dim*/, samples, 10 /* max leaf */, 0 /* concurrent build */);
// do a knn search
const size_t num_results = 1;
@@ -773,8 +751,7 @@ void L2_concurrent_build_vs_bruteforce_test(
{
double dist = 0.0;
for (size_t d = 0; d < DIM; d++)
dist += (query_pt[d] - samples[i][d]) *
(query_pt[d] - samples[i][d]);
dist += (query_pt[d] - samples[i][d]) * (query_pt[d] - samples[i][d]);
if (dist < min_dist_L2)
{
min_dist_L2 = dist;
@@ -807,8 +784,7 @@ void L2_concurrent_build_vs_L2_test(const size_t nSamples, const size_t DIM)
// construct a kd-tree index:
// Dimensionality set at run-time (default: L2)
// ------------------------------------------------------------
typedef KDTreeVectorOfVectorsAdaptor<std::vector<std::vector<NUM>>, NUM>
my_kd_tree_t;
typedef KDTreeVectorOfVectorsAdaptor<std::vector<std::vector<NUM>>, NUM> my_kd_tree_t;
my_kd_tree_t mat_index_concurrent_build(
DIM /*dim*/, samples, 10 /* max leaf */, 0 /* concurrent build */);
@@ -837,8 +813,7 @@ void L2_dynamic_sorted_test(const size_t N, const size_t num_results)
std::vector<num_t> dynamic_dist(num_results);
KNNResultSet<num_t> dynamic_knn_result(num_results);
std::vector<ResultItem<size_t, num_t>> radius_results_vec;
RadiusResultSet<num_t, size_t> dynamic_radius_result(
10.0 * 10.0, radius_results_vec);
RadiusResultSet<num_t, size_t> dynamic_radius_result(10.0 * 10.0, radius_results_vec);
// Prepare search params to sort result
const auto search_params = SearchParameters(0, true);
@@ -846,10 +821,8 @@ void L2_dynamic_sorted_test(const size_t N, const size_t num_results)
dynamic_knn_result.init(&dynamic_idx[0], &dynamic_dist[0]);
dynamic_radius_result.init();
dynamic_index.findNeighbors(
dynamic_knn_result, &query_pt[0], search_params);
dynamic_index.findNeighbors(
dynamic_radius_result, &query_pt[0], search_params);
dynamic_index.findNeighbors(dynamic_knn_result, &query_pt[0], search_params);
dynamic_index.findNeighbors(dynamic_radius_result, &query_pt[0], search_params);
// Check size
const size_t expected_size = std::min(N, num_results);
@@ -934,13 +907,11 @@ TEST(kdtree, robust_empty_tree)
// construct a kd-tree index:
typedef KDTreeSingleIndexAdaptor<
L2_Simple_Adaptor<double, PointCloud<double>>, PointCloud<double>,
3 /* dim */
L2_Simple_Adaptor<double, PointCloud<double>>, PointCloud<double>, 3 /* dim */
>
my_kd_tree_simple_t;
my_kd_tree_simple_t index1(
3 /*dim*/, cloud, KDTreeSingleIndexAdaptorParams(10 /* max leaf */));
my_kd_tree_simple_t index1(3 /*dim*/, cloud, KDTreeSingleIndexAdaptorParams(10 /* max leaf */));
// Now we will try to search in the tree, and WE EXPECT a result of
// no neighbors found if the error detection works fine:
@@ -1073,8 +1044,7 @@ TEST(kdtree, robust_nonempty_tree)
my_kd_tree_simple_t;
my_kd_tree_simple_t index1(
3 /*dim*/, cloud, KDTreeSingleIndexAdaptorParams(10 /* max leaf */),
max_point_count);
3 /*dim*/, cloud, KDTreeSingleIndexAdaptorParams(10 /* max leaf */), max_point_count);
// Try a search and expect a neighbor to exist because the dynamic tree was
// passed a non-empty cloud
@@ -1096,8 +1066,7 @@ TEST(kdtree, add_and_remove_points)
L2_Simple_Adaptor<double, PointCloud<double>>, PointCloud<double>, 3>
my_kd_tree_simple_t;
my_kd_tree_simple_t index(
3 /*dim*/, cloud, KDTreeSingleIndexAdaptorParams(10 /* max leaf */));
my_kd_tree_simple_t index(3 /*dim*/, cloud, KDTreeSingleIndexAdaptorParams(10 /* max leaf */));
const auto query = [&index]() -> size_t
{