Skip to content

Commit 45b1313

Browse files
update functions
1 parent 61f99da commit 45b1313

File tree

1 file changed

+21
-13
lines changed

1 file changed

+21
-13
lines changed

localization/ndt_scan_matcher/src/ndt_scan_matcher_core.cpp

+21-13
Original file line numberDiff line numberDiff line change
@@ -576,25 +576,33 @@ std::array<double, 36> NDTScanMatcher::covariance_modifier(std::array<double, 36
576576
ndt_covariance = in_ndt_covariance;
577577
close_ndt_pose_source_ = false;
578578

579-
if(trustedPose.pose_avarage_rmse_xy <= 0.10 && trustedPose.yaw_rmse < 0.3){
579+
if(trustedPose.pose_avarage_rmse_xy <= 0.10 && trustedPose.yaw_rmse < std::sqrt(in_ndt_covariance[35])){
580580
close_ndt_pose_source_ = true;
581581
}
582582
else if(trustedPose.pose_avarage_rmse_xy <= 0.10){
583583
ndt_covariance[0] = 1000000;
584584
ndt_covariance[7] = 1000000;
585585
}
586-
else if(trustedPose.pose_avarage_rmse_xy <= 0.25){
587-
ndt_covariance[0] = std::pow((std::sqrt(in_ndt_covariance[0]) * 2) - std::sqrt(trusted_source_pose_.pose.covariance[0]),2);
588-
ndt_covariance[7] = std::pow((std::sqrt(in_ndt_covariance[7]) * 2) - std::sqrt(trusted_source_pose_.pose.covariance[7]),2);
589-
ndt_covariance[14] = std::pow((std::sqrt(in_ndt_covariance[14]) * 2) - std::sqrt(trusted_source_pose_.pose.covariance[14]),2);
590-
591-
ndt_covariance[0] = (ndt_covariance[0] >= in_ndt_covariance[0]) ? ndt_covariance[0] : in_ndt_covariance[0];
592-
ndt_covariance[7] = (ndt_covariance[7] >= in_ndt_covariance[7]) ? ndt_covariance[7] : in_ndt_covariance[0];
593-
ndt_covariance[14] = (ndt_covariance[14] >= in_ndt_covariance[14]) ? ndt_covariance[14] : in_ndt_covariance[0];
594-
595-
if (trustedPose.yaw_rmse <= 0.3){
596-
ndt_covariance[35] = 1000000;
597-
}
586+
else if(trustedPose.pose_avarage_rmse_xy <= 0.25)
587+
{
588+
/*
589+
* ndt_rmse = ndt_max_rmse_meters - (gnss_rmse * (ndt_max_rmse_meters - ndt_min_rmse_meters) / normalization_coeff)
590+
* ndt_min_rmse_meters = in_ndt_rmse
591+
* ndt_max_rmse_meters = in_ndt_rmse * 2
592+
*/
593+
double normalization_coeff = 0.1;
594+
ndt_covariance[0] = std::pow(((std::sqrt(in_ndt_covariance[0]) * 2 ) - std::sqrt(trusted_source_pose_.pose.covariance[0])) * (std::sqrt(in_ndt_covariance[0])) / normalization_coeff,2);
595+
ndt_covariance[7] = std::pow(((std::sqrt(in_ndt_covariance[7]) * 2 ) - std::sqrt(trusted_source_pose_.pose.covariance[7])) * (std::sqrt(in_ndt_covariance[7])) / normalization_coeff,2);
596+
ndt_covariance[14] = std::pow(((std::sqrt(in_ndt_covariance[14]) * 2 ) - std::sqrt(trusted_source_pose_.pose.covariance[14])) * (std::sqrt(in_ndt_covariance[14])) / normalization_coeff,2);
597+
598+
// ndt_rmse = std::max(ndt_rmse, ndt_min_rmse_meters);
599+
ndt_covariance[0] = std::max(ndt_covariance[0] , in_ndt_covariance[0]);
600+
ndt_covariance[7] = std::max(ndt_covariance[7] , in_ndt_covariance[7]);
601+
ndt_covariance[14] = std::max(ndt_covariance[14], in_ndt_covariance[14]);
602+
603+
if (trustedPose.yaw_rmse <= std::sqrt(in_ndt_covariance[35])){
604+
ndt_covariance[35] = 1000000;
605+
}
598606
}
599607
else{
600608
RCLCPP_INFO(this->get_logger(), "NDT input covariance values will be used ");

0 commit comments

Comments
 (0)