Skip to content

Commit 8f223e1

Browse files
committed
Fix template bugs
1 parent 67ddc91 commit 8f223e1

File tree

4 files changed

+36
-32
lines changed

4 files changed

+36
-32
lines changed

registration/include/pcl/registration/icp.h

Lines changed: 22 additions & 22 deletions
Original file line numberDiff line numberDiff line change
@@ -109,28 +109,28 @@ namespace pcl
109109
typedef boost::shared_ptr<IterativeClosestPoint<PointSource, PointTarget, Scalar, MatrixType> > Ptr;
110110
typedef boost::shared_ptr<const IterativeClosestPoint<PointSource, PointTarget, Scalar> > ConstPtr;
111111

112-
using Registration<PointSource, PointTarget, Scalar>::reg_name_;
113-
using Registration<PointSource, PointTarget, Scalar>::getClassName;
114-
using Registration<PointSource, PointTarget, Scalar>::setInputSource;
115-
using Registration<PointSource, PointTarget, Scalar>::input_;
116-
using Registration<PointSource, PointTarget, Scalar>::indices_;
117-
using Registration<PointSource, PointTarget, Scalar>::target_;
118-
using Registration<PointSource, PointTarget, Scalar>::nr_iterations_;
119-
using Registration<PointSource, PointTarget, Scalar>::max_iterations_;
120-
using Registration<PointSource, PointTarget, Scalar>::previous_transformation_;
121-
using Registration<PointSource, PointTarget, Scalar>::final_transformation_;
122-
using Registration<PointSource, PointTarget, Scalar>::transformation_;
123-
using Registration<PointSource, PointTarget, Scalar>::transformation_epsilon_;
124-
using Registration<PointSource, PointTarget, Scalar>::converged_;
125-
using Registration<PointSource, PointTarget, Scalar>::corr_dist_threshold_;
126-
using Registration<PointSource, PointTarget, Scalar>::inlier_threshold_;
127-
using Registration<PointSource, PointTarget, Scalar>::min_number_correspondences_;
128-
using Registration<PointSource, PointTarget, Scalar>::update_visualizer_;
129-
using Registration<PointSource, PointTarget, Scalar>::euclidean_fitness_epsilon_;
130-
using Registration<PointSource, PointTarget, Scalar>::correspondences_;
131-
using Registration<PointSource, PointTarget, Scalar>::transformation_estimation_;
132-
using Registration<PointSource, PointTarget, Scalar>::correspondence_estimation_;
133-
using Registration<PointSource, PointTarget, Scalar>::correspondence_rejectors_;
112+
using Registration<PointSource, PointTarget, Scalar, MatrixType>::reg_name_;
113+
using Registration<PointSource, PointTarget, Scalar, MatrixType>::getClassName;
114+
using Registration<PointSource, PointTarget, Scalar, MatrixType>::setInputSource;
115+
using Registration<PointSource, PointTarget, Scalar, MatrixType>::input_;
116+
using Registration<PointSource, PointTarget, Scalar, MatrixType>::indices_;
117+
using Registration<PointSource, PointTarget, Scalar, MatrixType>::target_;
118+
using Registration<PointSource, PointTarget, Scalar, MatrixType>::nr_iterations_;
119+
using Registration<PointSource, PointTarget, Scalar, MatrixType>::max_iterations_;
120+
using Registration<PointSource, PointTarget, Scalar, MatrixType>::previous_transformation_;
121+
using Registration<PointSource, PointTarget, Scalar, MatrixType>::final_transformation_;
122+
using Registration<PointSource, PointTarget, Scalar, MatrixType>::transformation_;
123+
using Registration<PointSource, PointTarget, Scalar, MatrixType>::transformation_epsilon_;
124+
using Registration<PointSource, PointTarget, Scalar, MatrixType>::converged_;
125+
using Registration<PointSource, PointTarget, Scalar, MatrixType>::corr_dist_threshold_;
126+
using Registration<PointSource, PointTarget, Scalar, MatrixType>::inlier_threshold_;
127+
using Registration<PointSource, PointTarget, Scalar, MatrixType>::min_number_correspondences_;
128+
using Registration<PointSource, PointTarget, Scalar, MatrixType>::update_visualizer_;
129+
using Registration<PointSource, PointTarget, Scalar, MatrixType>::euclidean_fitness_epsilon_;
130+
using Registration<PointSource, PointTarget, Scalar, MatrixType>::correspondences_;
131+
using Registration<PointSource, PointTarget, Scalar, MatrixType>::transformation_estimation_;
132+
using Registration<PointSource, PointTarget, Scalar, MatrixType>::correspondence_estimation_;
133+
using Registration<PointSource, PointTarget, Scalar, MatrixType>::correspondence_rejectors_;
134134

135135
typename pcl::registration::DefaultConvergenceCriteria<Scalar>::Ptr convergence_criteria_;
136136
typedef typename Registration<PointSource, PointTarget, Scalar>::Matrix4 Matrix4;

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

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -182,12 +182,12 @@ pcl::Registration<PointSource, PointTarget, Scalar, MatrixType >::getFitnessScor
182182
template <typename PointSource, typename PointTarget, typename Scalar, typename MatrixType> inline void
183183
pcl::Registration<PointSource, PointTarget, Scalar, MatrixType>::align (PointCloudSource &output)
184184
{
185-
align (output, Matrix4::Identity ());
185+
align (output, MatrixType::Identity ());
186186
}
187187

188188
//////////////////////////////////////////////////////////////////////////////////////////////
189189
template <typename PointSource, typename PointTarget, typename Scalar, typename MatrixType> inline void
190-
pcl::Registration<PointSource, PointTarget, Scalar, MatrixType>::align (PointCloudSource &output, const Matrix4& guess)
190+
pcl::Registration<PointSource, PointTarget, Scalar, MatrixType>::align (PointCloudSource &output, const MatrixType& guess)
191191
{
192192
if (!initCompute ())
193193
return;
@@ -220,7 +220,7 @@ pcl::Registration<PointSource, PointTarget, Scalar, MatrixType>::align (PointClo
220220

221221
// Perform the actual transformation computation
222222
converged_ = false;
223-
final_transformation_ = transformation_ = previous_transformation_ = Matrix4::Identity ();
223+
final_transformation_ = transformation_ = previous_transformation_ = MatrixType::Identity ();
224224

225225
// Right before we estimate the transformation, we set all the point.data[3] values to 1 to aid the rigid
226226
// transformation

registration/include/pcl/registration/registration.h

Lines changed: 7 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -107,9 +107,9 @@ namespace pcl
107107
, max_iterations_ (10)
108108
, ransac_iterations_ (0)
109109
, target_ ()
110-
, final_transformation_ (Matrix4::Identity ())
111-
, transformation_ (Matrix4::Identity ())
112-
, previous_transformation_ (Matrix4::Identity ())
110+
, final_transformation_ (MatrixType::Identity ())
111+
, transformation_ (MatrixType::Identity ())
112+
, previous_transformation_ (MatrixType::Identity ())
113113
, transformation_epsilon_ (0.0)
114114
, euclidean_fitness_epsilon_ (-std::numeric_limits<double>::max ())
115115
, corr_dist_threshold_ (std::sqrt (std::numeric_limits<double>::max ()))
@@ -268,11 +268,11 @@ namespace pcl
268268
}
269269

270270
/** \brief Get the final transformation matrix estimated by the registration method. */
271-
inline Matrix4
271+
inline MatrixType
272272
getFinalTransformation () { return (final_transformation_); }
273273

274274
/** \brief Get the last incremental transformation matrix estimated by the registration method. */
275-
inline Matrix4
275+
inline MatrixType
276276
getLastIncrementalTransformation () { return (transformation_); }
277277

278278
/** \brief Set the maximum number of iterations the internal optimization should run for.
@@ -412,7 +412,7 @@ namespace pcl
412412
* \param[in] guess the initial gross estimation of the transformation
413413
*/
414414
inline void
415-
align (PointCloudSource &output, const Matrix4& guess);
415+
align (PointCloudSource &output, const MatrixType& guess);
416416

417417
/** \brief Abstract class get name method. */
418418
inline const std::string&
@@ -591,7 +591,7 @@ namespace pcl
591591

592592
/** \brief Abstract transformation computation method with initial guess */
593593
virtual void
594-
computeTransformation (PointCloudSource &output, const Matrix4& guess) = 0;
594+
computeTransformation (PointCloudSource &output, const MatrixType& guess) = 0;
595595

596596
private:
597597
/** \brief The point representation used (internal). */

tools/iterative_closest_point.cpp

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -130,6 +130,10 @@ compute (const sensor_msgs::PointCloud2::ConstPtr &source,
130130

131131
CorrespondenceRejectorTrimmed::Ptr cor_rej_tri (new CorrespondenceRejectorTrimmed);
132132

133+
//TEST
134+
IterativeClosestPointNonrigid<PointNormal, PointNormal, Scalar> icp2;
135+
icp2.setTransformationEstimation (te);
136+
133137
IterativeClosestPoint<PointNormal, PointNormal, Scalar> icp;
134138
icp.setCorrespondenceEstimation (cens);
135139
icp.setTransformationEstimation (te);

0 commit comments

Comments
 (0)