修改尺度bug
parent
5d57b1d807
commit
7efec05be4
|
@ -831,8 +831,8 @@ void EdgeInertialGS::linearizeOplus()
|
|||
// Jacobians wrt scale factor
|
||||
// _jacobianOplus[3] 9*1矩阵 总体来说就是三个残差分别对尺度求导
|
||||
_jacobianOplus[7].setZero();
|
||||
_jacobianOplus[7].block<3,1>(3,0) = Rbw1*(VV2->estimate()-VV1->estimate());
|
||||
_jacobianOplus[7].block<3,1>(6,0) = Rbw1*(VP2->estimate().twb-VP1->estimate().twb-VV1->estimate()*dt);
|
||||
_jacobianOplus[7].block<3,1>(3,0) = Rbw1*(VV2->estimate()-VV1->estimate()) * s;
|
||||
_jacobianOplus[7].block<3,1>(6,0) = Rbw1*(VP2->estimate().twb-VP1->estimate().twb-VV1->estimate()*dt) * s;
|
||||
}
|
||||
|
||||
/**
|
||||
|
|
Loading…
Reference in New Issue