Problem::Evaluate implementation.
1. Add Problem::Evaluate and tests.
2. Remove Solver::Summary::initial/final_*
3. Remove Solver::Options::return_* members.
4. Various cpplint cleanups.
Change-Id: I4266de53489896f72d9c6798c5efde6748d68a47
diff --git a/include/ceres/autodiff_cost_function.h b/include/ceres/autodiff_cost_function.h
index 2f86f56..e758d3a 100644
--- a/include/ceres/autodiff_cost_function.h
+++ b/include/ceres/autodiff_cost_function.h
@@ -159,8 +159,9 @@
int N7 = 0, // Number of parameters in block 7.
int N8 = 0, // Number of parameters in block 8.
int N9 = 0> // Number of parameters in block 9.
-class AutoDiffCostFunction :
- public SizedCostFunction<M, N0, N1, N2, N3, N4, N5, N6, N7, N8, N9> {
+class AutoDiffCostFunction : public SizedCostFunction<M,
+ N0, N1, N2, N3, N4,
+ N5, N6, N7, N8, N9> {
public:
// Takes ownership of functor. Uses the template-provided value for the
// number of residuals ("M").
diff --git a/include/ceres/cost_function_to_functor.h b/include/ceres/cost_function_to_functor.h
index 363ba12..b30ecd0 100644
--- a/include/ceres/cost_function_to_functor.h
+++ b/include/ceres/cost_function_to_functor.h
@@ -64,7 +64,8 @@
// struct CameraProjection {
// CameraProjection(double* observation) {
// intrinsic_projection_.reset(
-// new CostFunctionToFunctor<2, 5, 3>(new IntrinsicProjection(observation_)));
+// new CostFunctionToFunctor<2, 5, 3>(
+// new IntrinsicProjection(observation_)));
// }
// template <typename T>
// bool operator(const T* rotation,
@@ -78,7 +79,8 @@
// // Note that we call intrinsic_projection_, just like it was
// // any other templated functor.
//
-// return (*intrinsic_projection_)(intrinsics, transformed_point, residual); }
+// return (*intrinsic_projection_)(intrinsics, transformed_point, residual);
+// }
//
// private:
// scoped_ptr<CostFunctionToFunctor<2,5,3> > intrinsic_projection_;
@@ -102,11 +104,11 @@
int N5 = 0, int N6 = 0, int N7 = 0, int N8 = 0, int N9 = 0>
class CostFunctionToFunctor {
public:
- CostFunctionToFunctor(CostFunction* cost_function)
+ explicit CostFunctionToFunctor(CostFunction* cost_function)
: cost_function_(cost_function) {
CHECK_NOTNULL(cost_function);
- CHECK(kNumResiduals > 0);
+ CHECK_GE(kNumResiduals, 0);
CHECK_EQ(cost_function->num_residuals(), kNumResiduals);
// This block breaks the 80 column rule to keep it somewhat readable.
@@ -125,24 +127,26 @@
<< N3 << ", " << N4 << ", " << N5 << ", " << N6 << ", " << N7 << ", "
<< N8 << ", " << N9;
- const vector<int16>& parameter_block_sizes = cost_function->parameter_block_sizes();
+ const vector<int16>& parameter_block_sizes =
+ cost_function->parameter_block_sizes();
const int num_parameter_blocks =
(N0 > 0) + (N1 > 0) + (N2 > 0) + (N3 > 0) + (N4 > 0) +
(N5 > 0) + (N6 > 0) + (N7 > 0) + (N8 > 0) + (N9 > 0);
CHECK_EQ(parameter_block_sizes.size(), num_parameter_blocks);
CHECK_EQ(N0, parameter_block_sizes[0]);
- if (parameter_block_sizes.size() > 1) CHECK_EQ(N1, parameter_block_sizes[1]);
- if (parameter_block_sizes.size() > 2) CHECK_EQ(N2, parameter_block_sizes[2]);
- if (parameter_block_sizes.size() > 3) CHECK_EQ(N3, parameter_block_sizes[3]);
- if (parameter_block_sizes.size() > 4) CHECK_EQ(N4, parameter_block_sizes[4]);
- if (parameter_block_sizes.size() > 5) CHECK_EQ(N5, parameter_block_sizes[5]);
- if (parameter_block_sizes.size() > 6) CHECK_EQ(N6, parameter_block_sizes[6]);
- if (parameter_block_sizes.size() > 7) CHECK_EQ(N7, parameter_block_sizes[7]);
- if (parameter_block_sizes.size() > 8) CHECK_EQ(N8, parameter_block_sizes[8]);
- if (parameter_block_sizes.size() > 9) CHECK_EQ(N9, parameter_block_sizes[9]);
+ if (parameter_block_sizes.size() > 1) CHECK_EQ(N1, parameter_block_sizes[1]); // NOLINT
+ if (parameter_block_sizes.size() > 2) CHECK_EQ(N2, parameter_block_sizes[2]); // NOLINT
+ if (parameter_block_sizes.size() > 3) CHECK_EQ(N3, parameter_block_sizes[3]); // NOLINT
+ if (parameter_block_sizes.size() > 4) CHECK_EQ(N4, parameter_block_sizes[4]); // NOLINT
+ if (parameter_block_sizes.size() > 5) CHECK_EQ(N5, parameter_block_sizes[5]); // NOLINT
+ if (parameter_block_sizes.size() > 6) CHECK_EQ(N6, parameter_block_sizes[6]); // NOLINT
+ if (parameter_block_sizes.size() > 7) CHECK_EQ(N7, parameter_block_sizes[7]); // NOLINT
+ if (parameter_block_sizes.size() > 8) CHECK_EQ(N8, parameter_block_sizes[8]); // NOLINT
+ if (parameter_block_sizes.size() > 9) CHECK_EQ(N9, parameter_block_sizes[9]); // NOLINT
- CHECK_EQ(accumulate(parameter_block_sizes.begin(), parameter_block_sizes.end(), 0),
+ CHECK_EQ(accumulate(parameter_block_sizes.begin(),
+ parameter_block_sizes.end(), 0),
N0 + N1 + N2 + N3 + N4 + N5 + N6 + N7 + N8 + N9);
}
@@ -675,7 +679,8 @@
template <typename JetT>
bool EvaluateWithJets(const JetT** inputs, JetT* output) const {
const int kNumParameters = N0 + N1 + N2 + N3 + N4 + N5 + N6 + N7 + N8 + N9;
- const vector<int16>& parameter_block_sizes = cost_function_->parameter_block_sizes();
+ const vector<int16>& parameter_block_sizes =
+ cost_function_->parameter_block_sizes();
const int num_parameter_blocks = parameter_block_sizes.size();
const int num_residuals = cost_function_->num_residuals();
@@ -729,7 +734,8 @@
for (int j = 0; j < num_parameter_blocks; ++j) {
const int16 block_size = parameter_block_sizes[j];
for (int k = 0; k < parameter_block_sizes[j]; ++k) {
- output[i].v += jacobian_blocks[j][i * block_size + k] * inputs[j][k].v;
+ output[i].v +=
+ jacobian_blocks[j][i * block_size + k] * inputs[j][k].v;
}
}
}
diff --git a/include/ceres/dynamic_autodiff_cost_function.h b/include/ceres/dynamic_autodiff_cost_function.h
index f2e7c26..861164a 100644
--- a/include/ceres/dynamic_autodiff_cost_function.h
+++ b/include/ceres/dynamic_autodiff_cost_function.h
@@ -65,18 +65,20 @@
#include <cmath>
#include <numeric>
-#include <glog/logging.h>
+#include <vector>
+
#include "ceres/cost_function.h"
#include "ceres/internal/scoped_ptr.h"
#include "ceres/jet.h"
+#include "glog/logging.h"
namespace ceres {
template <typename CostFunctor, int Stride = 4>
class DynamicAutoDiffCostFunction : public CostFunction {
public:
- DynamicAutoDiffCostFunction(CostFunctor* functor)
- : functor_(functor) {}
+ explicit DynamicAutoDiffCostFunction(CostFunctor* functor)
+ : functor_(functor) {}
virtual ~DynamicAutoDiffCostFunction() {}
@@ -144,7 +146,9 @@
// Evaluate all of the strides. Each stride is a chunk of the derivative to
// evaluate, typically some size proportional to the size of the SIMD
// registers of the CPU.
- int num_strides = int(ceil(num_active_parameters / float(Stride)));
+ int num_strides = static_cast<int>(ceil(num_active_parameters /
+ static_cast<float>(Stride)));
+
for (int pass = 0; pass < num_strides; ++pass) {
// Set most of the jet components to zero, except for
// non-constant #Stride parameters.
@@ -180,7 +184,8 @@
if (jacobians[i] != NULL) {
for (int k = 0; k < num_residuals(); ++k) {
jacobians[i][k * parameter_block_sizes()[i] + j] =
- output_jets[k].v[parameter_cursor - start_derivative_section];
+ output_jets[k].v[parameter_cursor -
+ start_derivative_section];
}
++active_parameter_count;
}
diff --git a/include/ceres/fpclassify.h b/include/ceres/fpclassify.h
index 5a9ea15..b730832 100644
--- a/include/ceres/fpclassify.h
+++ b/include/ceres/fpclassify.h
@@ -41,6 +41,8 @@
#include <float.h>
#endif
+#include <limits>
+
namespace ceres {
#if defined(_MSC_VER)
diff --git a/include/ceres/gradient_checker.h b/include/ceres/gradient_checker.h
index 2ce605d..3ec8056 100644
--- a/include/ceres/gradient_checker.h
+++ b/include/ceres/gradient_checker.h
@@ -37,16 +37,16 @@
#ifndef CERES_PUBLIC_GRADIENT_CHECKER_H_
#define CERES_PUBLIC_GRADIENT_CHECKER_H_
-#include <algorithm>
#include <cstddef>
+#include <algorithm>
#include <vector>
-#include <glog/logging.h>
#include "ceres/internal/eigen.h"
#include "ceres/internal/fixed_array.h"
#include "ceres/internal/macros.h"
#include "ceres/internal/scoped_ptr.h"
#include "ceres/numeric_diff_cost_function.h"
+#include "glog/logging.h"
namespace ceres {
@@ -161,7 +161,8 @@
results->finite_difference_jacobians.resize(num_blocks);
internal::FixedArray<double*> term_jacobian_pointers(num_blocks);
- internal::FixedArray<double*> finite_difference_jacobian_pointers(num_blocks);
+ internal::FixedArray<double*>
+ finite_difference_jacobian_pointers(num_blocks);
for (int i = 0; i < num_blocks; i++) {
results->term_jacobians[i].resize(num_residuals, block_sizes[i]);
term_jacobian_pointers[i] = results->term_jacobians[i].data();
diff --git a/include/ceres/internal/autodiff.h b/include/ceres/internal/autodiff.h
index abc16e6..011f2a0 100644
--- a/include/ceres/internal/autodiff.h
+++ b/include/ceres/internal/autodiff.h
@@ -192,13 +192,15 @@
DCHECK(src);
DCHECK(dst);
for (int i = 0; i < M; ++i) {
- Eigen::Map<Eigen::Matrix<T, N, 1> >(dst + N * i, N) = src[i].v.template segment<N>(N0);
+ Eigen::Map<Eigen::Matrix<T, N, 1> >(dst + N * i, N) =
+ src[i].v.template segment<N>(N0);
}
}
-// This is in a struct because default template parameters on a function are not
-// supported in C++03 (though it is available in C++0x). N0 through N5 are the
-// dimension of the input arguments to the user supplied functor.
+// This is in a struct because default template parameters on a
+// function are not supported in C++03 (though it is available in
+// C++0x). N0 through N5 are the dimension of the input arguments to
+// the user supplied functor.
template <typename Functor, typename T,
int N0 = 0, int N1 = 0, int N2 = 0, int N3 = 0, int N4 = 0,
int N5 = 0, int N6 = 0, int N7 = 0, int N8 = 0, int N9 = 0>
diff --git a/include/ceres/internal/macros.h b/include/ceres/internal/macros.h
index 83ec311..388cf30 100644
--- a/include/ceres/internal/macros.h
+++ b/include/ceres/internal/macros.h
@@ -132,16 +132,16 @@
// - wan 2005-11-16
//
// Starting with Visual C++ 2005, WinNT.h includes ARRAYSIZE. However,
-// the definition comes from the over-broad windows.h header that
+// the definition comes from the over-broad windows.h header that
// introduces a macro, ERROR, that conflicts with the logging framework
// that Ceres uses. Instead, rename ARRAYSIZE to CERES_ARRAYSIZE.
-#define CERES_ARRAYSIZE(a) \
- ((sizeof(a) / sizeof(*(a))) / \
+#define CERES_ARRAYSIZE(a) \
+ ((sizeof(a) / sizeof(*(a))) / \
static_cast<size_t>(!(sizeof(a) % sizeof(*(a)))))
-// Tell the compiler to warn about unused return values for functions declared
-// with this macro. The macro should be used on function declarations
-// following the argument list:
+// Tell the compiler to warn about unused return values for functions
+// declared with this macro. The macro should be used on function
+// declarations following the argument list:
//
// Sprocket* AllocateSprocket() MUST_USE_RESULT;
//
diff --git a/include/ceres/internal/numeric_diff.h b/include/ceres/internal/numeric_diff.h
index 1837df4..4058366 100644
--- a/include/ceres/internal/numeric_diff.h
+++ b/include/ceres/internal/numeric_diff.h
@@ -35,13 +35,14 @@
#define CERES_PUBLIC_INTERNAL_NUMERIC_DIFF_H_
#include <cstring>
-#include <glog/logging.h>
+
#include "Eigen/Dense"
-#include "ceres/internal/scoped_ptr.h"
#include "ceres/cost_function.h"
+#include "ceres/internal/scoped_ptr.h"
#include "ceres/internal/variadic_evaluate.h"
#include "ceres/types.h"
-#include "ceres/cost_function.h"
+#include "glog/logging.h"
+
namespace ceres {
namespace internal {
diff --git a/include/ceres/internal/scoped_ptr.h b/include/ceres/internal/scoped_ptr.h
index 44f198b..5dfb551 100644
--- a/include/ceres/internal/scoped_ptr.h
+++ b/include/ceres/internal/scoped_ptr.h
@@ -38,6 +38,7 @@
#include <assert.h>
#include <stdlib.h>
#include <cstddef>
+#include <algorithm>
namespace ceres {
namespace internal {
@@ -49,18 +50,17 @@
template <class C>
scoped_ptr<C> make_scoped_ptr(C *);
-// A scoped_ptr<T> is like a T*, except that the destructor of scoped_ptr<T>
-// automatically deletes the pointer it holds (if any). That is, scoped_ptr<T>
-// owns the T object that it points to. Like a T*, a scoped_ptr<T> may hold
-// either NULL or a pointer to a T object. Also like T*, scoped_ptr<T> is
-// thread-compatible, and once you dereference it, you get the threadsafety
-// guarantees of T.
+// A scoped_ptr<T> is like a T*, except that the destructor of
+// scoped_ptr<T> automatically deletes the pointer it holds (if
+// any). That is, scoped_ptr<T> owns the T object that it points
+// to. Like a T*, a scoped_ptr<T> may hold either NULL or a pointer to
+// a T object. Also like T*, scoped_ptr<T> is thread-compatible, and
+// once you dereference it, you get the threadsafety guarantees of T.
//
// The size of a scoped_ptr is small: sizeof(scoped_ptr<C>) == sizeof(C*)
template <class C>
class scoped_ptr {
public:
-
// The element type
typedef C element_type;
@@ -193,7 +193,6 @@
template <class C>
class scoped_array {
public:
-
// The element type
typedef C element_type;
diff --git a/include/ceres/numeric_diff_cost_function.h b/include/ceres/numeric_diff_cost_function.h
index 54ba26f..555bc3d 100644
--- a/include/ceres/numeric_diff_cost_function.h
+++ b/include/ceres/numeric_diff_cost_function.h
@@ -158,7 +158,7 @@
template <typename CostFunctor,
NumericDiffMethod method = CENTRAL,
- int kNumResiduals = 0, // Number of residuals, or ceres::DYNAMIC
+ int kNumResiduals = 0, // Number of residuals, or ceres::DYNAMIC
int N0 = 0, // Number of parameters in block 0.
int N1 = 0, // Number of parameters in block 1.
int N2 = 0, // Number of parameters in block 2.
@@ -170,7 +170,9 @@
int N8 = 0, // Number of parameters in block 8.
int N9 = 0> // Number of parameters in block 9.
class NumericDiffCostFunction
- : public SizedCostFunction<kNumResiduals, N0, N1, N2, N3, N4, N5, N6, N7, N8, N9> {
+ : public SizedCostFunction<kNumResiduals,
+ N0, N1, N2, N3, N4,
+ N5, N6, N7, N8, N9> {
public:
NumericDiffCostFunction(CostFunctor* functor,
const double relative_step_size = 1e-6)
diff --git a/include/ceres/numeric_diff_functor.h b/include/ceres/numeric_diff_functor.h
index 40c0f9c..593c371 100644
--- a/include/ceres/numeric_diff_functor.h
+++ b/include/ceres/numeric_diff_functor.h
@@ -99,6 +99,9 @@
// of RotateAndTranslatePoint with a numerically differentiated
// version of IntrinsicProjection.
+#ifndef CERES_PUBLIC_NUMERIC_DIFF_FUNCTOR_H_
+#define CERES_PUBLIC_NUMERIC_DIFF_FUNCTOR_H_
+
#include "ceres/numeric_diff_cost_function.h"
#include "ceres/types.h"
#include "ceres/cost_function_to_functor.h"
@@ -114,13 +117,14 @@
public:
// relative_step_size controls the step size used by the numeric
// differentiation process.
- NumericDiffFunctor(double relative_step_size = 1e-6)
- : functor_(new NumericDiffCostFunction<Functor,
- kMethod,
- kNumResiduals,
- N0, N1, N2, N3, N4,
- N5, N6, N7, N8, N9>(
- new Functor, relative_step_size)) {
+ explicit NumericDiffFunctor(double relative_step_size = 1e-6)
+ : functor_(
+ new NumericDiffCostFunction<Functor,
+ kMethod,
+ kNumResiduals,
+ N0, N1, N2, N3, N4,
+ N5, N6, N7, N8, N9>(new Functor,
+ relative_step_size)) {
}
NumericDiffFunctor(Functor* functor, double relative_step_size = 1e-6)
@@ -335,7 +339,8 @@
CostFunctionToFunctor<kNumResiduals,
N0, N1, N2, N3, N4,
N5, N6, N7, N8, N9> functor_;
-
};
} // namespace ceres
+
+#endif // CERES_PUBLIC_NUMERIC_DIFF_FUNCTOR_H_
diff --git a/include/ceres/problem.h b/include/ceres/problem.h
index f0ed1b0..bccb329 100644
--- a/include/ceres/problem.h
+++ b/include/ceres/problem.h
@@ -39,11 +39,12 @@
#include <set>
#include <vector>
-#include <glog/logging.h>
#include "ceres/internal/macros.h"
#include "ceres/internal/port.h"
#include "ceres/internal/scoped_ptr.h"
#include "ceres/types.h"
+#include "glog/logging.h"
+
namespace ceres {
@@ -51,6 +52,7 @@
class LossFunction;
class LocalParameterization;
class Solver;
+struct CRSMatrix;
namespace internal {
class Preprocessor;
@@ -326,6 +328,76 @@
// sizes of all of the residual blocks.
int NumResiduals() const;
+ // Options struct to control Problem::Evaluate.
+ struct EvaluateOptions {
+ EvaluateOptions()
+ : num_threads(1) {
+ }
+
+ // The set of parameter blocks for which evaluation should be
+ // performed. This vector determines the order that parameter
+ // blocks occur in the gradient vector and in the columns of the
+ // jacobian matrix. If parameter_blocks is empty, then it is
+ // assumed to be equal to vector containing ALL the parameter
+ // blocks. Generally speaking the parameter blocks will occur in
+ // the order in which they were added to the problem. But, this
+ // may change if the user removes any parameter blocks from the
+ // problem.
+ //
+ // NOTE: This vector should contain the same pointers as the ones
+ // used to add parameter blocks to the Problem. These parmeter
+ // block should NOT point to new memory locations. Bad things will
+ // happen otherwise.
+ vector<double*> parameter_blocks;
+
+ // The set of residual blocks to evaluate. This vector determines
+ // the order in which the residuals occur, and how the rows of the
+ // jacobian are ordered. If residual_blocks is empty, then it is
+ // assumed to be equal to the vector containing all the residual
+ // blocks. If this vector is empty, then it is assumed to be equal
+ // to a vector containing ALL the residual blocks. Generally
+ // speaking the residual blocks will occur in the order in which
+ // they were added to the problem. But, this may change if the
+ // user removes any residual blocks from the problem.
+ vector<ResidualBlockId> residual_blocks;
+ int num_threads;
+ };
+
+ // Evaluate Problem. Any of the output pointers can be NULL. Which
+ // residual blocks and parameter blocks are used is controlled by
+ // the EvaluateOptions struct above.
+ //
+ // Note 1: The evaluation will use the values stored in the memory
+ // locations pointed to by the parameter block pointers used at the
+ // time of the construction of the problem. i.e.,
+ //
+ // Problem problem;
+ // double x = 1;
+ // problem.Add(new MyCostFunction, NULL, &x);
+ //
+ // double cost = 0.0;
+ // problem.Evaluate(Problem::EvaluateOptions(), &cost, NULL, NULL, NULL);
+ //
+ // The cost is evaluated at x = 1. If you wish to evaluate the
+ // problem at x = 2, then
+ //
+ // x = 2;
+ // problem.Evaluate(Problem::EvaluateOptions(), &cost, NULL, NULL, NULL);
+ //
+ // is the way to do so.
+ //
+ // Note 2: If no local parameterizations are used, then the size of
+ // the gradient vector (and the number of columns in the jacobian)
+ // is the sum of the sizes of all the parameter blocks. If a
+ // parameter block has a local parameterization, then it contributes
+ // "LocalSize" entries to the gradient vecto (and the number of
+ // columns in the jacobian).
+ bool Evaluate(const EvaluateOptions& options,
+ double* cost,
+ vector<double>* residuals,
+ vector<double>* gradient,
+ CRSMatrix* jacobian);
+
private:
friend class Solver;
internal::scoped_ptr<internal::ProblemImpl> problem_impl_;
diff --git a/include/ceres/rotation.h b/include/ceres/rotation.h
index 711687f..ffac4f1 100644
--- a/include/ceres/rotation.h
+++ b/include/ceres/rotation.h
@@ -67,8 +67,9 @@
template <typename T, int row_stride, int col_stride>
struct MatrixAdapter;
-// Convenience functions to create a MatrixAdapter that treats the array pointed to
-// by "pointer" as a 3x3 (contiguous) column-major or row-major matrix.
+// Convenience functions to create a MatrixAdapter that treats the
+// array pointed to by "pointer" as a 3x3 (contiguous) column-major or
+// row-major matrix.
template <typename T>
MatrixAdapter<T, 1, 3> ColumnMajorAdapter3x3(T* pointer);
@@ -101,8 +102,8 @@
template <typename T, int row_stride, int col_stride>
void RotationMatrixToAngleAxis(
- const MatrixAdapter<const T, row_stride, col_stride>& R,
- T* angle_axis);
+ const MatrixAdapter<const T, row_stride, col_stride>& R,
+ T* angle_axis);
template <typename T>
void AngleAxisToRotationMatrix(T const* angle_axis, T* R);
diff --git a/include/ceres/solver.h b/include/ceres/solver.h
index 07ce0e4..122870c 100644
--- a/include/ceres/solver.h
+++ b/include/ceres/solver.h
@@ -110,12 +110,6 @@
jacobi_scaling = true;
logging_type = PER_MINIMIZER_ITERATION;
minimizer_progress_to_stdout = false;
- return_initial_residuals = false;
- return_initial_gradient = false;
- return_initial_jacobian = false;
- return_final_residuals = false;
- return_final_gradient = false;
- return_final_jacobian = false;
lsqp_dump_directory = "/tmp";
lsqp_dump_format_type = TEXTFILE;
check_gradients = false;
@@ -481,14 +475,6 @@
// is sent to STDOUT.
bool minimizer_progress_to_stdout;
- bool return_initial_residuals;
- bool return_initial_gradient;
- bool return_initial_jacobian;
-
- bool return_final_residuals;
- bool return_final_gradient;
- bool return_final_jacobian;
-
// List of iterations at which the optimizer should dump the
// linear least squares problem to disk. Useful for testing and
// benchmarking. If empty (default), no problems are dumped.
@@ -596,54 +582,6 @@
// blocks that they depend on were fixed.
double fixed_cost;
- // Vectors of residuals before and after the optimization. The
- // entries of these vectors are in the order in which
- // ResidualBlocks were added to the Problem object.
- //
- // Whether the residual vectors are populated with values is
- // controlled by Solver::Options::return_initial_residuals and
- // Solver::Options::return_final_residuals respectively.
- vector<double> initial_residuals;
- vector<double> final_residuals;
-
- // Gradient vectors, before and after the optimization. The rows
- // are in the same order in which the ParameterBlocks were added
- // to the Problem object.
- //
- // NOTE: Since AddResidualBlock adds ParameterBlocks to the
- // Problem automatically if they do not already exist, if you wish
- // to have explicit control over the ordering of the vectors, then
- // use Problem::AddParameterBlock to explicitly add the
- // ParameterBlocks in the order desired.
- //
- // Whether the vectors are populated with values is controlled by
- // Solver::Options::return_initial_gradient and
- // Solver::Options::return_final_gradient respectively.
- vector<double> initial_gradient;
- vector<double> final_gradient;
-
- // Jacobian matrices before and after the optimization. The rows
- // of these matrices are in the same order in which the
- // ResidualBlocks were added to the Problem object. The columns
- // are in the same order in which the ParameterBlocks were added
- // to the Problem object.
- //
- // NOTE: Since AddResidualBlock adds ParameterBlocks to the
- // Problem automatically if they do not already exist, if you wish
- // to have explicit control over the column ordering of the
- // matrix, then use Problem::AddParameterBlock to explicitly add
- // the ParameterBlocks in the order desired.
- //
- // The Jacobian matrices are stored as compressed row sparse
- // matrices. Please see ceres/crs_matrix.h for more details of the
- // format.
- //
- // Whether the Jacboan matrices are populated with values is
- // controlled by Solver::Options::return_initial_jacobian and
- // Solver::Options::return_final_jacobian respectively.
- CRSMatrix initial_jacobian;
- CRSMatrix final_jacobian;
-
vector<IterationSummary> iterations;
int num_successful_steps;