Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

feat(localization_launch): add camera & vector map based localization #357

Closed
Closed
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -3,4 +3,5 @@
gnss_enabled: true
ndt_enabled: true
ekf_enabled: true
yabloc_enabled: false
stop_check_enabled: false
Original file line number Diff line number Diff line change
Expand Up @@ -3,4 +3,5 @@
gnss_enabled: false
ndt_enabled: false
ekf_enabled: false
yabloc_enabled: false
stop_check_enabled: false
Original file line number Diff line number Diff line change
@@ -0,0 +1,14 @@
/**:
ros__parameters:
# Declared in AbstParticleCorrector
acceptable_max_delay: 1.0
visualize: false

# Declared in ll2_cost_map
image_size: 800 # cost map image made by lanelet2
max_range: 40.0 # [m] a cost map scale size
gamma: 5.0 # cost map intensity gradient

min_prob: 0.1 # minimum weight of particles
far_weight_gain: 0.001 # exp(-far_weight_gain_ * squared_norm) is multiplied earch measurement
enabled_at_first: true # developing feature
Original file line number Diff line number Diff line change
@@ -0,0 +1,3 @@
/**:
ros__parameters:
angle_resolution: 30
Original file line number Diff line number Diff line change
@@ -0,0 +1,19 @@
/**:
ros__parameters:
# Declared in AbstParticleCorrector
acceptable_max_delay: 1.0
visualize: false

mahalanobis_distance_threshold: 30.0 # If the distance to GNSS observation exceeds this, the correction is skipped.
use_ublox_msg: true # Raw sensor data should not be used when running as Autoware.
ignore_less_than_float: false
#
for_fixed/max_weight: 5.0
for_fixed/flat_radius: 0.5
for_fixed/max_radius: 10.0
for_fixed/min_weight: 0.5
#
for_not_fixed/flat_radius: 5.0
for_not_fixed/max_radius: 20.0
for_not_fixed/min_weight: 0.5
for_not_fixed/max_weight: 1.0
Original file line number Diff line number Diff line change
@@ -0,0 +1,18 @@
/**:
ros__parameters:
# graph_node selects a road surface area from around this height
target_height_ratio: 0.85

#
target_candidate_box_width: 15

# graph_segment_node will pickup additional roadlike areas
pickup_additional_graph_segment: true

# used when the pickup_additional_graph_segment: true
similarity_score_threshold: 0.8

# parameters for cv::ximgproc::segmentation
sigma: 0.5
k: 300.0
min_size: 100.0
Original file line number Diff line number Diff line change
@@ -0,0 +1,5 @@
/**:
ros__parameters:
force_zero_tilt: false
K: 50
R: 10
Original file line number Diff line number Diff line change
@@ -0,0 +1,5 @@
/**:
ros__parameters:
road_marking_labels: [cross_walk, zebra_marking, line_thin, line_thick, pedestrian_marking, stop_line, road_border]
sign_board_labels: [sign-board]
bounding_box_labels: [none]
Original file line number Diff line number Diff line change
@@ -0,0 +1,3 @@
/**:
ros__parameters:
cov_xx_yy: [2.0,0.25]
Original file line number Diff line number Diff line change
@@ -0,0 +1,7 @@
/**:
ros__parameters:
gnss_enabled: true
ndt_enabled: false
ekf_enabled: true
yabloc_enabled: true
stop_check_enabled: false
12 changes: 12 additions & 0 deletions autoware_launch/config/localization/yabloc/predictor.param.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,12 @@
/**:
ros__parameters:
visualize: true

static_linear_covariance: 0.04
static_angular_covariance: 0.006

resampling_interval_seconds: 1.0
num_of_particles: 500
prediction_rate: 50.0

is_swap_mode: false # developing feature
Original file line number Diff line number Diff line change
@@ -0,0 +1,8 @@
/**:
ros__parameters:
min_segment_length: 1.5 # if it is negative, it is unlimited
max_segment_distance: 30.0 # if it is negative, it is unlimited
max_lateral_distance: 10.0 # if it is negative, it is unlimited
publish_image_with_segment_for_debug: true
max_range: 20.0
image_size: 800 # debug
Original file line number Diff line number Diff line change
@@ -0,0 +1,5 @@
/**:
ros__parameters:
use_sensor_qos: true
width: 800
override_frame_id: "" # Value for overriding the camera's frame_id. If blank, frame_id of static_tf is not overwritten
3 changes: 2 additions & 1 deletion autoware_launch/launch/autoware.launch.xml
Original file line number Diff line number Diff line change
Expand Up @@ -83,8 +83,9 @@

<!-- Localization -->
<group if="$(var launch_localization)">
<include file="$(find-pkg-share autoware_launch)/launch/components/tier4_localization_component.launch.xml"/>
<!-- <include file="$(find-pkg-share autoware_launch)/launch/components/tier4_localization_component.launch.xml"/> -->
<!-- <include file="$(find-pkg-share autoware_launch)/launch/components/map4_localization_component.launch.xml"/> -->
<include file="$(find-pkg-share autoware_launch)/launch/components/yabloc_localization_component.launch.xml"/>
</group>

<!-- Perception -->
Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,33 @@
<?xml version="1.0"?>
<launch>
<let name="pose_initializer_param_path" value="$(find-pkg-share autoware_launch)/config/localization/pose_initializer.param.yaml" if="$(eval &quot;'$(var system_run_mode)'=='online'&quot;)"/>
<let
name="pose_initializer_param_path"
value="$(find-pkg-share autoware_launch)/config/localization/yabloc/pose_initializer.logging_simulator.yabloc.param.yaml"
if="$(eval &quot;'$(var system_run_mode)'=='logging_simulation'&quot;)"
/>

<let name="yaml_path" value="$(find-pkg-share autoware_launch)/config/localization/yabloc"/>

<include file="$(find-pkg-share yabloc_localization_launch)/launch/localization.launch.xml">
<!-- yabloc initializer -->
<arg name="camera_pose_initializer_param_path" value="$(var yaml_path)/camera_pose_initializer.param.yaml"/>
<arg name="particle_initializer_param_path" value="$(var yaml_path)/particle_initializer.param.yaml"/>
<!-- yabloc particle filter-->
<arg name="camera_particle_corrector_param_path" value="$(var yaml_path)/camera_particle_corrector.param.yaml"/>
<arg name="gnss_particle_corrector_param_path" value="$(var yaml_path)/gnss_particle_corrector.param.yaml"/>
<arg name="predictor_param_path" value="$(var yaml_path)/predictor.param.yaml"/>
<!-- yabloc image processing -->
<arg name="graph_segment_param_path" value="$(var yaml_path)/graph_segment.param.yaml"/>
<arg name="segment_filter_param_path" value="$(var yaml_path)/segment_filter.param.yaml"/>
<arg name="undistort_param_path" value="$(var yaml_path)/undistort.param.yaml"/>
<!-- yabloc map -->
<arg name="ground_server_param_path" value="$(var yaml_path)/ground_server.param.yaml"/>
<arg name="ll2_decomposer_param_path" value="$(var yaml_path)/ll2_decomposer.param.yaml"/>

<arg name="localization_error_monitor_param_path" value="$(find-pkg-share autoware_launch)/config/localization/localization_error_monitor.param.yaml"/>
<arg name="ekf_localizer_param_path" value="$(find-pkg-share autoware_launch)/config/localization/ekf_localizer.param.yaml"/>
<arg name="pose_initializer_common_param_path" value="$(find-pkg-share autoware_launch)/config/localization/pose_initializer_common.param.yaml"/>
<arg name="pose_initializer_param_path" value="$(var pose_initializer_param_path)"/>
</include>
</launch>