Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

fix(autoware_ndt_scan_matcher): fix cppcheck unusedFunction #9275

Merged
merged 1 commit into from
Nov 11, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -48,14 +48,6 @@ ResultOfMultiNdtCovarianceEstimation estimate_xy_covariance_by_multi_ndt_score(
pclomp::MultiGridNormalDistributionsTransform<pcl::PointXYZ, pcl::PointXYZ>> & ndt_ptr,
const std::vector<Eigen::Matrix4f> & poses_to_search, const double temperature);

/** \brief Find rotation matrix aligning covariance to principal axes
* (1) Compute eigenvalues and eigenvectors
* (2) Compute angle for first eigenvector
* (3) Return rotation matrix
*/
Eigen::Matrix2d find_rotation_matrix_aligning_covariance_to_principal_axes(
const Eigen::Matrix2d & matrix);

/** \brief Propose poses to search.
* (1) Compute covariance by Laplace approximation
* (2) Find rotation matrix aligning covariance to principal axes
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -103,34 +103,13 @@ ResultOfMultiNdtCovarianceEstimation estimate_xy_covariance_by_multi_ndt_score(
return {mean, covariance, poses_to_search, ndt_results};
}

Eigen::Matrix2d find_rotation_matrix_aligning_covariance_to_principal_axes(
const Eigen::Matrix2d & matrix)
{
const Eigen::SelfAdjointEigenSolver<Eigen::Matrix2d> eigensolver(matrix);
if (eigensolver.info() == Eigen::Success) {
const Eigen::Vector2d eigen_vec = eigensolver.eigenvectors().col(0);
const double th = std::atan2(eigen_vec.y(), eigen_vec.x());
return Eigen::Rotation2Dd(th).toRotationMatrix();
}
throw std::runtime_error("Eigen solver failed. Return output_pose_covariance value.");
}

std::vector<Eigen::Matrix4f> propose_poses_to_search(
const NdtResult & ndt_result, const std::vector<double> & offset_x,
const std::vector<double> & offset_y)
{
assert(offset_x.size() == offset_y.size());
const Eigen::Matrix4f & center_pose = ndt_result.pose;

// (1) calculate rot by pose (default)
const Eigen::Matrix2d rot = ndt_result.pose.topLeftCorner<2, 2>().cast<double>();

// (2) calculate rot by covariance (alternative)
// const Eigen::Matrix<double, 6, 6> & hessian = ndt_result.hessian;
// const Eigen::Matrix2d covariance = estimate_xy_covariance_by_Laplace_approximation(hessian);
// const Eigen::Matrix2d rot =
// find_rotation_matrix_aligning_covariance_to_principal_axes(-covariance);

std::vector<Eigen::Matrix4f> poses_to_search;
for (int i = 0; i < static_cast<int>(offset_x.size()); i++) {
const Eigen::Vector2d pose_offset(offset_x[i], offset_y[i]);
Expand Down
Loading