Skip to content

Commit 9ca20d9

Browse files
authored
Revise get functions & (minor) fix typos in the comments (#185)
* Change `getNormals` to be an inline public function * (minor) Add a line break between functions * Add `getInputOrderedTranslationInliers` function for visualization purposes * (minor) Fix typos in the comments
1 parent 6ceb9c8 commit 9ca20d9

File tree

7 files changed

+40
-22
lines changed

7 files changed

+40
-22
lines changed

teaser/include/teaser/certification.h

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -31,7 +31,7 @@ class AbstractRotationCertifier {
3131

3232
/**
3333
* Abstract function for certifying rotation estimation results
34-
* @param rotation_solution [in] a solution to the rotatoin registration problem
34+
* @param rotation_solution [in] a solution to the rotation registration problem
3535
* @param src [in] Assume dst = R * src
3636
* @param dst [in] Assume dst = R * src
3737
* @param theta [in] a binary vector indicating inliers vs. outliers
@@ -185,7 +185,7 @@ class DRSCertifier : public AbstractRotationCertifier {
185185
(1) off-diagonal blocks must be skew-symmetric
186186
(2) diagonal blocks must satisfy W_00 = - sum(W_ii)
187187
(3) W_dual must also satisfy complementary slackness (because M_init satisfies complementary
188-
slackness) This projection is optimal in the sense of minimum Frobenious norm
188+
slackness) This projection is optimal in the sense of minimum Frobenius norm
189189
*/
190190
void getOptimalDualProjection(const Eigen::Matrix<double, Eigen::Dynamic, Eigen::Dynamic>& W,
191191
const Eigen::Matrix<double, 1, Eigen::Dynamic>& theta_prepended,

teaser/include/teaser/fpfh.h

Lines changed: 6 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -48,6 +48,12 @@ class FPFHEstimation {
4848
return fpfh_estimation_;
4949
}
5050

51+
/**
52+
* Return the normal vectors of the input cloud that are used in the calculation of FPFH
53+
* @return
54+
*/
55+
inline pcl::PointCloud<pcl::Normal> getNormals() { return *normals_; }
56+
5157
private:
5258
// pcl::FPFHEstimation<pcl::PointXYZ, pcl::Normal, pcl::FPFHSignature33>::Ptr fpfh_estimation_;
5359
pcl::FPFHEstimationOMP<pcl::PointXYZ, pcl::Normal, pcl::FPFHSignature33>::Ptr fpfh_estimation_;
@@ -82,12 +88,6 @@ class FPFHEstimation {
8288
* Wrapper function for the corresponding PCL function.
8389
*/
8490
void setRadiusSearch(double);
85-
86-
/**
87-
* Return the normal vectors of the input cloud that are used in the calculation of FPFH
88-
* @return
89-
*/
90-
pcl::PointCloud<pcl::Normal> getNormals();
9191
};
9292

9393
} // namespace teaser

teaser/include/teaser/graph.h

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -35,7 +35,7 @@ class Graph {
3535
* vertices v1 & v2, we assume that v2 exists in v1's list, and v1 also exists in v2's list. This
3636
* condition is not enforced. If violated, removeEdge() function might exhibit undefined
3737
* behaviors.
38-
* @param [in] adj_list an map representing an adjacency list
38+
* @param [in] adj_list a map representing an adjacency list
3939
*/
4040
explicit Graph(const std::map<int, std::vector<int>>& adj_list) {
4141
adj_list_.resize(adj_list.size());

teaser/include/teaser/linalg.h

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -78,7 +78,7 @@ Eigen::Matrix<NumT, Eigen::Dynamic, 1> vectorKron(const Eigen::Matrix<NumT, N, 1
7878
*
7979
* @tparam NumT numerical type for Eigen matrices (double, float, etc.)
8080
* @param A [in] input matrix
81-
* @param nearestPSD [out] output neaest positive semi-definite matrix
81+
* @param nearestPSD [out] output nearest positive semi-definite matrix
8282
* @param eig_threshold [in] optional threshold of determining the smallest eigen values
8383
*/
8484
template <typename NumT>

teaser/include/teaser/registration.h

Lines changed: 24 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -22,7 +22,7 @@
2222
#include "teaser/geometry.h"
2323

2424
// TODO: might be a good idea to template Eigen::Vector3f and Eigen::VectorXf such that later on we
25-
// can decide to use doulbe if we want. Double vs float might give nontrivial differences..
25+
// can decide to use double if we want. Double vs float might give nontrivial differences..
2626

2727
namespace teaser {
2828

@@ -283,7 +283,7 @@ class GNCTLSRotationSolver : public GNCRotationSolver {
283283
* For more information, please see the original paper on FGR:
284284
* Q.-Y. Zhou, J. Park, and V. Koltun, “Fast Global Registration,” in Computer Vision – ECCV 2016,
285285
* Cham, 2016, vol. 9906, pp. 766–782.
286-
* Notice that our implementation differ from the paper on the estimation of T matrix. We
286+
* Notice that our implementation differs from the paper on the estimation of T matrix. We
287287
* only estimate rotation, instead of rotation and translation.
288288
*
289289
*/
@@ -317,7 +317,7 @@ class FastGlobalRegistrationSolver : public GNCRotationSolver {
317317
/**
318318
* Use Quatro to solve for pairwise registration problems avoiding degeneracy
319319
*
320-
* For more information, please see the original paper on FGR:
320+
* For more information, please see the original paper on Quatro:
321321
* H. Lim et al., "A Single Correspondence Is Enough: Robust Global Registration
322322
* to Avoid Degeneracy in Urban Environments," in Robotics - ICRA 2022,
323323
* Accepted. To appear. arXiv:2203.06612 [cs], Mar. 2022.
@@ -714,12 +714,31 @@ class RobustRegistrationSolver {
714714
}
715715

716716
/**
717-
* Return inliers from rotation estimation
717+
* Return inliers from translation estimation
718718
*
719-
* @return a vector of indices of measurements deemed as inliers by rotation estimation
719+
* @return a vector of indices of measurements deemed as inliers by translation estimation
720720
*/
721721
inline std::vector<int> getTranslationInliers() { return translation_inliers_; }
722722

723+
/**
724+
* Return input-ordered inliers from translation estimation
725+
*
726+
* @return a vector of indices of given input correspondences deemed as inliers
727+
* by translation estimation.
728+
*/
729+
inline std::vector<int> getInputOrderedTranslationInliers() {
730+
if (params_.rotation_estimation_algorithm == ROTATION_ESTIMATION_ALGORITHM::FGR) {
731+
throw std::runtime_error(
732+
"This function is not supported when using FGR since FGR does not use max clique.");
733+
}
734+
std::vector<int> translation_inliers;
735+
translation_inliers.reserve(translation_inliers_.size());
736+
for (const auto& i : translation_inliers_) {
737+
translation_inliers.emplace_back(max_clique_[i]);
738+
}
739+
return translation_inliers;
740+
}
741+
723742
/**
724743
* Return a boolean Eigen row vector indicating whether specific measurements are inliers
725744
* according to translation measurements.

teaser/include/teaser/utils.h

Lines changed: 5 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -22,7 +22,7 @@ namespace utils {
2222
* randsample()
2323
* @tparam T A number type
2424
* @tparam URBG A UniformRandomBitGenerator type
25-
* @param input A input vector containing the whole population
25+
* @param input An input vector containing the whole population
2626
* @param num_samples Number of samples we want
2727
* @param g
2828
* @return
@@ -56,7 +56,7 @@ std::vector<T> randomSample(std::vector<T> input, size_t num_samples, URBG&& g)
5656
}
5757

5858
/**
59-
* Remove one row from matrix.
59+
* Remove one row from a matrix.
6060
* Credit to: https://stackoverflow.com/questions/13290395
6161
* @param matrix an Eigen::Matrix.
6262
* @param rowToRemove index of row to remove. If >= matrix.rows(), no operation will be taken
@@ -78,7 +78,7 @@ void removeRow(Eigen::Matrix<T, R, C>& matrix, unsigned int rowToRemove) {
7878
}
7979

8080
/**
81-
* Remove one column from matrix.
81+
* Remove one column from a matrix.
8282
* Credit to: https://stackoverflow.com/questions/13290395
8383
* @param matrix
8484
* @param colToRemove index of col to remove. If >= matrix.cols(), no operation will be taken
@@ -112,7 +112,7 @@ template <class T, int D> float calculateDiameter(const Eigen::Matrix<T, D, Eige
112112
}
113113

114114
/**
115-
* Helper function to use svd to estimate rotation.
115+
* Helper function to use SVD to estimate rotation.
116116
* Method described here: http://igl.ethz.ch/projects/ARAP/svd_rot.pdf
117117
* @param X
118118
* @param Y
@@ -160,7 +160,7 @@ inline Eigen::Matrix2d svdRot2d(const Eigen::Matrix<double, 2, Eigen::Dynamic>&
160160
}
161161

162162
/**
163-
* Use an boolean Eigen matrix to mask a vector
163+
* Use a boolean Eigen matrix to mask a vector
164164
* @param mask a 1-by-N boolean Eigen matrix
165165
* @param elements vector to be masked
166166
* @return

teaser/src/fpfh.cc

Lines changed: 1 addition & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -58,6 +58,5 @@ void teaser::FPFHEstimation::setSearchMethod(
5858
void teaser::FPFHEstimation::compute(pcl::PointCloud<pcl::FPFHSignature33>& output_cloud) {
5959
fpfh_estimation_->compute(output_cloud);
6060
}
61-
void teaser::FPFHEstimation::setRadiusSearch(double r) { fpfh_estimation_->setRadiusSearch(r); }
6261

63-
pcl::PointCloud<pcl::Normal> teaser::FPFHEstimation::getNormals() { return *normals_; }
62+
void teaser::FPFHEstimation::setRadiusSearch(double r) { fpfh_estimation_->setRadiusSearch(r); }

0 commit comments

Comments
 (0)