Hello, thanks for your contribution.
I am trying to add the code to Vins-mono, but the gyro bias is not converged in my code.
The gryo bias factor code as follows
class GyroscopeBiasCostFunction : public ceres::SizedCostFunction<3, 3> {
public:
GyroscopeBiasCostFunction(std::shared_ptr<IntegrationBase> pIntj, const Eigen::Matrix3d &Ri, const Eigen::Matrix3d &Rj) :
pIntj_(pIntj), Ri_(Ri), Rj_(Rj)
{
Eigen::SelfAdjointEigenSolver<Eigen::Matrix3d> solver(pIntj_ -> covariance.block<3,3>(3,3));
SqrtInformation_ = solver.operatorSqrt();
}
virtual ~GyroscopeBiasCostFunction() {}
bool Evaluate(double const* const* parameters, double* residuals, double** jacabians) const override {
Eigen::Map<const Eigen::Vector3d> bg(parameters[0]);
Eigen::Matrix3d dq_dbg = pIntj_ -> jacobian.block<3, 3>(3, 12);
Eigen::Vector3d dbg = bg - pIntj_ ->linearized_bg;
Eigen::Quaterniond corrected_delta_q = pIntj_ -> delta_q * Utility::deltaQ(dq_dbg * dbg);
// Eigen::Vector3d delta_bg = pIntj_ -> jacobian.block<3,3>(3,12) * (bg - pIntj_ -> linearized_bg);
// Eigen::Matrix3d deltaR = pIntj_ -> delta_q.toRotationMatrix() * Utility::ExpSO3(delta_bg.x(), delta_bg.y(), delta_bg.z());
const Eigen::Matrix3d eR = corrected_delta_q.toRotationMatrix().transpose() * Ri_.transpose() * Rj_;
const Eigen::Vector3d err = Utility::LogSO3(eR);
Eigen::Map<Eigen::Vector3d> e(residuals);
e = err;
e = SqrtInformation_ * e;
if(jacabians != nullptr) {
if(jacabians[0] != nullptr) {
const Eigen::Matrix3d invJr = Utility::InverseRightJacobianSO3(err[0], err[1], err[2]);
Eigen::Map<Eigen::Matrix<double, 3, 3, Eigen::RowMajor>> J(jacabians[0]);
Eigen::Vector3d J_RbgMultipDbg = pIntj_ -> jacobian.block<3,3>(3,12) * dbg;
J = -invJr * eR.transpose() * Utility::RightJacobianSO3(J_RbgMultipDbg.x(), J_RbgMultipDbg.y(), J_RbgMultipDbg.z()) * pIntj_ -> jacobian.block<3,3>(3,12);
J = SqrtInformation_ * J;
}
}
return true;
}
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
private:
std::shared_ptr<IntegrationBase> pIntj_;
const Eigen::Matrix3d Ri_, Rj_;
Eigen::Matrix3d SqrtInformation_;
};
Then my optimiation code as follows:
Eigen::Vector3d bias_;
bias_.setZero();
ceres::Problem problem;
map<double, ImageFrame>::iterator frame_i;
map<double, ImageFrame>::iterator frame_j;
for (frame_i = all_image_frame.begin(); next(frame_i) != all_image_frame.end(); frame_i++) {
frame_j = next(frame_i);
const Eigen::Matrix3d &Ri = frame_i->second.R;
const Eigen::Matrix3d &Rj = frame_j->second.R;
std::shared_ptr<IntegrationBase> p_int(new IntegrationBase(*(frame_j -> second.pre_integration)));
ceres::CostFunction* cost_function = new GyroscopeBiasCostFunction(p_int, Ri, Rj);
problem.AddResidualBlock(cost_function, nullptr, bias_.data());
}
TicToc time0;
ceres::Solver::Options options;
options.minimizer_progress_to_stdout = true;
ceres::Solver::Summary summary;
But the final output of bias is Zero. Then I printed the optimization process and found that the cost was very small before optimization.
iter cost cost_change |gradient| |step| tr_ratio tr_radius ls_iter iter_time total_time
0 1.578785e-12 0.00e+00 1.54e-11 0.00e+00 0.00e+00 1.00e+04 0 3.79e-05 8.99e-05
So I would like to ask you, what is wrong with the code. Thank you very much again.