Residuals for "invalid" projections in frame alignment problems

138 views
Skip to first unread message

Robert Maier

unread,
Dec 13, 2016, 6:06:37 PM12/13/16
to Ceres Solver
Hi,

I don't know whether the title is descriptive enough, but I have been thinking about this issue already several times and it looks like a few more people already asked about this. 
However, I am still not sure about what the solution to this problem is or the best way how to deal with it, so sorry for asking again.

The goal is to implement a simple algorithm for dense direct RGB-D frame alignment, similar to projective ICP. The minimization objective is to minimize the photometric error. I.e. given two RGB-D frames (color + aligned depth), estimate/adjust the pose in a way such that the difference between the reference image and the warped current image is as small as possible. (See https://vision.in.tum.de/_media/spezial/bib/kerl13icra.pdf )

The way I implemented this algorithm with auto differentiation is roughly:
- add a residual for each pixel in the reference frame.
- get intensity value in this reference frame (valRef).
- warp each 3D point in the reference frame (back-projected using it's depth and cam intrinsics) into the current frame using the pose, which are the parameters to be optimized (angle-axis in my case).
- project warped 3D point in current frame to 2D image coordinates.
- lookup intensity value in current frame (valCur) at these 2D coordinates using BiCubicInterpolator.
- residual[0] = valRef - valCur;
(I could also provide with my implemention if this helps)

The point is: in case the 2D lookup coordinates after warping do not project into the current image (or project to an invalid depth value), I do not want the residual to be included in the overall cost (and actually also not in the Jacobian, which is a contradiction to the design of Ceres solver as far as I have understood).

I have seen in another topic, that one could assign a constant penalty to these "invalid" projections.
If I am not wrong, a constant penalty could result in the problem, that the pose will be adjusted in order to make as many residuals project onto valid values, right? But the actual goal is to make only the "valid" projections as compatible as possible. A penalty of zero may be problematic as well (less pixels that project into the other view result in a smaller cost?).

I have stumbled across the same problematic as well in other (more complex) scenarios that involve camera pose estimation. How would you suggest to deal with this scenario?

Thanks a lot and best,
Robert

Luis-Jorge Romeo

unread,
Dec 14, 2016, 3:23:49 AM12/14/16
to ceres-...@googlegroups.com
Hi Robert,
did you take a look to Robust Loss functions?


Regards,
Jorge

--
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+unsubscribe@googlegroups.com.
To view this discussion on the web visit https://groups.google.com/d/msgid/ceres-solver/c7358c52-c830-460e-94c2-2c8e9454436f%40googlegroups.com.
For more options, visit https://groups.google.com/d/optout.

Robert Maier

unread,
Dec 14, 2016, 2:57:09 PM12/14/16
to Ceres Solver
Hi Jorge,

thanks for your response. In principle, Huber Loss is already employed in this approach in order to deal with outliers. 
However, outliers are pixels with high residuals; so in my case basically pixels in the reference image with valid projections into the current image but with quite "different" intensity values.
As far as I can see this does not cover pixels with "invalid" projections.

One of the implications is the magnitude of the final error, which can inconsistently increase by obtaining more and more valid projections/lookups.
The "normalized" average error (avg_err  = overall_cost / num_valid_residuals) should in the end decrease instead of the overall error/cost, which is not possible with the constant number of residuals, right?
(In Levenberg-Marquardt, also the damping parameter lambda should be adjusted accordingly based on the average error, correct?)

Or am I missing something?

Cheers,
Robert
To unsubscribe from this group and stop receiving emails from it, send an email to ceres-solver...@googlegroups.com.

William Rucklidge

unread,
Dec 14, 2016, 4:00:07 PM12/14/16
to ceres-...@googlegroups.com
There are a couple of things you can do.

One weird trick you can use is to detect the failed reprojection and assign some non-constant penalty cost that tends to push the solution back in the direction of making the reprojection succeed. If you assign a constant penalty cost then the Jacobian will be zero for that residual, so Ceres doesn't know what way to go. In your example, your penalty cost could be based on the distance outside the current frame that the point projected to (with some offset and scale so that costs increase as you cross the border of the frame - it should always be cheaper to be inside the frame); that tells Ceres the way that it has to push the pose in order to get this point back into the frame. This helps if valid points are getting lost.

But if invalid points are causing invalid projections, then (compared with constant penalty costs) this will cause them to contribute to the solution, which is less than ideal. You've got a couple of options in this case. The first is of course robustification via loss functions, as you're doing. The second is, in addition to using loss function, to run Ceres twice: once with all the points included, then (after it's found a pose) you remove all points that are clearly just plain wrong - reprojecting to far outside the frame (you probably want to leave the ones that are close to the edge of the frame, under the assumption that this first pose is slightly off). Then rerun Ceres with this reduced problem. You might do this more than once.

This may not work depending on your initial conditions: the way you've set up the problem depends critically on the pose being roughly correct. If it isn't, then points will reproject into completely the wrong part of the frame, and so any similarity in intensities will be purely coincidental, and Ceres will do its best but is unlikely to be able to escape any nearby local minimum. This is a hard problem and I'm not that familiar with it... my intuition says that doing something like "heavily blur the two frames; estimate a pose; reduce the blur, improve the pose; ..." might work but I haven't tried it (and people have probably come up with many better ideas already). Or do something like a SIFT/sparse SFM-based approach to produce an initial pose estimate...



To unsubscribe from this group and stop receiving emails from it, send an email to ceres-solver+unsubscribe@googlegroups.com.
To view this discussion on the web visit https://groups.google.com/d/msgid/ceres-solver/d4422ab8-1683-41ab-9b95-be4b16c0dfc5%40googlegroups.com.

Chris Sweeney

unread,
Dec 14, 2016, 4:46:14 PM12/14/16
to ceres-...@googlegroups.com
To add to that last point, a common strategy seen in SLAM is to perform this sort of refinement on an image pyramid (starting with the smallest images in the pyramid then upsampling the result, refining it, and repeat). This is similar to blurring the images as you suggest but has some additional benefits. But this still requires that the pose is fairly accurate to begin with and would not work for wide baseline scenarios without a good initialization.

--
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.

Robert Maier

unread,
Dec 14, 2016, 4:47:25 PM12/14/16
to Ceres Solver
Hey William, thanks for your detailed response.


One weird trick you can use is to detect the failed reprojection and assign some non-constant penalty cost that tends to push the solution back in the direction of making the reprojection succeed. If you assign a constant penalty cost then the Jacobian will be zero for that residual, so Ceres doesn't know what way to go. In your example, your penalty cost could be based on the distance outside the current frame that the point projected to (with some offset and scale so that costs increase as you cross the border of the frame - it should always be cheaper to be inside the frame); that tells Ceres the way that it has to push the pose in order to get this point back into the frame. This helps if valid points are getting lost.
 
The actual goal is not to make the reprojections succeed but rather to minimize the (average) error of only the valid reprojections. Hence the distance based penalty in order to push back the solution is not really what we desire I think. :-/

The main problem in summary is:
- A constant penalty would be okay for computing the update since then the residual would not contribute to the computed parameter update if I'm not mistaking (due to the zero Jacobian). 
- But still the overall cost would increase with this constant penalty, even for each invalid residual (which should simply not contribute to the cost). This is what we want to avoid. 
- Giving the residual a constant penalty of 0 does not work, since in the end the solution with the least cost might be the one with the most invalid projections.
- In the end I rather want to minimize the average cost per valid residual than the overall cost.
 

But if invalid points are causing invalid projections, then (compared with constant penalty costs) this will cause them to contribute to the solution, which is less than ideal. You've got a couple of options in this case. The first is of course robustification via loss functions, as you're doing. The second is, in addition to using loss function, to run Ceres twice: once with all the points included, then (after it's found a pose) you remove all points that are clearly just plain wrong - reprojecting to far outside the frame (you probably want to leave the ones that are close to the edge of the frame, under the assumption that this first pose is slightly off). Then rerun Ceres with this reduced problem. You might do this more than once.

The main issue that I see are the varying number of successfully computed residuals that should be used for computing the overall cost.
I had already thought about something similar, basically something like manually embedding the solver in an outside Gauss-Newton/LM or so.
 
This may not work depending on your initial conditions: the way you've set up the problem depends critically on the pose being roughly correct. If it isn't, then points will reproject into completely the wrong part of the frame, and so any similarity in intensities will be purely coincidental, and Ceres will do its best but is unlikely to be able to escape any nearby local minimum. This is a hard problem and I'm not that familiar with it... my intuition says that doing something like "heavily blur the two frames; estimate a pose; reduce the blur, improve the pose; ..." might work but I haven't tried it (and people have probably come up with many better ideas already). Or do something like a SIFT/sparse SFM-based approach to produce an initial pose estimate...
 
What I had also left out so far: the entire procedure is embedded into a coarse-to-fine approach, starting at coarse input frame resolutions (blurred and downsampled from original input) and refining the solutions in finer levels. Also, the motion between two frames is assumed to be not too large, which is usually the case in these real-time camera tracking scenarios. The approach itself converges quite well in practice and has been used a lot in the recent years.
[edit: Chris just added this as a comment as well]
Reply all
Reply to author
Forward
0 new messages