Skip to content

Commit

Permalink
Merge pull request #5974 from mvieth/eigen_block_operations
Browse files Browse the repository at this point in the history
undefined
  • Loading branch information
mvieth authored Mar 9, 2024
2 parents aa05e54 + 6c22ff9 commit eebcfcb
Show file tree
Hide file tree
Showing 25 changed files with 70 additions and 71 deletions.
4 changes: 2 additions & 2 deletions apps/src/face_detection/filesystem_face_detection.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -98,7 +98,7 @@ run(pcl::RFFaceDetectorTrainer& fdrf,
bool result = face_detection_apps_utils::readMatrixFromFile(pose_file, pose_mat);

if (result) {
Eigen::Vector3f ea = pose_mat.block<3, 3>(0, 0).eulerAngles(0, 1, 2);
Eigen::Vector3f ea = pose_mat.topLeftCorner<3, 3>().eulerAngles(0, 1, 2);
Eigen::Vector3f trans_vector =
Eigen::Vector3f(pose_mat(0, 3), pose_mat(1, 3), pose_mat(2, 3));
std::cout << ea << std::endl;
Expand Down Expand Up @@ -127,7 +127,7 @@ run(pcl::RFFaceDetectorTrainer& fdrf,
Eigen::AngleAxisf(ea[1], Eigen::Vector3f::UnitY()) *
Eigen::AngleAxisf(ea[2], Eigen::Vector3f::UnitZ());

// matrixxx = pose_mat.block<3,3>(0,0);
// matrixxx = pose_mat.topLeftCorner<3,3>();
vec = matrixxx * vec;

cylinder_coeff.values[3] = vec[0];
Expand Down
8 changes: 4 additions & 4 deletions common/include/pcl/common/impl/centroid.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -695,8 +695,8 @@ computeCentroidAndOBB (const pcl::PointCloud<PointT> &cloud,
//[R^t , -R^t*Centroid ]
//[0 , 1 ]
Eigen::Matrix<Scalar, 4, 4> transform = Eigen::Matrix<Scalar, 4, 4>::Identity();
transform.topLeftCorner(3, 3) = obb_rotational_matrix.transpose();
transform.topRightCorner(3, 1) =-transform.topLeftCorner(3, 3)*centroid;
transform.template topLeftCorner<3, 3>() = obb_rotational_matrix.transpose();
transform.template topRightCorner<3, 1>() =-transform.template topLeftCorner<3, 3>()*centroid;

//when Scalar==double on a Windows 10 machine and MSVS:
//if you substitute the following Scalars with floats you get a 20% worse processing time, if with 2 PointT 55% worse
Expand Down Expand Up @@ -829,8 +829,8 @@ computeCentroidAndOBB (const pcl::PointCloud<PointT> &cloud,
//[R^t , -R^t*Centroid ]
//[0 , 1 ]
Eigen::Matrix<Scalar, 4, 4> transform = Eigen::Matrix<Scalar, 4, 4>::Identity();
transform.topLeftCorner(3, 3) = obb_rotational_matrix.transpose();
transform.topRightCorner(3, 1) =-transform.topLeftCorner(3, 3)*centroid;
transform.template topLeftCorner<3, 3>() = obb_rotational_matrix.transpose();
transform.template topRightCorner<3, 1>() =-transform.template topLeftCorner<3, 3>()*centroid;

//when Scalar==double on a Windows 10 machine and MSVS:
//if you substitute the following Scalars with floats you get a 20% worse processing time, if with 2 PointT 55% worse
Expand Down
2 changes: 1 addition & 1 deletion common/include/pcl/common/impl/transforms.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -507,7 +507,7 @@ getPrincipalTransformation (const pcl::PointCloud<PointT> &cloud,
double rel1 = eigen_vals.coeff (0) / eigen_vals.coeff (1);
double rel2 = eigen_vals.coeff (1) / eigen_vals.coeff (2);

transform.translation () = centroid.head (3);
transform.translation () = centroid.template head<3> ();
transform.linear () = eigen_vects;

return (std::min (rel1, rel2));
Expand Down
4 changes: 2 additions & 2 deletions people/include/pcl/people/impl/head_based_subcluster.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -136,7 +136,7 @@ pcl::people::HeadBasedSubclustering<PointT>::mergeClustersCloseInFloorCoordinate
{
float min_distance_between_cluster_centers = 0.4; // meters
float normalize_factor = std::pow(sqrt_ground_coeffs_, 2); // sqrt_ground_coeffs ^ 2 (precomputed for speed)
Eigen::Vector3f head_ground_coeffs = ground_coeffs_.head(3); // ground plane normal (precomputed for speed)
Eigen::Vector3f head_ground_coeffs = ground_coeffs_.head<3>(); // ground plane normal (precomputed for speed)
std::vector <std::vector<int> > connected_clusters;
connected_clusters.resize(input_clusters.size());
std::vector<bool> used_clusters; // 0 in correspondence of clusters remained to process, 1 for already used clusters
Expand Down Expand Up @@ -196,7 +196,7 @@ pcl::people::HeadBasedSubclustering<PointT>::createSubClusters (pcl::people::Per
{
// create new clusters from the current cluster and put corresponding indices into sub_clusters_indices:
float normalize_factor = std::pow(sqrt_ground_coeffs_, 2); // sqrt_ground_coeffs ^ 2 (precomputed for speed)
Eigen::Vector3f head_ground_coeffs = ground_coeffs_.head(3); // ground plane normal (precomputed for speed)
Eigen::Vector3f head_ground_coeffs = ground_coeffs_.head<3>(); // ground plane normal (precomputed for speed)
Eigen::Matrix3Xf maxima_projected(3,maxima_number); // matrix containing the projection of maxima onto the ground plane
Eigen::VectorXi subclusters_number_of_points(maxima_number); // subclusters number of points
std::vector <pcl::Indices> sub_clusters_indices; // vector of vectors with the cluster indices for every maximum
Expand Down
8 changes: 4 additions & 4 deletions people/include/pcl/people/impl/height_map_2d.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -213,16 +213,16 @@ pcl::people::HeightMap2D<PointT>::filterMaxima ()

PointT* p_current = &(*cloud_)[maxima_cloud_indices_[i]]; // pointcloud point referring to the current maximum
Eigen::Vector3f p_current_eigen(p_current->x, p_current->y, p_current->z); // conversion to eigen
float t = p_current_eigen.dot(ground_coeffs_.head(3)) / std::pow(sqrt_ground_coeffs_, 2); // height from the ground
p_current_eigen -= ground_coeffs_.head(3) * t; // projection of the point on the groundplane
float t = p_current_eigen.dot(ground_coeffs_.head<3>()) / std::pow(sqrt_ground_coeffs_, 2); // height from the ground
p_current_eigen -= ground_coeffs_.head<3>() * t; // projection of the point on the groundplane

int j = i-1;
while ((j >= 0) && (good_maximum))
{
PointT* p_previous = &(*cloud_)[maxima_cloud_indices_[j]]; // pointcloud point referring to an already validated maximum
Eigen::Vector3f p_previous_eigen(p_previous->x, p_previous->y, p_previous->z); // conversion to eigen
float t = p_previous_eigen.dot(ground_coeffs_.head(3)) / std::pow(sqrt_ground_coeffs_, 2); // height from the ground
p_previous_eigen -= ground_coeffs_.head(3) * t; // projection of the point on the groundplane
float t = p_previous_eigen.dot(ground_coeffs_.head<3>()) / std::pow(sqrt_ground_coeffs_, 2); // height from the ground
p_previous_eigen -= ground_coeffs_.head<3>() * t; // projection of the point on the groundplane

// distance of the projection of the points on the groundplane:
float distance = (p_current_eigen-p_previous_eigen).norm();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -93,7 +93,7 @@ void pcl::face_detection::FaceDetectorDataProvider<FeatureType, DataSet, LabelTy

if (readMatrixFromFile (pose_file, pose_mat))
{
Eigen::Vector3f ea = pose_mat.block<3, 3> (0, 0).eulerAngles (0, 1, 2);
Eigen::Vector3f ea = pose_mat.topLeftCorner<3, 3> ().eulerAngles (0, 1, 2);
ea *= 57.2957795f; //transform it to degrees to do the binning
int y = static_cast<int>(pcl_round ((ea[0] + static_cast<float>(std::abs (min_yaw))) / res_yaw));
int p = static_cast<int>(pcl_round ((ea[1] + static_cast<float>(std::abs (min_pitch))) / res_pitch));
Expand Down Expand Up @@ -354,7 +354,7 @@ void pcl::face_detection::FaceDetectorDataProvider<FeatureType, DataSet, LabelTy
pose_mat.setIdentity (4, 4);
readMatrixFromFile (pose_file, pose_mat);

Eigen::Vector3f ea = pose_mat.block<3, 3> (0, 0).eulerAngles (0, 1, 2);
Eigen::Vector3f ea = pose_mat.topLeftCorner<3, 3> ().eulerAngles (0, 1, 2);
Eigen::Vector3f trans_vector = Eigen::Vector3f (pose_mat (0, 3), pose_mat (1, 3), pose_mat (2, 3));

pcl::PointXYZ center_point;
Expand Down
4 changes: 2 additions & 2 deletions recognition/src/face_detection/rf_face_detector_trainer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -479,7 +479,7 @@ void pcl::RFFaceDetectorTrainer::detectFaces()

Eigen::Matrix4f guess;
guess.setIdentity ();
guess.block<3, 3> (0, 0) = matrixxx;
guess.topLeftCorner<3, 3> () = matrixxx;
guess (0, 3) = head_clusters_centers_[i][0];
guess (1, 3) = head_clusters_centers_[i][1];
guess (2, 3) = head_clusters_centers_[i][2];
Expand Down Expand Up @@ -519,7 +519,7 @@ void pcl::RFFaceDetectorTrainer::detectFaces()
head_clusters_centers_[i][1] = icp_trans (1, 3);
head_clusters_centers_[i][2] = icp_trans (2, 3);

Eigen::Vector3f ea = icp_trans.block<3, 3> (0, 0).eulerAngles (0, 1, 2);
Eigen::Vector3f ea = icp_trans.topLeftCorner<3, 3> ().eulerAngles (0, 1, 2);
head_clusters_rotation_[i][0] = ea[0];
head_clusters_rotation_[i][1] = ea[1];
head_clusters_rotation_[i][2] = ea[2];
Expand Down
4 changes: 2 additions & 2 deletions registration/include/pcl/registration/impl/elch.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -192,7 +192,7 @@ pcl::registration::ELCH<PointT>::initCompute()

PointCloudPtr tmp(new PointCloud);
// Eigen::Vector4f diff = pose_start - pose_end;
// Eigen::Translation3f translation (diff.head (3));
// Eigen::Translation3f translation (diff.head<3> ());
// Eigen::Affine3f trans = translation * Eigen::Quaternionf::Identity ();
// pcl::transformPointCloud (*(*loop_graph_)[loop_end_].cloud, *tmp, trans);

Expand Down Expand Up @@ -240,7 +240,7 @@ pcl::registration::ELCH<PointT>::compute()
// TODO use pose
// Eigen::Vector4f cend;
// pcl::compute3DCentroid (*((*loop_graph_)[loop_end_].cloud), cend);
// Eigen::Translation3f tend (cend.head (3));
// Eigen::Translation3f tend (cend.head<3> ());
// Eigen::Affine3f aend (tend);
// Eigen::Affine3f aendI = aend.inverse ();

Expand Down
8 changes: 4 additions & 4 deletions registration/include/pcl/registration/impl/gicp.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -635,9 +635,9 @@ GeneralizedIterativeClosestPoint<PointSource, PointTarget, Scalar>::
p_trans_src[1] - p_tgt[1],
p_trans_src[2] - p_tgt[2]);
const Eigen::Matrix3d& M = gicp_->mahalanobis(src_idx);
const Eigen::Vector3d Md(M * d); // Md = M*d
gradient.head<3>() += Md; // translation gradient
hessian.block<3, 3>(0, 0) += M; // translation-translation hessian
const Eigen::Vector3d Md(M * d); // Md = M*d
gradient.head<3>() += Md; // translation gradient
hessian.topLeftCorner<3, 3>() += M; // translation-translation hessian
p_trans_src = base_transformation_float * p_src;
const Eigen::Vector3d p_base_src(p_trans_src[0], p_trans_src[1], p_trans_src[2]);
dCost_dR_T.noalias() += p_base_src * Md.transpose();
Expand All @@ -657,7 +657,7 @@ GeneralizedIterativeClosestPoint<PointSource, PointTarget, Scalar>::
gradient.head<3>() *= 2.0 / m; // translation gradient
dCost_dR_T *= 2.0 / m;
gicp_->computeRDerivative(x, dCost_dR_T, gradient); // rotation gradient
hessian.block<3, 3>(0, 0) *= 2.0 / m; // translation-translation hessian
hessian.topLeftCorner<3, 3>() *= 2.0 / m; // translation-translation hessian
// translation-rotation hessian
dCost_dR_T1.row(0) = dCost_dR_T1b.col(0);
dCost_dR_T1.row(1) = dCost_dR_T2b.col(0);
Expand Down
2 changes: 1 addition & 1 deletion registration/include/pcl/registration/impl/ia_fpcs.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -350,7 +350,7 @@ pcl::registration::FPCSInitialAlignment<PointSource, PointTarget, NormalT, Scala
float d1 = pcl::squaredEuclideanDistance(*pt4, *pt1);
float d2 = pcl::squaredEuclideanDistance(*pt4, *pt2);
float d3 = pcl::squaredEuclideanDistance(*pt4, *pt3);
float d4 = (pt4->getVector3fMap() - centre_pt.head(3)).squaredNorm();
float d4 = (pt4->getVector3fMap() - centre_pt.head<3>()).squaredNorm();

// check distance between points w.r.t minimum sampling distance; EDITED -> 4th
// point now also limited by max base line
Expand Down
6 changes: 3 additions & 3 deletions registration/include/pcl/registration/impl/ia_kfpcs.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -166,7 +166,7 @@ KFPCSInitialAlignment<PointSource, PointTarget, NormalT, Scalar>::
// translation score (solutions with small translation are down-voted)
float scale = 1.f;
if (use_trl_score_) {
float trl = transformation.rightCols<1>().head(3).norm();
float trl = transformation.rightCols<1>().head<3>().norm();
float trl_ratio =
(trl - lower_trl_boundary_) / (upper_trl_boundary_ - lower_trl_boundary_);

Expand Down Expand Up @@ -244,7 +244,7 @@ KFPCSInitialAlignment<PointSource, PointTarget, NormalT, Scalar>::getNBestCandid
for (const auto& c2 : candidates) {
Eigen::Matrix4f diff =
candidate.transformation.colPivHouseholderQr().solve(c2.transformation);
const float angle3d = Eigen::AngleAxisf(diff.block<3, 3>(0, 0)).angle();
const float angle3d = Eigen::AngleAxisf(diff.topLeftCorner<3, 3>()).angle();
const float translation3d = diff.block<3, 1>(0, 3).norm();
unique = angle3d > min_angle3d && translation3d > min_translation3d;
if (!unique) {
Expand Down Expand Up @@ -281,7 +281,7 @@ KFPCSInitialAlignment<PointSource, PointTarget, NormalT, Scalar>::getTBestCandid
for (const auto& c2 : candidates) {
Eigen::Matrix4f diff =
candidate.transformation.colPivHouseholderQr().solve(c2.transformation);
const float angle3d = Eigen::AngleAxisf(diff.block<3, 3>(0, 0)).angle();
const float angle3d = Eigen::AngleAxisf(diff.topLeftCorner<3, 3>()).angle();
const float translation3d = diff.block<3, 1>(0, 3).norm();
unique = angle3d > min_angle3d && translation3d > min_translation3d;
if (!unique) {
Expand Down
4 changes: 2 additions & 2 deletions registration/include/pcl/registration/impl/lum.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -254,8 +254,8 @@ LUM<PointT>::compute()

// Fill in elements of G and B
if (vj > 0)
G.block(6 * (vi - 1), 6 * (vj - 1), 6, 6) = -(*slam_graph_)[e].cinv_;
G.block(6 * (vi - 1), 6 * (vi - 1), 6, 6) += (*slam_graph_)[e].cinv_;
G.block<6, 6>(6 * (vi - 1), 6 * (vj - 1)) = -(*slam_graph_)[e].cinv_;
G.block<6, 6>(6 * (vi - 1), 6 * (vi - 1)) += (*slam_graph_)[e].cinv_;
B.segment(6 * (vi - 1), 6) += (present1 ? 1 : -1) * (*slam_graph_)[e].cinvd_;
}
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -166,7 +166,7 @@ TransformationEstimation2D<PointSource, PointTarget, Scalar>::

// Assemble the correlation matrix H = source * target'
Eigen::Matrix<Scalar, 3, 3> H =
(cloud_src_demean * cloud_tgt_demean.transpose()).topLeftCorner(3, 3);
(cloud_src_demean * cloud_tgt_demean.transpose()).template topLeftCorner<3, 3>();

float angle = std::atan2((H(0, 1) - H(1, 0)), (H(0, 0) + H(1, 1)));

Expand All @@ -176,9 +176,10 @@ TransformationEstimation2D<PointSource, PointTarget, Scalar>::
R(1, 0) = std::sin(angle);

// Return the correct transformation
transformation_matrix.topLeftCorner(3, 3).matrix() = R;
const Eigen::Matrix<Scalar, 3, 1> Rc(R * centroid_src.head(3).matrix());
transformation_matrix.block(0, 3, 3, 1).matrix() = centroid_tgt.head(3) - Rc;
transformation_matrix.template topLeftCorner<3, 3>().matrix() = R;
const Eigen::Matrix<Scalar, 3, 1> Rc(R * centroid_src.template head<3>().matrix());
transformation_matrix.template block<3, 1>(0, 3).matrix() =
centroid_tgt.template head<3>() - Rc;
}

} // namespace registration
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -155,11 +155,11 @@ pcl::registration::TransformationEstimation3Point<PointSource, PointTarget, Scal
target_it.reset();

Eigen::Matrix<Scalar, 3, 1> s1 =
source_demean.col(1).head(3) - source_demean.col(0).head(3);
source_demean.col(1).template head<3>() - source_demean.col(0).template head<3>();
s1.normalize();

Eigen::Matrix<Scalar, 3, 1> s2 =
source_demean.col(2).head(3) - source_demean.col(0).head(3);
source_demean.col(2).template head<3>() - source_demean.col(0).template head<3>();
s2 -= s2.dot(s1) * s1;
s2.normalize();

Expand All @@ -169,11 +169,11 @@ pcl::registration::TransformationEstimation3Point<PointSource, PointTarget, Scal
source_rot.col(2) = s1.cross(s2);

Eigen::Matrix<Scalar, 3, 1> t1 =
target_demean.col(1).head(3) - target_demean.col(0).head(3);
target_demean.col(1).template head<3>() - target_demean.col(0).template head<3>();
t1.normalize();

Eigen::Matrix<Scalar, 3, 1> t2 =
target_demean.col(2).head(3) - target_demean.col(0).head(3);
target_demean.col(2).template head<3>() - target_demean.col(0).template head<3>();
t2 -= t2.dot(t1) * t1;
t2.normalize();

Expand All @@ -184,11 +184,11 @@ pcl::registration::TransformationEstimation3Point<PointSource, PointTarget, Scal

// Eigen::Matrix <Scalar, 3, 3> R = source_rot * target_rot.transpose ();
Eigen::Matrix<Scalar, 3, 3> R = target_rot * source_rot.transpose();
transformation_matrix.topLeftCorner(3, 3) = R;
// transformation_matrix.block (0, 3, 3, 1) = source_mean.head (3) - R *
// target_mean.head (3);
transformation_matrix.block(0, 3, 3, 1) =
target_mean.head(3) - R * source_mean.head(3);
transformation_matrix.template topLeftCorner<3, 3>() = R;
// transformation_matrix.block<3, 1>(0, 3) = source_mean.head<3>() - R *
// target_mean.head<3>();
transformation_matrix.template block<3, 1>(0, 3) =
target_mean.template head<3>() - R * source_mean.template head<3>();
}

//#define PCL_INSTANTIATE_TransformationEstimation3Point(T,U) template class PCL_EXPORTS
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -194,7 +194,7 @@ TransformationEstimationSVD<PointSource, PointTarget, Scalar>::

// Assemble the correlation matrix H = source * target'
Eigen::Matrix<Scalar, 3, 3> H =
(cloud_src_demean * cloud_tgt_demean.transpose()).topLeftCorner(3, 3);
(cloud_src_demean * cloud_tgt_demean.transpose()).template topLeftCorner<3, 3>();

// Compute the Singular Value Decomposition
Eigen::JacobiSVD<Eigen::Matrix<Scalar, 3, 3>> svd(
Expand All @@ -211,9 +211,10 @@ TransformationEstimationSVD<PointSource, PointTarget, Scalar>::
Eigen::Matrix<Scalar, 3, 3> R = v * u.transpose();

// Return the correct transformation
transformation_matrix.topLeftCorner(3, 3) = R;
const Eigen::Matrix<Scalar, 3, 1> Rc(R * centroid_src.head(3));
transformation_matrix.block(0, 3, 3, 1) = centroid_tgt.head(3) - Rc;
transformation_matrix.template topLeftCorner<3, 3>() = R;
const Eigen::Matrix<Scalar, 3, 1> Rc(R * centroid_src.template head<3>());
transformation_matrix.template block<3, 1>(0, 3) =
centroid_tgt.template head<3>() - Rc;

if (pcl::console::isVerbosityLevelEnabled(pcl::console::L_DEBUG)) {
size_t N = cloud_src_demean.cols();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -58,7 +58,7 @@ TransformationEstimationSVDScale<PointSource, PointTarget, Scalar>::

// Assemble the correlation matrix H = source * target'
Eigen::Matrix<Scalar, 3, 3> H =
(cloud_src_demean * cloud_tgt_demean.transpose()).topLeftCorner(3, 3);
(cloud_src_demean * cloud_tgt_demean.transpose()).template topLeftCorner<3, 3>();

// Compute the Singular Value Decomposition
Eigen::JacobiSVD<Eigen::Matrix<Scalar, 3, 3>> svd(
Expand All @@ -76,7 +76,7 @@ TransformationEstimationSVDScale<PointSource, PointTarget, Scalar>::

// rotated cloud
Eigen::Matrix<Scalar, 4, 4> R4;
R4.block(0, 0, 3, 3) = R;
R4.template topLeftCorner<3, 3>() = R;
R4(0, 3) = 0;
R4(1, 3) = 0;
R4(2, 3) = 0;
Expand All @@ -96,9 +96,10 @@ TransformationEstimationSVDScale<PointSource, PointTarget, Scalar>::
}

float scale = sum_tt / sum_ss;
transformation_matrix.topLeftCorner(3, 3) = scale * R;
const Eigen::Matrix<Scalar, 3, 1> Rc(scale * R * centroid_src.head(3));
transformation_matrix.block(0, 3, 3, 1) = centroid_tgt.head(3) - Rc;
transformation_matrix.template topLeftCorner<3, 3>() = scale * R;
const Eigen::Matrix<Scalar, 3, 1> Rc(scale * R * centroid_src.template head<3>());
transformation_matrix.template block<3, 1>(0, 3) =
centroid_tgt.template head<3>() - Rc;
}

} // namespace registration
Expand Down
4 changes: 2 additions & 2 deletions registration/include/pcl/registration/warp_point_rigid.h
Original file line number Diff line number Diff line change
Expand Up @@ -95,9 +95,9 @@ class WarpPointRigid {
pnt_out.z = static_cast<float>(
transform_matrix_(2, 0) * pnt_in.x + transform_matrix_(2, 1) * pnt_in.y +
transform_matrix_(2, 2) * pnt_in.z + transform_matrix_(2, 3));
// pnt_out.getVector3fMap () = transform_matrix_.topLeftCorner (3, 3) *
// pnt_out.getVector3fMap () = transform_matrix_.topLeftCorner<3, 3> () *
// pnt_in.getVector3fMap () +
// transform_matrix_.block (0, 3, 3, 1);
// transform_matrix_.block<3, 1> (0, 3);
// pnt_out.data[3] = pnt_in.data[3];
}

Expand Down
4 changes: 2 additions & 2 deletions registration/include/pcl/registration/warp_point_rigid_3d.h
Original file line number Diff line number Diff line change
Expand Up @@ -82,11 +82,11 @@ class WarpPointRigid3D : public WarpPointRigid<PointSourceT, PointTargetT, Scala
trans(2, 2) = 1; // Rotation around the Z-axis

// Copy the rotation and translation components
trans.block(0, 3, 4, 1) = Eigen::Matrix<Scalar, 4, 1>(p[0], p[1], 0, 1.0);
trans.template block<4, 1>(0, 3) = Eigen::Matrix<Scalar, 4, 1>(p[0], p[1], 0, 1.0);

// Compute w from the unit quaternion
Eigen::Rotation2D<Scalar> r(p[2]);
trans.topLeftCorner(2, 2) = r.toRotationMatrix();
trans.template topLeftCorner<2, 2>() = r.toRotationMatrix();
}
};
} // namespace registration
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -89,7 +89,7 @@ class WarpPointRigid6D : public WarpPointRigid<PointSourceT, PointTargetT, Scala
Eigen::Quaternion<Scalar> q(0, p[3], p[4], p[5]);
q.w() = static_cast<Scalar>(std::sqrt(1 - q.dot(q)));
q.normalize();
transform_matrix_.topLeftCorner(3, 3) = q.toRotationMatrix();
transform_matrix_.template topLeftCorner<3, 3>() = q.toRotationMatrix();
}
};
} // namespace registration
Expand Down
Loading

0 comments on commit eebcfcb

Please sign in to comment.