From 18ba094bab5b99626a4078099275c31943da05d2 Mon Sep 17 00:00:00 2001 From: Diego Hu Date: Wed, 24 Jun 2020 06:05:14 +0800 Subject: [PATCH] D-KIT: Add two mode for D-KIT (#11529) * Update Dev Kit Calibration files set * add DEV_KIT mode in HMI modes * Add two hmi mode, one for closeloop, one for debug * add camera driver for dev kit close loop * remove planning related conf * move dev kit perception launch to calibration/data * update vehicle_data.pb.txt --- .../Perception_Configuration_cn.md | 5 +- .../Perception_Configuration_cn.md | 8 +- .../localization_conf/localization.conf | 213 ++++++++++++++++++ ...ag_streaming_perception_dev_kit_camera.dag | 11 + ...ag_streaming_perception_dev_kit_lidar.dag} | 0 .../dev_kit_perception_camera.launch | 2 +- .../dev_kit_perception_lidar.launch} | 2 +- .../conf/hmi_modes/dev_kit_close_loop.pb.txt | 144 ++++++++++++ .../conf/hmi_modes/dev_kit_debug.pb.txt | 167 ++++++++++++++ modules/dreamview/conf/vehicle_data.pb.txt | 16 ++ 10 files changed, 560 insertions(+), 8 deletions(-) create mode 100644 modules/calibration/data/dev_kit/localization_conf/localization.conf create mode 100644 modules/calibration/data/dev_kit/perception_dag/dag_streaming_perception_dev_kit_camera.dag rename modules/{perception/production/dag/dev_kit_dag_streaming_perception.dag => calibration/data/dev_kit/perception_dag/dag_streaming_perception_dev_kit_lidar.dag} (100%) rename modules/{perception/production/launch => calibration/data/dev_kit/perception_launch}/dev_kit_perception_camera.launch (92%) rename modules/{perception/production/launch/dev_kit_perception.launch => calibration/data/dev_kit/perception_launch/dev_kit_perception_lidar.launch} (92%) create mode 100644 modules/dreamview/conf/hmi_modes/dev_kit_close_loop.pb.txt create mode 100644 modules/dreamview/conf/hmi_modes/dev_kit_debug.pb.txt diff --git a/docs/specs/D-kit/Camera_Based_Auto_Driving/Perception_Configuration_cn.md b/docs/specs/D-kit/Camera_Based_Auto_Driving/Perception_Configuration_cn.md index 957bd787a1..398d4686cb 100644 --- a/docs/specs/D-kit/Camera_Based_Auto_Driving/Perception_Configuration_cn.md +++ b/docs/specs/D-kit/Camera_Based_Auto_Driving/Perception_Configuration_cn.md @@ -32,8 +32,7 @@ |序号 | 待修改文件 | 修改内容 | |---|---|---| | 1 | `modules/common/data/global_flagfile.txt` | 添加`--half_vehicle_width=0.43` | -| 2 | `modules/perception/production/launch/dev_kit_perception_camera.launch` |重命名为`perception_camera.launch ` 并替换原`perception_camera.launch`文件 | -| 3 | `modules/perception/production/conf/perception/camera/fusion_camera_detection_component.pb.txt` | 文件中`output_obstacles_channel_name`对应的内容修改为 `/apollo/perception/obstacles` | +| 2 | `modules/perception/production/conf/perception/camera/fusion_camera_detection_component.pb.txt` | 文件中`output_obstacles_channel_name`对应的内容修改为 `/apollo/perception/obstacles` | ## 启动Camera感知 @@ -70,7 +69,7 @@ 使用如下命令启动perception模块,使用`cyber_monitor`查看`/apollo/perception/obstacles`是否正常输出,并在dreamview上查看障碍物信息: ``` -budaoshi@in_dev_docker:/apollo$ cyber_launch start modules/perception/production/launch/perception_camera.launch +budaoshi@in_dev_docker:/apollo$ cyber_launch start modules/perception/production/launch/dev_kit_perception_camera.launch ``` #### 5. 验证Camera感知效果 查看车前方运动的人或者自行车(自行车上要有人),在DreamView上查看障碍物颜色以及位置速度信息(自行车青蓝色,行人黄色,车辆绿色),如下图所示: diff --git a/docs/specs/D-kit/Lidar_Based_Auto_Driving/Perception_Configuration_cn.md b/docs/specs/D-kit/Lidar_Based_Auto_Driving/Perception_Configuration_cn.md index 92c3dc287a..0232b24a49 100644 --- a/docs/specs/D-kit/Lidar_Based_Auto_Driving/Perception_Configuration_cn.md +++ b/docs/specs/D-kit/Lidar_Based_Auto_Driving/Perception_Configuration_cn.md @@ -30,8 +30,6 @@ |序号 | 待修改文件 | 修改内容 | |---|---|---| | 1 | `modules/common/data/global_flagfile.txt` | 添加`--half_vehicle_width=0.43` | -| 2 | `modules/perception/production/launch/dev_kit_perception.launch` |重命名为`perception.launch` 并替换原`perception.launch`文件 | -| 3 | `modules/perception/production/dag/dev_kit_dag_streaming_perception.dag` | 重命名为`dag_streaming_perception.dag` 并替换原`dag_streaming_perception.dag`文件| ## 启动Lidar感知 @@ -72,7 +70,11 @@ |`/tf_static`|确保能正常输出数据| #### 4. 启动Lidar感知 -确认各模块正常启动且channel输出正常后,在DreamView上启动Lidar感知模块(Perception模块),使用`cyber_monitor`查看`/apollo/perception/obstacles`是否正常输出 +使用如下命令启动perception模块,使用`cyber_monitor`查看`/apollo/perception/obstacles`是否正常输出,并在dreamview上查看障碍物信息: + +``` +budaoshi@in_dev_docker:/apollo$ cyber_launch start modules/perception/production/launch/dev_kit_perception_lidar.launch +``` ![lidar_adaptation_dreamview3](images/lidar_adaptation_dreamview3.png) ## 验证Lidar感知效果 diff --git a/modules/calibration/data/dev_kit/localization_conf/localization.conf b/modules/calibration/data/dev_kit/localization_conf/localization.conf new file mode 100644 index 0000000000..e3a82cb996 --- /dev/null +++ b/modules/calibration/data/dev_kit/localization_conf/localization.conf @@ -0,0 +1,213 @@ +--flagfile=/apollo/modules/common/data/global_flagfile.txt +--noenable_gps_imu_interprolate + +# Redefine the map_dir of global_flagfile.txt +#--map_dir=/apollo/modules/localization/testdata + +# The directory name of localization map. +# type: string +# default: local_map +--local_map_name=local_map + +# Enable lidar-based localization. +# type: bool +# defalult: true +--enable_lidar_localization=true + +# Localization mode, 0 for intensity, 1 for altitude, 2 for fusion. +# type: int +# default: 2 +--lidar_localization_mode=2 + +# image yaw align mode, 0 for align off, 1 for fusion, 2 for fusion with multithread. +# type: int +# default: 2 +--lidar_yaw_align_mode=2 + +# Lidar filter size +# type: int +# default: 11 +--lidar_filter_size=17 + +# point cloud step +# type: int +# default: 2 +--point_cloud_step=2 + +# The height from the center of lidar to ground plane +# type: double +# default: 1.80 +--lidar_height_default=1.80 + +# idar msg and imu msg max delay time. +# type: double +# default: 0.4 +--lidar_imu_lidar_max_delay_time=0.4 + +# The valid coverage of pointcloud and map. +# type: double +# default: 0.8 +--lidar_map_coverage_theshold=0.8 + +# Lidar debug switch. +# type: bool +# default: false +--lidar_debug_log_flag=false + +# integ_ins_can_self_align. +# type: bool +# default: false +--integ_ins_can_self_align=false + +# integ_sins_align_with_vel. +# type: bool +# default: true +--integ_sins_align_with_vel=true + +# Whether check state of sins. If true, sins will restart in bad state. +# type: bool +# default: true +--integ_sins_state_check=true + +# The param of sins state check. +# type: double +# default: 30.0 +--integ_sins_state_span_time=30.0 + +# The param of sins state check. +# type: double +# default: 1.0 +--integ_sins_state_pos_std=1.0 + +# vel_threshold_get_yaw. +# type: double +# default: 5.0 +--vel_threshold_get_yaw=5.0 + +# enable flag ins_aid_rtk. +# type: bool +# default: false +--enable_ins_aid_rtk=false + +# eph_buffer_path. +# type: string +# default: "" +--eph_buffer_path="" + +# gnss_debug_log_flag. +# type: bool +# default: false +--gnss_debug_log_flag=false + +# imu_rate. +# type: double +# default: 1.0 +--imu_rate=1.0 + +# Whether load utm zone id from local map folder +# type: bool +# default: true +--if_utm_zone_id_from_folder=true + +# local_utm_zone_id. +# type: int +# default: int +--local_utm_zone_id=50 + +# trans_gpstime_to_utctime. +# type: bool +# default: true +--trans_gpstime_to_utctime=true + +# GNSS Mode, 0 for bestgnss pose, 1 for self gnss. +# type: string +# default: 0 +--gnss_mode=0 + +# The pointcloud topic name. +# type: string +# default: /apollo/sensor/velodyne64/compensator/PointCloud2 +--lidar_topic=/apollo/sensor/lidar128/compensator/PointCloud2 + +# The lidar extrinsics file +# type: string +# default: /apollo/modules/localization/msf/params/velodyne_params/velodyne128_novatel_extrinsics.yaml +--lidar_extrinsics_file=/apollo/modules/localization/msf/params/velodyne_params/velodyne128_novatel_extrinsics.yaml + +# imu coordinate, true->flu, false->rfu +# type: bool +# default: true +--imu_coord_rfu=true + +# Whether use bestgnsspose as measure after initializaiton. +# type: bool +# default: false +--gnss_only_init=false + +# Whether use imu ant leverarm from ant imu yaml file +# type: bool +# default: true +--if_imuant_from_file=true + +# Imu ant offset x +# type: double +# default: 0.0 +--imu_to_ant_offset_x=0.0 + +# Imu ant offset y +# type: double +# default: 0.0 +--imu_to_ant_offset_y=0.788 + +# Imu ant offset z +# type: double +# default: 0.0 +--imu_to_ant_offset_z=1.077 + +# Imu ant offset x uncertainty +# type: double +# default: 0.0 +--imu_to_ant_offset_ux=0.05 + +# Imu ant offset y uncertainty +# type: double +# default: 0.0 +--imu_to_ant_offset_uy=0.05 + +# Imu ant offset z uncertainty +# type: double +# default: 0.0 +--imu_to_ant_offset_uz=0.08 + +# Whether load vehicle coord to imu coord quaternion from yaml file +# type: bool +# default: true +--if_vehicle_imu_from_file=true + +# vehicle coord to imu coord quaternion qx +# type: double +# default: 0.0 +--imu_vehicle_qx=0.0 + +# vehicle coord to imu coord quaternion qy +# type: double +# default: 0.0 +--imu_vehicle_qy=0.0 + +# vehicle coord to imu coord quaternion qz +# type: double +# default: 0.0 +--imu_vehicle_qz=0.0 + +# vehicle coord to imu coord quaternion qw +# type: double +# default: 1.0 +--imu_vehicle_qw=1.0 + +# The tem folder for localziation visualziation +--map_visual_dir=data/map_visual + +# if use avx to accelerate lidar localization +# need cpu to support avx intel intrinsics +# default: false +--if_use_avx=true diff --git a/modules/calibration/data/dev_kit/perception_dag/dag_streaming_perception_dev_kit_camera.dag b/modules/calibration/data/dev_kit/perception_dag/dag_streaming_perception_dev_kit_camera.dag new file mode 100644 index 0000000000..6f7c1c6c77 --- /dev/null +++ b/modules/calibration/data/dev_kit/perception_dag/dag_streaming_perception_dev_kit_camera.dag @@ -0,0 +1,11 @@ +module_config { + module_library : "/apollo/bazel-bin/modules/perception/onboard/component/libperception_component_camera.so" + components { + class_name : "FusionCameraDetectionComponent" + config { + name: "FusionCameraComponent" + config_file_path: "/apollo/modules/perception/production/conf/perception/camera/fusion_camera_detection_component.pb.txt" + flag_file_path: "/apollo/modules/perception/production/conf/perception/perception_common.flag" + } + } +} diff --git a/modules/perception/production/dag/dev_kit_dag_streaming_perception.dag b/modules/calibration/data/dev_kit/perception_dag/dag_streaming_perception_dev_kit_lidar.dag similarity index 100% rename from modules/perception/production/dag/dev_kit_dag_streaming_perception.dag rename to modules/calibration/data/dev_kit/perception_dag/dag_streaming_perception_dev_kit_lidar.dag diff --git a/modules/perception/production/launch/dev_kit_perception_camera.launch b/modules/calibration/data/dev_kit/perception_launch/dev_kit_perception_camera.launch similarity index 92% rename from modules/perception/production/launch/dev_kit_perception_camera.launch rename to modules/calibration/data/dev_kit/perception_launch/dev_kit_perception_camera.launch index 88052a670a..eef364a88b 100755 --- a/modules/perception/production/launch/dev_kit_perception_camera.launch +++ b/modules/calibration/data/dev_kit/perception_launch/dev_kit_perception_camera.launch @@ -12,7 +12,7 @@ perception_camera - /apollo/modules/perception/production/dag/dag_streaming_perception_camera.dag + /apollo/modules/perception/production/dag/dag_streaming_perception_dev_kit_camera.dag 1.0.0 diff --git a/modules/perception/production/launch/dev_kit_perception.launch b/modules/calibration/data/dev_kit/perception_launch/dev_kit_perception_lidar.launch similarity index 92% rename from modules/perception/production/launch/dev_kit_perception.launch rename to modules/calibration/data/dev_kit/perception_launch/dev_kit_perception_lidar.launch index 419589629c..b8df442333 100755 --- a/modules/perception/production/launch/dev_kit_perception.launch +++ b/modules/calibration/data/dev_kit/perception_launch/dev_kit_perception_lidar.launch @@ -10,7 +10,7 @@ perception - /apollo/modules/perception/production/dag/dag_streaming_perception.dag + /apollo/modules/perception/production/dag/dag_streaming_perception_dev_kit_lidar.dag lidar_perception 1.0.0 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 new file mode 100644 index 0000000000..f74080e26a --- /dev/null +++ b/modules/dreamview/conf/hmi_modes/dev_kit_close_loop.pb.txt @@ -0,0 +1,144 @@ +cyber_modules { + key: "Camera" + value: { + dag_files: "/apollo/modules/drivers/camera/dag/camera.dag" + dag_files: "/apollo/modules/drivers/video/dag/video.dag" + required_for_safety: false + } +} +cyber_modules { + key: "Lidar" + value: { + dag_files: "/apollo/modules/drivers/velodyne/dag/velodyne16.dag" + } +} +cyber_modules { + key: "Canbus" + value: { + dag_files: "/apollo/modules/canbus/dag/canbus.dag" + } +} +cyber_modules { + key: "Control" + value: { + dag_files: "/apollo/modules/control/dag/control.dag" + } +} +cyber_modules { + key: "GPS" + value: { + dag_files: "/apollo/modules/drivers/gnss/dag/gnss.dag" + } +} +cyber_modules { + key: "Guardian" + value: { + dag_files: "/apollo/modules/guardian/dag/guardian.dag" + } +} +cyber_modules { + key: "Localization" + value: { + dag_files: "/apollo/modules/localization/dag/dag_streaming_msf_localization.dag" + } +} +cyber_modules { + key: "Lidar Perception" + value: { + dag_files: "/apollo/modules/perception/production/dag/dag_streaming_perception_dev_kit_lidar.dag" + } +} +cyber_modules { + key: "Traffic Light" + value: { + dag_files: "/apollo/modules/perception/production/dag/dag_streaming_perception_trafficlights.dag" + required_for_safety: false + } +} +cyber_modules { + key: "Planning" + value: { + dag_files: "/apollo/modules/planning/dag/planning.dag" + } +} +cyber_modules { + key: "Prediction" + value: { + dag_files: "/apollo/modules/prediction/dag/prediction.dag" + } +} +cyber_modules { + key: "Routing" + value: { + dag_files: "/apollo/modules/routing/dag/routing.dag" + } +} +cyber_modules { + key: "Transform" + value: { + dag_files: "/apollo/modules/transform/dag/static_transform.dag" + } +} +modules { + key: "Recorder" + value: { + start_command: "/apollo/scripts/record_bag.py --start" + stop_command: "/apollo/scripts/record_bag.py --stop" + process_monitor_config { + command_keywords: "cyber_recorder record" + } + } +} +monitored_components { + key: "Recorder" + value: { + process { + command_keywords: "cyber_recorder record" + } + resource { + disk_spaces { + # For logs. + path: "/apollo/data" + insufficient_space_warning: 8 + insufficient_space_error: 2 + } + disk_spaces { + # For records. + path: "/media/apollo/internal_nvme" + insufficient_space_warning: 128 + insufficient_space_error: 32 + } + } + } +} +monitored_components { + key: "GPS" + value: { + process { + command_keywords: "mainboard" + command_keywords: "/apollo/modules/drivers/gnss/dag/gnss.dag" + } + # We also have a special GPSMonitor to check message status. + } +} +monitored_components { + key: "Localization" + value: { + # Special LocalizationMonitor. + } +} +# Disbale ESD-CAN for a while as in some cars we are using B-CAN. +# monitored_components { +# key: "ESD-CAN" +# value: { +# # Special EsdCanMonitor. +# } +# } +monitored_components { + key: "Lidar 16" + value: { + channel { + name: "/apollo/sensor/lidar16/compensator/PointCloud2" + } + } +} diff --git a/modules/dreamview/conf/hmi_modes/dev_kit_debug.pb.txt b/modules/dreamview/conf/hmi_modes/dev_kit_debug.pb.txt new file mode 100644 index 0000000000..c693459021 --- /dev/null +++ b/modules/dreamview/conf/hmi_modes/dev_kit_debug.pb.txt @@ -0,0 +1,167 @@ +cyber_modules { + key: "Camera" + value: { + dag_files: "/apollo/modules/drivers/camera/dag/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" + } +} +cyber_modules { + key: "Canbus" + value: { + dag_files: "/apollo/modules/canbus/dag/canbus.dag" + } +} +cyber_modules { + key: "Control" + value: { + dag_files: "/apollo/modules/control/dag/control.dag" + } +} +cyber_modules { + key: "GPS" + value: { + dag_files: "/apollo/modules/drivers/gnss/dag/gnss.dag" + } +} +cyber_modules { + key: "Guardian" + value: { + dag_files: "/apollo/modules/guardian/dag/guardian.dag" + } +} +cyber_modules { + key: "Localization" + value: { + dag_files: "/apollo/modules/localization/dag/dag_streaming_msf_localization.dag" + } +} +cyber_modules { + key: "Lidar Perception" + value: { + dag_files: "/apollo/modules/perception/production/dag/dag_streaming_perception_dev_kit_lidar.dag" + } +} +cyber_modules { + key: "Camera Perception" + value: { + dag_files: "/apollo/modules/perception/production/dag/dag_streaming_perception_dev_kit_camera.dag" + } +} +cyber_modules { + key: "Traffic Light" + value: { + dag_files: "/apollo/modules/perception/production/dag/dag_streaming_perception_trafficlights.dag" + } +} +cyber_modules { + key: "Planning" + value: { + dag_files: "/apollo/modules/planning/dag/planning.dag" + } +} +cyber_modules { + key: "Prediction" + value: { + dag_files: "/apollo/modules/prediction/dag/prediction.dag" + } +} +cyber_modules { + key: "Radar" + value: { + dag_files: "/apollo/modules/drivers/radar/conti_radar/dag/conti_radar.dag" + } +} +cyber_modules { + key: "Routing" + value: { + dag_files: "/apollo/modules/routing/dag/routing.dag" + } +} +cyber_modules { + key: "Transform" + value: { + dag_files: "/apollo/modules/transform/dag/static_transform.dag" + } +} + +cyber_modules { + key: "SmarterEye" + value: { + dag_files: "/apollo/modules/drivers/smartereye/dag/smartereye.dag" + } +} +cyber_modules { + key: "Third Party Perception" + value: { + dag_files: "/apollo/modules/third_party_perception/dag/third_party_perception.dag" + } +} +modules { + key: "Recorder" + value: { + start_command: "/apollo/scripts/record_bag.py --start" + stop_command: "/apollo/scripts/record_bag.py --stop" + process_monitor_config { + command_keywords: "cyber_recorder record" + } + } +} +monitored_components { + key: "Recorder" + value: { + process { + command_keywords: "cyber_recorder record" + } + resource { + disk_spaces { + # For logs. + path: "/apollo/data" + insufficient_space_warning: 8 + insufficient_space_error: 2 + } + disk_spaces { + # For records. + path: "/media/apollo/internal_nvme" + insufficient_space_warning: 128 + insufficient_space_error: 32 + } + } + } +} +monitored_components { + key: "GPS" + value: { + process { + command_keywords: "mainboard" + command_keywords: "/apollo/modules/drivers/gnss/dag/gnss.dag" + } + # We also have a special GPSMonitor to check message status. + } +} +monitored_components { + key: "Localization" + value: { + # Special LocalizationMonitor. + } +} +# Disbale ESD-CAN for a while as in some cars we are using B-CAN. +# monitored_components { +# key: "ESD-CAN" +# value: { +# # Special EsdCanMonitor. +# } +# } +monitored_components { + key: "Lidar 16" + value: { + channel { + name: "/apollo/sensor/lidar16/compensator/PointCloud2" + } + } +} diff --git a/modules/dreamview/conf/vehicle_data.pb.txt b/modules/dreamview/conf/vehicle_data.pb.txt index d1467d8334..cfd1c3508d 100644 --- a/modules/dreamview/conf/vehicle_data.pb.txt +++ b/modules/dreamview/conf/vehicle_data.pb.txt @@ -110,3 +110,19 @@ data_files { source_path: "transform_conf/static_transform_conf.pb.txt" dest_path: "/apollo/modules/transform/conf/static_transform_conf.pb.txt" } +data_files { + source_path: "planning_conf" + dest_path: "/apollo/modules/planning/conf" +} +data_files { + source_path: "localization_conf" + dest_path: "/apollo/modules/localization/conf" +} +data_files { + source_path: "perception_dag" + dest_path: "/apollo/modules/perception/production/dag" +} +data_files { + source_path: "perception_launch" + dest_path: "/apollo/modules/perception/production/launch" +} -- GitLab