Skip to content

"EstimateGyroBias",why ignore extrinsic parameters beween IMU and Lidar? #76

@ZzJiachenchen

Description

@ZzJiachenchen

why in function "EstimateGyroBias", when estimating gyro bias of IMU, there can ignore the extrinsic parameters beween IMU and Lidar?

 Eigen::Quaterniond q_ij(laser_trans_i.second.transform.rot.conjugate() * laser_trans_j.second.transform.rot);

tmp_A = laser_trans_j.second.pre_integration->jacobian_.template block<3, 3>(O_R, O_BG);
 /// Jacobian of dr12_bg

tmp_b = 2 * (laser_trans_j.second.pre_integration->delta_q_.conjugate() * q_ij).vec();
 /// 2*vec(IMU_ij^T * q_ij)

Why tmp_b is not :

2*vec(IMU_ij^T *(rbl* q_ij* rlb))

Thanks a lot!

Metadata

Metadata

Assignees

No one assigned

    Labels

    No labels
    No labels

    Projects

    No projects

    Milestone

    No milestone

    Relationships

    None yet

    Development

    No branches or pull requests

    Issue actions