Skip to content

Commit

Permalink
feat(autoware_launch): move config from autoware.universe for system (a…
Browse files Browse the repository at this point in the history
…utowarefoundation#130)

* feat(autoware_launch): move config to autoware_launch for system

Signed-off-by: kminoda <[email protected]>

* fix

Signed-off-by: kminoda <[email protected]>

Signed-off-by: kminoda <[email protected]>
  • Loading branch information
kminoda authored Dec 21, 2022
1 parent d748556 commit a4b7ccb
Show file tree
Hide file tree
Showing 18 changed files with 416 additions and 1 deletion.
1 change: 1 addition & 0 deletions autoware_launch/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -13,4 +13,5 @@ ament_auto_package(
INSTALL_TO_SHARE
launch
rviz
config
)
182 changes: 182 additions & 0 deletions autoware_launch/config/system/component_state_monitor/topics.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,182 @@
- module: map
mode: [online, planning_simulation]
type: launch
args:
node_name_suffix: vector_map
topic: /map/vector_map
topic_type: autoware_auto_mapping_msgs/msg/HADMapBin
best_effort: false
transient_local: true
warn_rate: 0.0
error_rate: 0.0
timeout: 0.0

- module: map
mode: [online]
type: launch
args:
node_name_suffix: pointcloud_map
topic: /map/pointcloud_map
topic_type: sensor_msgs/msg/PointCloud2
best_effort: false
transient_local: true
warn_rate: 0.0
error_rate: 0.0
timeout: 0.0

- module: localization
mode: [online, planning_simulation]
type: autonomous
args:
node_name_suffix: initialpose3d
topic: /initialpose3d
topic_type: geometry_msgs/msg/PoseWithCovarianceStamped
best_effort: false
transient_local: false
warn_rate: 0.0
error_rate: 0.0
timeout: 0.0

- module: localization
mode: [online]
type: autonomous
args:
node_name_suffix: pose_twist_fusion_filter_pose
topic: /localization/pose_twist_fusion_filter/pose
topic_type: geometry_msgs/msg/PoseStamped
best_effort: false
transient_local: false
warn_rate: 5.0
error_rate: 1.0
timeout: 1.0

- module: perception
mode: [online]
type: launch
args:
node_name_suffix: obstacle_segmentation_pointcloud
topic: /perception/obstacle_segmentation/pointcloud
topic_type: sensor_msgs/msg/PointCloud2
best_effort: true
transient_local: false
warn_rate: 5.0
error_rate: 1.0
timeout: 1.0

- module: perception
mode: [online, planning_simulation]
type: autonomous
args:
node_name_suffix: object_recognition_objects
topic: /perception/object_recognition/objects
topic_type: autoware_auto_perception_msgs/msg/PredictedObjects
best_effort: false
transient_local: false
warn_rate: 5.0
error_rate: 1.0
timeout: 1.0

- module: planning
mode: [online, planning_simulation]
type: autonomous
args:
node_name_suffix: mission_planning_route
topic: /planning/mission_planning/route
topic_type: autoware_planning_msgs/msg/LaneletRoute
best_effort: false
transient_local: true
warn_rate: 0.0
error_rate: 0.0
timeout: 0.0

- module: planning
mode: [online, planning_simulation]
type: autonomous
args:
node_name_suffix: scenario_planning_trajectory
topic: /planning/scenario_planning/trajectory
topic_type: autoware_auto_planning_msgs/msg/Trajectory
best_effort: false
transient_local: false
warn_rate: 5.0
error_rate: 1.0
timeout: 1.0

- module: control
mode: [online, planning_simulation]
type: autonomous
args:
node_name_suffix: trajectory_follower_control_cmd
topic: /control/trajectory_follower/control_cmd
topic_type: autoware_auto_control_msgs/msg/AckermannControlCommand
best_effort: false
transient_local: false
warn_rate: 5.0
error_rate: 1.0
timeout: 1.0

- module: control
mode: [online, planning_simulation]
type: autonomous
args:
node_name_suffix: control_command_control_cmd
topic: /control/command/control_cmd
topic_type: autoware_auto_control_msgs/msg/AckermannControlCommand
best_effort: false
transient_local: false
warn_rate: 5.0
error_rate: 1.0
timeout: 1.0

- module: vehicle
mode: [online, planning_simulation]
type: autonomous
args:
node_name_suffix: vehicle_status_velocity_status
topic: /vehicle/status/velocity_status
topic_type: autoware_auto_vehicle_msgs/msg/VelocityReport
best_effort: false
transient_local: false
warn_rate: 5.0
error_rate: 1.0
timeout: 1.0

- module: vehicle
mode: [online, planning_simulation]
type: autonomous
args:
node_name_suffix: vehicle_status_steering_status
topic: /vehicle/status/steering_status
topic_type: autoware_auto_vehicle_msgs/msg/SteeringReport
best_effort: false
transient_local: false
warn_rate: 5.0
error_rate: 1.0
timeout: 1.0

- module: system
mode: [online, planning_simulation]
type: launch
args:
node_name_suffix: system_emergency_control_cmd
topic: /system/emergency/control_cmd
topic_type: autoware_auto_control_msgs/msg/AckermannControlCommand
best_effort: false
transient_local: false
warn_rate: 5.0
error_rate: 1.0
timeout: 1.0

- module: localization
mode: [online, planning_simulation]
type: autonomous
args:
node_name_suffix: transform_map_to_base_link
topic: /tf
frame_id: map
child_frame_id: base_link
best_effort: false
transient_local: false
warn_rate: 5.0
error_rate: 1.0
timeout: 1.0
Original file line number Diff line number Diff line change
@@ -0,0 +1,14 @@
# Default configuration for emergency handler
---
/**:
ros__parameters:
update_rate: 10
timeout_hazard_status: 0.5
timeout_takeover_request: 10.0
use_takeover_request: false
use_parking_after_stopped: false
use_comfortable_stop: false

# setting whether to turn hazard lamp on for each situation
turning_hazard_on:
emergency: true
Original file line number Diff line number Diff line change
@@ -0,0 +1,6 @@
/**:
ros__parameters:
update_rate: 10
min_acceleration: -1.0
max_jerk: 0.3
min_jerk: -0.3
Original file line number Diff line number Diff line change
@@ -0,0 +1,5 @@
/**:
ros__parameters:
update_rate: 30
target_acceleration: -2.5
target_jerk: -1.5
Original file line number Diff line number Diff line change
@@ -0,0 +1,11 @@
/**:
ros__parameters:
vehicle:
type: diagnostic_aggregator/AnalyzerGroup
path: vehicle
analyzers:
vehicle_errors:
type: diagnostic_aggregator/GenericAnalyzer
path: vehicle_errors
contains: [": vehicle_errors"]
timeout: 1.0
Original file line number Diff line number Diff line change
@@ -0,0 +1,52 @@
# Description:
# name: diag name
# sf_at: diag level where it becomes Safe Fault
# lf_at: diag level where it becomes Latent Fault
# spf_at: diag level where it becomes Single Point Fault
# auto_recovery: Determines whether the system will automatically recover when it recovers from an error.
#
# Note:
# empty-value for sf_at, lf_at and spf_at is "none"
# default values are:
# sf_at: "none"
# lf_at: "warn"
# spf_at: "error"
# auto_recovery: "true"
---
/**:
ros__parameters:
required_modules:
autonomous_driving:
/autoware/control/autonomous_driving/node_alive_monitoring: default
/autoware/control/autonomous_driving/performance_monitoring/lane_departure: default
/autoware/control/control_command_gate/node_alive_monitoring: default

/autoware/localization/node_alive_monitoring: default
/autoware/localization/performance_monitoring/matching_score: { sf_at: "warn", lf_at: "none", spf_at: "none" }
/autoware/localization/performance_monitoring/localization_accuracy: default

/autoware/map/node_alive_monitoring: default

/autoware/perception/node_alive_monitoring: default

/autoware/planning/node_alive_monitoring: default
/autoware/planning/performance_monitoring/trajectory_validation: default

# /autoware/sensing/node_alive_monitoring: default

/autoware/system/node_alive_monitoring: default
/autoware/system/emergency_stop_operation: default
/autoware/system/service_log_checker: { sf_at: "warn", lf_at: "none", spf_at: "none" }
/autoware/system/resource_monitoring: { sf_at: "warn", lf_at: "none", spf_at: "none" }

/autoware/vehicle/node_alive_monitoring: default

external_control:
/autoware/control/control_command_gate/node_alive_monitoring: default
/autoware/control/external_control/external_command_selector/node_alive_monitoring: default

/autoware/system/node_alive_monitoring: default
/autoware/system/emergency_stop_operation: default
/autoware/system/service_log_checker: { sf_at: "warn", lf_at: "none", spf_at: "none" }

/autoware/vehicle/node_alive_monitoring: default
Original file line number Diff line number Diff line change
@@ -0,0 +1,52 @@
# Description:
# name: diag name
# sf_at: diag level where it becomes Safe Fault
# lf_at: diag level where it becomes Latent Fault
# spf_at: diag level where it becomes Single Point Fault
# auto_recovery: Determines whether the system will automatically recover when it recovers from an error.
#
# Note:
# empty-value for sf_at, lf_at and spf_at is "none"
# default values are:
# sf_at: "none"
# lf_at: "warn"
# spf_at: "error"
# auto_recovery: "true"
---
/**:
ros__parameters:
required_modules:
autonomous_driving:
/autoware/control/autonomous_driving/node_alive_monitoring: default
/autoware/control/autonomous_driving/performance_monitoring/lane_departure: default
/autoware/control/control_command_gate/node_alive_monitoring: default

/autoware/localization/node_alive_monitoring: default
# /autoware/localization/performance_monitoring/matching_score: { sf_at: "warn", lf_at: "none", spf_at: "none" }
# /autoware/localization/performance_monitoring/localization_accuracy: default

/autoware/map/node_alive_monitoring: default

/autoware/perception/node_alive_monitoring: default

/autoware/planning/node_alive_monitoring: default
/autoware/planning/performance_monitoring/trajectory_validation: default

# /autoware/sensing/node_alive_monitoring: default

/autoware/system/node_alive_monitoring: default
/autoware/system/emergency_stop_operation: default
/autoware/system/service_log_checker: { sf_at: "warn", lf_at: "none", spf_at: "none" }
# /autoware/system/resource_monitoring: { sf_at: "warn", lf_at: "error", spf_at: "none" }

/autoware/vehicle/node_alive_monitoring: default

external_control:
/autoware/control/control_command_gate/node_alive_monitoring: default
/autoware/control/external_control/external_command_selector/node_alive_monitoring: default

/autoware/system/node_alive_monitoring: default
/autoware/system/emergency_stop_operation: default
/autoware/system/service_log_checker: { sf_at: "warn", lf_at: "none", spf_at: "none" }

/autoware/vehicle/node_alive_monitoring: default
Original file line number Diff line number Diff line change
@@ -0,0 +1,8 @@
/**:
ros__parameters:
usage_warn: 0.96
usage_error: 0.96
usage_warn_count: 1
usage_error_count: 2
usage_avg: true
msr_reader_port: 7634
Original file line number Diff line number Diff line change
@@ -0,0 +1,8 @@
/**:
ros__parameters:
temp_warn: 90.0
temp_error: 95.0
gpu_usage_warn: 0.90
gpu_usage_error: 1.00
memory_usage_warn: 0.95
memory_usage_error: 0.99
Original file line number Diff line number Diff line change
@@ -0,0 +1,23 @@
/**:
ros__parameters:
hdd_reader_port: 7635
num_disks: 1
disks: # Until multi type lists are allowed, name N the disks as disk0...disk{N-1}
disk0:
name: /
temp_attribute_id: 0xC2
temp_warn: 55.0
temp_error: 70.0
power_on_hours_attribute_id: 0x09
power_on_hours_warn: 3000000
total_data_written_attribute_id: 0xF1
total_data_written_warn: 4915200 # =150TB (1unit=32MB)
total_data_written_safety_factor: 0.05
recovered_error_attribute_id: 0xC3
recovered_error_warn: 1
free_warn: 5120 # MB(8hour)
free_error: 100 # MB(last 1 minute)
read_data_rate_warn: 360.0 # MB/s
write_data_rate_warn: 103.5 # MB/s
read_iops_warn: 63360.0 # IOPS
write_iops_warn: 24120.0 # IOPS
Original file line number Diff line number Diff line change
@@ -0,0 +1,3 @@
/**:
ros__parameters:
available_size: 1024 # MB
Original file line number Diff line number Diff line change
@@ -0,0 +1,9 @@
/**:
ros__parameters:
devices: ["*"]
traffic_reader_port: 7636
monitor_program: "greengrass"
crc_error_check_duration: 1
crc_error_count_threshold: 1
reassembles_failed_check_duration: 1
reassembles_failed_check_count: 1
Original file line number Diff line number Diff line change
@@ -0,0 +1,5 @@
/**:
ros__parameters:
server: ntp.nict.jp
offset_warn: 0.1
offset_error: 5.0
Loading

0 comments on commit a4b7ccb

Please sign in to comment.