Skip to content

Commit 8ca055d

Browse files
add timeout check for trusted pose
Signed-off-by: melike <melike@leodrive.ai>
1 parent 45b1313 commit 8ca055d

File tree

2 files changed

+18
-0
lines changed

2 files changed

+18
-0
lines changed

localization/ndt_scan_matcher/include/ndt_scan_matcher/ndt_scan_matcher_core.hpp

+4
Original file line numberDiff line numberDiff line change
@@ -213,6 +213,10 @@ class NDTScanMatcher : public rclcpp::Node
213213

214214
std::array<double, 36> covariance_modifier(std::array<double, 36> & in_ndt_covariance);
215215

216+
// To be used for timeout control
217+
bool checkTrustedPoseTimeout();
218+
rclcpp::Time trustedPoseCallbackTime;
219+
216220
HyperParameters param_;
217221
};
218222

localization/ndt_scan_matcher/src/ndt_scan_matcher_core.cpp

+14
Original file line numberDiff line numberDiff line change
@@ -331,6 +331,8 @@ void NDTScanMatcher::callback_trusted_source_pose(
331331
trusted_source_pose_ = *pose_conv_msg_ptr;
332332
trustedPose.pose_avarage_rmse_xy = (std::sqrt(trusted_source_pose_.pose.covariance[0]) + std::sqrt(trusted_source_pose_.pose.covariance[7])) / 2;
333333
trustedPose.yaw_rmse = std::sqrt(trusted_source_pose_.pose.covariance[35]);
334+
// To be used for timeout control
335+
trustedPoseCallbackTime = this->now();
334336
}
335337

336338

@@ -571,11 +573,23 @@ void NDTScanMatcher::publish_tf(
571573
tier4_autoware_utils::pose2transform(result_pose_stamped_msg, param_.frame.ndt_base_frame));
572574
}
573575

576+
bool NDTScanMatcher::checkTrustedPoseTimeout(){
577+
auto timeDiff = this->now() - trustedPoseCallbackTime;
578+
if (timeDiff.seconds() > 1.0){
579+
return true;
580+
}
581+
return false;
582+
}
574583
std::array<double, 36> NDTScanMatcher::covariance_modifier(std::array<double, 36> & in_ndt_covariance){
575584
std::array<double, 36> ndt_covariance;
576585
ndt_covariance = in_ndt_covariance;
577586
close_ndt_pose_source_ = false;
578587

588+
if (NDTScanMatcher::checkTrustedPoseTimeout()){
589+
RCLCPP_WARN(this->get_logger(),"Trusted Pose Timeout");
590+
return ndt_covariance;
591+
}
592+
579593
if(trustedPose.pose_avarage_rmse_xy <= 0.10 && trustedPose.yaw_rmse < std::sqrt(in_ndt_covariance[35])){
580594
close_ndt_pose_source_ = true;
581595
}

0 commit comments

Comments
 (0)