hku-mars / Point-LIO

Other
767 stars 129 forks source link

hesai雷达 aft_mapped_to_init话题输出频率只有10hz #12

Closed 0ontheroad closed 1 year ago

0ontheroad commented 1 year ago

尊敬的作者,您好 首先十分感谢您开源了这么棒的工作!!其次我们也看到了代码中有hesai雷达的相关配置,但是我们在运行自己的数据集过程中,aft_mapped_to_init话题输出频率只有10HZ,是我们需要修改什么相关配置吗,以下是我们的配置参数,如果作者有相应的指教,将感激不尽!! common: lid_topic: "/hesai/pandar" imu_topic: "/imu/data" con_frame: false # true: if you need to combine several LiDAR frames into one con_frame_num: 1 # the number of frames combined cut_frame: false # true: if you need to cut one LiDAR frame into several subframes cut_frame_time_interval: 0.1 # should be integral fraction of 1 / LiDAR frequency
time_diff_lidar_to_imu: 0.0 # Time offset between LiDAR and IMU calibrated by other algorithms, e.g., LI-Init (find in Readme)

preprocess: lidar_type: 4 scan_line: 16 timestamp_unit: 2 # the unit of time/t field in the PointCloud2 rostopic: 0-second, 1-milisecond, 2-microsecond, 3-nanosecond. blind: 2.0

mapping: imu_en: true extrinsic_est_en: false # for aggressive motion, set this variable false imu_time_inte: 0.01 # = 1 / frequency of IMU satu_acc: 30.0 # the saturation value of IMU's acceleration. not related to the units satu_gyro: 35 # the saturation value of IMU's angular velocity. not related to the units acc_norm: 9.81 # 1.0 for g as unit, 9.81 for m/s^2 as unit of the IMU's acceleration lidar_meas_cov: 0.01 # 0.001 acc_cov_output: 500 gyr_cov_output: 1000 b_acc_cov: 0.0001 b_gyr_cov: 0.0001 imu_meas_acc_cov: 0.1 #0.1 # 2 imu_meas_omg_cov: 0.1 #0.1 # 2 gyr_cov_input: 0.01 # for IMU as input model acc_cov_input: 0.1 # for IMU as input model plane_thr: 0.1 # 0.05, the threshold for plane criteria, the smaller, the flatter a plane match_s: 81 fov_degree: 180 det_range: 100.0 gravity: [0.0, 0.0, -9.810] # [-0.30, 0.880, -9.76] # liosam [0.0, 9.810, 0.0] # # preknown gravity, use when imu_en is false or start from a non-stationary state extrinsic_T: [ 0, 0, 0.28] # ulhk # [-0.5, 1.4, 1.5] # utbm

extrinsic_R: [ 0, 1, 0,

#                -1, 0, 0,
#                0, 0, 1 ] # ulhk 5 6
# extrinsic_R: [ 0, -1, 0,
#                 1, 0, 0,
#                 0, 0, 1 ] # utbm 1, 2
extrinsic_R: [ 0, 1, 0,
               -1, 0, 0,
               0, 0, 1 ] # ulhk 4 utbm 3

odometry: publish_odometry_without_downsample: false

publish: path_en: true # false: close the path output scan_publish_en: true # false: close all the point cloud output scan_bodyframe_pub_en: false # true: output the point cloud scans in IMU-body-frame

pcd_save: pcd_save_en: false interval: -1 # how many LiDAR frames saved in each pcd file;

-1 : all frames will be saved in ONE pcd file, may lead to memory crash when having too much frames.

ouguangjun commented 1 year ago

publish_odometry_without_downsample 改为true

0ontheroad commented 1 year ago

成功输出了,感谢!!