rpng / open_vins

An open source platform for visual-inertial navigation research.
https://docs.openvins.com
GNU General Public License v3.0
2.06k stars 615 forks source link

Position velocity drift for Monocular VIO on a Vehicle #368

Closed KleistvonLiu closed 10 months ago

KleistvonLiu commented 10 months ago

Hello, thanks for the amazing work! I tried to run openVins on my own dataset collected from a vehicle. And I found that when the car turns its direction, the estimated position and attitude also maybe velocity becomes inconsistent as shown in following figure. I guess the reason might be the delayed initialization of feature points, because the pose of feature points are calculated from historical poses of IMU state, but it's also used to update these poses. Have you faced same issues or have some ideas?(I found that FEJ can solve this issue to certain extent, but I cannot think out of the reason.) image image

KleistvonLiu commented 10 months ago

By the way, I only have one camera, I don't know if it matters or not.

goldbattle commented 10 months ago

When on a vehicle with monocular VIO you will run into problem since the vehicle is traveling at constant velocity and additionally moving "into" the features which causes errors in the forward velocity of the car. These build up until a turn after-which there is likely a very large update where things can go wrong.

If you wish to read more this paper is the go to reference: http://mars.cs.umn.edu/papers/KejianWu_VINSonWheels.pdf

I don't have any good suggestion for you to otherwise ensure you don't perform any sensor extrinsic or time offset calibration, and the best suggestion is to use a stereo pair.

KleistvonLiu commented 10 months ago

When on a vehicle with monocular VIO you will run into problem since the vehicle is traveling at constant velocity and additionally moving "into" the features which causes errors in the forward velocity of the car. These build up until a turn after-which there is likely a very large update where things can go wrong.

If you wish to read more this paper is the go to reference: http://mars.cs.umn.edu/papers/KejianWu_VINSonWheels.pdf

I don't have any good suggestion for you to otherwise ensure you don't perform any sensor extrinsic or time offset calibration, and the best suggestion is to use a stereo pair.

Thanks a lot for you reply! I think for a mono VIO when running at a constant velocity the scale is unobservable. And this property will not change no matter the VIO system is based on kalman filter or optimization. But when I try to run orbslam2 and vins mono on the same dataset, the scale is of course incorrect but the trajectory is smoother at a turn. Therefore, I wonder if this phenomenon is related to feature points that are wrongly initialized. Do you have any idea about this point?

goldbattle commented 10 months ago

It is hard to say. One thing important is those two approaches perform some sort of motion keyframing have different state representations.

KleistvonLiu commented 10 months ago

Ok, thanks a lot. By the way, I think I found a bug from line 459 of Propagator.cpp:

// Construct our discrete noise covariance matrix // Note that we need to convert our continuous time noises to discrete // Equations (129) amd (130) of Trawny tech report Eigen::Matrix<double, 12, 12> Qc = Eigen::Matrix<double, 12, 12>::Zero(); Qc.block(0, 0, 3, 3) = std::pow(_noises.sigma_w, 2) / dt Eigen::Matrix3d::Identity(); Qc.block(3, 3, 3, 3) = std::pow(_noises.sigma_a, 2) / dt Eigen::Matrix3d::Identity(); Qc.block(6, 6, 3, 3) = std::pow(_noises.sigma_wb, 2) / dt Eigen::Matrix3d::Identity(); Qc.block(9, 9, 3, 3) = std::pow(_noises.sigma_ab, 2) / dt Eigen::Matrix3d::Identity();

Should it be: Qc.block(6, 6, 3, 3) = std::pow(_noises.sigma_wb, 2) dt Eigen::Matrix3d::Identity(); Qc.block(9, 9, 3, 3) = std::pow(_noises.sigma_ab, 2) dt Eigen::Matrix3d::Identity();