a2ckr jp
unread,Apr 20, 2022, 10:59:52 AM4/20/22Sign in to reply to author
Sign in to forward
You do not have permission to delete messages in this group
Either email addresses are anonymous for this group or you need the view member email addresses permission to view the original message
to Ceres Solver
Hi,
I'm implementing Photometric Error minimization problem for visual SLAM,
I am having trouble converging to the wrong parameters.
I dumped the residuals and gradients using ceres::Problem::Evaluate().
The residuals look fine, but the gradients are all 0 except the first 12 elements.
As for the array size, it is as follows.
length of gradients = length of residuals + 12
Is this correct behavior?
I enabled the check_gradients option, then reported numerous errors.
I have tried disabling the operations in operator() one by one and
it seems that the image differentiation (BiCubicInterpolator::Evaluate) is producing large errors.
This code using automatic differentiation, but the situation did not change when I used numerical differentiation.
Is there something wrong with my usage?
Any advice would be appreciated.
Gradient Error detected!
Extra info for this residual: Residual block id 11; depends on parameters [0x11a6cc560, 0x11a83e8d0, 0x7fb0e03f8058]
Detected 12 bad Jacobian component(s). Worst relative error was 1.06237.
========== Jacobian for block 0: (1 by 6)) ==========
block row col user dx/dy num diff dx/dy abs error relative error parameter residual
0 0 0 -1716.46 99.8032 1816.26 1.05814 0 -4.94906 ------ (0,0,0) Relative error worse than 1e-08
0 0 1 548.512 335.143 213.369 0.388996 1.5 -4.94906 ------ (0,0,1) Relative error worse than 1e-08
0 0 2 -217.634 -47.2698 170.364 0.782801 0 -4.94906 ------ (0,0,2) Relative error worse than 1e-08
0 0 3 -2872.55 -408.652 2463.9 0.857739 0 -4.94906 ------ (0,0,3) Relative error worse than 1e-08
0 0 4 -7306.54 454.039 7760.58 1.06214 0 -4.94906 ------ (0,0,4) Relative error worse than 1e-08
0 0 5 4240.51 -43.2049 4283.72 1.01019 1 -4.94906 ------ (0,0,5) Relative error worse than 1e-08
========== Jacobian for block 1: (1 by 6)) ==========
block row col user dx/dy num diff dx/dy abs error relative error parameter residual
1 0 0 1716.46 -99.8032 1816.26 1.05814 -0.00312495 -4.94906 ------ (1,0,0) Relative error worse than 1e-08
1 0 1 -548.512 -334.945 213.567 0.389357 1.50205 -4.94906 ------ (1,0,1) Relative error worse than 1e-08
1 0 2 217.634 47.2698 170.364 0.782801 -0.000709919 -4.94906 ------ (1,0,2) Relative error worse than 1e-08
1 0 3 2872.44 410.629 2461.81 0.857045 -0.000340966 -4.94906 ------ (1,0,3) Relative error worse than 1e-08
1 0 4 7307.62 -455.8 7763.42 1.06237 0.00502782 -4.94906 ------ (1,0,4) Relative error worse than 1e-08
1 0 5 -4236.9 44.8138 4281.72 1.01058 0.999985 -4.94906 ------ (1,0,5) Relative error worse than 1e-08
========== Jacobian for block 2: (1 by 1)) ==========
block row col user dx/dy num diff dx/dy abs error relative error parameter residual
2 0 0 -14.2295 -14.2295 2.61196e-10 1.83559e-11 0.466832 -4.94906
//
// (Only the relevant parts are excerpted.)
//
class PhotometricErrorFunctor
{
// cam0 pose:7, cam1 pose:7, inv depth:1(fixed)
typedef ceres::AutoDiffCostFunction<PhotometricErrorFunctor, 1, 7, 7, 1> PhotometricErrorFunction;
typedef ceres::NumericDiffCostFunction<PhotometricErrorFunctor, ceres::NumericDiffMethodType::CENTRAL, 1, 7, 7, 1> PhotometricErrorFunctionNumeric;
template <class T> inline
bool operator()(const T* const cam0, const T* const cam1, const T* const invDepth, T* residuals) const
{
Eigen::Map<const Eigen::Vector<T,3> > cam0_t(cam0, 3);
Eigen::Map<const Eigen::Quaternion<T> > cam0_q(&cam0[3]);
Eigen::Map<const Eigen::Vector<T,3> > cam1_t(cam1, 3);
Eigen::Map<const Eigen::Quaternion<T> > cam1_q(&cam1[3]);
// <Inverse Camera Projection> ...
// <Coordinate Transformation> ...
// <Camera Projection> ...
Eigen::Matrix<T, 3, 1> p2;
// ...
T pe;
if (!_is_valid_point(p2)) {
pe = T(0);
}
else{
T tarPixel;
m_cam1Interpolator.Evaluate(p2(1), p2(0), &tarPixel);
pe = T(m_cam0Image(m_yPos, m_xPos)) - tarPixel;
}
residuals[0] = pe;
return true;
}
// ...
};
// BiCubicInterpolator
auto pGrid = new ceres::Grid2D<double,1>(pFrame->data(), 0, pFrame->rows(), 0, pFrame->cols());
auto cam1Interpolator = new ceres::BiCubicInterpolator<ceres::Grid2D<double,1>>(*pGrid);
// localization
m_pProblem->AddParameterBlock(cam0.pPose->data(),7,
new ceres::ProductManifold(
new ceres::EuclideanManifold<3>(),
new ceres::EigenQuaternionManifold()));
m_pProblem->AddParameterBlock(cam1.pPose->data(),7,
new ceres::ProductManifold(
new ceres::EuclideanManifold<3>(),
new ceres::EigenQuaternionManifold()));