From 0012714aa0ca30765fe227b4bb77c01906693bf3 Mon Sep 17 00:00:00 2001 From: "pre-commit-ci[bot]" <66853113+pre-commit-ci[bot]@users.noreply.github.com> Date: Fri, 26 Apr 2024 08:49:31 +0000 Subject: [PATCH] style(pre-commit): autofix --- localization/ndt_scan_matcher/README.md | 2 +- localization/ndt_scan_matcher/src/ndt_scan_matcher_core.cpp | 3 ++- 2 files changed, 3 insertions(+), 2 deletions(-) diff --git a/localization/ndt_scan_matcher/README.md b/localization/ndt_scan_matcher/README.md index d23ce7b07767d..0e0b20d821a8b 100644 --- a/localization/ndt_scan_matcher/README.md +++ b/localization/ndt_scan_matcher/README.md @@ -267,7 +267,7 @@ initial_pose_offset_model_x & initial_pose_offset_model_y must have the same num | `topic_time_stamp` | the time stamp of input topic | none | none | no | | `sensor_points_size` | the size of sensor points | the size is 0 | none | yes | | `sensor_points_delay_time_sec` | the delay time of sensor points | the time is **longer** than `validation.lidar_topic_timeout_sec` | none | yes | -| `is_succeed_transform_sensor_points` | whether transform sensor points is succeed or not | none | faild | yes | +| `is_succeed_transform_sensor_points` | whether transform sensor points is succeed or not | none | faild | yes | | `sensor_points_max_distance` | the max distance of sensor points | the max distance is **shorter** than `sensor_points.required_distance` | none | yes | | `is_activated` | whether the node is in the "activate" state or not | not "activate" state | none | yes | | `is_succeed_interpolate_initial_pose` | whether the interpolate of initial pose is succeed or not | failed.
(1) the size of `initial_pose_buffer_` is **smaller** than 2.
(2) the timestamp difference between initial_pose and sensor pointcloud is **longer** than `validation.initial_pose_timeout_sec`.
(3) distance difference between two initial poses used for linear interpolation is **longer** than `validation.initial_pose_distance_tolerance_m` | none | yes | diff --git a/localization/ndt_scan_matcher/src/ndt_scan_matcher_core.cpp b/localization/ndt_scan_matcher/src/ndt_scan_matcher_core.cpp index 77a88a3e53299..1e3188a15acc9 100644 --- a/localization/ndt_scan_matcher/src/ndt_scan_matcher_core.cpp +++ b/localization/ndt_scan_matcher/src/ndt_scan_matcher_core.cpp @@ -491,7 +491,8 @@ bool NDTScanMatcher::callback_sensor_points_main( bool is_ok_score = (score > score_threshold); if (!is_ok_score) { std::stringstream message; - message << "Score is below the threshold. Score: " << score << ", Threshold: " << score_threshold; + message << "Score is below the threshold. Score: " << score + << ", Threshold: " << score_threshold; diagnostics_scan_points_->updateLevelAndMessage( diagnostic_msgs::msg::DiagnosticStatus::WARN, message.str()); RCLCPP_WARN_STREAM(this->get_logger(), message.str());