Skip to content

Commit 4c3b36e

Browse files
AlrIsmailmvieth
authored andcommitted
Fix getFitnessScore to respect user-provided indices in Registration
1 parent 100ed8b commit 4c3b36e

3 files changed

Lines changed: 48 additions & 3 deletions

File tree

registration/include/pcl/registration/impl/registration.hpp

Lines changed: 6 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -131,13 +131,17 @@ Registration<PointSource, PointTarget, Scalar>::getFitnessScore(
131131

132132
template <typename PointSource, typename PointTarget, typename Scalar>
133133
inline double
134-
Registration<PointSource, PointTarget, Scalar>::getFitnessScore(double max_range)
134+
Registration<PointSource, PointTarget, Scalar>::getFitnessScore(double max_range,
135+
bool use_indices)
135136
{
136137
double fitness_score = 0.0;
137138

138139
// Transform the input dataset using the final transformation
139140
PointCloudSource input_transformed;
140-
transformPointCloud(*input_, input_transformed, final_transformation_);
141+
if (use_indices && indices_ && indices_->size() != input_->size())
142+
transformPointCloud(*input_, *indices_, input_transformed, final_transformation_);
143+
else
144+
transformPointCloud(*input_, input_transformed, final_transformation_);
141145

142146
pcl::Indices nn_indices(1);
143147
std::vector<float> nn_dists(1);

registration/include/pcl/registration/registration.h

Lines changed: 4 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -444,9 +444,12 @@ class Registration : public PCLBase<PointSource> {
444444
/** \brief Obtain the Euclidean fitness score (e.g., mean of squared distances from
445445
* the source to the target) \param[in] max_range maximum allowable distance between a
446446
* point and its correspondence in the target (default: double::max)
447+
* \param[in] use_indices whether to use the registered indices or all points
448+
* (default: false)
447449
*/
448450
inline double
449-
getFitnessScore(double max_range = std::numeric_limits<double>::max());
451+
getFitnessScore(double max_range = std::numeric_limits<double>::max(),
452+
bool use_indices = false);
450453

451454
/** \brief Obtain the Euclidean fitness score (e.g., mean of squared distances from
452455
* the source to the target) from two sets of correspondence distances (distances

test/registration/test_registration.cpp

Lines changed: 38 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -194,6 +194,44 @@ TEST(PCL, ICP_translated)
194194
EXPECT_NEAR(icp.getFinalTransformation()(2, 3), 0.2, 2e-3);
195195
}
196196

197+
//////////////////////////////////////////////////////////////////////////////////////////////////////////////////
198+
TEST(PCL, Registration_getFitnessScore_Indices)
199+
{
200+
pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_in(new pcl::PointCloud<pcl::PointXYZ>);
201+
pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_out(new pcl::PointCloud<pcl::PointXYZ>);
202+
203+
cloud_in->push_back(pcl::PointXYZ(0, 0, 0));
204+
cloud_in->push_back(pcl::PointXYZ(0, 1, 0));
205+
cloud_in->push_back(pcl::PointXYZ(0, 0, 1));
206+
cloud_in->push_back(pcl::PointXYZ(10, 0, 0));
207+
208+
cloud_out->push_back(pcl::PointXYZ(0, 0, 0));
209+
cloud_out->push_back(pcl::PointXYZ(0, 1, 0));
210+
cloud_out->push_back(pcl::PointXYZ(0, 0, 1));
211+
cloud_out->push_back(pcl::PointXYZ(10, 0, 0.5)); // Dist squared = 0.25
212+
213+
RegistrationWrapper<pcl::PointXYZ, pcl::PointXYZ> reg;
214+
reg.setInputSource(cloud_in);
215+
reg.setInputTarget(cloud_out);
216+
217+
pcl::IndicesPtr indices(new pcl::Indices());
218+
indices->push_back(0);
219+
indices->push_back(1);
220+
indices->push_back(2);
221+
reg.setIndices(indices);
222+
223+
pcl::PointCloud<pcl::PointXYZ> final_cloud;
224+
reg.align(final_cloud);
225+
226+
// With use_indices = false (default), should calculate score using all points
227+
// mean of squared distances: (0 + 0 + 0 + 0.25) / 4 = 0.0625
228+
EXPECT_NEAR(reg.getFitnessScore(1.0, false), 0.0625, 1e-4);
229+
230+
// With use_indices = true, should calculate score using only indices (points 0, 1, 2)
231+
// mean of squared distances: (0 + 0 + 0) / 3 = 0.0
232+
EXPECT_NEAR(reg.getFitnessScore(1.0, true), 0.0, 1e-4);
233+
}
234+
197235
//////////////////////////////////////////////////////////////////////////////////////////////////////////////////
198236
TEST (PCL, IterativeClosestPoint)
199237
{

0 commit comments

Comments
 (0)