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(autoware_launch): enable pose initialization while running (only for sim) #243

Original file line number Diff line number Diff line change
@@ -0,0 +1,6 @@
/**:
ros__parameters:
gnss_enabled: true
ndt_enabled: true
ekf_enabled: true
stop_check_enabled: false
Original file line number Diff line number Diff line change
@@ -0,0 +1,6 @@
/**:
ros__parameters:
gnss_enabled: true
ndt_enabled: true
ekf_enabled: true
stop_check_enabled: true
Original file line number Diff line number Diff line change
@@ -0,0 +1,6 @@
/**:
ros__parameters:
gnss_enabled: false
ndt_enabled: false
ekf_enabled: false
stop_check_enabled: false
Original file line number Diff line number Diff line change
@@ -0,0 +1,26 @@
/**:
ros__parameters:
gnss_pose_timeout: 3.0 # [sec]
stop_check_duration: 3.0 # [sec]

# from gnss
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,
]

# output
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,
]
28 changes: 14 additions & 14 deletions autoware_launch/config/system/component_state_monitor/topics.yaml
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
- module: map
mode: [online, planning_simulation]
mode: [online, logging_simulation, planning_simulation]
type: launch
args:
node_name_suffix: vector_map
Expand All @@ -12,7 +12,7 @@
timeout: 0.0

- module: map
mode: [online]
mode: [online, logging_simulation]
type: launch
args:
node_name_suffix: pointcloud_map
Expand All @@ -25,7 +25,7 @@
timeout: 0.0

- module: localization
mode: [online, planning_simulation]
mode: [online, logging_simulation, planning_simulation]
type: autonomous
args:
node_name_suffix: initialpose3d
Expand All @@ -38,7 +38,7 @@
timeout: 0.0

- module: localization
mode: [online]
mode: [online, logging_simulation]
type: autonomous
args:
node_name_suffix: pose_twist_fusion_filter_pose
Expand All @@ -51,7 +51,7 @@
timeout: 1.0

- module: perception
mode: [online]
mode: [online, logging_simulation]
type: launch
args:
node_name_suffix: obstacle_segmentation_pointcloud
Expand All @@ -64,7 +64,7 @@
timeout: 1.0

- module: perception
mode: [online, planning_simulation]
mode: [online, logging_simulation, planning_simulation]
type: autonomous
args:
node_name_suffix: object_recognition_objects
Expand All @@ -77,7 +77,7 @@
timeout: 1.0

- module: planning
mode: [online, planning_simulation]
mode: [online, logging_simulation, planning_simulation]
type: autonomous
args:
node_name_suffix: mission_planning_route
Expand All @@ -90,7 +90,7 @@
timeout: 0.0

- module: planning
mode: [online, planning_simulation]
mode: [online, logging_simulation, planning_simulation]
type: autonomous
args:
node_name_suffix: scenario_planning_trajectory
Expand All @@ -103,7 +103,7 @@
timeout: 1.0

- module: control
mode: [online, planning_simulation]
mode: [online, logging_simulation, planning_simulation]
type: autonomous
args:
node_name_suffix: trajectory_follower_control_cmd
Expand All @@ -116,7 +116,7 @@
timeout: 1.0

- module: control
mode: [online, planning_simulation]
mode: [online, logging_simulation, planning_simulation]
type: autonomous
args:
node_name_suffix: control_command_control_cmd
Expand All @@ -129,7 +129,7 @@
timeout: 1.0

- module: vehicle
mode: [online, planning_simulation]
mode: [online, logging_simulation, planning_simulation]
type: autonomous
args:
node_name_suffix: vehicle_status_velocity_status
Expand All @@ -142,7 +142,7 @@
timeout: 1.0

- module: vehicle
mode: [online, planning_simulation]
mode: [online, logging_simulation, planning_simulation]
type: autonomous
args:
node_name_suffix: vehicle_status_steering_status
Expand All @@ -155,7 +155,7 @@
timeout: 1.0

- module: system
mode: [online, planning_simulation]
mode: [online, logging_simulation, planning_simulation]
type: launch
args:
node_name_suffix: system_emergency_control_cmd
Expand All @@ -168,7 +168,7 @@
timeout: 1.0

- module: localization
mode: [online, planning_simulation]
mode: [online, logging_simulation, planning_simulation]
type: autonomous
args:
node_name_suffix: transform_map_to_base_link
Expand Down
Original file line number Diff line number Diff line change
@@ -1,5 +1,12 @@
<?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/pose_initializer.logging_simulator.param.yaml"
if="$(eval &quot;'$(var system_run_mode)'=='logging_simulation'&quot;)"
/>

<include file="$(find-pkg-share tier4_localization_launch)/launch/localization.launch.xml">
<arg name="use_pointcloud_container" value="$(var use_pointcloud_container)"/>
<arg name="pointcloud_container_name" value="$(var pointcloud_container_name)"/>
Expand All @@ -9,5 +16,7 @@
<arg name="random_downsample_filter_param_path" value="$(find-pkg-share autoware_launch)/config/localization/random_downsample_filter.param.yaml"/>
<arg name="ndt_scan_matcher_param_path" value="$(find-pkg-share autoware_launch)/config/localization/ndt_scan_matcher.param.yaml"/>
<arg name="localization_error_monitor_param_path" value="$(find-pkg-share autoware_launch)/config/localization/localization_error_monitor.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>
Original file line number Diff line number Diff line change
Expand Up @@ -30,5 +30,7 @@
name="object_recognition_tracking_multi_object_tracker_data_association_matrix_param_path"
value="$(find-pkg-share autoware_launch)/config/perception/object_recognition/tracking/multi_object_tracker/data_association_matrix.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="$(find-pkg-share autoware_launch)/config/localization/pose_initializer.planning_simulator.param.yaml"/>
</include>
</launch>
2 changes: 1 addition & 1 deletion autoware_launch/launch/logging_simulator.launch.xml
Original file line number Diff line number Diff line change
Expand Up @@ -56,7 +56,7 @@
<arg name="launch_vehicle_interface" value="$(var launch_vehicle_interface)"/>
<!-- System -->
<arg name="launch_system" value="$(var system)"/>
<arg name="system_run_mode" value="online"/>
<arg name="system_run_mode" value="logging_simulation"/>
<arg name="launch_system_monitor" value="$(var launch_system_monitor)"/>
<arg name="launch_dummy_diag_publisher" value="$(var launch_dummy_diag_publisher)"/>
<!-- Map -->
Expand Down