Closed zwmisdu closed 4 years ago
After reading the pinned issue, I have figured out something.So about theh dataset in https://github.com/TixiaoShan/Stevens-VLP16-Datase, how to get the correct params?
Did you change the extrinsic matrix to identity matrix?
Did you change the extrinsic matrix to identity matrix?
Yes, with the config now I can run west.bag correctly, but the dataset from Stevens-VLP16-Dataset can not be applied (the names of the topics have been renamed to /points_raw and /imu_raw)
Try these settings:
lio_sam:
# Topics
pointCloudTopic: "velodyne_points" # Point cloud data
imuTopic: "imu/data" # IMU data
odomTopic: "odometry/imu" # IMU pre-preintegration odometry, same frequency as IMU
gpsTopic: "odometry/gpsz" # GPS odometry topic from navsat, see module_navsat.launch file
# GPS Settings
useImuHeadingInitialization: true # if using GPS data, set to "true"
useGpsElevation: false # if GPS elevation is bad, set to "false"
gpsCovThreshold: 2.0 # m^2, threshold for using GPS data
poseCovThreshold: 25.0 # m^2, threshold for using GPS data
# Export settings
savePCD: false # https://github.com/TixiaoShan/LIO-SAM/issues/3
savePCDDirectory: "/Downloads/LOAM/" # in your home folder, starts and ends with "/". Warning: the code deletes "LOAM" folder then recreates it. See "mapOptimization" for implementation
# Sensor Settings
N_SCAN: 16 # number of lidar channel (i.e., 16, 32, 64, 128)
Horizon_SCAN: 1800 # lidar horizontal resolution (Velodyne:1800, Ouster:512,1024,2048)
timeField: "time" # point timestamp field, Velodyne - "time", Ouster - "t"
downsampleRate: 1 # default: 1. Downsample your data if too many points. i.e., 16 = 64 / 4, 16 = 16 / 1
# IMU Settings
imuAccNoise: 3.9939570888238808e-03
imuGyrNoise: 1.5636343949698187e-03
imuAccBiasN: 6.4356659353532566e-05
imuGyrBiasN: 3.5640318696367613e-05
imuGravity: 9.80511
# Extrinsics (lidar -> IMU)
extrinsicTrans: [0.0, 0.0, 0.0]
# extrinsicRot: [-1, 0, 0,
# 0, 1, 0,
# 0, 0, -1]
# extrinsicRPY: [0, 1, 0,
# -1, 0, 0,
# 0, 0, 1]
extrinsicRot: [1, 0, 0,
0, 1, 0,
0, 0, 1]
extrinsicRPY: [1, 0, 0,
0, 1, 0,
0, 0, 1]
rosbag play 2018-05-18-14-49-12_0.bag --topic /velodyne_points /imu/data
Try these settings:
lio_sam: # Topics pointCloudTopic: "velodyne_points" # Point cloud data imuTopic: "imu/data" # IMU data odomTopic: "odometry/imu" # IMU pre-preintegration odometry, same frequency as IMU gpsTopic: "odometry/gpsz" # GPS odometry topic from navsat, see module_navsat.launch file # GPS Settings useImuHeadingInitialization: true # if using GPS data, set to "true" useGpsElevation: false # if GPS elevation is bad, set to "false" gpsCovThreshold: 2.0 # m^2, threshold for using GPS data poseCovThreshold: 25.0 # m^2, threshold for using GPS data # Export settings savePCD: false # https://github.com/TixiaoShan/LIO-SAM/issues/3 savePCDDirectory: "/Downloads/LOAM/" # in your home folder, starts and ends with "/". Warning: the code deletes "LOAM" folder then recreates it. See "mapOptimization" for implementation # Sensor Settings N_SCAN: 16 # number of lidar channel (i.e., 16, 32, 64, 128) Horizon_SCAN: 1800 # lidar horizontal resolution (Velodyne:1800, Ouster:512,1024,2048) timeField: "time" # point timestamp field, Velodyne - "time", Ouster - "t" downsampleRate: 1 # default: 1. Downsample your data if too many points. i.e., 16 = 64 / 4, 16 = 16 / 1 # IMU Settings imuAccNoise: 3.9939570888238808e-03 imuGyrNoise: 1.5636343949698187e-03 imuAccBiasN: 6.4356659353532566e-05 imuGyrBiasN: 3.5640318696367613e-05 imuGravity: 9.80511 # Extrinsics (lidar -> IMU) extrinsicTrans: [0.0, 0.0, 0.0] # extrinsicRot: [-1, 0, 0, # 0, 1, 0, # 0, 0, -1] # extrinsicRPY: [0, 1, 0, # -1, 0, 0, # 0, 0, 1] extrinsicRot: [1, 0, 0, 0, 1, 0, 0, 0, 1] extrinsicRPY: [1, 0, 0, 0, 1, 0, 0, 0, 1]
rosbag play 2018-05-18-14-49-12_0.bag --topic /velodyne_points /imu/data
Thanks and I rebuild the workspace with the lastest source code, it works.
Thank you for your work again! When I use the dataset in https://github.com/TixiaoShan/Stevens-VLP16-Dataset or my own dataset, the map will be in a chaotic state shoortly after the beginning. Just as the picture shows from the bag(2018-0518-14-49-12_0.bag)
I have checked the output of odometry and found that the data is wrong. And for my own data, I have known the relative position between imu and lidar, but after modifying the extrinsicRot and extrinsicRPY following the introduction in Readme, I still can not make LIO-SAM run properly. How does the following sentence mean ? "The transformation of attitude readings is slightly different. We rotate the attitude measurements by -90 degrees around "lidar-z" axis and get the corresponding roll, pitch, and yaw readings in the lidar frame."