Photometric Error minimization issue about the gradient and BiCubicInterpolator

301 views
Skip to first unread message

a2ckr jp

unread,
Apr 20, 2022, 10:59:52 AM4/20/22
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()));

Sameer Agarwal

unread,
Apr 20, 2022, 2:04:32 PM4/20/22
to ceres-...@googlegroups.com
this is weird. is it possible for you to share a minimal example that I can compile and look at ?
You should be able to replicate the problems with the cost function without constructing the whole problem and by using gradient_checker.h instead.
Sameer


--
You received this message because you are subscribed to the Google Groups "Ceres Solver" group.
To unsubscribe from this group and stop receiving emails from it, send an email to ceres-solver...@googlegroups.com.
To view this discussion on the web visit https://groups.google.com/d/msgid/ceres-solver/f9d5a152-f551-4497-a400-a1ff16b7d7b8n%40googlegroups.com.

a2ckr

unread,
Apr 21, 2022, 12:58:04 AM4/21/22
to Ceres Solver
Hi Sameer,

Thanks for the reply. I was able to reproduce the error with only the gradient checker without building the whole problem.
I'll let you know when I have created a minimal example.

a2ckr

2022年4月21日木曜日 3:04:32 UTC+9 Sameer Agarwal:

a2ckr

unread,
Apr 21, 2022, 8:48:59 AM4/21/22
to Ceres Solver
Hi,

Instead of photometric error minimization using 3D poses, I pushed a simpler sample of 2D translation estimation to github.


    $ ./cmake-build-debug/ceres-translate-example
    An error has occurred:

    Detected 2 bad Jacobian component(s). Worst relative error was 0.95278.

    ========== Jacobian for block 0: (1 by 2)) ==========

     block  row  col        user dx/dy    num diff dx/dy         abs error    relative error         parameter          residual
         0    0    0          -73.4594          -3.46872           69.9907           0.95278                10          -146.038 ------ (0,0,0) Relative error worse than 1e-08
         0    0    1           -42.367          -62.8923           20.5253          0.326356                 5          -146.038 ------ (0,0,1) Relative error worse than 1e-08

    ProbeResults
    return_value : 1
    maximum_relative_error : 0.95278
    residuals : -146.038
    jacobians : -73.4594, -42.367
    local_jacobians : -73.4594, -42.367
    numeric_jacobians : -3.46872, -62.8923
    local_numeric_jacobians : -3.46872, -62.8923

The error value varies depending on the parameters(tx,ty,xPos,yPos,..), but gradient cheker always reports ERROR.
I suspect that there is a mistake somewhere in my code, but I have no idea.

a2ckr

2022年4月21日木曜日 13:58:04 UTC+9 a2ckr:

a2ckr

unread,
Apr 21, 2022, 8:55:59 AM4/21/22
to Ceres Solver
Test environment is as follows:

macOS Monterey(12.3.1)

    $ brew info ceres-solver
    ceres-solver: stable 2.1.0 (bottled), HEAD
    C++ library for large-scale optimization
    http://ceres-solver.org/
    /usr/local/Cellar/ceres-solver/2.1.0 (166 files, 8.8MB) *
      Poured from bottle on 2022-04-07 at 09:59:19
    From: https://github.com/Homebrew/homebrew-core/blob/HEAD/Formula/ceres-solver.rb
    License: BSD-3-Clause
    ==> Dependencies
    Build: cmake ✔
    Required: eigen ✔, gflags ✔, glog ✔, metis ✔, openblas ✔, suite-sparse ✔, tbb ✔
    ==> Options
    --HEAD
        Install HEAD version
    ==> Analytics
    install: 15,370 (30 days), 50,831 (90 days), 188,334 (365 days)
    install-on-request: 5,819 (30 days), 30,926 (90 days), 95,052 (365 days)
    build-error: 19 (30 days)


a2ckr

2022年4月21日木曜日 21:48:59 UTC+9 a2ckr:

a2ckr

unread,
Apr 22, 2022, 4:04:08 AM4/22/22
to Ceres Solver
Hi,

I have implemented solver execution, residual and gradient dumps.

https://github.com/a2ckr/ceres-translate-sample

As with the original program, numerous errors due to the check_gradients option occur.
Also, the dump of the residual is fine, but the gradient has only 2 elements.

a2ckr

2022年4月21日木曜日 21:55:59 UTC+9 a2ckr:

Sameer Agarwal

unread,
Apr 22, 2022, 8:09:08 AM4/22/22
to ceres-...@googlegroups.com
Thank you, I will take a look.
Sameer 

Sameer Agarwal

unread,
Apr 22, 2022, 9:10:44 PM4/22/22
to ceres-...@googlegroups.com
Thank you for sharing the code.

Here is what I think is going on:

GradientChecker (same as setting check_gradients=true) currently uses Ridders' method to compute a numerical gradient which it then compares to the gradients computed by the user.

The problem is that Ridders' method starts out with a fairly large step size which works on relatively smooth functions, but is not great for cubic interpolation which is only twice differentiable. (I am sure I can make this statement more rigorous), so these derivatives do not match and you get what appears to be large errors.

Indeed if I replace RIDDERs' method with CENTRAL differences (you can't do this as a user, I had to modify gradient_checker.cc), things get much better, since it makes much fewer assumptions about the underlying function and uses much smaller step sizes. The jacobian evaluation error goes from 2.5e-2 to 6.6e-6. 

So you seem to have hit a corner case with gradient checking and cubic interpolation and its generating false positives. Your derivatives are fine.

I will think about how to prevent these false negatives, unfortunately I do not have any good ideas right now.

Sameer

a2ckr

unread,
Apr 23, 2022, 9:19:57 AM4/23/22
to Ceres Solver
Hi Sameer,

Thank you for your analysis of my code and explanation of the situation.

I understand that this is a false positive because gradient checker is not suitable in my use case.

However, my real goal is not to silence the gradient checker,
but to make the SOLVER converge to a true solution. Let me clarify my question again.

1. If the derivative is correct, why doesn't even simpler samples converge to the correct value?

2. Why is the size of the gradient obtained by Evaluate() sometimes 2 and sometimes residual+12(besides, most of the values are zero.)?

Sincerest thanks,
a2ckr

2022年4月23日土曜日 10:10:44 UTC+9 Sameer Agarwal:

Sameer Agarwal

unread,
Apr 23, 2022, 3:26:15 PM4/23/22
to ceres-...@googlegroups.com
My guess is that is something else. 
perhaps you could as a test replace the interpolator with a dummy which computes exact and smooth derivatives of the functions you are using to populate the image in your test and see how the optimizer does and use that for debugging?

Reply all
Reply to author
Forward
0 new messages