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

feat(ndt_scan_matcher): change coordinate of output_pose_covariance #6065

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 @@ -127,6 +127,8 @@ class NDTScanMatcher : public rclcpp::Node
const double & transform_probability, const double & nearest_voxel_transformation_likelihood);
static int count_oscillation(const std::vector<geometry_msgs::msg::Pose> & result_pose_msg_array);

std::array<double, 36> rotate_covariance(
const std::array<double, 36> & src_covariance, const Eigen::Matrix3d & rotation) const;
std::array<double, 36> estimate_covariance(
const pclomp::NdtResult & ndt_result, const Eigen::Matrix4f & initial_pose_matrix,
const rclcpp::Time & sensor_ros_time);
Expand Down
32 changes: 31 additions & 1 deletion localization/ndt_scan_matcher/src/ndt_scan_matcher_core.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -486,7 +486,15 @@
}

// covariance estimation
std::array<double, 36> ndt_covariance = output_pose_covariance_;
const Eigen::Quaterniond map_to_base_link_quat = Eigen::Quaterniond(
result_pose_msg.orientation.w, result_pose_msg.orientation.x, result_pose_msg.orientation.y,
result_pose_msg.orientation.z);
const Eigen::Matrix3d map_to_base_link_rotation =
map_to_base_link_quat.normalized().toRotationMatrix();

std::array<double, 36> ndt_covariance =
rotate_covariance(output_pose_covariance_, map_to_base_link_rotation);

Check warning on line 497 in localization/ndt_scan_matcher/src/ndt_scan_matcher_core.cpp

View check run for this annotation

CodeScene Delta Analysis / CodeScene Cloud Delta Analysis (main)

❌ Getting worse: Complex Method

NDTScanMatcher::callback_sensor_points already has high cyclomatic complexity, and now it increases in Lines of Code from 137 to 143. This function has many conditional statements (e.g. if, for, while), leading to lower code health. Avoid adding more conditionals and code to it without refactoring.
if (is_converged && use_cov_estimation_) {
const auto estimated_covariance =
estimate_covariance(ndt_result, initial_pose_matrix, sensor_ros_time);
Expand Down Expand Up @@ -766,6 +774,28 @@
return max_oscillation_cnt;
}

std::array<double, 36> NDTScanMatcher::rotate_covariance(
const std::array<double, 36> & src_covariance, const Eigen::Matrix3d & rotation) const
{
std::array<double, 36> ret_covariance = src_covariance;

Eigen::Matrix3d src_cov;
src_cov << src_covariance[0], src_covariance[1], src_covariance[2], src_covariance[6],
src_covariance[7], src_covariance[8], src_covariance[12], src_covariance[13],
src_covariance[14];

Eigen::Matrix3d ret_cov;
ret_cov = rotation * src_cov * rotation.transpose();

for (Eigen::Index i = 0; i < 3; ++i) {
ret_covariance[i] = ret_cov(0, i);
ret_covariance[i + 6] = ret_cov(1, i);
ret_covariance[i + 12] = ret_cov(2, i);
}

return ret_covariance;
}

std::array<double, 36> NDTScanMatcher::estimate_covariance(
const pclomp::NdtResult & ndt_result, const Eigen::Matrix4f & initial_pose_matrix,
const rclcpp::Time & sensor_ros_time)
Expand Down
Loading