Skip to content

Commit 1bab84e

Browse files
feat(ndt_scan_matcher): add tolerance of initial pose (#408)
* feat(ndt_scan_matcher): add tolerance of initial pose Signed-off-by: Yamato Ando <yamato.ando@gmail.com> * move codes Signed-off-by: YamatoAndo <yamato.ando@gmail.com> * modify the default value Signed-off-by: YamatoAndo <yamato.ando@gmail.com> * change the variable names Signed-off-by: YamatoAndo <yamato.ando@gmail.com> * ci(pre-commit): autofix * fix typo Signed-off-by: YamatoAndo <yamato.ando@gmail.com> * add depend fmt Signed-off-by: YamatoAndo <yamato.ando@gmail.com> * ci(pre-commit): autofix Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com>
1 parent fbb7be7 commit 1bab84e

File tree

5 files changed

+81
-1
lines changed

5 files changed

+81
-1
lines changed

launch/tier4_localization_launch/config/ndt_scan_matcher.param.yaml

+6
Original file line numberDiff line numberDiff line change
@@ -29,6 +29,12 @@
2929
# The number of particles to estimate initial pose
3030
initial_estimate_particles_num: 100
3131

32+
# Tolerance of timestamp difference between initial_pose and sensor pointcloud. [sec]
33+
initial_pose_timeout_sec: 1.0
34+
35+
# Tolerance of distance difference between two initial poses used for linear interpolation. [m]
36+
initial_pose_distance_tolerance_m: 10.0
37+
3238
# neighborhood search method in OMP
3339
# 0=KDTREE, 1=DIRECT26, 2=DIRECT7, 3=DIRECT1
3440
omp_neighborhood_search_method: 0

localization/ndt_scan_matcher/config/ndt_scan_matcher.param.yaml

+6
Original file line numberDiff line numberDiff line change
@@ -30,6 +30,12 @@
3030
# The number of particles to estimate initial pose
3131
initial_estimate_particles_num: 100
3232

33+
# Tolerance of timestamp difference between initial_pose and sensor pointcloud. [sec]
34+
initial_pose_timeout_sec: 1.0
35+
36+
# Tolerance of distance difference between two initial poses used for linear interpolation. [m]
37+
initial_pose_distance_tolerance_m: 10.0
38+
3339
# neighborhood search method in OMP
3440
# 0=KDTREE, 1=DIRECT26, 2=DIRECT7, 3=DIRECT1
3541
omp_neighborhood_search_method: 0

localization/ndt_scan_matcher/include/ndt_scan_matcher/ndt_scan_matcher_core.hpp

+9
Original file line numberDiff line numberDiff line change
@@ -113,6 +113,13 @@ class NDTScanMatcher : public rclcpp::Node
113113
const std::string & target_frame, const std::string & source_frame,
114114
const geometry_msgs::msg::TransformStamped::SharedPtr & transform_stamped_ptr);
115115

116+
bool validateTimeStampDifference(
117+
const rclcpp::Time & target_time, const rclcpp::Time & reference_time,
118+
const double time_tolerance_sec);
119+
bool validatePositionDifference(
120+
const geometry_msgs::msg::Point & target_point,
121+
const geometry_msgs::msg::Point & reference_point, const double distance_tolerance_m_);
122+
116123
void timerDiagnostic();
117124

118125
rclcpp::Subscription<geometry_msgs::msg::PoseWithCovarianceStamped>::SharedPtr initial_pose_sub_;
@@ -154,6 +161,8 @@ class NDTScanMatcher : public rclcpp::Node
154161
std::string map_frame_;
155162
double converged_param_transform_probability_;
156163
int initial_estimate_particles_num_;
164+
double initial_pose_timeout_sec_;
165+
double initial_pose_distance_tolerance_m_;
157166
float inversion_vector_threshold_;
158167
float oscillation_threshold_;
159168
std::array<double, 36> output_pose_covariance_;

localization/ndt_scan_matcher/package.xml

+1
Original file line numberDiff line numberDiff line change
@@ -8,6 +8,7 @@
88
<buildtool_depend>ament_cmake_auto</buildtool_depend>
99

1010
<depend>diagnostic_msgs</depend>
11+
<depend>fmt</depend>
1112
<depend>geometry_msgs</depend>
1213
<depend>nav_msgs</depend>
1314
<depend>ndt</depend>

localization/ndt_scan_matcher/src/ndt_scan_matcher_core.cpp

+59-1
Original file line numberDiff line numberDiff line change
@@ -104,6 +104,8 @@ NDTScanMatcher::NDTScanMatcher()
104104
map_frame_("map"),
105105
converged_param_transform_probability_(4.5),
106106
initial_estimate_particles_num_(100),
107+
initial_pose_timeout_sec_(1.0),
108+
initial_pose_distance_tolerance_m_(10.0),
107109
inversion_vector_threshold_(-0.9),
108110
oscillation_threshold_(10)
109111
{
@@ -169,6 +171,12 @@ NDTScanMatcher::NDTScanMatcher()
169171
initial_estimate_particles_num_ =
170172
this->declare_parameter("initial_estimate_particles_num", initial_estimate_particles_num_);
171173

174+
initial_pose_timeout_sec_ =
175+
this->declare_parameter("initial_pose_timeout_sec", initial_pose_timeout_sec_);
176+
177+
initial_pose_distance_tolerance_m_ = this->declare_parameter(
178+
"initial_pose_distance_tolerance_m", initial_pose_distance_tolerance_m_);
179+
172180
std::vector<double> output_pose_covariance =
173181
this->declare_parameter<std::vector<double>>("output_pose_covariance");
174182
for (std::size_t i = 0; i < output_pose_covariance.size(); ++i) {
@@ -433,9 +441,27 @@ void NDTScanMatcher::callbackSensorPoints(
433441
initial_pose_msg_ptr_array_, sensor_ros_time, initial_pose_old_msg_ptr,
434442
initial_pose_new_msg_ptr);
435443
popOldPose(initial_pose_msg_ptr_array_, sensor_ros_time);
436-
// TODO(Tier IV): check pose_timestamp - sensor_ros_time
444+
445+
// check the time stamp
446+
bool valid_old_timestamp = validateTimeStampDifference(
447+
initial_pose_old_msg_ptr->header.stamp, sensor_ros_time, initial_pose_timeout_sec_);
448+
bool valid_new_timestamp = validateTimeStampDifference(
449+
initial_pose_new_msg_ptr->header.stamp, sensor_ros_time, initial_pose_timeout_sec_);
450+
451+
// check the position jumping (ex. immediately after the initial pose estimation)
452+
bool valid_new_to_old_distance = validatePositionDifference(
453+
initial_pose_old_msg_ptr->pose.pose.position, initial_pose_new_msg_ptr->pose.pose.position,
454+
initial_pose_distance_tolerance_m_);
455+
456+
// must all validations are true
457+
if (!(valid_old_timestamp && valid_new_timestamp && valid_new_to_old_distance)) {
458+
RCLCPP_WARN(get_logger(), "Validation error.");
459+
return;
460+
}
461+
437462
const auto initial_pose_msg =
438463
interpolatePose(*initial_pose_old_msg_ptr, *initial_pose_new_msg_ptr, sensor_ros_time);
464+
439465
// enf of critical section for initial_pose_msg_ptr_array_
440466
initial_pose_array_lock.unlock();
441467

@@ -688,3 +714,35 @@ bool NDTScanMatcher::getTransform(
688714
}
689715
return true;
690716
}
717+
718+
bool NDTScanMatcher::validateTimeStampDifference(
719+
const rclcpp::Time & target_time, const rclcpp::Time & reference_time,
720+
const double time_tolerance_sec)
721+
{
722+
const double dt = std::abs((target_time - reference_time).seconds());
723+
if (dt > time_tolerance_sec) {
724+
RCLCPP_WARN(
725+
get_logger(),
726+
"Validation error. The reference time is %lf[sec], but the target time is %lf[sec]. The "
727+
"difference is %lf[sec] (the tolerance is %lf[sec]).",
728+
reference_time.seconds(), target_time.seconds(), dt, time_tolerance_sec);
729+
return false;
730+
}
731+
return true;
732+
}
733+
734+
bool NDTScanMatcher::validatePositionDifference(
735+
const geometry_msgs::msg::Point & target_point, const geometry_msgs::msg::Point & reference_point,
736+
const double distance_tolerance_m_)
737+
{
738+
double distance = norm(target_point, reference_point);
739+
if (distance > distance_tolerance_m_) {
740+
RCLCPP_WARN(
741+
get_logger(),
742+
"Validation error. The distance from reference position to target position is %lf[m] (the "
743+
"tolerance is %lf[m]).",
744+
distance, distance_tolerance_m_);
745+
return false;
746+
}
747+
return true;
748+
}

0 commit comments

Comments
 (0)