@@ -104,6 +104,8 @@ NDTScanMatcher::NDTScanMatcher()
104
104
map_frame_(" map" ),
105
105
converged_param_transform_probability_(4.5 ),
106
106
initial_estimate_particles_num_(100 ),
107
+ initial_pose_timeout_sec_(1.0 ),
108
+ initial_pose_distance_tolerance_m_(10.0 ),
107
109
inversion_vector_threshold_(-0.9 ),
108
110
oscillation_threshold_(10 )
109
111
{
@@ -169,6 +171,12 @@ NDTScanMatcher::NDTScanMatcher()
169
171
initial_estimate_particles_num_ =
170
172
this ->declare_parameter (" initial_estimate_particles_num" , initial_estimate_particles_num_);
171
173
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
+
172
180
std::vector<double > output_pose_covariance =
173
181
this ->declare_parameter <std::vector<double >>(" output_pose_covariance" );
174
182
for (std::size_t i = 0 ; i < output_pose_covariance.size (); ++i) {
@@ -433,9 +441,27 @@ void NDTScanMatcher::callbackSensorPoints(
433
441
initial_pose_msg_ptr_array_, sensor_ros_time, initial_pose_old_msg_ptr,
434
442
initial_pose_new_msg_ptr);
435
443
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
+
437
462
const auto initial_pose_msg =
438
463
interpolatePose (*initial_pose_old_msg_ptr, *initial_pose_new_msg_ptr, sensor_ros_time);
464
+
439
465
// enf of critical section for initial_pose_msg_ptr_array_
440
466
initial_pose_array_lock.unlock ();
441
467
@@ -688,3 +714,35 @@ bool NDTScanMatcher::getTransform(
688
714
}
689
715
return true ;
690
716
}
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