UZ-SLAMLab / ORB_SLAM3

ORB-SLAM3: An Accurate Open-Source Library for Visual, Visual-Inertial and Multi-Map SLAM
GNU General Public License v3.0
6.39k stars 2.51k forks source link

Are jacobians wrong in G2oTypes.cc? #330

Open leavesnight opened 3 years ago

leavesnight commented 3 years ago

we found computeError uses bprior - VA/VG->estimate() but linearizeOplus() gives Identity() not -I, is this part wrong? `void computeError(){ const VertexAccBias VA = static_cast<const VertexAccBias>(_vertices[0]); _error = bprior - VA->estimate(); }

void EdgePriorAcc::linearizeOplus(){ // Jacobian wrt bias _jacobianOplusXi.block<3,3>(0,0) = Eigen::Matrix3d::Identity(); } void EdgePriorGyro::linearizeOplus(){ // Jacobian wrt bias _jacobianOplusXi.block<3,3>(0,0) = Eigen::Matrix3d::Identity(); }`

treememory commented 3 years ago

maybe a wrong. it goes better after i add -: _jacobianOplusXi.block<3,3>(0,0) = -Eigen::Matrix3d::Identity();

sherman-luo commented 1 year ago

Agreed, this is incorrect. I unit tested this code and it the bias will not converge properly