No version for distro humble. Known supported distros are highlighted in the buttons above.
No version for distro jazzy. Known supported distros are highlighted in the buttons above.
No version for distro rolling. Known supported distros are highlighted in the buttons above.

autoware_ndt_scan_matcher package from autoware_universe repo

autoware_adapi_specs autoware_agnocast_wrapper autoware_auto_common autoware_component_interface_specs_universe autoware_component_interface_tools autoware_component_interface_utils autoware_cuda_dependency_meta autoware_fake_test_node autoware_glog_component autoware_goal_distance_calculator autoware_grid_map_utils autoware_path_distance_calculator autoware_polar_grid autoware_time_utils autoware_traffic_light_recognition_marker_publisher autoware_traffic_light_utils autoware_universe_utils tier4_api_utils autoware_autonomous_emergency_braking autoware_collision_detector autoware_control_performance_analysis autoware_control_validator autoware_external_cmd_selector autoware_joy_controller autoware_lane_departure_checker autoware_mpc_lateral_controller autoware_obstacle_collision_checker autoware_operation_mode_transition_manager autoware_pid_longitudinal_controller autoware_predicted_path_checker autoware_pure_pursuit autoware_shift_decider autoware_smart_mpc_trajectory_follower autoware_trajectory_follower_base autoware_trajectory_follower_node autoware_vehicle_cmd_gate autoware_control_evaluator autoware_kinematic_evaluator autoware_localization_evaluator autoware_perception_online_evaluator autoware_planning_evaluator autoware_scenario_simulator_v2_adapter tier4_autoware_api_launch tier4_control_launch tier4_localization_launch tier4_map_launch tier4_perception_launch tier4_planning_launch tier4_sensing_launch tier4_simulator_launch tier4_system_launch tier4_vehicle_launch autoware_geo_pose_projector autoware_gyro_odometer autoware_ar_tag_based_localizer autoware_landmark_manager autoware_lidar_marker_localizer autoware_localization_error_monitor autoware_ndt_scan_matcher autoware_pose2twist autoware_pose_covariance_modifier autoware_pose_estimator_arbiter autoware_pose_initializer autoware_pose_instability_detector yabloc_common yabloc_image_processing yabloc_monitor yabloc_particle_filter yabloc_pose_initializer autoware_lanelet2_map_visualizer autoware_map_height_fitter autoware_map_tf_generator autoware_bytetrack autoware_cluster_merger autoware_compare_map_segmentation autoware_crosswalk_traffic_light_estimator autoware_detected_object_feature_remover autoware_detected_object_validation autoware_detection_by_tracker autoware_elevation_map_loader autoware_euclidean_cluster autoware_ground_segmentation autoware_image_projection_based_fusion autoware_lidar_apollo_instance_segmentation autoware_lidar_centerpoint autoware_lidar_transfusion autoware_map_based_prediction autoware_multi_object_tracker autoware_object_merger autoware_object_range_splitter autoware_object_velocity_splitter autoware_occupancy_grid_map_outlier_filter autoware_probabilistic_occupancy_grid_map autoware_radar_crossing_objects_noise_filter autoware_radar_fusion_to_detected_object autoware_radar_object_clustering autoware_radar_object_tracker autoware_radar_tracks_msgs_converter autoware_raindrop_cluster_filter autoware_shape_estimation autoware_simple_object_merger autoware_tensorrt_classifier autoware_tensorrt_common autoware_tensorrt_yolox autoware_tracking_object_merger autoware_traffic_light_arbiter autoware_traffic_light_category_merger autoware_traffic_light_classifier autoware_traffic_light_fine_detector autoware_traffic_light_map_based_detector autoware_traffic_light_multi_camera_fusion autoware_traffic_light_occlusion_predictor autoware_traffic_light_selector autoware_traffic_light_visualization perception_utils autoware_costmap_generator autoware_external_velocity_limit_selector autoware_freespace_planner autoware_freespace_planning_algorithms autoware_mission_planner_universe autoware_obstacle_cruise_planner autoware_obstacle_stop_planner autoware_path_optimizer autoware_path_smoother autoware_planning_validator autoware_remaining_distance_time_calculator autoware_rtc_interface autoware_scenario_selector autoware_surround_obstacle_checker autoware_behavior_path_avoidance_by_lane_change_module autoware_behavior_path_dynamic_obstacle_avoidance_module autoware_behavior_path_external_request_lane_change_module autoware_behavior_path_goal_planner_module autoware_behavior_path_lane_change_module autoware_behavior_path_planner autoware_behavior_path_planner_common autoware_behavior_path_sampling_planner_module autoware_behavior_path_side_shift_module autoware_behavior_path_start_planner_module autoware_behavior_path_static_obstacle_avoidance_module autoware_behavior_velocity_blind_spot_module autoware_behavior_velocity_crosswalk_module autoware_behavior_velocity_detection_area_module autoware_behavior_velocity_intersection_module autoware_behavior_velocity_no_drivable_lane_module autoware_behavior_velocity_no_stopping_area_module autoware_behavior_velocity_occlusion_spot_module autoware_behavior_velocity_rtc_interface autoware_behavior_velocity_run_out_module autoware_behavior_velocity_speed_bump_module autoware_behavior_velocity_template_module autoware_behavior_velocity_traffic_light_module autoware_behavior_velocity_virtual_traffic_light_module autoware_behavior_velocity_walkway_module autoware_motion_velocity_dynamic_obstacle_stop_module autoware_motion_velocity_obstacle_cruise_module autoware_motion_velocity_obstacle_slow_down_module autoware_motion_velocity_obstacle_velocity_limiter_module autoware_motion_velocity_out_of_lane_module autoware_bezier_sampler autoware_frenet_planner autoware_path_sampler autoware_sampler_common autoware_cuda_pointcloud_preprocessor autoware_cuda_utils autoware_image_diagnostics autoware_image_transport_decompressor autoware_imu_corrector autoware_pcl_extensions autoware_pointcloud_preprocessor autoware_radar_scan_to_pointcloud2 autoware_radar_static_pointcloud_filter autoware_radar_threshold_filter autoware_radar_tracks_noise_filter autoware_livox_tag_filter autoware_carla_interface autoware_dummy_perception_publisher autoware_fault_injection autoware_learning_based_vehicle_model autoware_simple_planning_simulator autoware_vehicle_door_simulator tier4_dummy_object_rviz_plugin autoware_bluetooth_monitor autoware_component_monitor autoware_component_state_monitor autoware_default_adapi autoware_adapi_adaptors autoware_adapi_visualizers autoware_automatic_pose_initializer autoware_diagnostic_graph_aggregator autoware_diagnostic_graph_utils autoware_dummy_diag_publisher autoware_dummy_infrastructure autoware_duplicated_node_checker autoware_hazard_status_converter autoware_mrm_comfortable_stop_operator autoware_mrm_emergency_stop_operator autoware_mrm_handler autoware_processing_time_checker autoware_system_diagnostic_monitor autoware_system_monitor autoware_topic_relay_controller autoware_topic_state_monitor autoware_velodyne_monitor reaction_analyzer autoware_accel_brake_map_calibrator autoware_external_cmd_converter autoware_raw_vehicle_cmd_converter autoware_steer_offset_estimator autoware_bag_time_manager_rviz_plugin autoware_mission_details_overlay_rviz_plugin autoware_overlay_rviz_plugin autoware_string_stamped_rviz_plugin autoware_perception_rviz_plugin tier4_adapi_rviz_plugin tier4_camera_view_rviz_plugin tier4_datetime_rviz_plugin tier4_localization_rviz_plugin tier4_planning_factor_rviz_plugin tier4_planning_rviz_plugin tier4_state_rviz_plugin tier4_system_rviz_plugin tier4_traffic_light_rviz_plugin tier4_vehicle_rviz_plugin

Package Summary

Tags No category tags.
Version 0.43.0
License Apache License 2.0
Build type AMENT_CMAKE
Use RECOMMENDED

Repository Summary

Checkout URI https://github.com/autowarefoundation/autoware_universe.git
VCS Type git
VCS Version main
Last Updated 2025-04-03
Dev Status UNMAINTAINED
CI status No Continuous Integration
Released UNRELEASED
Tags No category tags.
Contributing Help Wanted (0)
Good First Issues (0)
Pull Requests to Review (0)

Package Description

The autoware_ndt_scan_matcher package

Additional Links

No additional links.

Maintainers

  • Yamato Ando
  • Kento Yabuuchi
  • Masahiro Sakamoto
  • NGUYEN Viet Anh
  • Taiki Yamada
  • Shintaro Sakoda
  • Ryu Yamamoto

Authors

  • Yamato Ando

autoware_ndt_scan_matcher

Purpose

autoware_ndt_scan_matcher is a package for position estimation using the NDT scan matching method.

There are two main functions in this package:

  • estimate position by scan matching
  • estimate initial position via the ROS service using the Monte Carlo method

One optional function is regularization. Please see the regularization chapter in the back for details. It is disabled by default.

Inputs / Outputs

Input

Name Type Description
ekf_pose_with_covariance geometry_msgs::msg::PoseWithCovarianceStamped initial pose
points_raw sensor_msgs::msg::PointCloud2 sensor pointcloud
sensing/gnss/pose_with_covariance sensor_msgs::msg::PoseWithCovarianceStamped base position for regularization term

sensing/gnss/pose_with_covariance is required only when regularization is enabled.

Output

Name Type Description
ndt_pose geometry_msgs::msg::PoseStamped estimated pose
ndt_pose_with_covariance geometry_msgs::msg::PoseWithCovarianceStamped estimated pose with covariance
/diagnostics diagnostic_msgs::msg::DiagnosticArray diagnostics
points_aligned sensor_msgs::msg::PointCloud2 [debug topic] pointcloud aligned by scan matching
points_aligned_no_ground sensor_msgs::msg::PointCloud2 [debug topic] no ground pointcloud aligned by scan matching
initial_pose_with_covariance geometry_msgs::msg::PoseWithCovarianceStamped [debug topic] initial pose used in scan matching
multi_ndt_pose geometry_msgs::msg::PoseArray [debug topic] estimated poses from multiple initial poses in real-time covariance estimation
multi_initial_pose geometry_msgs::msg::PoseArray [debug topic] initial poses for real-time covariance estimation
exe_time_ms autoware_internal_debug_msgs::msg::Float32Stamped [debug topic] execution time for scan matching [ms]
transform_probability autoware_internal_debug_msgs::msg::Float32Stamped [debug topic] score of scan matching
no_ground_transform_probability autoware_internal_debug_msgs::msg::Float32Stamped [debug topic] score of scan matching based on no ground LiDAR scan
iteration_num autoware_internal_debug_msgs::msg::Int32Stamped [debug topic] number of scan matching iterations
initial_to_result_relative_pose geometry_msgs::msg::PoseStamped [debug topic] relative pose between the initial point and the convergence point
initial_to_result_distance autoware_internal_debug_msgs::msg::Float32Stamped [debug topic] distance difference between the initial point and the convergence point [m]
initial_to_result_distance_old autoware_internal_debug_msgs::msg::Float32Stamped [debug topic] distance difference between the older of the two initial points used in linear interpolation and the convergence point [m]
initial_to_result_distance_new autoware_internal_debug_msgs::msg::Float32Stamped [debug topic] distance difference between the newer of the two initial points used in linear interpolation and the convergence point [m]
ndt_marker visualization_msgs::msg::MarkerArray [debug topic] markers for debugging
monte_carlo_initial_pose_marker visualization_msgs::msg::MarkerArray [debug topic] particles used in initial position estimation

Service

Name Type Description
ndt_align_srv autoware_localization_srvs::srv::PoseWithCovarianceStamped service to estimate initial pose

Parameters

Core Parameters

Frame

{{ json_to_markdown(“localization/autoware_ndt_scan_matcher/schema/sub/frame.json”) }}

Sensor Points

{{ json_to_markdown(“localization/autoware_ndt_scan_matcher/schema/sub/sensor_points.json”) }}

Ndt

{{ json_to_markdown(“localization/autoware_ndt_scan_matcher/schema/sub/ndt.json”) }}

Initial Pose Estimation

{{ json_to_markdown(“localization/autoware_ndt_scan_matcher/schema/sub/initial_pose_estimation.json”) }}

Validation

{{ json_to_markdown(“localization/autoware_ndt_scan_matcher/schema/sub/validation.json”) }}

Score Estimation

{{ json_to_markdown(“localization/autoware_ndt_scan_matcher/schema/sub/score_estimation.json”) }}

Covariance

{{ json_to_markdown(“localization/autoware_ndt_scan_matcher/schema/sub/covariance.json”) }}

Regularization

Abstract

This is a function that adds the regularization term to the NDT optimization problem as follows.

\[\begin{align} \min_{\mathbf{R},\mathbf{t}} \mathrm{NDT}(\mathbf{R},\mathbf{t}) +\mathrm{scale\ factor}\cdot \left| \mathbf{R}^\top (\mathbf{t_{base}-\mathbf{t}}) \cdot \begin{pmatrix} 1\\ 0\\ 0 \end{pmatrix} \right|^2 \end{align}\]

, where t_base is base position measured by GNSS or other means. NDT(R,t) stands for the pure NDT cost function. The regularization term shifts the optimal solution to the base position in the longitudinal direction of the vehicle. Only errors along the longitudinal direction with respect to the base position are considered; errors along Z-axis and lateral-axis error are not considered.

Although the regularization term has rotation as a parameter, the gradient and hessian associated with it is not computed to stabilize the optimization. Specifically, the gradients are computed as follows.

\[\begin{align} &g_x=\nabla_x \mathrm{NDT}(\mathbf{R},\mathbf{t}) + 2 \mathrm{scale\ factor} \cos\theta_z\cdot e_{\mathrm{longitudinal}} \\ &g_y=\nabla_y \mathrm{NDT}(\mathbf{R},\mathbf{t}) + 2 \mathrm{scale\ factor} \sin\theta_z\cdot e_{\mathrm{longitudinal}} \\ &g_z=\nabla_z \mathrm{NDT}(\mathbf{R},\mathbf{t}) \\ &g_\mathbf{R}=\nabla_\mathbf{R} \mathrm{NDT}(\mathbf{R},\mathbf{t}) \end{align}\]

Regularization is disabled by default. If you wish to use it, please edit the following parameters to enable it.

Where is regularization available

This feature is effective on feature-less roads where GNSS is available, such as

  • bridges
  • highways
  • farm roads

By remapping the base position topic to something other than GNSS, as described below, it can be valid outside of these.

Using other base position

Other than GNSS, you can give other global position topics obtained from magnetic markers, visual markers or etc. if they are available in your environment. (Currently Autoware does not provide a node that gives such pose.) To use your topic for regularization, you need to remap the input_regularization_pose_topic with your topic in ndt_scan_matcher.launch.xml. By default, it is remapped with /sensing/gnss/pose_with_covariance.

Limitations

Since this function determines the base position by linear interpolation from the recently subscribed poses, topics that are published at a low frequency relative to the driving speed cannot be used. Inappropriate linear interpolation may result in bad optimization results.

When using GNSS for base location, the regularization can have negative effects in tunnels, indoors, and near skyscrapers. This is because if the base position is far off from the true value, NDT scan matching may converge to inappropriate optimal position.

Parameters

{{ json_to_markdown(“localization/autoware_ndt_scan_matcher/schema/sub/ndt_regularization.json”) }}

Regularization is disabled by default because GNSS is not always accurate enough to serve the appropriate base position in any scenes.

If the scale_factor is too large, the NDT will be drawn to the base position and scan matching may fail. Conversely, if it is too small, the regularization benefit will be lost.

Note that setting scale_factor to 0 is equivalent to disabling regularization.

Example

The following figures show tested maps.

  • The left is a map with enough features that NDT can successfully localize.
  • The right is a map with so few features that the NDT cannot localize well.

drawing drawing

The following figures show the trajectories estimated on the feature-less map with standard NDT and regularization-enabled NDT, respectively. The color of the trajectory indicates the error (meter) from the reference trajectory, which is computed with the feature-rich map.

  • The left figure shows that the pure NDT causes a longitudinal error in the bridge and is not able to recover.
  • The right figure shows that the regularization suppresses the longitudinal error.

drawing drawing

Dynamic map loading

Autoware supports dynamic map loading feature for ndt_scan_matcher. Using this feature, NDT dynamically requests for the surrounding pointcloud map to pointcloud_map_loader, and then receive and preprocess the map in an online fashion.

Using the feature, ndt_scan_matcher can theoretically handle any large size maps in terms of memory usage. (Note that it is still possible that there exists a limitation due to other factors, e.g. floating-point error)

drawing

Additional interfaces

Additional outputs

Name Type Description
debug/loaded_pointcloud_map sensor_msgs::msg::PointCloud2 pointcloud maps used for localization (for debug)

Additional client

Name Type Description
client_map_loader autoware_map_msgs::srv::GetDifferentialPointCloudMap map loading client

Parameters

{{ json_to_markdown(“localization/autoware_ndt_scan_matcher/schema/sub/dynamic_map_loading.json”) }}

Notes for dynamic map loading

To use dynamic map loading feature for ndt_scan_matcher, you also need to split the PCD files into grids (recommended size: 20[m] x 20[m])

Note that the dynamic map loading may FAIL if the map is split into two or more large size map (e.g. 1000[m] x 1000[m]). Please provide either of

  • one PCD map file
  • multiple PCD map files divided into small size (~20[m])

Here is a split PCD map for sample-map-rosbag from Autoware tutorial: sample-map-rosbag_split.zip

PCD files How NDT loads map(s)
single file at once (standard)
multiple files dynamically

Scan matching score based on no ground LiDAR scan

Abstract

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. related issue.

Parameters

{{ json_to_markdown(“localization/autoware_ndt_scan_matcher/schema/sub/score_estimation_no_ground_points.json”) }}

2D real-time covariance estimation

Abstract

Initially, the covariance of NDT scan matching is a fixed value(FIXED_VALUE mode). So, three modes are provided for 2D covariance (xx, xy, yx, yy) estimation in real time: LAPLACE_APPROXIMATION, MULTI_NDT, and MULTI_NDT_SCORE. LAPLACE_APPROXIMATION calculates the inverse matrix of the XY (2x2) part of the Hessian obtained by NDT scan matching and uses it as the covariance matrix. On the other hand, MULTI_NDT, and MULTI_NDT_SCORE use NDT convergence from multiple initial poses to obtain 2D covariance. Ideally, the arrangement of multiple initial poses is efficiently limited by the Hessian matrix of the NDT score function. In this implementation, the number of initial positions is fixed to simplify the code. To obtain the covariance, MULTI_NDT computes until convergence at each initial position, while MULTI_NDT_SCORE uses the nearest voxel transformation likelihood. The covariance can be seen as error ellipse from ndt_pose_with_covariance setting on rviz2. original paper.

drawing

Note that this function may spoil healthy system behavior if it consumes much calculation resources.

Parameters

There are three types in the calculation of 2D covariance in real time.You can select the method by changing covariance_estimation_type. initial_pose_offset_model is rotated around (x,y) = (0,0) in the direction of the first principal component of the Hessian matrix. initial_pose_offset_model_x & initial_pose_offset_model_y must have the same number of elements. In MULTI_NDT_SCORE mode, the scale of the output 2D covariance can be adjusted according to the temperature.

{{ json_to_markdown(“localization/autoware_ndt_scan_matcher/schema/sub/covariance_covariance_estimation.json”) }}

Diagnostics

scan_matching_status

drawing

Name Description Transition condition to Warning Transition condition to Error Whether to reject the estimation result (affects skipping_publish_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 sensor_points.timeout_sec none yes
is_succeed_transform_sensor_points whether transform sensor points is succeed or not none failed 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 if is_activated is false, then estimation is not executed and skipping_publish_num is set to 0.
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
is_set_map_points whether the map points is set or not not set none yes
iteration_num the number of times calculate alignment the number of times is larger than ndt.max_iterations none yes
local_optimal_solution_oscillation_num the number of times the solution is judged to be oscillating the number of times is larger than 10 none yes
transform_probability the score of how well the map aligns with the sensor points the score is smaller thanscore_estimation.converged_param_transform_probability (only in the case of score_estimation.converged_param_type is 0=TRANSFORM_PROBABILITY) none yes
transform_probability_diff the tp score difference for the current ndt optimization none none no
transform_probability_before the tp score before the current ndt optimization none none no
nearest_voxel_transformation_likelihood the score of how well the map aligns with the sensor points the score is smaller than score_estimation.converged_param_nearest_voxel_transformation_likelihood (only in the case of score_estimation.converged_param_type is 1=NEAREST_VOXEL_TRANSFORMATION_LIKELIHOOD) none yes
nearest_voxel_transformation_likelihood_diff the nvtl score difference for the current ndt optimization none none no
nearest_voxel_transformation_likelihood_before the nvtl score before the current ndt optimization none none no
distance_initial_to_result the distance between the position before convergence processing and the position after the distance is longer than validation.initial_to_result_distance_tolerance_m none no
execution_time the time for convergence processing the time is longer than validation.critical_upper_bound_exe_time_ms none no
skipping_publish_num the number of times rejected estimation results consecutively the number of times is validation.skipping_publish_num or more none -

※The sensor_points_callback shares the same callback group as the trigger_node_service and ndt_align_service. Consequently, if the initial pose estimation takes too long, this diagnostic may become stale.

initial_pose_subscriber_status

drawing

Name Description Transition condition to Warning Transition condition to Error
topic_time_stamp the time stamp of input topic none none
is_activated whether the node is in the “activate” state or not not “activate” state none
is_expected_frame_id whether the input frame_id is the same as frame.map_frame or not none not the same

regularization_pose_subscriber_status

drawing

Name Description Transition condition to Warning Transition condition to Error
topic_time_stamp the time stamp of input topic none none

trigger_node_service_status

drawing

Name Description Transition condition to Warning Transition condition to Error
service_call_time_stamp the time stamp of service calling none none
is_activated whether the node is in the “activate” state or not none none
is_succeed_service whether the process of service is succeed or not none none

※ This diagnostic is only published when the service is called, so it becomes stale after the initial pose estimation is completed.

ndt_align_service_status

drawing

Name Description Transition condition to Warning Transition condition to Error
service_call_time_stamp the time stamp of service calling none none
is_succeed_transform_initial_pose whether transform initial pose is succeed or not none failed
is_need_rebuild whether it need to rebuild the map. If the map has not been loaded yet or if distance_last_update_position_to_current_position encounters is an Error state, it is considered necessary to reconstruct the map, and is_need_rebuild becomes True. none none
maps_size_before the number of maps before update map none none
is_succeed_call_pcd_loader whether call pcd_loader service is succeed or not failed none
maps_to_add_size the number of maps to be added none none
maps_to_remove_size the number of maps to be removed none none
map_update_execution_time the time for map updating none none
maps_size_after the number of maps after update map none none
is_updated_map whether map is updated. If the map update couldn’t be performed or there was no need to update the map, it becomes False none is_updated_map is False but is_need_rebuild is True
is_set_map_points whether the map points is set or not not set none
is_set_sensor_points whether the sensor points is set or not not set none
best_particle_score the best score of particle none none
is_succeed_service whether the process of service is succeed or not failed none

※ This diagnostic is only published when the service is called, so it becomes stale after the initial pose estimation is completed.

map_update_status

drawing

Name Description Transition condition to Warning Transition condition to Error
timer_callback_time_stamp the time stamp of timer_callback calling none none
is_activated whether the node is in the “activate” state or not not “activate” state none
is_set_last_update_position whether the last_update_position is set or not not set none
distance_last_update_position_to_current_position the distance of last_update_position to current position none (the distance + dynamic_map_loading.lidar_radius) is larger than dynamic_map_loading.map_radius
is_need_rebuild whether it need to rebuild the map. If the map has not been loaded yet or if distance_last_update_position_to_current_position encounters is an Error state, it is considered necessary to reconstruct the map, and is_need_rebuild becomes True. none none
maps_size_before the number of maps before update map none none
is_succeed_call_pcd_loader whether call pcd_loader service is succeed or not failed none
maps_to_add_size the number of maps to be added none none
maps_to_remove_size the number of maps to be removed none none
map_update_execution_time the time for map updating none none
maps_size_after the number of maps after update map none none
is_updated_map whether map is updated. If the map update couldn’t be performed or there was no need to update the map, it becomes False none is_updated_map is False but is_need_rebuild is True
CHANGELOG

Changelog for package autoware_ndt_scan_matcher

0.43.0 (2025-03-21)

  • Merge remote-tracking branch 'origin/main' into chore/bump-version-0.43
  • chore: rename from [autoware.universe]{.title-ref} to [autoware_universe]{.title-ref} (#10306)
  • fix(ndt_scan_matcher): fix the covariance calculation (#10252) Fix the covariance calculation
  • Contributors: Anh Nguyen, Hayato Mizushima, Yutaka Kondo

0.42.0 (2025-03-03)

  • Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base
  • feat(autoware_utils): replace autoware_universe_utils with autoware_utils (#10191)
  • Contributors: Fumiya Watanabe, 心刚

0.41.2 (2025-02-19)

  • chore: bump version to 0.41.1 (#10088)
  • Contributors: Ryohsuke Mitsudome

0.41.1 (2025-02-10)

0.41.0 (2025-01-29)

  • Merge remote-tracking branch 'origin/main' into tmp/bot/bump_version_base
  • feat: tier4_debug_msgs changed to autoware-internal_debug_msgs in files localization/autoware_ndt_scan_matcher (#9861) Co-authored-by: SakodaShintaro <<shintaro.sakoda@tier4.jp>>
  • refactor(autoware_universe_utils): add missing 's' in the class of diagnostics_interface (#9777)
  • feat!: move diagnostics_module from localization_util to unverse_utils (#9714)
    • feat!: move diagnostics_module from localization_util to unverse_utils
    • remove diagnostics module from localization_util
    • style(pre-commit): autofix
    • minor fix in pose_initializer
    • add test
    • style(pre-commit): autofix
    • remove unnecessary declaration
    • module -> interface
    • remove unnecessary equal expression
    • revert the remove of template function
    • style(pre-commit): autofix
    • use overload instead

    * include what you use -- test_diagnostics_interface.cpp ---------Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]\@users.noreply.github.com>

  • Contributors: Fumiya Watanabe, Vishal Chauhan, kminoda

0.40.0 (2024-12-12)

  • Merge branch 'main' into release-0.40.0
  • Revert "chore(package.xml): bump version to 0.39.0 (#9587)" This reverts commit c9f0f2688c57b0f657f5c1f28f036a970682e7f5.
  • fix: fix ticket links in CHANGELOG.rst (#9588)
  • chore(package.xml): bump version to 0.39.0 (#9587)
    • chore(package.xml): bump version to 0.39.0
    • fix: fix ticket links in CHANGELOG.rst

    * fix: remove unnecessary diff ---------Co-authored-by: Yutaka Kondo <<yutaka.kondo@youtalk.jp>>

  • fix: fix ticket links in CHANGELOG.rst (#9588)
  • fix(cpplint): include what you use - localization (#9567)
  • 0.39.0
  • update changelog
  • Merge commit '6a1ddbd08bd' into release-0.39.0
  • fix: fix ticket links to point to https://github.com/autowarefoundation/autoware_universe (#9304)
  • fix(autoware_ndt_scan_matcher): remove unsed functions (#9387)
  • perf(autoware_ndt_scan_matcher): remove evecs_, evals_ of Leaf for memory efficiency (#9281) * fix(lane_change): correct computation of maximum lane changing length threshold (#9279) fix computation of maximum lane changing length threshold
    • perf: remove evecs, evals from Leaf

    * perf: remove evecs, evals from Leaf ---------Co-authored-by: mkquda <<168697710+mkquda@users.noreply.github.com>>

  • fix: fix ticket links to point to https://github.com/autowarefoundation/autoware_universe (#9304)
  • chore(package.xml): bump version to 0.38.0 (#9266) (#9284)
    • unify package.xml version to 0.37.0
    • remove system_monitor/CHANGELOG.rst
    • add changelog

    * 0.38.0

  • fix(autoware_ndt_scan_matcher): fix cppcheck unusedFunction (#9275)
  • fix(autoware_ndt_scan_matcher): reduce initial_pose_estimation.particles_num from 200 to 100 on tests (#9218) Reduced initial_pose_estimation.particles_num from 200 to 100 on tests
  • refactor(ndt_scan_matcher, ndt_omp): move ndt_omp into ndt_scan_matcher (#8912)
    • Moved ndt_omp into ndt_scan_matcher
    • Added Copyright
    • style(pre-commit): autofix
    • Fixed include
    • Fixed cast style
    • Fixed include
    • Fixed honorific title
    • Fixed honorific title
    • style(pre-commit): autofix
    • Fixed include hierarchy
    • style(pre-commit): autofix
    • Fixed include hierarchy
    • style(pre-commit): autofix
    • Fixed hierarchy
    • Fixed NVTP to NVTL
    • Added cspell:ignore
    • Fixed miss spell
    • style(pre-commit): autofix
    • Fixed include
    • Renamed applyFilter
    • Moved ***_impl.hpp from include/ to src/
    • style(pre-commit): autofix
    • Fixed variable scope

    * Fixed to pass by reference ---------Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]\@users.noreply.github.com>

  • Contributors: Esteve Fernandez, Fumiya Watanabe, Kento Osa, M. Fatih Cırıt, Ryohsuke Mitsudome, Ryuta Kambe, SakodaShintaro, Yutaka Kondo

0.39.0 (2024-11-25)

  • Merge commit '6a1ddbd08bd' into release-0.39.0
  • fix: fix ticket links to point to https://github.com/autowarefoundation/autoware_universe (#9304)
  • perf(autoware_ndt_scan_matcher): remove evecs_, evals_ of Leaf for memory efficiency (#9281) * fix(lane_change): correct computation of maximum lane changing length threshold (#9279) fix computation of maximum lane changing length threshold
    • perf: remove evecs, evals from Leaf

    * perf: remove evecs, evals from Leaf ---------Co-authored-by: mkquda <<168697710+mkquda@users.noreply.github.com>>

  • fix: fix ticket links to point to https://github.com/autowarefoundation/autoware_universe (#9304)
  • chore(package.xml): bump version to 0.38.0 (#9266) (#9284)
    • unify package.xml version to 0.37.0
    • remove system_monitor/CHANGELOG.rst
    • add changelog

    * 0.38.0

  • fix(autoware_ndt_scan_matcher): fix cppcheck unusedFunction (#9275)
  • fix(autoware_ndt_scan_matcher): reduce initial_pose_estimation.particles_num from 200 to 100 on tests (#9218) Reduced initial_pose_estimation.particles_num from 200 to 100 on tests
  • refactor(ndt_scan_matcher, ndt_omp): move ndt_omp into ndt_scan_matcher (#8912)
    • Moved ndt_omp into ndt_scan_matcher
    • Added Copyright
    • style(pre-commit): autofix
    • Fixed include
    • Fixed cast style
    • Fixed include
    • Fixed honorific title
    • Fixed honorific title
    • style(pre-commit): autofix
    • Fixed include hierarchy
    • style(pre-commit): autofix
    • Fixed include hierarchy
    • style(pre-commit): autofix
    • Fixed hierarchy
    • Fixed NVTP to NVTL
    • Added cspell:ignore
    • Fixed miss spell
    • style(pre-commit): autofix
    • Fixed include
    • Renamed applyFilter
    • Moved ***_impl.hpp from include/ to src/
    • style(pre-commit): autofix
    • Fixed variable scope

    * Fixed to pass by reference ---------Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]\@users.noreply.github.com>

  • Contributors: Esteve Fernandez, Kento Osa, Ryuta Kambe, SakodaShintaro, Yutaka Kondo

0.38.0 (2024-11-08)

  • unify package.xml version to 0.37.0
  • refactor(localization_util)!: prefix package and namespace with autoware (#8922) add autoware prefix to localization_util
  • refactor(ndt_scan_matcher)!: prefix package and namespace with autoware (#8904) add autoware_ prefix
  • Contributors: Masaki Baba, Yutaka Kondo

0.26.0 (2024-04-03)

Wiki Tutorials

This package does not provide any links to tutorials in it's rosindex metadata. You can check on the ROS Wiki Tutorials page for the package.

Launch files

  • launch/ndt_scan_matcher.launch.xml
      • param_file [default: $(find-pkg-share autoware_ndt_scan_matcher)/config/ndt_scan_matcher.param.yaml]
      • input_pointcloud [default: points_raw]
      • input_initial_pose_topic [default: ekf_pose_with_covariance]
      • input_regularization_pose_topic [default: regularization_pose_with_covariance]
      • input_service_trigger_node [default: trigger_node]
      • output_pose_topic [default: ndt_pose]
      • output_pose_with_covariance_topic [default: ndt_pose_with_covariance]
      • client_map_loader [default: pcd_loader_service]
      • node_name [default: ndt_scan_matcher]

Messages

No message files found.

Services

No service files found

Plugins

No plugins found.

Recent questions tagged autoware_ndt_scan_matcher at Robotics Stack Exchange

No version for distro noetic. Known supported distros are highlighted in the buttons above.
No version for distro ardent. Known supported distros are highlighted in the buttons above.
No version for distro bouncy. Known supported distros are highlighted in the buttons above.
No version for distro crystal. Known supported distros are highlighted in the buttons above.
No version for distro eloquent. Known supported distros are highlighted in the buttons above.
No version for distro dashing. Known supported distros are highlighted in the buttons above.
No version for distro galactic. Known supported distros are highlighted in the buttons above.
No version for distro foxy. Known supported distros are highlighted in the buttons above.
No version for distro iron. Known supported distros are highlighted in the buttons above.
No version for distro lunar. Known supported distros are highlighted in the buttons above.
No version for distro jade. Known supported distros are highlighted in the buttons above.
No version for distro indigo. Known supported distros are highlighted in the buttons above.
No version for distro hydro. Known supported distros are highlighted in the buttons above.
No version for distro kinetic. Known supported distros are highlighted in the buttons above.
No version for distro melodic. Known supported distros are highlighted in the buttons above.