Skip to content

Commit f6e4550

Browse files
refactor(ndt_scan_matcher): rename de-grounded (#6186)
* refactor(ndt_scan_matcher): rename de-grounded Signed-off-by: Yamato Ando <yamato.ando@tier4.jp> * style(pre-commit): autofix --------- Signed-off-by: Yamato Ando <yamato.ando@tier4.jp> Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com>
1 parent f9ed5b0 commit f6e4550

File tree

4 files changed

+15
-20
lines changed

4 files changed

+15
-20
lines changed

localization/ndt_scan_matcher/README.md

+8-10
Original file line numberDiff line numberDiff line change
@@ -31,13 +31,13 @@ One optional function is regularization. Please see the regularization chapter i
3131
| `ndt_pose_with_covariance` | `geometry_msgs::msg::PoseWithCovarianceStamped` | estimated pose with covariance |
3232
| `/diagnostics` | `diagnostic_msgs::msg::DiagnosticArray` | diagnostics |
3333
| `points_aligned` | `sensor_msgs::msg::PointCloud2` | [debug topic] pointcloud aligned by scan matching |
34-
| `points_aligned_no_ground` | `sensor_msgs::msg::PointCloud2` | [debug topic] de-grounded pointcloud aligned by scan matching |
34+
| `points_aligned_no_ground` | `sensor_msgs::msg::PointCloud2` | [debug topic] no ground pointcloud aligned by scan matching |
3535
| `initial_pose_with_covariance` | `geometry_msgs::msg::PoseWithCovarianceStamped` | [debug topic] initial pose used in scan matching |
3636
| `multi_ndt_pose` | `geometry_msgs::msg::PoseArray` | [debug topic] estimated poses from multiple initial poses in real-time covariance estimation |
3737
| `multi_initial_pose` | `geometry_msgs::msg::PoseArray` | [debug topic] initial poses for real-time covariance estimation |
3838
| `exe_time_ms` | `tier4_debug_msgs::msg::Float32Stamped` | [debug topic] execution time for scan matching [ms] |
3939
| `transform_probability` | `tier4_debug_msgs::msg::Float32Stamped` | [debug topic] score of scan matching |
40-
| `no_ground_transform_probability` | `tier4_debug_msgs::msg::Float32Stamped` | [debug topic] score of scan matching based on de-grounded LiDAR scan |
40+
| `no_ground_transform_probability` | `tier4_debug_msgs::msg::Float32Stamped` | [debug topic] score of scan matching based on no ground LiDAR scan |
4141
| `iteration_num` | `tier4_debug_msgs::msg::Int32Stamped` | [debug topic] number of scan matching iterations |
4242
| `initial_to_result_relative_pose` | `geometry_msgs::msg::PoseStamped` | [debug topic] relative pose between the initial point and the convergence point |
4343
| `initial_to_result_distance` | `tier4_debug_msgs::msg::Float32Stamped` | [debug topic] distance difference between the initial point and the convergence point [m] |
@@ -228,21 +228,19 @@ Here is a split PCD map for `sample-map-rosbag` from Autoware tutorial: [`sample
228228
| single file | at once (standard) |
229229
| multiple files | dynamically |
230230

231-
## Scan matching score based on de-grounded LiDAR scan
231+
## Scan matching score based on no ground LiDAR scan
232232

233233
### Abstract
234234

235-
This is a function that uses de-grounded LiDAR scan to estimate the scan matching score. This score can reflect the current localization performance more accurately.
235+
This is a function that uses no ground LiDAR scan to estimate the scan matching score. This score can reflect the current localization performance more accurately.
236236
[related issue](https://github.com/autowarefoundation/autoware.universe/issues/2044).
237237

238238
### Parameters
239239

240-
<!-- cspell: ignore degrounded -->
241-
242-
| Name | Type | Description |
243-
| ------------------------------------- | ------ | ------------------------------------------------------------------------------------- |
244-
| `estimate_scores_for_degrounded_scan` | bool | Flag for using scan matching score based on de-grounded LiDAR scan (FALSE by default) |
245-
| `z_margin_for_ground_removal` | double | Z-value margin for removal ground points |
240+
| Name | Type | Description |
241+
| ------------------------------------- | ------ | ----------------------------------------------------------------------------------- |
242+
| `estimate_scores_by_no_ground_points` | bool | Flag for using scan matching score based on no ground LiDAR scan (FALSE by default) |
243+
| `z_margin_for_ground_removal` | double | Z-value margin for removal ground points |
246244

247245
## 2D real-time covariance estimation
248246

localization/ndt_scan_matcher/config/ndt_scan_matcher.param.yaml

+2-3
Original file line numberDiff line numberDiff line change
@@ -95,9 +95,8 @@
9595
# Radius of input LiDAR range (used for diagnostics of dynamic map loading)
9696
lidar_radius: 100.0
9797

98-
# cspell: ignore degrounded
99-
# A flag for using scan matching score based on de-grounded LiDAR scan
100-
estimate_scores_for_degrounded_scan: false
98+
# A flag for using scan matching score based on no ground LiDAR scan
99+
estimate_scores_by_no_ground_points: false
101100

102101
# If lidar_point.z - base_link.z <= this threshold , the point will be removed
103102
z_margin_for_ground_removal: 0.8

localization/ndt_scan_matcher/include/ndt_scan_matcher/ndt_scan_matcher_core.hpp

+1-2
Original file line numberDiff line numberDiff line change
@@ -220,8 +220,7 @@ class NDTScanMatcher : public rclcpp::Node
220220
std::unique_ptr<MapUpdateModule> map_update_module_;
221221
std::unique_ptr<tier4_autoware_utils::LoggerLevelConfigure> logger_configure_;
222222

223-
// cspell: ignore degrounded
224-
bool estimate_scores_for_degrounded_scan_;
223+
bool estimate_scores_by_no_ground_points_;
225224
double z_margin_for_ground_removal_;
226225

227226
// The execution time which means probably NDT cannot matches scans properly

localization/ndt_scan_matcher/src/ndt_scan_matcher_core.cpp

+4-5
Original file line numberDiff line numberDiff line change
@@ -64,7 +64,6 @@ Eigen::Matrix2d find_rotation_matrix_aligning_covariance_to_principal_axes(
6464
throw std::runtime_error("Eigen solver failed. Return output_pose_covariance value.");
6565
}
6666

67-
// cspell: ignore degrounded
6867
NDTScanMatcher::NDTScanMatcher()
6968
: Node("ndt_scan_matcher"),
7069
tf2_broadcaster_(*this),
@@ -160,8 +159,8 @@ NDTScanMatcher::NDTScanMatcher()
160159
this->declare_parameter<int64_t>("initial_estimate_particles_num");
161160
n_startup_trials_ = this->declare_parameter<int64_t>("n_startup_trials");
162161

163-
estimate_scores_for_degrounded_scan_ =
164-
this->declare_parameter<bool>("estimate_scores_for_degrounded_scan");
162+
estimate_scores_by_no_ground_points_ =
163+
this->declare_parameter<bool>("estimate_scores_by_no_ground_points");
165164

166165
z_margin_for_ground_removal_ = this->declare_parameter<double>("z_margin_for_ground_removal");
167166

@@ -526,8 +525,8 @@ void NDTScanMatcher::callback_sensor_points(
526525
*sensor_points_in_baselink_frame, *sensor_points_in_map_ptr, ndt_result.pose);
527526
publish_point_cloud(sensor_ros_time, map_frame_, sensor_points_in_map_ptr);
528527

529-
// whether use de-grounded points calculate score
530-
if (estimate_scores_for_degrounded_scan_) {
528+
// whether use no ground points to calculate score
529+
if (estimate_scores_by_no_ground_points_) {
531530
// remove ground
532531
pcl::shared_ptr<pcl::PointCloud<PointSource>> no_ground_points_in_map_ptr(
533532
new pcl::PointCloud<PointSource>);

0 commit comments

Comments
 (0)