Skip to content

Commit

Permalink
refactor(ndt scan matcher): update parameter (#1018)
Browse files Browse the repository at this point in the history
* rename to sensor_points.timeout_sec

Signed-off-by: Yamato Ando <[email protected]>

* parameterize skipping_publish_num

Signed-off-by: Yamato Ando <[email protected]>

* parameterize initial_to_result_distance_tolerance_m

Signed-off-by: Yamato Ando <[email protected]>

* add new line

Signed-off-by: Yamato Ando <[email protected]>

---------

Signed-off-by: Yamato Ando <[email protected]>
  • Loading branch information
YamatoAndo authored Jun 13, 2024
1 parent 4c03755 commit 7671a29
Showing 1 changed file with 9 additions and 3 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -12,6 +12,9 @@


sensor_points:
# Tolerance of timestamp difference between current time and sensor pointcloud. [sec]
timeout_sec: 1.0

# Required distance of input sensor points. [m]
# If the max distance of input sensor points is lower than this value, the scan matching will not be performed.
required_distance: 10.0
Expand Down Expand Up @@ -52,18 +55,21 @@


validation:
# Tolerance of timestamp difference between current time and sensor pointcloud. [sec]
lidar_topic_timeout_sec: 1.0

# Tolerance of timestamp difference between initial_pose and sensor pointcloud. [sec]
initial_pose_timeout_sec: 1.0

# Tolerance of distance difference between two initial poses used for linear interpolation. [m]
initial_pose_distance_tolerance_m: 10.0

# Tolerance of distance difference from initial pose to result pose. [m]
initial_to_result_distance_tolerance_m: 3.0

# The execution time which means probably NDT cannot matches scans properly. [ms]
critical_upper_bound_exe_time_ms: 100.0

# Tolerance for the number of times rejected estimation results consecutively
skipping_publish_num: 5


score_estimation:
# Converged param type
Expand Down

0 comments on commit 7671a29

Please sign in to comment.