Problems of this form comes up in a broad range of areas across
science and engineering - from fitting curves in statistics, to
constructing 3D models from photographs in computer vision.
In this chapter we will learn how to solve (1) using
Ceres Solver. Full working code for all the examples described in this
chapter and more can be found in the examples
directory.
The expression
\(\rho_i\left(\left\|f_i\left(x_{i_1},...,x_{i_k}\right)\right\|^2\right)\)
is known as a ResidualBlock, where \(f_i(\cdot)\) is a
CostFunction that depends on the parameter blocks
\(\left[x_{i_1},... , x_{i_k}\right]\). In most optimization
problems small groups of scalars occur together. For example the three
components of a translation vector and the four components of the
quaternion that define the pose of a camera. We refer to such a group
of small scalars as a ParameterBlock. Of course a
ParameterBlock can just be a single parameter. \(l_j\) and
\(u_j\) are bounds on the parameter block \(x_j\).
\(\rho_i\) is a LossFunction. A LossFunction is
a scalar function that is used to reduce the influence of outliers on
the solution of non-linear least squares problems.
As a special case, when \(\rho_i(x) = x\), i.e., the identity
function, and \(l_j = -\infty\) and \(u_j = \infty\) we get
the more familiar non-linear least squares problem.
To get started, consider the problem of finding the minimum of the
function
\[\frac{1}{2}(10 -x)^2.\]
This is a trivial problem, whose minimum is located at \(x = 10\),
but it is a good place to start to illustrate the basics of solving a
problem with Ceres [1].
The first step is to write a functor that will evaluate this the
function \(f(x) = 10 - x\):
The important thing to note here is that operator() is a templated
method, which assumes that all its inputs and outputs are of some type
T. The use of templating here allows Ceres to call
CostFunctor::operator<T>(), with T=double when just the value
of the residual is needed, and with a special type T=Jet when the
Jacobians are needed. In Derivatives we will discuss the
various ways of supplying derivatives to Ceres in more detail.
Once we have a way of computing the residual function, it is now time
to construct a non-linear least squares problem using it and have
Ceres solve it.
intmain(intargc,char**argv){google::InitGoogleLogging(argv[0]);// The variable to solve for with its initial value.doubleinitial_x=5.0;doublex=initial_x;// Build the problem.Problemproblem;// Set up the only cost function (also known as residual). This uses// auto-differentiation to obtain the derivative (jacobian).CostFunction*cost_function=newAutoDiffCostFunction<CostFunctor,1,1>();problem.AddResidualBlock(cost_function,nullptr,&x);// Run the solver!Solver::Optionsoptions;options.linear_solver_type=ceres::DENSE_QR;options.minimizer_progress_to_stdout=true;Solver::Summarysummary;Solve(options,&problem,&summary);std::cout<<summary.BriefReport()<<"\n";std::cout<<"x : "<<initial_x<<" -> "<<x<<"\n";return0;}
Starting from a \(x=5\), the solver in two iterations goes to 10
[2]. The careful reader will note that this is a linear problem and
one linear solve should be enough to get the optimal value. The
default configuration of the solver is aimed at non-linear problems,
and for reasons of simplicity we did not change it in this example. It
is indeed possible to obtain the solution to this problem using Ceres
in one iteration. Also note that the solver did get very close to the
optimal function value of 0 in the very first iteration. We will
discuss these issues in greater detail when we talk about convergence
and parameter settings for Ceres.
Ceres Solver like most optimization packages, depends on being able to
evaluate the value and the derivatives of each term in the objective
function at arbitrary parameter values. Doing so correctly and
efficiently is essential to getting good results. Ceres Solver
provides a number of ways of doing so. You have already seen one of
them in action –
Automatic Differentiation in examples/helloworld.cc
We now consider the other two possibilities. Analytic and numeric
derivatives.
In some cases, its not possible to define a templated cost functor,
for example when the evaluation of the residual involves a call to a
library function that you do not have control over. In such a
situation, numerical differentiation can be used. The user defines a
functor which computes the residual value and construct a
NumericDiffCostFunction using it. e.g., for \(f(x) = 10 - x\)
the corresponding functor would be
The construction looks almost identical to the one used for automatic
differentiation, except for an extra template parameter that indicates
the kind of finite differencing scheme to be used for computing the
numerical derivatives [3]. For more details see the documentation
for NumericDiffCostFunction.
Generally speaking we recommend automatic differentiation instead of
numeric differentiation. The use of C++ templates makes automatic
differentiation efficient, whereas numeric differentiation is
expensive, prone to numeric errors, and leads to slower convergence.
In some cases, using automatic differentiation is not possible. For
example, it may be the case that it is more efficient to compute the
derivatives in closed form instead of relying on the chain rule used
by the automatic differentiation code.
In such cases, it is possible to supply your own residual and jacobian
computation code. To do this, define a subclass of
CostFunction or SizedCostFunction if you know the
sizes of the parameters and residuals at compile time. Here for
example is SimpleCostFunction that implements \(f(x) = 10 -
x\).
classQuadraticCostFunction:publicceres::SizedCostFunction<1,1>{public:virtual~QuadraticCostFunction(){}virtualboolEvaluate(doubleconst*const*parameters,double*residuals,double**jacobians)const{constdoublex=parameters[0][0];residuals[0]=10-x;// Compute the Jacobian if asked for.if(jacobians!=nullptr&&jacobians[0]!=nullptr){jacobians[0][0]=-1;}returntrue;}};
SimpleCostFunction::Evaluate is provided with an input array of
parameters, an output array residuals for residuals and an
output array jacobians for Jacobians. The jacobians array is
optional, Evaluate is expected to check when it is non-null, and
if it is the case then fill it with the values of the derivative of
the residual function. In this case since the residual function is
linear, the Jacobian is constant [4] .
As can be seen from the above code fragments, implementing
CostFunction objects is a bit tedious. We recommend that
unless you have a good reason to manage the jacobian computation
yourself, you use AutoDiffCostFunction or
NumericDiffCostFunction to construct your residual blocks.
Computing derivatives is by far the most complicated part of using
Ceres, and depending on the circumstance the user may need more
sophisticated ways of computing derivatives. This section just
scratches the surface of how derivatives can be supplied to
Ceres. Once you are comfortable with using
NumericDiffCostFunction and AutoDiffCostFunction we
recommend taking a look at DynamicAutoDiffCostFunction,
CostFunctionToFunctor, NumericDiffFunctor and
ConditionedCostFunction for more advanced ways of
constructing and computing cost functions.
Similarly, we can define classes F1, F2 and F3 to evaluate
\(f_1(x_1, x_2)\), \(f_2(x_3, x_4)\) and \(f_3(x_2, x_3)\)
respectively. Using these, the problem can be constructed as follows:
doublex1=3.0;doublex2=-1.0;doublex3=0.0;doublex4=1.0;Problemproblem;// Add residual terms to the problem using the autodiff// wrapper to get the derivatives automatically.problem.AddResidualBlock(newAutoDiffCostFunction<F1,1,1,1>(),nullptr,&x1,&x2);problem.AddResidualBlock(newAutoDiffCostFunction<F2,1,1,1>(),nullptr,&x3,&x4);problem.AddResidualBlock(newAutoDiffCostFunction<F3,1,1,1>(),nullptr,&x2,&x3);problem.AddResidualBlock(newAutoDiffCostFunction<F4,1,1,1>(),nullptr,&x1,&x4);
Note that each ResidualBlock only depends on the two parameters
that the corresponding residual object depends on and not on all four
parameters. Compiling and running examples/powell.cc
gives us:
It is easy to see that the optimal solution to this problem is at
\(x_1=0, x_2=0, x_3=0, x_4=0\) with an objective function value of
\(0\). In 10 iterations, Ceres finds a solution with an objective
function value of \(4\times 10^{-12}\).
The examples we have seen until now are simple optimization problems
with no data. The original purpose of least squares and non-linear
least squares analysis was fitting curves to data. It is only
appropriate that we now consider an example of such a problem
[6]. It contains data generated by sampling the curve \(y =
e^{0.3x + 0.1}\) and adding Gaussian noise with standard deviation
\(\sigma = 0.2\). Let us fit some data to the curve
\[y = e^{mx + c}.\]
We begin by defining a templated object to evaluate the
residual. There will be a residual for each observation.
structExponentialResidual{ExponentialResidual(doublex,doubley):x_(x),y_(y){}template<typenameT>booloperator()(constT*constm,constT*constc,T*residual)const{residual[0]=y_-exp(m[0]*x_+c[0]);returntrue;}private:// Observations for a sample.constdoublex_;constdoubley_;};
Assuming the observations are in a \(2n\) sized array called
data the problem construction is a simple matter of creating a
CostFunction for every observation.
Starting from parameter values \(m = 0, c=0\) with an initial
objective function value of \(121.173\) Ceres finds a solution
\(m= 0.291861, c = 0.131439\) with an objective function value of
\(1.05675\). These values are a bit different than the
parameters of the original model \(m=0.3, c= 0.1\), but this is
expected. When reconstructing a curve from noisy data, we expect to
see such deviations. Indeed, if you were to evaluate the objective
function for \(m=0.3, c=0.1\), the fit is worse with an objective
function value of \(1.082425\). The figure below illustrates the fit.
Now suppose the data we are given has some outliers, i.e., we have
some points that do not obey the noise model. If we were to use the
code above to fit such data, we would get a fit that looks as
below. Notice how the fitted curve deviates from the ground truth.
To deal with outliers, a standard technique is to use a
LossFunction. Loss functions reduce the influence of
residual blocks with high residuals, usually the ones corresponding to
outliers. To associate a loss function with a residual block, we change
CauchyLoss is one of the loss functions that ships with Ceres
Solver. The argument \(0.5\) specifies the scale of the loss
function. As a result, we get the fit below [7]. Notice how the
fitted curve moves back closer to the ground truth curve.
One of the main reasons for writing Ceres was our need to solve large
scale bundle adjustment problems [HartleyZisserman], [Triggs].
Given a set of measured image feature locations and correspondences,
the goal of bundle adjustment is to find 3D point positions and camera
parameters that minimize the reprojection error. This optimization
problem is usually formulated as a non-linear least squares problem,
where the error is the squared \(L_2\) norm of the difference between
the observed feature location and the projection of the corresponding
3D point on the image plane of the camera. Ceres has extensive support
for solving bundle adjustment problems.
The first step as usual is to define a templated functor that computes
the reprojection error/residual. The structure of the functor is
similar to the ExponentialResidual, in that there is an
instance of this object responsible for each image observation.
Each residual in a BAL problem depends on a three dimensional point
and a nine parameter camera. The nine parameters defining the camera
are: three for rotation as a Rodrigues’ axis-angle vector, three
for translation, one for focal length and two for radial distortion.
The details of this camera model can be found the Bundler homepage and the BAL homepage.
structSnavelyReprojectionError{SnavelyReprojectionError(doubleobserved_x,doubleobserved_y):observed_x(observed_x),observed_y(observed_y){}template<typenameT>booloperator()(constT*constcamera,constT*constpoint,T*residuals)const{// camera[0,1,2] are the angle-axis rotation.Tp[3];ceres::AngleAxisRotatePoint(camera,point,p);// camera[3,4,5] are the translation.p[0]+=camera[3];p[1]+=camera[4];p[2]+=camera[5];// Compute the center of distortion. The sign change comes from// the camera model that Noah Snavely's Bundler assumes, whereby// the camera coordinate system has a negative z axis.Txp=-p[0]/p[2];Typ=-p[1]/p[2];// Apply second and fourth order radial distortion.constT&l1=camera[7];constT&l2=camera[8];Tr2=xp*xp+yp*yp;Tdistortion=1.0+r2*(l1+l2*r2);// Compute final projected point position.constT&focal=camera[6];Tpredicted_x=focal*distortion*xp;Tpredicted_y=focal*distortion*yp;// The error is the difference between the predicted and observed position.residuals[0]=predicted_x-T(observed_x);residuals[1]=predicted_y-T(observed_y);returntrue;}// Factory to hide the construction of the CostFunction object from// the client code.staticceres::CostFunction*Create(constdoubleobserved_x,constdoubleobserved_y){returnnewceres::AutoDiffCostFunction<SnavelyReprojectionError,2,9,3>(observed_x,observed_y);}doubleobserved_x;doubleobserved_y;};
Note that unlike the examples before, this is a non-trivial function
and computing its analytic Jacobian is a bit of a pain. Automatic
differentiation makes life much simpler. The function
AngleAxisRotatePoint() and other functions for manipulating
rotations can be found in include/ceres/rotation.h.
Given this functor, the bundle adjustment problem can be constructed
as follows:
ceres::Problemproblem;for(inti=0;i<bal_problem.num_observations();++i){ceres::CostFunction*cost_function=SnavelyReprojectionError::Create(bal_problem.observations()[2*i+0],bal_problem.observations()[2*i+1]);problem.AddResidualBlock(cost_function,nullptr/* squared loss */,bal_problem.mutable_camera_for_observation(i),bal_problem.mutable_point_for_observation(i));}
Notice that the problem construction for bundle adjustment is very
similar to the curve fitting example – one term is added to the
objective function per observation.
Since this is a large sparse problem (well large for DENSE_QR
anyways), one way to solve this problem is to set
Solver::Options::linear_solver_type to
SPARSE_NORMAL_CHOLESKY and call Solve(). And while this is
a reasonable thing to do, bundle adjustment problems have a special
sparsity structure that can be exploited to solve them much more
efficiently. Ceres provides three specialized solvers (collectively
known as Schur-based solvers) for this task. The example code uses the
simplest of them DENSE_SCHUR.
For a more sophisticated bundle adjustment example which demonstrates
the use of Ceres’ more advanced features including its various linear
solvers, robust loss functions and manifolds see
examples/bundle_adjuster.cc
ellipse_approximation.cc
fits points randomly distributed on an ellipse with an approximate
line segment contour. This is done by jointly optimizing the
control points of the line segment contour along with the preimage
positions for the data points. The purpose of this example is to
show an example use case for Solver::Options::dynamic_sparsity,
and how it can benefit problems which are numerically dense but
dynamically sparse.
Testing Unconstrained Optimization Software
Jorge J. More, Burton S. Garbow and Kenneth E. Hillstrom
ACM Transactions on Mathematical Software, 7(1), pp. 17-41, 1981
which were augmented with bounds and used for testing bounds
constrained optimization algorithms by
A Trust Region Approach to Linearly Constrained Optimization
David M. Gay
Numerical Analysis (Griffiths, D.F., ed.), pp. 72-105
Lecture Notes in Mathematics 1066, Springer Verlag, 1984.
libmv_homography.cc
This file demonstrates solving for a homography between two sets of
points and using a custom exit criterion by having a callback check
for image-space error.
robot_pose_mle.cc
This example demonstrates how to use the DynamicAutoDiffCostFunction
variant of CostFunction. The DynamicAutoDiffCostFunction is meant to
be used in cases where the number of parameter blocks or the sizes are not
known at compile time.
This example simulates a robot traversing down a 1-dimension hallway with
noise odometry readings and noisy range readings of the end of the hallway.
By fusing the noisy odometry and sensor readings this example demonstrates
how to compute the maximum likelihood estimate (MLE) of the robot’s pose at
each timestep.
slam/pose_graph_2d/pose_graph_2d.cc
The Simultaneous Localization and Mapping (SLAM) problem consists of building
a map of an unknown environment while simultaneously localizing against this
map. The main difficulty of this problem stems from not having any additional
external aiding information such as GPS. SLAM has been considered one of the
fundamental challenges of robotics. There are many resources on SLAM
[9]. A pose graph optimization problem is one example of a SLAM
problem. The following explains how to formulate the pose graph based SLAM
problem in 2-Dimensions with relative pose constraints.
Consider a robot moving in a 2-Dimensional plane. The robot has access to a
set of sensors such as wheel odometry or a laser range scanner. From these
raw measurements, we want to estimate the trajectory of the robot as well as
build a map of the environment. In order to reduce the computational
complexity of the problem, the pose graph approach abstracts the raw
measurements away. Specifically, it creates a graph of nodes which represent
the pose of the robot, and edges which represent the relative transformation
(delta position and orientation) between the two nodes. The edges are virtual
measurements derived from the raw sensor measurements, e.g. by integrating
the raw wheel odometry or aligning the laser range scans acquired from the
robot. A visualization of the resulting graph is shown below.
The figure depicts the pose of the robot as the triangles, the measurements
are indicated by the connecting lines, and the loop closure measurements are
shown as dotted lines. Loop closures are measurements between non-sequential
robot states and they reduce the accumulation of error over time. The
following will describe the mathematical formulation of the pose graph
problem.
The robot at timestamp \(t\) has state \(x_t = [p^T, \psi]^T\) where
\(p\) is a 2D vector that represents the position in the plane and
\(\psi\) is the orientation in radians. The measurement of the relative
transform between the robot state at two timestamps \(a\) and \(b\)
is given as: \(z_{ab} = [\hat{p}_{ab}^T, \hat{\psi}_{ab}]\). The residual
implemented in the Ceres cost function which computes the error between the
measurement and the predicted measurement is:
To finish the cost function, we need to weight the residual by the
uncertainty of the measurement. Hence, we pre-multiply the residual by the
inverse square root of the covariance matrix for the measurement,
i.e. \(\Sigma_{ab}^{-\frac{1}{2}} r_{ab}\) where \(\Sigma_{ab}\) is
the covariance.
Lastly, we use a manifold to normalize the orientation in the range
\([-\pi,\pi)\). Specially, we define the
AngleManifold::Plus() function to be:
\(\mathrm{Normalize}(\psi + \Delta)\) and
AngleManifold::Minus() function to be
\(\mathrm{Normalize}(y) - \mathrm{Normalize}(x)\).
This package includes an executable pose_graph_2d that will read a
problem definition file. This executable can work with any 2D problem
definition that uses the g2o format. It would be relatively straightforward
to implement a new reader for a different format such as TORO or
others. pose_graph_2d will print the Ceres solver full summary and
then output to disk the original and optimized poses (poses_original.txt
and poses_optimized.txt, respectively) of the robot in the following
format:
As an example, a standard synthetic benchmark dataset [10] created by
Edwin Olson which has 3500 nodes in a grid world with a total of 5598 edges
was solved. Visualizing the results with the provided script produces:
with the original poses in green and the optimized poses in blue. As shown,
the optimized poses more closely match the underlying grid world. Note, the
left side of the graph has a small yaw drift due to a lack of relative
constraints to provide enough information to reconstruct the trajectory.
Footnotes
slam/pose_graph_3d/pose_graph_3d.cc
The following explains how to formulate the pose graph based SLAM problem in
3-Dimensions with relative pose constraints. The example also illustrates how
to use Eigen’s geometry module with Ceres’s automatic differentiation
functionality.
The robot at timestamp \(t\) has state \(x_t = [p^T, q^T]^T\) where
\(p\) is a 3D vector that represents the position and \(q\) is the
orientation represented as an Eigen quaternion. The measurement of the
relative transform between the robot state at two timestamps \(a\) and
\(b\) is given as: \(z_{ab} = [\hat{p}_{ab}^T, \hat{q}_{ab}^T]^T\).
The residual implemented in the Ceres cost function which computes the error
between the measurement and the predicted measurement is:
where the function \(\mathrm{vec}()\) returns the vector part of the
quaternion, i.e. \([q_x, q_y, q_z]\), and \(R(q)\) is the rotation
matrix for the quaternion.
To finish the cost function, we need to weight the residual by the
uncertainty of the measurement. Hence, we pre-multiply the residual by the
inverse square root of the covariance matrix for the measurement,
i.e. \(\Sigma_{ab}^{-\frac{1}{2}} r_{ab}\) where \(\Sigma_{ab}\) is
the covariance.
Given that we are using a quaternion to represent the orientation,
we need to use a manifold (EigenQuaternionManifold) to
only apply updates orthogonal to the 4-vector defining the
quaternion. Eigen’s quaternion uses a different internal memory
layout for the elements of the quaternion than what is commonly
used. Specifically, Eigen stores the elements in memory as
\([x, y, z, w]\) where the real part is last whereas it is
typically stored first. Note, when creating an Eigen quaternion
through the constructor the elements are accepted in \(w\),
\(x\), \(y\), \(z\) order. Since Ceres operates on
parameter blocks which are raw double pointers this difference is
important and requires a different parameterization.
This package includes an executable pose_graph_3d that will read a
problem definition file. This executable can work with any 3D problem
definition that uses the g2o format with quaternions used for the orientation
representation. It would be relatively straightforward to implement a new
reader for a different format such as TORO or others. pose_graph_3d
will print the Ceres solver full summary and then output to disk the original
and optimized poses (poses_original.txt and poses_optimized.txt,
respectively) of the robot in the following format:
As an example, a standard synthetic benchmark dataset [9] where the robot is
traveling on the surface of a sphere which has 2500 nodes with a total of
4949 edges was solved. Visualizing the results with the provided script
produces: