Extract residual, jacobian (covariance?) at each iteration

2,061 views
Skip to first unread message

Rémi Cura

unread,
Nov 3, 2014, 10:31:36 AM11/3/14
to ceres-...@googlegroups.com

Hello dear Ceres users.

This question must be trivial.
I'm starting to have a few complex cost functions and I would need to understand how each contribute and in witch case
to be able to fine tune everything.
 
For this I need some info about cost & jacobian at each iteration,
then I can exploit it in visualization software.

How can we get cost& jacobian at each iteration for every residual block?

I know I could trigger the writing of such data manually (using the "IterationCallback").

I noticed the Problem::Evaluate(const EvaluateOptions& options,
                double* cost,
                vector<double>* residuals,
                vector<double>* gradient,
                CRSMatrix* jacobian)
function, but I'm having a hard time understanding it.

According to the comments, the residuals should be in the order of the construction.
What is this "gradient" exactly, and what is its dimension?
How is the jacobian matrix fabricated from all the small jacobian matrices, is the big jacobian a block matrix containing all the small jacobian matrix on the diagonal?
  .

I have the same kind of questions for the covariance
I noticed the function Covariance::Compute(const vector<pair<const double*, const double*>>& covariance_blocks, Problem* problem)
I guess if I'm only interested in diagonal elements I have to create a vector of (1,1),(2,2)...

Can this function be called in the iteration call back?

Many thanks for the help,
Cheers,
Rémi-C

Sameer Agarwal

unread,
Nov 3, 2014, 10:41:40 AM11/3/14
to ceres-...@googlegroups.com
Remi,

This question must be trivial.

Not entirely trivial.
 
I'm starting to have a few complex cost functions and I would need to understand how each contribute and in witch case
to be able to fine tune everything.
 
For this I need some info about cost & jacobian at each iteration,
then I can exploit it in visualization software.

Ceres does not provide a way of accessing the jacobian at every iteration. The overall cost is available and can be accessed by writing your own IterationCallback.
 
How can we get cost& jacobian at each iteration for every residual block?

Not possible in the current API. I am curious as to what is it that you are going to do with this rather huge amount of information?
 
I know I could trigger the writing of such data manually (using the "IterationCallback").

Not quite, what you can do is trigger that your parameter blocks are updated every iteration by setting

Solver::Options::update_state_every_variable = true.
 
And then have an external function evaluate your cost functions.. but that seems rather tedious.


I noticed the Problem::Evaluate(const EvaluateOptions& options,
                double* cost,
                vector<double>* residuals,
                vector<double>* gradient,
                CRSMatrix* jacobian)
function, but I'm having a hard time understanding it.

This cannot be called mid optimization. Bad things will happen if you do this. This function is meant to evaluate the cost functions/residuals/jacobians independent of the call to Solve.


According to the comments, the residuals should be in the order of the construction.
What is this "gradient" exactly, and what is its dimension?

If you are not using any local parameterizations, then the gradient is vector whose dimension is the sum of the dimensions of all parameter blocks.

If you are using local parameterizations, then you have to sum the local dimensions of the parameter blocks.

 How is the jacobian matrix fabricated from all the small jacobian matrices, is the big jacobian a block matrix containing all the small jacobian matrix on the diagonal?

No, it is constructed by inserting the blocks of the jacobian for each parameter blocks in the appropriate location. For example
if your problem has three parameter blocks and two residual blocks, where the first residual block depends on the first two parameter blocks and the second depends on the first and third parameter block, then the jacobian will look like

A1 A2 0
B1   0 B2

Where, A1 and A2 are the two jacobians evaluated by the first cost function and B1 and B2 are the jacobians evaluated by the second cost function. Ceres takes care of putting them into the larger jacobian matrix.

I have the same kind of questions for the covariance
I noticed the function Covariance::Compute(const vector<pair<const double*, const double*>>& covariance_blocks, Problem* problem)
I guess if I'm only interested in diagonal elements I have to create a vector of (1,1),(2,2)...

yes.
 

Can this function be called in the iteration call back?

no.

Sameer
 

Many thanks for the help,
Cheers,
Rémi-C

--
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/fa88969d-5c42-4d88-a5dd-ab51fd954cbd%40googlegroups.com.
For more options, visit https://groups.google.com/d/optout.

Rémi Cura

unread,
Nov 3, 2014, 11:02:58 AM11/3/14
to ceres-...@googlegroups.com
Hey Sameer,
thanks for the super fast answer.

If I get you right there is no easy way to get the residuals at each iteration step.
I solve a geometric problem so jacobian and residuals can be added to my map as a 2D vector +color  (for instance).

I already use the iteration callback to write the state of the parameters at each iteration, this allow me to "follow" what' going on using a sliders to go trough iterations
(that is, get the parameter evolution following time (iteration) ).

Again if I understand you right, I have to manually evaluate every function (or store the current residuals and jac in each functor ) if I want to access these informations.
I wanted to be sure because calling manually seems to be a rewrite of what Ceres already does at each iteration.
 
Here is a visu : yellow dot represent observations used in residual block (fixed, not parameters)
The parameter are the bottom lines forming a kind of T (yellow to red, following the iteration number)
Blue lines represent which residual uses which parameter (here every residuals refers to same parameter).
Here you can see that the yellow to red lines are dragged toward the observations, which is the expected behaviour.



















 Cheers,
Rémi-C
Remi,


MMMany thanks for the help,
Cheers,
Rémi-C

Rémi Cura

unread,
Nov 3, 2014, 11:42:17 AM11/3/14
to ceres-...@googlegroups.com

Oups just another small precision ;

Is there any guarantee that the last time all "evaluate()" for cost function have been called in an iteration will be for the retained temporary solution?

That is, can I just store the value of residuals and jac every time the evaluate function is called, then export it when the iteration callback executes?

This would be so much simpler !

Cheers,
Rémi-C

Sameer Agarwal

unread,
Nov 3, 2014, 4:43:17 PM11/3/14
to ceres-...@googlegroups.com
Remi,
 
If I get you right there is no easy way to get the residuals at each iteration step.

You are right.
 
I solve a geometric problem so jacobian and residuals can be added to my map as a 2D vector +color  (for instance).

I already use the iteration callback to write the state of the parameters at each iteration, this allow me to "follow" what' going on using a sliders to go trough iterations
(that is, get the parameter evolution following time (iteration) ).

Again if I understand you right, I have to manually evaluate every function (or store the current residuals and jac in each functor ) if I want to access these informations.
I wanted to be sure because calling manually seems to be a rewrite of what Ceres already does at each iteration.

I am curious as to why you want to do this evaluation. Because the individual evaluations in the context of the full solve do not have a lot of meaning.

Sameer
 

Sameer Agarwal

unread,
Nov 3, 2014, 4:43:35 PM11/3/14
to ceres-...@googlegroups.com
On Mon Nov 03 2014 at 8:42:18 AM Rémi Cura <remi...@gmail.com> wrote:
Oups just another small precision ;

Is there any guarantee that the last time all "evaluate()" for cost function have been called in an iteration will be for the retained temporary solution?

no.

Sameer
 
That is, can I just store the value of residuals and jac every time the evaluate function is called, then export it when the iteration callback executes?

This would be so much simpler !

Cheers,
Rémi-C

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

Rémi Cura

unread,
Nov 4, 2014, 4:31:29 AM11/4/14
to ceres-...@googlegroups.com

Thanks Sameer for this answers!
I'll try to evaluate everything myself, output it and make a pretty print ,
then it will be easier to understand how it is useful.
Cheers,
Rémi-C
Reply all
Reply to author
Forward
0 new messages