KumarRobotics / msckf_vio

Robust Stereo Visual Inertial Odometry for Fast Autonomous Flight
Other
1.66k stars 592 forks source link

Question about the observability constrain of measurement Jacobian #108

Closed brick-ai closed 3 years ago

brick-ai commented 3 years ago

In paper Observability-constrained Vision-aided Inertial Navigation, the measurement Jacobian is modified with Imu state rather than camera state. See the difference below:

1

2

Which one should we use to modify the measurement Jacobian? Why?

ke-sun commented 3 years ago

In paper Observability-constrained Vision-aided Inertial Navigation, the measurement Jacobian is modified with Imu state rather than camera state.

I am not 100% sure I understand the question (I probably become rusty on this). May I ask how the referenced paper section is related to the question?

brick-ai commented 3 years ago

@ke-sun

Sorry, I didn't make this question clearer.

To satisfy the observability constrain, the state transition matrix and the measurement Jacobian need to be modified according to following method: image image

When modifying the measurement Jacobian, the equation (25) is simplified to image And then modified according to image Just like what the code does: 1

But the difference is that the paper modifies H with IMU states while the code with camera states.

To satisfy the observability constrain, should we modify the measurement Jacobian H with IMU states or camera states?

ke-sun commented 3 years ago

I see what you meant.

The original work on observability constraint (http://seanbow.com/papers/tr_2012_1.pdf) does not exactly use an multi-state extended Kalman filter, but an extended Kalman filter with just IMU state in the state vector. As in the footnote on page 5, the work assumes the IMU frame is coincident with the CAM frame for simplicity. Therefore, the IMU state shows up in the measurement model, so as in the computation of observability constraints.

If we include the CAM states in the state vector (as in the original MSCKF), only CAM states show up in the measurement model. Therefore, their estimates should be used in enfocing the observability constraints.

brick-ai commented 3 years ago

Oh, I see. Thanks!

Does that mean we have different right nullspace N of the observability matrix from EKF-SLAM?

Do you have any materials or references so I can deduce the formulations for MSCKF?

ke-sun commented 3 years ago

I am not sure if there is a specific reference for that. But if you replace the IMU state with the CAM state in the measurement model, I think the observability analysis from the paper should translate.