diegoavillegasg / IMU-GNSS-Lidar-sensor-fusion-using-Extended-Kalman-Filter-for-State-Estimation

State Estimation and Localization of an autonomous vehicle based on IMU (high rate), GNSS (GPS) and Lidar data with sensor fusion techniques using the Extended Kalman Filter (EKF).
208 stars 38 forks source link

How to integrate this module with real system. #2

Open ajay1606 opened 4 years ago

ajay1606 commented 4 years ago

@diegoavillegasg Thanks for the very useful source scripts with detailed comments. I have a few quick questions regarding, data types of LiDAR and GPS IMU sensor used in this pickle file. In the comment description, it is mentioned that, actual data but unable to get the actual data types to input into the method.

Could you kindly provide me little more details about IMU,GNSS and LIDAR data input in raw data formats.

diegoavillegasg commented 4 years ago

Hi @ajay1606 , thank you for asking.

The pickle contains in a binary form a dictionary with 4 StampedData objects and 1 Data object with the following keys:

with open('data/pt1_data.pkl', 'rb') as file: 
   ...:     print("Using the following raw data: ", file.name) 
   ...:     data = pickle.load(file) 
data.keys()
dict_keys(['imu_w', 'imu_f', 'gnss', 'lidar', 'gt'])

StampedData class is defined in /data/utils.py, whereas Data class is defined in /data/data.py

where:

imu_w : it's the imu rotational velocity (given in the vehicle frame) imu_f : it's the imu specific force data (given in vehicle frame). gnss : GNSS data. lidar : it's the Lidar data previously converted to positions only (after doing a mapping and ego-localization step) gt : it's a Data object containing ground truth.

In this way you can get the raw data

data['imu_w'].data[0]                              
array([-0.00247717, -0.06861742,  0.08961386]) # in [rad/s]

data['imu_f'].data[0]                                                          
array([-0.01996148,  0.03136036,  9.78135591]) # in [m/s^2]

data['gnss'].data[12]
array([68.63192948, 26.96739014,  0.10098256]) # lat, long and altitude

data['lidar'].data[12]                                                         
array([ 0.39913648, -0.02572134, -0.5827075 ]) # in meters

Here you can find more details info about sensor in Carla Simulator: https://carla.readthedocs.io/en/latest/ref_sensors/#gnss-sensor

Please, let me know if it solved your question!

(from the description given by the Coursera SDC mentors and collaborators, like Trevor Ablett and Jonathan Kelly)

ajay1606 commented 4 years ago

@diegoavillegasg Thanks a lot for a detailed explanation. Really appreciate it.

ajay1606 commented 4 years ago

@diegoavillegasg Could you please give me clarification on this. ?

  1. Question

    imu_w : it's the imu rotational velocity (given in the vehicle frame) imu_f : it's the imu specific force data (given in vehicle frame).

Are the above-mentioned parameters are the same that, Angular velocity and Linear accelerations?

  1. Question: GroundTruthAndEstimatedTrajectory

By the way, with trajectory plotted using sample data provided with this package, looks quite noisy, I mean EKF predicted trajectory too noisy compared to GT. What could be the reason for this? My guess

  1. Covariance matrix
  2. Extrinsic parameters between the sensors?

could you please comment on this !

ajay1606 commented 4 years ago

@diegoavillegasg Actually am trying to test with LGSVL simulator with Autoware localization output recorded in the bag file is as follows. LiDAR topic: /ndt_pose header: seq: 1181 stamp: secs: 1586413606 nsecs: 42914560 frame_id: "/map" pose: position: x: 218.45111084 y: 201.877670288 z: 10.4493160248 orientation: x: 0.000352217090688 y: 0.000392276372959 z: 0.999999861008 w: 6.7813633464e-06

GNSS topic: /odom header: seq: 22 stamp: secs: 1586413606 nsecs: 572914176 frame_id: "gps" child_frame_id: '' pose: pose: position: x: -217.719894 y: 201.878997803 z: 10.1301298141 orientation: x: -0.000125643069623 y: -0.707106888294 z: -0.000125829130411 w: 0.707106649876 covariance: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0] twist: twist: linear: x: 4.51865616924e-07 y: 0.0 z: 0.0 angular: x: 0.0 y: 0.0 z: 2.05273775755e-09 covariance: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]

IMU topic : /imu_raw header: seq: 12096 stamp: secs: 1586413606 nsecs: 972913664 frame_id: "imu" orientation: x: 0.000125986451167 y: 0.000125759470393 z: 0.707106769085 w: 0.707106769085 orientation_covariance: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0] angular_velocity: x: 2.5880042358e-06 y: -5.91429898122e-06 z: -2.00730432276e-09 angular_velocity_covariance: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0] linear_acceleration: x: 0.0035758598242 y: -0.000114643706183 z: 9.81069660187 linear_acceleration_covariance: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]

I am looking to fuse the data highlighted in the bold font. Will, it possible to share the script to convert the bag to pickle file format to use with your EKF package? It will be more helpful. Looking forward to hearing from you.

kind regards.