From 5b62b0599ed111c3a5a6ff397e936b72f3e7d685 Mon Sep 17 00:00:00 2001 From: SeasoulChris <274224843@qq.com> Date: Thu, 10 Sep 2020 15:58:19 +0800 Subject: [PATCH] D-kit: change config file structure to adjust multiple lidars models --- .../dev_kit/camera_dag}/dev_kit_camera.dag | 0 .../lidar_compensator.pb.txt} | 0 .../lidar_conf.pb.txt} | 0 .../lidar_fusion_compensator.pb.txt} | 0 .../data/dev_kit/lidar_dag/lidar.dag | 40 +++++++++++++++++++ .../conf/hmi_modes/dev_kit_close_loop.pb.txt | 4 +- .../conf/hmi_modes/dev_kit_debug.pb.txt | 4 +- modules/dreamview/conf/vehicle_data.pb.txt | 8 ++++ .../lidar/conf/lidar_compensator.pb.txt | 3 ++ modules/drivers/lidar/conf/lidar_conf.pb.txt | 18 +++++++++ .../conf/lidar_fusion_compensator.pb.txt | 3 ++ modules/drivers/lidar/dag/lidar.dag | 40 +++++++++++++++++++ 12 files changed, 116 insertions(+), 4 deletions(-) rename modules/{drivers/camera/dag => calibration/data/dev_kit/camera_dag}/dev_kit_camera.dag (100%) rename modules/calibration/data/dev_kit/{velodyne_conf/velodyne16_compensator.pb.txt => lidar_conf/lidar_compensator.pb.txt} (100%) rename modules/calibration/data/dev_kit/{velodyne_conf/velodyne16_conf.pb.txt => lidar_conf/lidar_conf.pb.txt} (100%) rename modules/calibration/data/dev_kit/{velodyne_conf/velodyne16_fusion_compensator.pb.txt => lidar_conf/lidar_fusion_compensator.pb.txt} (100%) create mode 100755 modules/calibration/data/dev_kit/lidar_dag/lidar.dag create mode 100644 modules/drivers/lidar/conf/lidar_compensator.pb.txt create mode 100644 modules/drivers/lidar/conf/lidar_conf.pb.txt create mode 100644 modules/drivers/lidar/conf/lidar_fusion_compensator.pb.txt create mode 100755 modules/drivers/lidar/dag/lidar.dag diff --git a/modules/drivers/camera/dag/dev_kit_camera.dag b/modules/calibration/data/dev_kit/camera_dag/dev_kit_camera.dag similarity index 100% rename from modules/drivers/camera/dag/dev_kit_camera.dag rename to modules/calibration/data/dev_kit/camera_dag/dev_kit_camera.dag diff --git a/modules/calibration/data/dev_kit/velodyne_conf/velodyne16_compensator.pb.txt b/modules/calibration/data/dev_kit/lidar_conf/lidar_compensator.pb.txt similarity index 100% rename from modules/calibration/data/dev_kit/velodyne_conf/velodyne16_compensator.pb.txt rename to modules/calibration/data/dev_kit/lidar_conf/lidar_compensator.pb.txt diff --git a/modules/calibration/data/dev_kit/velodyne_conf/velodyne16_conf.pb.txt b/modules/calibration/data/dev_kit/lidar_conf/lidar_conf.pb.txt similarity index 100% rename from modules/calibration/data/dev_kit/velodyne_conf/velodyne16_conf.pb.txt rename to modules/calibration/data/dev_kit/lidar_conf/lidar_conf.pb.txt diff --git a/modules/calibration/data/dev_kit/velodyne_conf/velodyne16_fusion_compensator.pb.txt b/modules/calibration/data/dev_kit/lidar_conf/lidar_fusion_compensator.pb.txt similarity index 100% rename from modules/calibration/data/dev_kit/velodyne_conf/velodyne16_fusion_compensator.pb.txt rename to modules/calibration/data/dev_kit/lidar_conf/lidar_fusion_compensator.pb.txt diff --git a/modules/calibration/data/dev_kit/lidar_dag/lidar.dag b/modules/calibration/data/dev_kit/lidar_dag/lidar.dag new file mode 100755 index 0000000000..45f1487a42 --- /dev/null +++ b/modules/calibration/data/dev_kit/lidar_dag/lidar.dag @@ -0,0 +1,40 @@ +# Define all coms in DAG streaming. +module_config { + module_library : "/apollo/bazel-bin/modules/drivers/velodyne/driver/libvelodyne_driver_component.so" + + components { + class_name : "VelodyneDriverComponent" + config { + name : "velodyne_driver" + config_file_path : "/apollo/modules/drivers/lidar/conf/lidar_conf.pb.txt" + } + } +} + +module_config { + module_library : "/apollo/bazel-bin/modules/drivers/velodyne/parser/libvelodyne_convert_component.so" + + components { + class_name : "VelodyneConvertComponent" + config { + name : "velodyne_convert" + config_file_path : "/apollo/modules/drivers/lidar/conf/lidar_conf.pb.txt" + readers {channel: "/apollo/sensor/lidar16/Scan"} + } + } +} + +module_config { + module_library : "/apollo/bazel-bin/modules/drivers/velodyne/compensator/libvelodyne_compensator_component.so" + + components { + class_name : "CompensatorComponent" + config { + name : "velodyne_compensator" + config_file_path : "/apollo/modules/drivers/lidar/conf/lidar_fusion_compensator.pb.txt" + readers {channel: "/apollo/sensor/lidar16/PointCloud2"} + } + } +} + + diff --git a/modules/dreamview/conf/hmi_modes/dev_kit_close_loop.pb.txt b/modules/dreamview/conf/hmi_modes/dev_kit_close_loop.pb.txt index a92f931633..e4b1472e36 100644 --- a/modules/dreamview/conf/hmi_modes/dev_kit_close_loop.pb.txt +++ b/modules/dreamview/conf/hmi_modes/dev_kit_close_loop.pb.txt @@ -1,7 +1,7 @@ cyber_modules { key: "Camera" value: { - dag_files: "/apollo/modules/drivers/camera/dag/camera.dag" + dag_files: "/apollo/modules/drivers/camera/dag/dev_kit_camera.dag" dag_files: "/apollo/modules/drivers/video/dag/video.dag" required_for_safety: false } @@ -9,7 +9,7 @@ cyber_modules { cyber_modules { key: "Lidar" value: { - dag_files: "/apollo/modules/drivers/velodyne/dag/velodyne16.dag" + dag_files: "/apollo/modules/drivers/lidar/dag/lidar.dag" } } cyber_modules { diff --git a/modules/dreamview/conf/hmi_modes/dev_kit_debug.pb.txt b/modules/dreamview/conf/hmi_modes/dev_kit_debug.pb.txt index 97eaa2d966..36d02047b1 100644 --- a/modules/dreamview/conf/hmi_modes/dev_kit_debug.pb.txt +++ b/modules/dreamview/conf/hmi_modes/dev_kit_debug.pb.txt @@ -1,14 +1,14 @@ cyber_modules { key: "Camera" value: { - dag_files: "/apollo/modules/drivers/camera/dag/camera.dag" + dag_files: "/apollo/modules/drivers/camera/dag/dev_kit_camera.dag" dag_files: "/apollo/modules/drivers/video/dag/video.dag" } } cyber_modules { key: "Lidar" value: { - dag_files: "/apollo/modules/drivers/velodyne/dag/velodyne16.dag" + dag_files: "/apollo/modules/drivers/lidar/dag/lidar.dag" } } cyber_modules { diff --git a/modules/dreamview/conf/vehicle_data.pb.txt b/modules/dreamview/conf/vehicle_data.pb.txt index 6856e0a71a..117bb17f36 100644 --- a/modules/dreamview/conf/vehicle_data.pb.txt +++ b/modules/dreamview/conf/vehicle_data.pb.txt @@ -138,3 +138,11 @@ data_files { source_path: "perception_launch" dest_path: "/apollo/modules/perception/production/launch" } +data_files { + source_path: "lidar_dag" + dest_path: "/apollo/modules/drivers/lidar/dag" +} +data_files { + source_path: "lidar_conf" + dest_path: "/apollo/modules/drivers/lidar/conf" +} \ No newline at end of file diff --git a/modules/drivers/lidar/conf/lidar_compensator.pb.txt b/modules/drivers/lidar/conf/lidar_compensator.pb.txt new file mode 100644 index 0000000000..10f8b069d9 --- /dev/null +++ b/modules/drivers/lidar/conf/lidar_compensator.pb.txt @@ -0,0 +1,3 @@ +world_frame_id: "world" +transform_query_timeout: 0.02 +output_channel: "/apollo/sensor/lidar16/compensator/PointCloud2" diff --git a/modules/drivers/lidar/conf/lidar_conf.pb.txt b/modules/drivers/lidar/conf/lidar_conf.pb.txt new file mode 100644 index 0000000000..de6364b9e0 --- /dev/null +++ b/modules/drivers/lidar/conf/lidar_conf.pb.txt @@ -0,0 +1,18 @@ +frame_id: "velodyne128" +scan_channel: "/apollo/sensor/lidar16/Scan" +rpm: 600.0 +model: VLP16 +mode: STRONGEST +prefix_angle: 18000 +firing_data_port: 2369 +positioning_data_port: 8309 +use_sensor_sync: false +max_range: 100.0 +min_range: 0.9 +use_gps_time: true +calibration_online: false +calibration_file: "/apollo/modules/drivers/velodyne/params/VLP16_calibration.yaml" +organized: false +convert_channel_name: "/apollo/sensor/lidar16/PointCloud2" +use_poll_sync: true +is_main_frame: true diff --git a/modules/drivers/lidar/conf/lidar_fusion_compensator.pb.txt b/modules/drivers/lidar/conf/lidar_fusion_compensator.pb.txt new file mode 100644 index 0000000000..10f8b069d9 --- /dev/null +++ b/modules/drivers/lidar/conf/lidar_fusion_compensator.pb.txt @@ -0,0 +1,3 @@ +world_frame_id: "world" +transform_query_timeout: 0.02 +output_channel: "/apollo/sensor/lidar16/compensator/PointCloud2" diff --git a/modules/drivers/lidar/dag/lidar.dag b/modules/drivers/lidar/dag/lidar.dag new file mode 100755 index 0000000000..45f1487a42 --- /dev/null +++ b/modules/drivers/lidar/dag/lidar.dag @@ -0,0 +1,40 @@ +# Define all coms in DAG streaming. +module_config { + module_library : "/apollo/bazel-bin/modules/drivers/velodyne/driver/libvelodyne_driver_component.so" + + components { + class_name : "VelodyneDriverComponent" + config { + name : "velodyne_driver" + config_file_path : "/apollo/modules/drivers/lidar/conf/lidar_conf.pb.txt" + } + } +} + +module_config { + module_library : "/apollo/bazel-bin/modules/drivers/velodyne/parser/libvelodyne_convert_component.so" + + components { + class_name : "VelodyneConvertComponent" + config { + name : "velodyne_convert" + config_file_path : "/apollo/modules/drivers/lidar/conf/lidar_conf.pb.txt" + readers {channel: "/apollo/sensor/lidar16/Scan"} + } + } +} + +module_config { + module_library : "/apollo/bazel-bin/modules/drivers/velodyne/compensator/libvelodyne_compensator_component.so" + + components { + class_name : "CompensatorComponent" + config { + name : "velodyne_compensator" + config_file_path : "/apollo/modules/drivers/lidar/conf/lidar_fusion_compensator.pb.txt" + readers {channel: "/apollo/sensor/lidar16/PointCloud2"} + } + } +} + + -- GitLab