Skip to content

pose_initializer#

Purpose#

The pose_initializer is the package to send an initial pose to ekf_localizer. It receives roughly estimated initial pose from GNSS/user. Passing the pose to ndt_scan_matcher, and it gets a calculated ego pose from ndt_scan_matcher via service. Finally, it publishes the initial pose to ekf_localizer. This node depends on the map height fitter library. See here for more details.

Interfaces#

Parameters#

Name Type Description Default Range
user_defined_initial_pose.enable string If true, user_defined_initial_pose.pose is set as the initial position. [boolean] false N/A
user_defined_initial_pose.pose string initial pose (x, y, z, quat_x, quat_y, quat_z, quat_w). [array] [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.0] N/A
gnss_pose_timeout float The duration that the GNSS pose is valid. [sec] 3.0 ≥0.0
stop_check_enabled string If true, initialization is accepted only when the vehicle is stopped. true N/A
stop_check_duration float The duration used for the stop check above. [sec] 3.0 ≥0.0
ekf_enabled string If true, EKF localizer is activated. true N/A
gnss_enabled string If true, use the GNSS pose when no pose is specified. true N/A
yabloc_enabled string If true, YabLocModule is used. true N/A
ndt_enabled string If true, the pose will be estimated by NDT scan matcher, otherwise it is passed through. true N/A
gnss_particle_covariance array gnss particle covariance [1.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 10.0] N/A
output_pose_covariance array output pose covariance [1.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.01, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.2] N/A

Services#

Name Type Description
/localization/initialize autoware_adapi_v1_msgs::srv::InitializeLocalization initial pose from api

Clients#

Name Type Description
/localization/pose_estimator/ndt_align_srv tier4_localization_msgs::srv::PoseWithCovarianceStamped pose estimation service

Subscriptions#

Name Type Description
/sensing/gnss/pose_with_covariance geometry_msgs::msg::PoseWithCovarianceStamped pose from gnss
/sensing/vehicle_velocity_converter/twist_with_covariance geometry_msgs::msg::TwistStamped twist for stop check

Publications#

Name Type Description
/localization/initialization_state autoware_adapi_v1_msgs::msg::LocalizationInitializationState pose initialization state
/initialpose3d geometry_msgs::msg::PoseWithCovarianceStamped calculated initial ego pose

Connection with Default AD API#

This pose_initializer is used via default AD API. For detailed description of the API description, please refer to the description of default_ad_api.

drawing