diff --git a/.github/workflows/lint-autoware-system-design-format.yml b/.github/workflows/lint-autoware-system-design-format.yml new file mode 100644 index 000000000..5a272ce02 --- /dev/null +++ b/.github/workflows/lint-autoware-system-design-format.yml @@ -0,0 +1,30 @@ +name: Lint Autoware System Design Format + +on: + pull_request: + paths: + - "**/*.node.yaml" + - "**/*.module.yaml" + - "**/*.system.yaml" + - "**/*.parameter_set.yaml" + push: + branches: + - main + paths: + - "**/*.node.yaml" + - "**/*.module.yaml" + - "**/*.system.yaml" + - "**/*.parameter_set.yaml" + +jobs: + lint: + runs-on: ubuntu-latest + + steps: + - name: Checkout code + uses: actions/checkout@v4 + + - name: Lint system design format files + uses: autowarefoundation/autoware_system_designer@v0.3.0 + with: + design_files_path: . diff --git a/.pre-commit-config.yaml b/.pre-commit-config.yaml index a8bc283de..4076bc2e3 100644 --- a/.pre-commit-config.yaml +++ b/.pre-commit-config.yaml @@ -94,4 +94,10 @@ repos: args: [--quiet, '--filter=-runtime/arrays,-build/c++17,-readability/casting'] exclude: .cu + - repo: https://github.com/autowarefoundation/autoware_system_designer + rev: v0.3.0 + hooks: + - id: lint-system-design-format + args: [--format=github-actions] + exclude: .svg diff --git a/src/nebula_continental/nebula_continental/design/NebulaArs548.node.yaml b/src/nebula_continental/nebula_continental/design/NebulaArs548.node.yaml new file mode 100644 index 000000000..02e7e8d41 --- /dev/null +++ b/src/nebula_continental/nebula_continental/design/NebulaArs548.node.yaml @@ -0,0 +1,89 @@ +autoware_system_design_format: 0.3.0 + +name: NebulaArs548.node + +package: + name: nebula_continental + provider: nebula + +launch: + plugin: nebula::ros::ContinentalARS548RosWrapper + executable: continental_ars548_ros_wrapper_node + node_output: screen + +# interfaces +subscribers: + - name: odometry_input + message_type: geometry_msgs/msg/TwistWithCovarianceStamped + remap_target: odometry_input + - name: acceleration_input + message_type: geometry_msgs/msg/AccelWithCovarianceStamped + remap_target: acceleration_input + - name: steering_angle_input + message_type: std_msgs/msg/Float32 + remap_target: steering_angle_input +publishers: + - name: nebula_packets + message_type: nebula_msgs/msg/NebulaPackets + remap_target: nebula_packets + - name: continental_detections + message_type: continental_msgs/msg/ContinentalArs548DetectionList + remap_target: continental_detections + - name: continental_objects + message_type: continental_msgs/msg/ContinentalArs548ObjectList + remap_target: continental_objects + - name: detection_points + message_type: sensor_msgs/msg/PointCloud2 + remap_target: detection_points + - name: object_points + message_type: sensor_msgs/msg/PointCloud2 + remap_target: object_points + - name: scan_raw + message_type: radar_msgs/msg/RadarScan + remap_target: scan_raw + - name: objects_raw + message_type: radar_msgs/msg/RadarTracks + remap_target: objects_raw + - name: marker_array + message_type: visualization_msgs/msg/MarkerArray + remap_target: marker_array + - name: radar_objects + message_type: autoware_sensing_msgs/msg/RadarObjects + remap_target: radar_objects + - name: radar_info + message_type: autoware_sensing_msgs/msg/RadarInfo + remap_target: radar_info + +# parameters +param_files: + - name: config_file + default: config/ARS548.param.yaml + schema: schema/ARS548.schema.json + allow_substs: true + +param_values: + - name: launch_hw + type: bool + default: true + +# processes +processes: + - name: hw_interface + trigger_conditions: + - periodic: 100 # Hz + outcomes: + - to_output: nebula_packets + - name: decoder + trigger_conditions: + - periodic: 10 # Hz + outcomes: + - to_output: continental_objects + - to_output: continental_detections + - to_output: detection_points + - to_output: object_points + - to_output: radar_objects + - to_output: scan_raw + - to_output: objects_raw + - to_output: marker_array + - to_output: diagnostics + - to_output: radar_info diff --git a/src/nebula_continental/nebula_continental/design/NebulaArs548_decode.node.yaml b/src/nebula_continental/nebula_continental/design/NebulaArs548_decode.node.yaml new file mode 100644 index 000000000..49b3e5ed7 --- /dev/null +++ b/src/nebula_continental/nebula_continental/design/NebulaArs548_decode.node.yaml @@ -0,0 +1,40 @@ +autoware_system_design_format: 0.3.0 + +name: NebulaArs548_decode.node + +base: NebulaArs548.node + +override: + subscribers: + - name: nebula_packets + message_type: nebula_msgs/msg/NebulaPackets + remap_target: nebula_packets + processes: + - name: decoder + trigger_conditions: + - from_input: nebula_packets + outcomes: + - to_output: continental_objects + - to_output: continental_detections + - to_output: detection_points + - to_output: object_points + - to_output: radar_objects + - to_output: scan_raw + - to_output: objects_raw + - to_output: marker_array + - to_output: diagnostics + - to_output: radar_info + param_values: + - name: launch_hw + type: bool + default: false + +remove: + subscribers: + - name: odometry_input + - name: acceleration_input + - name: steering_angle_input + publishers: + - name: nebula_packets + processes: + - name: hw_interface diff --git a/src/nebula_hesai/nebula_hesai/design/NebulaHesaiPandar128E4X.node.yaml b/src/nebula_hesai/nebula_hesai/design/NebulaHesaiPandar128E4X.node.yaml new file mode 100644 index 000000000..19dc28dbc --- /dev/null +++ b/src/nebula_hesai/nebula_hesai/design/NebulaHesaiPandar128E4X.node.yaml @@ -0,0 +1,74 @@ +autoware_system_design_format: 0.3.0 + +name: NebulaHesaiPandar128E4X.node + +package: + name: nebula_hesai + provider: nebula + +launch: + plugin: HesaiRosWrapper + executable: hesai_ros_wrapper_node + node_output: screen + +# interfaces +subscribers: [] + +publishers: + - name: pandar_packets + message_type: pandar_msgs/msg/PandarScan + remap_target: pandar_packets + qos: + depth: 10 + reliability: best_effort + - name: pandar_points + message_type: sensor_msgs/msg/PointCloud2 + remap_target: pandar_points + qos: + depth: 10 + reliability: best_effort + - name: aw_points + message_type: sensor_msgs/msg/PointCloud2 + remap_target: aw_points + qos: + depth: 10 + reliability: best_effort + - name: aw_points_ex + message_type: sensor_msgs/msg/PointCloud2 + remap_target: aw_points_ex + qos: + depth: 10 + reliability: best_effort + - name: blockage_mask + message_type: sensor_msgs/msg/Image + remap_target: blockage_mask + +# parameters +param_files: + - name: config_file + default: config/Pandar128E4X.param.yaml + schema: schema/Pandar128E4X.schema.json + allow_substs: true + +param_values: + - name: launch_hw + type: boolean + default: true + - name: point_filters.downsample_mask.path + type: string + default: "" + +# processes +processes: + - name: hw_interface + trigger_conditions: + - periodic: 10.0 # Hz + outcomes: + - to_output: pandar_packets + - name: decoder + trigger_conditions: + - and: + - on_trigger: hw_interface + - periodic: 10 # Hz + outcomes: + - to_output: pandar_points diff --git a/src/nebula_hesai/nebula_hesai/design/NebulaHesaiPandar128E4X_decode.node.yaml b/src/nebula_hesai/nebula_hesai/design/NebulaHesaiPandar128E4X_decode.node.yaml new file mode 100644 index 000000000..2918e06b8 --- /dev/null +++ b/src/nebula_hesai/nebula_hesai/design/NebulaHesaiPandar128E4X_decode.node.yaml @@ -0,0 +1,27 @@ +autoware_system_design_format: 0.3.0 + +name: NebulaHesaiPandar128E4X_decode.node + +base: NebulaHesaiPandar128E4X.node + +override: + subscribers: + - name: pandar_packets + message_type: pandar_msgs/msg/PandarScan + remap_target: pandar_packets + processes: + - name: decoder + trigger_conditions: + - from_input: pandar_packets + outcomes: + - to_output: pandar_points + param_values: + - name: launch_hw + type: bool + default: false + +remove: + publishers: + - name: pandar_packets + processes: + - name: hw_interface diff --git a/src/nebula_velodyne/nebula_velodyne/design/NebulaVelodyneVLP16.node.yaml b/src/nebula_velodyne/nebula_velodyne/design/NebulaVelodyneVLP16.node.yaml new file mode 100644 index 000000000..9be9e4c0c --- /dev/null +++ b/src/nebula_velodyne/nebula_velodyne/design/NebulaVelodyneVLP16.node.yaml @@ -0,0 +1,66 @@ +autoware_system_design_format: 0.3.0 + +name: NebulaVelodyneVLP16.node + +package: + name: nebula_velodyne + provider: nebula + +launch: + plugin: VelodyneRosWrapper + executable: velodyne_ros_wrapper_node + node_output: screen + +# interfaces +subscribers: [] + +publishers: + - name: velodyne_packets + message_type: velodyne_msgs/msg/VelodyneScan + remap_target: velodyne_packets + qos: + depth: 10 + reliability: best_effort + - name: velodyne_points + message_type: sensor_msgs/msg/PointCloud2 + remap_target: velodyne_points + qos: + depth: 10 + reliability: best_effort + - name: aw_points + message_type: sensor_msgs/msg/PointCloud2 + remap_target: aw_points + qos: + depth: 10 + reliability: best_effort + - name: aw_points_ex + message_type: sensor_msgs/msg/PointCloud2 + remap_target: aw_points_ex + qos: + depth: 10 + reliability: best_effort + +# parameters +param_files: + - name: config_file + default: config/VLP16.param.yaml + schema: schema/VLP16.schema.json + allow_substs: true + +param_values: + - name: launch_hw + type: bool + default: true + +# processes +processes: + - name: hw_interface + trigger_conditions: + - periodic: 100 # Hz + outcomes: + - to_output: velodyne_packets + - name: decoder + trigger_conditions: + - periodic: 10 # Hz + outcomes: + - to_output: velodyne_points diff --git a/src/nebula_velodyne/nebula_velodyne/design/NebulaVelodyneVLP16_decode.node.yaml b/src/nebula_velodyne/nebula_velodyne/design/NebulaVelodyneVLP16_decode.node.yaml new file mode 100644 index 000000000..de87bef9a --- /dev/null +++ b/src/nebula_velodyne/nebula_velodyne/design/NebulaVelodyneVLP16_decode.node.yaml @@ -0,0 +1,27 @@ +autoware_system_design_format: 0.3.0 + +name: NebulaVelodyneVLP16_decode.node + +base: NebulaVelodyneVLP16.node + +override: + subscribers: + - name: velodyne_packets + message_type: velodyne_msgs/msg/VelodyneScan + remap_target: velodyne_packets + processes: + - name: decoder + trigger_conditions: + - from_input: velodyne_packets + outcomes: + - to_output: velodyne_points + param_values: + - name: launch_hw + type: bool + default: false + +remove: + publishers: + - name: velodyne_packets + processes: + - name: hw_interface diff --git a/src/nebula_velodyne/nebula_velodyne/design/NebulaVelodyneVLS128.node.yaml b/src/nebula_velodyne/nebula_velodyne/design/NebulaVelodyneVLS128.node.yaml new file mode 100644 index 000000000..a44ce8d68 --- /dev/null +++ b/src/nebula_velodyne/nebula_velodyne/design/NebulaVelodyneVLS128.node.yaml @@ -0,0 +1,66 @@ +autoware_system_design_format: 0.3.0 + +name: NebulaVelodyneVLS128.node + +package: + name: nebula_velodyne + provider: nebula + +launch: + plugin: VelodyneRosWrapper + executable: velodyne_ros_wrapper_node + node_output: screen + +# interfaces +subscribers: [] + +publishers: + - name: velodyne_packets + message_type: velodyne_msgs/msg/VelodyneScan + remap_target: velodyne_packets + qos: + depth: 10 + reliability: best_effort + - name: velodyne_points + message_type: sensor_msgs/msg/PointCloud2 + remap_target: velodyne_points + qos: + depth: 10 + reliability: best_effort + - name: aw_points + message_type: sensor_msgs/msg/PointCloud2 + remap_target: aw_points + qos: + depth: 10 + reliability: best_effort + - name: aw_points_ex + message_type: sensor_msgs/msg/PointCloud2 + remap_target: aw_points_ex + qos: + depth: 10 + reliability: best_effort + +# parameters +param_files: + - name: config_file + default: config/VLS128.param.yaml + schema: schema/VLS128.schema.json + allow_substs: true + +param_values: + - name: launch_hw + type: bool + default: true + +# processes +processes: + - name: hw_interface + trigger_conditions: + - periodic: 100 # Hz + outcomes: + - to_output: velodyne_packets + - name: decoder + trigger_conditions: + - periodic: 10 # Hz + outcomes: + - to_output: velodyne_points diff --git a/src/nebula_velodyne/nebula_velodyne/design/NebulaVelodyneVLS128_decode.node.yaml b/src/nebula_velodyne/nebula_velodyne/design/NebulaVelodyneVLS128_decode.node.yaml new file mode 100644 index 000000000..e23f086c8 --- /dev/null +++ b/src/nebula_velodyne/nebula_velodyne/design/NebulaVelodyneVLS128_decode.node.yaml @@ -0,0 +1,27 @@ +autoware_system_design_format: 0.3.0 + +name: NebulaVelodyneVLS128_decode.node + +base: NebulaVelodyneVLS128.node + +override: + subscribers: + - name: velodyne_packets + message_type: velodyne_msgs/msg/VelodyneScan + remap_target: velodyne_packets + processes: + - name: decoder + trigger_conditions: + - from_input: velodyne_packets + outcomes: + - to_output: velodyne_points + param_values: + - name: launch_hw + type: bool + default: false + +remove: + publishers: + - name: velodyne_packets + processes: + - name: hw_interface