Austin Schuh | 3de38b0 | 2024-06-25 18:25:10 -0700 | [diff] [blame^] | 1 | .. highlight:: c++ |
| 2 | |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 3 | .. default-domain:: cpp |
| 4 | |
| 5 | .. cpp:namespace:: ceres |
| 6 | |
| 7 | .. _`chapter-nnls_modeling`: |
| 8 | |
| 9 | ================================= |
| 10 | Modeling Non-linear Least Squares |
| 11 | ================================= |
| 12 | |
| 13 | Introduction |
| 14 | ============ |
| 15 | |
| 16 | Ceres solver consists of two distinct parts. A modeling API which |
| 17 | provides a rich set of tools to construct an optimization problem one |
| 18 | term at a time and a solver API that controls the minimization |
| 19 | algorithm. This chapter is devoted to the task of modeling |
| 20 | optimization problems using Ceres. :ref:`chapter-nnls_solving` discusses |
| 21 | the various ways in which an optimization problem can be solved using |
| 22 | Ceres. |
| 23 | |
| 24 | Ceres solves robustified bounds constrained non-linear least squares |
| 25 | problems of the form: |
| 26 | |
| 27 | .. math:: :label: ceresproblem_modeling |
| 28 | |
| 29 | \min_{\mathbf{x}} &\quad \frac{1}{2}\sum_{i} |
| 30 | \rho_i\left(\left\|f_i\left(x_{i_1}, |
| 31 | ... ,x_{i_k}\right)\right\|^2\right) \\ |
| 32 | \text{s.t.} &\quad l_j \le x_j \le u_j |
| 33 | |
| 34 | In Ceres parlance, the expression |
| 35 | :math:`\rho_i\left(\left\|f_i\left(x_{i_1},...,x_{i_k}\right)\right\|^2\right)` |
| 36 | is known as a **residual block**, where :math:`f_i(\cdot)` is a |
| 37 | :class:`CostFunction` that depends on the **parameter blocks** |
| 38 | :math:`\left\{x_{i_1},... , x_{i_k}\right\}`. |
| 39 | |
| 40 | In most optimization problems small groups of scalars occur |
| 41 | together. For example the three components of a translation vector and |
| 42 | the four components of the quaternion that define the pose of a |
| 43 | camera. We refer to such a group of scalars as a **parameter block**. Of |
| 44 | course a parameter block can be just a single scalar too. |
| 45 | |
| 46 | :math:`\rho_i` is a :class:`LossFunction`. A :class:`LossFunction` is |
| 47 | a scalar valued function that is used to reduce the influence of |
| 48 | outliers on the solution of non-linear least squares problems. |
| 49 | |
| 50 | :math:`l_j` and :math:`u_j` are lower and upper bounds on the |
| 51 | parameter block :math:`x_j`. |
| 52 | |
| 53 | As a special case, when :math:`\rho_i(x) = x`, i.e., the identity |
| 54 | function, and :math:`l_j = -\infty` and :math:`u_j = \infty` we get |
Austin Schuh | 3de38b0 | 2024-06-25 18:25:10 -0700 | [diff] [blame^] | 55 | the usual unconstrained `non-linear least squares problem |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 56 | <http://en.wikipedia.org/wiki/Non-linear_least_squares>`_. |
| 57 | |
| 58 | .. math:: :label: ceresproblemunconstrained |
| 59 | |
| 60 | \frac{1}{2}\sum_{i} \left\|f_i\left(x_{i_1}, ... ,x_{i_k}\right)\right\|^2. |
| 61 | |
| 62 | :class:`CostFunction` |
| 63 | ===================== |
| 64 | |
| 65 | For each term in the objective function, a :class:`CostFunction` is |
| 66 | responsible for computing a vector of residuals and Jacobian |
| 67 | matrices. Concretely, consider a function |
| 68 | :math:`f\left(x_{1},...,x_{k}\right)` that depends on parameter blocks |
| 69 | :math:`\left[x_{1}, ... , x_{k}\right]`. |
| 70 | |
| 71 | Then, given :math:`\left[x_{1}, ... , x_{k}\right]`, |
| 72 | :class:`CostFunction` is responsible for computing the vector |
| 73 | :math:`f\left(x_{1},...,x_{k}\right)` and the Jacobian matrices |
| 74 | |
Austin Schuh | 1d1e6ea | 2020-12-23 21:56:30 -0800 | [diff] [blame] | 75 | .. math:: J_i = D_i f(x_1, ..., x_k) \quad \forall i \in \{1, \ldots, k\} |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 76 | |
| 77 | .. class:: CostFunction |
| 78 | |
| 79 | .. code-block:: c++ |
| 80 | |
| 81 | class CostFunction { |
| 82 | public: |
| 83 | virtual bool Evaluate(double const* const* parameters, |
| 84 | double* residuals, |
Austin Schuh | 3de38b0 | 2024-06-25 18:25:10 -0700 | [diff] [blame^] | 85 | double** jacobians) const = 0; |
| 86 | const std::vector<int32>& parameter_block_sizes(); |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 87 | int num_residuals() const; |
| 88 | |
| 89 | protected: |
Austin Schuh | 3de38b0 | 2024-06-25 18:25:10 -0700 | [diff] [blame^] | 90 | std::vector<int32>* mutable_parameter_block_sizes(); |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 91 | void set_num_residuals(int num_residuals); |
| 92 | }; |
| 93 | |
| 94 | |
| 95 | The signature of the :class:`CostFunction` (number and sizes of input |
| 96 | parameter blocks and number of outputs) is stored in |
| 97 | :member:`CostFunction::parameter_block_sizes_` and |
| 98 | :member:`CostFunction::num_residuals_` respectively. User code |
| 99 | inheriting from this class is expected to set these two members with |
| 100 | the corresponding accessors. This information will be verified by the |
| 101 | :class:`Problem` when added with :func:`Problem::AddResidualBlock`. |
| 102 | |
Austin Schuh | 3de38b0 | 2024-06-25 18:25:10 -0700 | [diff] [blame^] | 103 | .. function:: bool CostFunction::Evaluate(double const* const* parameters, double* residuals, double** jacobians) const |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 104 | |
| 105 | Compute the residual vector and the Jacobian matrices. |
| 106 | |
| 107 | ``parameters`` is an array of arrays of size |
| 108 | ``CostFunction::parameter_block_sizes_.size()`` and |
| 109 | ``parameters[i]`` is an array of size ``parameter_block_sizes_[i]`` |
| 110 | that contains the :math:`i^{\text{th}}` parameter block that the |
| 111 | ``CostFunction`` depends on. |
| 112 | |
Austin Schuh | 1d1e6ea | 2020-12-23 21:56:30 -0800 | [diff] [blame] | 113 | ``parameters`` is never ``nullptr``. |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 114 | |
| 115 | ``residuals`` is an array of size ``num_residuals_``. |
| 116 | |
Austin Schuh | 1d1e6ea | 2020-12-23 21:56:30 -0800 | [diff] [blame] | 117 | ``residuals`` is never ``nullptr``. |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 118 | |
| 119 | ``jacobians`` is an array of arrays of size |
| 120 | ``CostFunction::parameter_block_sizes_.size()``. |
| 121 | |
Austin Schuh | 1d1e6ea | 2020-12-23 21:56:30 -0800 | [diff] [blame] | 122 | If ``jacobians`` is ``nullptr``, the user is only expected to compute |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 123 | the residuals. |
| 124 | |
| 125 | ``jacobians[i]`` is a row-major array of size ``num_residuals x |
| 126 | parameter_block_sizes_[i]``. |
| 127 | |
Austin Schuh | 1d1e6ea | 2020-12-23 21:56:30 -0800 | [diff] [blame] | 128 | If ``jacobians[i]`` is **not** ``nullptr``, the user is required to |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 129 | compute the Jacobian of the residual vector with respect to |
| 130 | ``parameters[i]`` and store it in this array, i.e. |
| 131 | |
| 132 | ``jacobians[i][r * parameter_block_sizes_[i] + c]`` = |
| 133 | :math:`\frac{\displaystyle \partial \text{residual}[r]}{\displaystyle \partial \text{parameters}[i][c]}` |
| 134 | |
Austin Schuh | 1d1e6ea | 2020-12-23 21:56:30 -0800 | [diff] [blame] | 135 | If ``jacobians[i]`` is ``nullptr``, then this computation can be |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 136 | skipped. This is the case when the corresponding parameter block is |
| 137 | marked constant. |
| 138 | |
| 139 | The return value indicates whether the computation of the residuals |
| 140 | and/or jacobians was successful or not. This can be used to |
| 141 | communicate numerical failures in Jacobian computations for |
| 142 | instance. |
| 143 | |
| 144 | :class:`SizedCostFunction` |
| 145 | ========================== |
| 146 | |
| 147 | .. class:: SizedCostFunction |
| 148 | |
| 149 | If the size of the parameter blocks and the size of the residual |
| 150 | vector is known at compile time (this is the common case), |
| 151 | :class:`SizeCostFunction` can be used where these values can be |
| 152 | specified as template parameters and the user only needs to |
| 153 | implement :func:`CostFunction::Evaluate`. |
| 154 | |
| 155 | .. code-block:: c++ |
| 156 | |
Austin Schuh | 1d1e6ea | 2020-12-23 21:56:30 -0800 | [diff] [blame] | 157 | template<int kNumResiduals, int... Ns> |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 158 | class SizedCostFunction : public CostFunction { |
| 159 | public: |
| 160 | virtual bool Evaluate(double const* const* parameters, |
| 161 | double* residuals, |
| 162 | double** jacobians) const = 0; |
| 163 | }; |
| 164 | |
| 165 | |
| 166 | :class:`AutoDiffCostFunction` |
| 167 | ============================= |
| 168 | |
| 169 | .. class:: AutoDiffCostFunction |
| 170 | |
| 171 | Defining a :class:`CostFunction` or a :class:`SizedCostFunction` |
| 172 | can be a tedious and error prone especially when computing |
| 173 | derivatives. To this end Ceres provides `automatic differentiation |
| 174 | <http://en.wikipedia.org/wiki/Automatic_differentiation>`_. |
| 175 | |
| 176 | .. code-block:: c++ |
| 177 | |
| 178 | template <typename CostFunctor, |
| 179 | int kNumResiduals, // Number of residuals, or ceres::DYNAMIC. |
Austin Schuh | 1d1e6ea | 2020-12-23 21:56:30 -0800 | [diff] [blame] | 180 | int... Ns> // Size of each parameter block |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 181 | class AutoDiffCostFunction : public |
Austin Schuh | 1d1e6ea | 2020-12-23 21:56:30 -0800 | [diff] [blame] | 182 | SizedCostFunction<kNumResiduals, Ns> { |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 183 | public: |
Austin Schuh | 3de38b0 | 2024-06-25 18:25:10 -0700 | [diff] [blame^] | 184 | // Instantiate CostFunctor using the supplied arguments. |
| 185 | template<class ...Args> |
| 186 | explicit AutoDiffCostFunction(Args&& ...args); |
| 187 | explicit AutoDiffCostFunction(std::unique_ptr<CostFunctor> functor); |
| 188 | explicit AutoDiffCostFunction(CostFunctor* functor, ownership = TAKE_OWNERSHIP); |
| 189 | |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 190 | // Ignore the template parameter kNumResiduals and use |
| 191 | // num_residuals instead. |
Austin Schuh | 1d1e6ea | 2020-12-23 21:56:30 -0800 | [diff] [blame] | 192 | AutoDiffCostFunction(CostFunctor* functor, |
| 193 | int num_residuals, |
| 194 | ownership = TAKE_OWNERSHIP); |
Austin Schuh | 3de38b0 | 2024-06-25 18:25:10 -0700 | [diff] [blame^] | 195 | AutoDiffCostFunction(std::unique_ptr<CostFunctor> functor, |
| 196 | int num_residuals); |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 197 | }; |
| 198 | |
| 199 | To get an auto differentiated cost function, you must define a |
| 200 | class with a templated ``operator()`` (a functor) that computes the |
| 201 | cost function in terms of the template parameter ``T``. The |
| 202 | autodiff framework substitutes appropriate ``Jet`` objects for |
| 203 | ``T`` in order to compute the derivative when necessary, but this |
| 204 | is hidden, and you should write the function as if ``T`` were a |
| 205 | scalar type (e.g. a double-precision floating point number). |
| 206 | |
| 207 | The function must write the computed value in the last argument |
| 208 | (the only non-``const`` one) and return true to indicate success. |
| 209 | |
| 210 | For example, consider a scalar error :math:`e = k - x^\top y`, |
| 211 | where both :math:`x` and :math:`y` are two-dimensional vector |
| 212 | parameters and :math:`k` is a constant. The form of this error, |
| 213 | which is the difference between a constant and an expression, is a |
| 214 | common pattern in least squares problems. For example, the value |
| 215 | :math:`x^\top y` might be the model expectation for a series of |
| 216 | measurements, where there is an instance of the cost function for |
| 217 | each measurement :math:`k`. |
| 218 | |
| 219 | The actual cost added to the total problem is :math:`e^2`, or |
| 220 | :math:`(k - x^\top y)^2`; however, the squaring is implicitly done |
| 221 | by the optimization framework. |
| 222 | |
| 223 | To write an auto-differentiable cost function for the above model, |
| 224 | first define the object |
| 225 | |
| 226 | .. code-block:: c++ |
| 227 | |
| 228 | class MyScalarCostFunctor { |
| 229 | MyScalarCostFunctor(double k): k_(k) {} |
| 230 | |
| 231 | template <typename T> |
| 232 | bool operator()(const T* const x , const T* const y, T* e) const { |
| 233 | e[0] = k_ - x[0] * y[0] - x[1] * y[1]; |
| 234 | return true; |
| 235 | } |
| 236 | |
| 237 | private: |
| 238 | double k_; |
| 239 | }; |
| 240 | |
| 241 | |
| 242 | Note that in the declaration of ``operator()`` the input parameters |
| 243 | ``x`` and ``y`` come first, and are passed as const pointers to arrays |
| 244 | of ``T``. If there were three input parameters, then the third input |
| 245 | parameter would come after ``y``. The output is always the last |
| 246 | parameter, and is also a pointer to an array. In the example above, |
| 247 | ``e`` is a scalar, so only ``e[0]`` is set. |
| 248 | |
| 249 | Then given this class definition, the auto differentiated cost |
| 250 | function for it can be constructed as follows. |
| 251 | |
| 252 | .. code-block:: c++ |
| 253 | |
Austin Schuh | 3de38b0 | 2024-06-25 18:25:10 -0700 | [diff] [blame^] | 254 | auto* cost_function |
| 255 | = new AutoDiffCostFunction<MyScalarCostFunctor, 1, 2, 2>(1.0); |
| 256 | ^ ^ ^ |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 257 | | | | |
| 258 | Dimension of residual ------+ | | |
| 259 | Dimension of x ----------------+ | |
| 260 | Dimension of y -------------------+ |
| 261 | |
| 262 | |
| 263 | In this example, there is usually an instance for each measurement |
| 264 | of ``k``. |
| 265 | |
| 266 | In the instantiation above, the template parameters following |
| 267 | ``MyScalarCostFunction``, ``<1, 2, 2>`` describe the functor as |
| 268 | computing a 1-dimensional output from two arguments, both |
| 269 | 2-dimensional. |
| 270 | |
Austin Schuh | 1d1e6ea | 2020-12-23 21:56:30 -0800 | [diff] [blame] | 271 | By default :class:`AutoDiffCostFunction` will take ownership of the cost |
| 272 | functor pointer passed to it, ie. will call `delete` on the cost functor |
| 273 | when the :class:`AutoDiffCostFunction` itself is deleted. However, this may |
| 274 | be undesirable in certain cases, therefore it is also possible to specify |
| 275 | :class:`DO_NOT_TAKE_OWNERSHIP` as a second argument in the constructor, |
| 276 | while passing a pointer to a cost functor which does not need to be deleted |
| 277 | by the AutoDiffCostFunction. For example: |
| 278 | |
| 279 | .. code-block:: c++ |
| 280 | |
| 281 | MyScalarCostFunctor functor(1.0) |
Austin Schuh | 3de38b0 | 2024-06-25 18:25:10 -0700 | [diff] [blame^] | 282 | auto* cost_function |
Austin Schuh | 1d1e6ea | 2020-12-23 21:56:30 -0800 | [diff] [blame] | 283 | = new AutoDiffCostFunction<MyScalarCostFunctor, 1, 2, 2>( |
| 284 | &functor, DO_NOT_TAKE_OWNERSHIP); |
| 285 | |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 286 | :class:`AutoDiffCostFunction` also supports cost functions with a |
| 287 | runtime-determined number of residuals. For example: |
| 288 | |
| 289 | .. code-block:: c++ |
| 290 | |
Austin Schuh | 3de38b0 | 2024-06-25 18:25:10 -0700 | [diff] [blame^] | 291 | auto functor = std::make_unique<CostFunctorWithDynamicNumResiduals>(1.0); |
| 292 | auto* cost_function |
| 293 | = new AutoDiffCostFunction<CostFunctorWithDynamicNumResiduals, |
| 294 | DYNAMIC, 2, 2>( |
| 295 | std::move(functor), ^ ^ ^ |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 296 | runtime_number_of_residuals); <----+ | | | |
| 297 | | | | | |
| 298 | | | | | |
| 299 | Actual number of residuals ------+ | | | |
| 300 | Indicate dynamic number of residuals --------+ | | |
| 301 | Dimension of x ------------------------------------+ | |
| 302 | Dimension of y ---------------------------------------+ |
| 303 | |
Austin Schuh | 3de38b0 | 2024-06-25 18:25:10 -0700 | [diff] [blame^] | 304 | .. warning:: |
| 305 | A common beginner's error when first using :class:`AutoDiffCostFunction` |
| 306 | is to get the sizing wrong. In particular, there is a tendency to set the |
| 307 | template parameters to (dimension of residual, number of parameters) |
| 308 | instead of passing a dimension parameter for *every parameter block*. In |
| 309 | the example above, that would be ``<MyScalarCostFunction, 1, 2>``, which |
| 310 | is missing the 2 as the last template argument. |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 311 | |
| 312 | |
| 313 | :class:`DynamicAutoDiffCostFunction` |
| 314 | ==================================== |
| 315 | |
| 316 | .. class:: DynamicAutoDiffCostFunction |
| 317 | |
| 318 | :class:`AutoDiffCostFunction` requires that the number of parameter |
Austin Schuh | 1d1e6ea | 2020-12-23 21:56:30 -0800 | [diff] [blame] | 319 | blocks and their sizes be known at compile time. In a number of |
| 320 | applications, this is not enough e.g., Bezier curve fitting, Neural |
| 321 | Network training etc. |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 322 | |
| 323 | .. code-block:: c++ |
| 324 | |
| 325 | template <typename CostFunctor, int Stride = 4> |
| 326 | class DynamicAutoDiffCostFunction : public CostFunction { |
| 327 | }; |
| 328 | |
| 329 | In such cases :class:`DynamicAutoDiffCostFunction` can be |
| 330 | used. Like :class:`AutoDiffCostFunction` the user must define a |
| 331 | templated functor, but the signature of the functor differs |
| 332 | slightly. The expected interface for the cost functors is: |
| 333 | |
| 334 | .. code-block:: c++ |
| 335 | |
| 336 | struct MyCostFunctor { |
| 337 | template<typename T> |
| 338 | bool operator()(T const* const* parameters, T* residuals) const { |
| 339 | } |
| 340 | } |
| 341 | |
| 342 | Since the sizing of the parameters is done at runtime, you must |
| 343 | also specify the sizes after creating the dynamic autodiff cost |
| 344 | function. For example: |
| 345 | |
| 346 | .. code-block:: c++ |
| 347 | |
Austin Schuh | 3de38b0 | 2024-06-25 18:25:10 -0700 | [diff] [blame^] | 348 | auto* cost_function = new DynamicAutoDiffCostFunction<MyCostFunctor, 4>(); |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 349 | cost_function->AddParameterBlock(5); |
| 350 | cost_function->AddParameterBlock(10); |
| 351 | cost_function->SetNumResiduals(21); |
| 352 | |
| 353 | Under the hood, the implementation evaluates the cost function |
| 354 | multiple times, computing a small set of the derivatives (four by |
| 355 | default, controlled by the ``Stride`` template parameter) with each |
| 356 | pass. There is a performance tradeoff with the size of the passes; |
| 357 | Smaller sizes are more cache efficient but result in larger number |
| 358 | of passes, and larger stride lengths can destroy cache-locality |
| 359 | while reducing the number of passes over the cost function. The |
| 360 | optimal value depends on the number and sizes of the various |
| 361 | parameter blocks. |
| 362 | |
| 363 | As a rule of thumb, try using :class:`AutoDiffCostFunction` before |
| 364 | you use :class:`DynamicAutoDiffCostFunction`. |
| 365 | |
| 366 | :class:`NumericDiffCostFunction` |
| 367 | ================================ |
| 368 | |
| 369 | .. class:: NumericDiffCostFunction |
| 370 | |
| 371 | In some cases, its not possible to define a templated cost functor, |
| 372 | for example when the evaluation of the residual involves a call to a |
| 373 | library function that you do not have control over. In such a |
| 374 | situation, `numerical differentiation |
| 375 | <http://en.wikipedia.org/wiki/Numerical_differentiation>`_ can be |
| 376 | used. |
| 377 | |
| 378 | .. NOTE :: |
| 379 | |
| 380 | TODO(sameeragarwal): Add documentation for the constructor and for |
| 381 | NumericDiffOptions. Update DynamicNumericDiffOptions in a similar |
| 382 | manner. |
| 383 | |
| 384 | .. code-block:: c++ |
| 385 | |
| 386 | template <typename CostFunctor, |
| 387 | NumericDiffMethodType method = CENTRAL, |
| 388 | int kNumResiduals, // Number of residuals, or ceres::DYNAMIC. |
Austin Schuh | 1d1e6ea | 2020-12-23 21:56:30 -0800 | [diff] [blame] | 389 | int... Ns> // Size of each parameter block. |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 390 | class NumericDiffCostFunction : public |
Austin Schuh | 1d1e6ea | 2020-12-23 21:56:30 -0800 | [diff] [blame] | 391 | SizedCostFunction<kNumResiduals, Ns> { |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 392 | }; |
| 393 | |
| 394 | To get a numerically differentiated :class:`CostFunction`, you must |
| 395 | define a class with a ``operator()`` (a functor) that computes the |
| 396 | residuals. The functor must write the computed value in the last |
| 397 | argument (the only non-``const`` one) and return ``true`` to |
| 398 | indicate success. Please see :class:`CostFunction` for details on |
| 399 | how the return value may be used to impose simple constraints on the |
| 400 | parameter block. e.g., an object of the form |
| 401 | |
| 402 | .. code-block:: c++ |
| 403 | |
| 404 | struct ScalarFunctor { |
| 405 | public: |
| 406 | bool operator()(const double* const x1, |
| 407 | const double* const x2, |
| 408 | double* residuals) const; |
| 409 | } |
| 410 | |
| 411 | For example, consider a scalar error :math:`e = k - x'y`, where both |
| 412 | :math:`x` and :math:`y` are two-dimensional column vector |
| 413 | parameters, the prime sign indicates transposition, and :math:`k` is |
| 414 | a constant. The form of this error, which is the difference between |
| 415 | a constant and an expression, is a common pattern in least squares |
| 416 | problems. For example, the value :math:`x'y` might be the model |
| 417 | expectation for a series of measurements, where there is an instance |
| 418 | of the cost function for each measurement :math:`k`. |
| 419 | |
| 420 | To write an numerically-differentiable class:`CostFunction` for the |
| 421 | above model, first define the object |
| 422 | |
| 423 | .. code-block:: c++ |
| 424 | |
| 425 | class MyScalarCostFunctor { |
| 426 | MyScalarCostFunctor(double k): k_(k) {} |
| 427 | |
| 428 | bool operator()(const double* const x, |
| 429 | const double* const y, |
| 430 | double* residuals) const { |
| 431 | residuals[0] = k_ - x[0] * y[0] + x[1] * y[1]; |
| 432 | return true; |
| 433 | } |
| 434 | |
| 435 | private: |
| 436 | double k_; |
| 437 | }; |
| 438 | |
| 439 | Note that in the declaration of ``operator()`` the input parameters |
| 440 | ``x`` and ``y`` come first, and are passed as const pointers to |
| 441 | arrays of ``double`` s. If there were three input parameters, then |
| 442 | the third input parameter would come after ``y``. The output is |
| 443 | always the last parameter, and is also a pointer to an array. In the |
| 444 | example above, the residual is a scalar, so only ``residuals[0]`` is |
| 445 | set. |
| 446 | |
| 447 | Then given this class definition, the numerically differentiated |
| 448 | :class:`CostFunction` with central differences used for computing |
| 449 | the derivative can be constructed as follows. |
| 450 | |
| 451 | .. code-block:: c++ |
| 452 | |
Austin Schuh | 3de38b0 | 2024-06-25 18:25:10 -0700 | [diff] [blame^] | 453 | auto* cost_function |
| 454 | = new NumericDiffCostFunction<MyScalarCostFunctor, CENTRAL, 1, 2, 2>(1.0) |
| 455 | ^ ^ ^ ^ |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 456 | | | | | |
| 457 | Finite Differencing Scheme -+ | | | |
| 458 | Dimension of residual ------------+ | | |
| 459 | Dimension of x ----------------------+ | |
| 460 | Dimension of y -------------------------+ |
| 461 | |
| 462 | In this example, there is usually an instance for each measurement |
| 463 | of `k`. |
| 464 | |
| 465 | In the instantiation above, the template parameters following |
| 466 | ``MyScalarCostFunctor``, ``1, 2, 2``, describe the functor as |
| 467 | computing a 1-dimensional output from two arguments, both |
| 468 | 2-dimensional. |
| 469 | |
| 470 | NumericDiffCostFunction also supports cost functions with a |
| 471 | runtime-determined number of residuals. For example: |
| 472 | |
| 473 | .. code-block:: c++ |
| 474 | |
Austin Schuh | 3de38b0 | 2024-06-25 18:25:10 -0700 | [diff] [blame^] | 475 | auto functor = std::make_unique<CostFunctorWithDynamicNumResiduals>(1.0); |
| 476 | auto* cost_function |
| 477 | = new NumericDiffCostFunction<CostFunctorWithDynamicNumResiduals, |
| 478 | CENTRAL, DYNAMIC, 2, 2>( |
| 479 | std::move(functor), ^ ^ ^ |
| 480 | runtime_number_of_residuals); <----+ | | | |
| 481 | | | | | |
| 482 | | | | | |
| 483 | Actual number of residuals ------+ | | | |
| 484 | Indicate dynamic number of residuals --------+ | | |
| 485 | Dimension of x ------------------------------------+ | |
| 486 | Dimension of y ---------------------------------------+ |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 487 | |
| 488 | |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 489 | There are three available numeric differentiation schemes in ceres-solver: |
| 490 | |
| 491 | The ``FORWARD`` difference method, which approximates :math:`f'(x)` |
| 492 | by computing :math:`\frac{f(x+h)-f(x)}{h}`, computes the cost |
| 493 | function one additional time at :math:`x+h`. It is the fastest but |
| 494 | least accurate method. |
| 495 | |
| 496 | The ``CENTRAL`` difference method is more accurate at the cost of |
| 497 | twice as many function evaluations than forward difference, |
| 498 | estimating :math:`f'(x)` by computing |
| 499 | :math:`\frac{f(x+h)-f(x-h)}{2h}`. |
| 500 | |
| 501 | The ``RIDDERS`` difference method[Ridders]_ is an adaptive scheme |
| 502 | that estimates derivatives by performing multiple central |
| 503 | differences at varying scales. Specifically, the algorithm starts at |
| 504 | a certain :math:`h` and as the derivative is estimated, this step |
| 505 | size decreases. To conserve function evaluations and estimate the |
| 506 | derivative error, the method performs Richardson extrapolations |
| 507 | between the tested step sizes. The algorithm exhibits considerably |
| 508 | higher accuracy, but does so by additional evaluations of the cost |
| 509 | function. |
| 510 | |
| 511 | Consider using ``CENTRAL`` differences to begin with. Based on the |
| 512 | results, either try forward difference to improve performance or |
| 513 | Ridders' method to improve accuracy. |
| 514 | |
Austin Schuh | 3de38b0 | 2024-06-25 18:25:10 -0700 | [diff] [blame^] | 515 | .. warning:: |
| 516 | A common beginner's error when first using |
| 517 | :class:`NumericDiffCostFunction` is to get the sizing wrong. In |
| 518 | particular, there is a tendency to set the template parameters to |
| 519 | (dimension of residual, number of parameters) instead of passing a |
| 520 | dimension parameter for *every parameter*. In the example above, that |
| 521 | would be ``<MyScalarCostFunctor, 1, 2>``, which is missing the last ``2`` |
| 522 | argument. Please be careful when setting the size parameters. |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 523 | |
| 524 | |
Austin Schuh | 3de38b0 | 2024-06-25 18:25:10 -0700 | [diff] [blame^] | 525 | Numeric Differentiation & Manifolds |
| 526 | ----------------------------------- |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 527 | |
| 528 | If your cost function depends on a parameter block that must lie on |
| 529 | a manifold and the functor cannot be evaluated for values of that |
| 530 | parameter block not on the manifold then you may have problems |
| 531 | numerically differentiating such functors. |
| 532 | |
| 533 | This is because numeric differentiation in Ceres is performed by |
| 534 | perturbing the individual coordinates of the parameter blocks that |
Austin Schuh | 3de38b0 | 2024-06-25 18:25:10 -0700 | [diff] [blame^] | 535 | a cost functor depends on. This perturbation assumes that the |
| 536 | parameter block lives on a Euclidean Manifold rather than the |
| 537 | actual manifold associated with the parameter block. As a result |
| 538 | some of the perturbed points may not lie on the manifold anymore. |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 539 | |
| 540 | For example consider a four dimensional parameter block that is |
| 541 | interpreted as a unit Quaternion. Perturbing the coordinates of |
| 542 | this parameter block will violate the unit norm property of the |
| 543 | parameter block. |
| 544 | |
| 545 | Fixing this problem requires that :class:`NumericDiffCostFunction` |
Austin Schuh | 3de38b0 | 2024-06-25 18:25:10 -0700 | [diff] [blame^] | 546 | be aware of the :class:`Manifold` associated with each |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 547 | parameter block and only generate perturbations in the local |
| 548 | tangent space of each parameter block. |
| 549 | |
| 550 | For now this is not considered to be a serious enough problem to |
| 551 | warrant changing the :class:`NumericDiffCostFunction` API. Further, |
| 552 | in most cases it is relatively straightforward to project a point |
| 553 | off the manifold back onto the manifold before using it in the |
| 554 | functor. For example in case of the Quaternion, normalizing the |
| 555 | 4-vector before using it does the trick. |
| 556 | |
| 557 | **Alternate Interface** |
| 558 | |
| 559 | For a variety of reasons, including compatibility with legacy code, |
| 560 | :class:`NumericDiffCostFunction` can also take |
| 561 | :class:`CostFunction` objects as input. The following describes |
| 562 | how. |
| 563 | |
| 564 | To get a numerically differentiated cost function, define a |
| 565 | subclass of :class:`CostFunction` such that the |
| 566 | :func:`CostFunction::Evaluate` function ignores the ``jacobians`` |
| 567 | parameter. The numeric differentiation wrapper will fill in the |
| 568 | jacobian parameter if necessary by repeatedly calling the |
| 569 | :func:`CostFunction::Evaluate` with small changes to the |
| 570 | appropriate parameters, and computing the slope. For performance, |
| 571 | the numeric differentiation wrapper class is templated on the |
| 572 | concrete cost function, even though it could be implemented only in |
| 573 | terms of the :class:`CostFunction` interface. |
| 574 | |
| 575 | The numerically differentiated version of a cost function for a |
| 576 | cost function can be constructed as follows: |
| 577 | |
| 578 | .. code-block:: c++ |
| 579 | |
Austin Schuh | 3de38b0 | 2024-06-25 18:25:10 -0700 | [diff] [blame^] | 580 | auto* cost_function |
| 581 | = new NumericDiffCostFunction<MyCostFunction, CENTRAL, 1, 4, 8>(...); |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 582 | |
| 583 | where ``MyCostFunction`` has 1 residual and 2 parameter blocks with |
| 584 | sizes 4 and 8 respectively. Look at the tests for a more detailed |
| 585 | example. |
| 586 | |
| 587 | :class:`DynamicNumericDiffCostFunction` |
| 588 | ======================================= |
| 589 | |
| 590 | .. class:: DynamicNumericDiffCostFunction |
| 591 | |
| 592 | Like :class:`AutoDiffCostFunction` :class:`NumericDiffCostFunction` |
| 593 | requires that the number of parameter blocks and their sizes be |
Austin Schuh | 1d1e6ea | 2020-12-23 21:56:30 -0800 | [diff] [blame] | 594 | known at compile time. In a number of applications, this is not enough. |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 595 | |
| 596 | .. code-block:: c++ |
| 597 | |
| 598 | template <typename CostFunctor, NumericDiffMethodType method = CENTRAL> |
| 599 | class DynamicNumericDiffCostFunction : public CostFunction { |
| 600 | }; |
| 601 | |
| 602 | In such cases when numeric differentiation is desired, |
| 603 | :class:`DynamicNumericDiffCostFunction` can be used. |
| 604 | |
| 605 | Like :class:`NumericDiffCostFunction` the user must define a |
| 606 | functor, but the signature of the functor differs slightly. The |
| 607 | expected interface for the cost functors is: |
| 608 | |
| 609 | .. code-block:: c++ |
| 610 | |
| 611 | struct MyCostFunctor { |
| 612 | bool operator()(double const* const* parameters, double* residuals) const { |
| 613 | } |
| 614 | } |
| 615 | |
| 616 | Since the sizing of the parameters is done at runtime, you must |
| 617 | also specify the sizes after creating the dynamic numeric diff cost |
| 618 | function. For example: |
| 619 | |
| 620 | .. code-block:: c++ |
| 621 | |
Austin Schuh | 3de38b0 | 2024-06-25 18:25:10 -0700 | [diff] [blame^] | 622 | auto cost_function = std::make_unique<DynamicNumericDiffCostFunction<MyCostFunctor>>(); |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 623 | cost_function->AddParameterBlock(5); |
| 624 | cost_function->AddParameterBlock(10); |
| 625 | cost_function->SetNumResiduals(21); |
| 626 | |
| 627 | As a rule of thumb, try using :class:`NumericDiffCostFunction` before |
| 628 | you use :class:`DynamicNumericDiffCostFunction`. |
| 629 | |
Austin Schuh | 3de38b0 | 2024-06-25 18:25:10 -0700 | [diff] [blame^] | 630 | .. warning:: |
| 631 | The same caution about mixing manifolds with numeric differentiation |
| 632 | applies as is the case with :class:`NumericDiffCostFunction`. |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 633 | |
| 634 | :class:`CostFunctionToFunctor` |
| 635 | ============================== |
| 636 | |
| 637 | .. class:: CostFunctionToFunctor |
| 638 | |
| 639 | :class:`CostFunctionToFunctor` is an adapter class that allows |
| 640 | users to use :class:`CostFunction` objects in templated functors |
| 641 | which are to be used for automatic differentiation. This allows |
| 642 | the user to seamlessly mix analytic, numeric and automatic |
| 643 | differentiation. |
| 644 | |
| 645 | For example, let us assume that |
| 646 | |
| 647 | .. code-block:: c++ |
| 648 | |
| 649 | class IntrinsicProjection : public SizedCostFunction<2, 5, 3> { |
| 650 | public: |
| 651 | IntrinsicProjection(const double* observation); |
| 652 | virtual bool Evaluate(double const* const* parameters, |
| 653 | double* residuals, |
| 654 | double** jacobians) const; |
| 655 | }; |
| 656 | |
| 657 | is a :class:`CostFunction` that implements the projection of a |
| 658 | point in its local coordinate system onto its image plane and |
| 659 | subtracts it from the observed point projection. It can compute its |
| 660 | residual and either via analytic or numerical differentiation can |
| 661 | compute its jacobians. |
| 662 | |
| 663 | Now we would like to compose the action of this |
| 664 | :class:`CostFunction` with the action of camera extrinsics, i.e., |
| 665 | rotation and translation. Say we have a templated function |
| 666 | |
| 667 | .. code-block:: c++ |
| 668 | |
| 669 | template<typename T> |
| 670 | void RotateAndTranslatePoint(const T* rotation, |
| 671 | const T* translation, |
| 672 | const T* point, |
| 673 | T* result); |
| 674 | |
| 675 | |
| 676 | Then we can now do the following, |
| 677 | |
| 678 | .. code-block:: c++ |
| 679 | |
| 680 | struct CameraProjection { |
Austin Schuh | 3de38b0 | 2024-06-25 18:25:10 -0700 | [diff] [blame^] | 681 | explicit CameraProjection(double* observation) |
| 682 | : intrinsic_projection_(std::make_unique<IntrinsicProjection>(observation)) { |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 683 | } |
| 684 | |
| 685 | template <typename T> |
| 686 | bool operator()(const T* rotation, |
| 687 | const T* translation, |
| 688 | const T* intrinsics, |
| 689 | const T* point, |
| 690 | T* residual) const { |
| 691 | T transformed_point[3]; |
| 692 | RotateAndTranslatePoint(rotation, translation, point, transformed_point); |
| 693 | |
| 694 | // Note that we call intrinsic_projection_, just like it was |
| 695 | // any other templated functor. |
| 696 | return intrinsic_projection_(intrinsics, transformed_point, residual); |
| 697 | } |
| 698 | |
| 699 | private: |
Austin Schuh | 3de38b0 | 2024-06-25 18:25:10 -0700 | [diff] [blame^] | 700 | CostFunctionToFunctor<2, 5, 3> intrinsic_projection_; |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 701 | }; |
| 702 | |
| 703 | Note that :class:`CostFunctionToFunctor` takes ownership of the |
| 704 | :class:`CostFunction` that was passed in to the constructor. |
| 705 | |
| 706 | In the above example, we assumed that ``IntrinsicProjection`` is a |
| 707 | ``CostFunction`` capable of evaluating its value and its |
| 708 | derivatives. Suppose, if that were not the case and |
| 709 | ``IntrinsicProjection`` was defined as follows: |
| 710 | |
| 711 | .. code-block:: c++ |
| 712 | |
Austin Schuh | 1d1e6ea | 2020-12-23 21:56:30 -0800 | [diff] [blame] | 713 | struct IntrinsicProjection { |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 714 | IntrinsicProjection(const double* observation) { |
| 715 | observation_[0] = observation[0]; |
| 716 | observation_[1] = observation[1]; |
| 717 | } |
| 718 | |
| 719 | bool operator()(const double* calibration, |
| 720 | const double* point, |
Austin Schuh | 1d1e6ea | 2020-12-23 21:56:30 -0800 | [diff] [blame] | 721 | double* residuals) const { |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 722 | double projection[2]; |
| 723 | ThirdPartyProjectionFunction(calibration, point, projection); |
| 724 | residuals[0] = observation_[0] - projection[0]; |
| 725 | residuals[1] = observation_[1] - projection[1]; |
| 726 | return true; |
| 727 | } |
Austin Schuh | 1d1e6ea | 2020-12-23 21:56:30 -0800 | [diff] [blame] | 728 | double observation_[2]; |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 729 | }; |
| 730 | |
| 731 | |
| 732 | Here ``ThirdPartyProjectionFunction`` is some third party library |
| 733 | function that we have no control over. So this function can compute |
| 734 | its value and we would like to use numeric differentiation to |
| 735 | compute its derivatives. In this case we can use a combination of |
| 736 | ``NumericDiffCostFunction`` and ``CostFunctionToFunctor`` to get the |
| 737 | job done. |
| 738 | |
| 739 | .. code-block:: c++ |
| 740 | |
| 741 | struct CameraProjection { |
Austin Schuh | 3de38b0 | 2024-06-25 18:25:10 -0700 | [diff] [blame^] | 742 | explicit CameraProjection(double* observation) |
Austin Schuh | 1d1e6ea | 2020-12-23 21:56:30 -0800 | [diff] [blame] | 743 | : intrinsic_projection_( |
Austin Schuh | 3de38b0 | 2024-06-25 18:25:10 -0700 | [diff] [blame^] | 744 | std::make_unique<NumericDiffCostFunction<IntrinsicProjection, CENTRAL, 2, 5, 3>>()) {} |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 745 | |
| 746 | template <typename T> |
| 747 | bool operator()(const T* rotation, |
| 748 | const T* translation, |
| 749 | const T* intrinsics, |
| 750 | const T* point, |
| 751 | T* residuals) const { |
| 752 | T transformed_point[3]; |
| 753 | RotateAndTranslatePoint(rotation, translation, point, transformed_point); |
Austin Schuh | 1d1e6ea | 2020-12-23 21:56:30 -0800 | [diff] [blame] | 754 | return intrinsic_projection_(intrinsics, transformed_point, residuals); |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 755 | } |
| 756 | |
| 757 | private: |
Austin Schuh | 1d1e6ea | 2020-12-23 21:56:30 -0800 | [diff] [blame] | 758 | CostFunctionToFunctor<2, 5, 3> intrinsic_projection_; |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 759 | }; |
| 760 | |
Austin Schuh | 1d1e6ea | 2020-12-23 21:56:30 -0800 | [diff] [blame] | 761 | |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 762 | :class:`DynamicCostFunctionToFunctor` |
| 763 | ===================================== |
| 764 | |
| 765 | .. class:: DynamicCostFunctionToFunctor |
| 766 | |
| 767 | :class:`DynamicCostFunctionToFunctor` provides the same functionality as |
| 768 | :class:`CostFunctionToFunctor` for cases where the number and size of the |
| 769 | parameter vectors and residuals are not known at compile-time. The API |
| 770 | provided by :class:`DynamicCostFunctionToFunctor` matches what would be |
| 771 | expected by :class:`DynamicAutoDiffCostFunction`, i.e. it provides a |
| 772 | templated functor of this form: |
| 773 | |
| 774 | .. code-block:: c++ |
| 775 | |
| 776 | template<typename T> |
| 777 | bool operator()(T const* const* parameters, T* residuals) const; |
| 778 | |
| 779 | Similar to the example given for :class:`CostFunctionToFunctor`, let us |
| 780 | assume that |
| 781 | |
| 782 | .. code-block:: c++ |
| 783 | |
| 784 | class IntrinsicProjection : public CostFunction { |
| 785 | public: |
| 786 | IntrinsicProjection(const double* observation); |
| 787 | virtual bool Evaluate(double const* const* parameters, |
| 788 | double* residuals, |
| 789 | double** jacobians) const; |
| 790 | }; |
| 791 | |
| 792 | is a :class:`CostFunction` that projects a point in its local coordinate |
| 793 | system onto its image plane and subtracts it from the observed point |
| 794 | projection. |
| 795 | |
| 796 | Using this :class:`CostFunction` in a templated functor would then look like |
| 797 | this: |
| 798 | |
| 799 | .. code-block:: c++ |
| 800 | |
| 801 | struct CameraProjection { |
Austin Schuh | 3de38b0 | 2024-06-25 18:25:10 -0700 | [diff] [blame^] | 802 | explicit CameraProjection(double* observation) |
| 803 | : intrinsic_projection_(std::make_unique<IntrinsicProjection>(observation)) { |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 804 | } |
| 805 | |
| 806 | template <typename T> |
| 807 | bool operator()(T const* const* parameters, |
| 808 | T* residual) const { |
| 809 | const T* rotation = parameters[0]; |
| 810 | const T* translation = parameters[1]; |
| 811 | const T* intrinsics = parameters[2]; |
| 812 | const T* point = parameters[3]; |
| 813 | |
| 814 | T transformed_point[3]; |
| 815 | RotateAndTranslatePoint(rotation, translation, point, transformed_point); |
| 816 | |
| 817 | const T* projection_parameters[2]; |
| 818 | projection_parameters[0] = intrinsics; |
| 819 | projection_parameters[1] = transformed_point; |
| 820 | return intrinsic_projection_(projection_parameters, residual); |
| 821 | } |
| 822 | |
| 823 | private: |
| 824 | DynamicCostFunctionToFunctor intrinsic_projection_; |
| 825 | }; |
| 826 | |
| 827 | Like :class:`CostFunctionToFunctor`, :class:`DynamicCostFunctionToFunctor` |
| 828 | takes ownership of the :class:`CostFunction` that was passed in to the |
| 829 | constructor. |
| 830 | |
| 831 | :class:`ConditionedCostFunction` |
| 832 | ================================ |
| 833 | |
| 834 | .. class:: ConditionedCostFunction |
| 835 | |
| 836 | This class allows you to apply different conditioning to the residual |
| 837 | values of a wrapped cost function. An example where this is useful is |
| 838 | where you have an existing cost function that produces N values, but you |
| 839 | want the total cost to be something other than just the sum of these |
| 840 | squared values - maybe you want to apply a different scaling to some |
| 841 | values, to change their contribution to the cost. |
| 842 | |
| 843 | Usage: |
| 844 | |
| 845 | .. code-block:: c++ |
| 846 | |
| 847 | // my_cost_function produces N residuals |
| 848 | CostFunction* my_cost_function = ... |
| 849 | CHECK_EQ(N, my_cost_function->num_residuals()); |
Austin Schuh | 3de38b0 | 2024-06-25 18:25:10 -0700 | [diff] [blame^] | 850 | std::vector<CostFunction*> conditioners; |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 851 | |
| 852 | // Make N 1x1 cost functions (1 parameter, 1 residual) |
| 853 | CostFunction* f_1 = ... |
| 854 | conditioners.push_back(f_1); |
| 855 | |
| 856 | CostFunction* f_N = ... |
| 857 | conditioners.push_back(f_N); |
| 858 | ConditionedCostFunction* ccf = |
| 859 | new ConditionedCostFunction(my_cost_function, conditioners); |
| 860 | |
| 861 | |
| 862 | Now ``ccf`` 's ``residual[i]`` (i=0..N-1) will be passed though the |
| 863 | :math:`i^{\text{th}}` conditioner. |
| 864 | |
| 865 | .. code-block:: c++ |
| 866 | |
| 867 | ccf_residual[i] = f_i(my_cost_function_residual[i]) |
| 868 | |
| 869 | and the Jacobian will be affected appropriately. |
| 870 | |
| 871 | |
| 872 | :class:`GradientChecker` |
Austin Schuh | 3de38b0 | 2024-06-25 18:25:10 -0700 | [diff] [blame^] | 873 | ======================== |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 874 | |
| 875 | .. class:: GradientChecker |
| 876 | |
Austin Schuh | 3de38b0 | 2024-06-25 18:25:10 -0700 | [diff] [blame^] | 877 | This class compares the Jacobians returned by a cost function |
| 878 | against derivatives estimated using finite differencing. It is |
| 879 | meant as a tool for unit testing, giving you more fine-grained |
| 880 | control than the check_gradients option in the solver options. |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 881 | |
| 882 | The condition enforced is that |
| 883 | |
| 884 | .. math:: \forall{i,j}: \frac{J_{ij} - J'_{ij}}{max_{ij}(J_{ij} - J'_{ij})} < r |
| 885 | |
Austin Schuh | 3de38b0 | 2024-06-25 18:25:10 -0700 | [diff] [blame^] | 886 | where :math:`J_{ij}` is the jacobian as computed by the supplied |
| 887 | cost function multiplied by the `Manifold::PlusJacobian`, |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 888 | :math:`J'_{ij}` is the jacobian as computed by finite differences, |
Austin Schuh | 3de38b0 | 2024-06-25 18:25:10 -0700 | [diff] [blame^] | 889 | multiplied by the `Manifold::PlusJacobian` as well, and :math:`r` |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 890 | is the relative precision. |
| 891 | |
| 892 | Usage: |
| 893 | |
| 894 | .. code-block:: c++ |
| 895 | |
Austin Schuh | 3de38b0 | 2024-06-25 18:25:10 -0700 | [diff] [blame^] | 896 | // my_cost_function takes two parameter blocks. The first has a |
| 897 | // manifold associated with it. |
| 898 | |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 899 | CostFunction* my_cost_function = ... |
Austin Schuh | 3de38b0 | 2024-06-25 18:25:10 -0700 | [diff] [blame^] | 900 | Manifold* my_manifold = ... |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 901 | NumericDiffOptions numeric_diff_options; |
| 902 | |
Austin Schuh | 3de38b0 | 2024-06-25 18:25:10 -0700 | [diff] [blame^] | 903 | std::vector<Manifold*> manifolds; |
| 904 | manifolds.push_back(my_manifold); |
| 905 | manifolds.push_back(nullptr); |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 906 | |
| 907 | std::vector parameter1; |
| 908 | std::vector parameter2; |
| 909 | // Fill parameter 1 & 2 with test data... |
| 910 | |
| 911 | std::vector<double*> parameter_blocks; |
| 912 | parameter_blocks.push_back(parameter1.data()); |
| 913 | parameter_blocks.push_back(parameter2.data()); |
| 914 | |
| 915 | GradientChecker gradient_checker(my_cost_function, |
Austin Schuh | 3de38b0 | 2024-06-25 18:25:10 -0700 | [diff] [blame^] | 916 | manifolds, |
| 917 | numeric_diff_options); |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 918 | GradientCheckResults results; |
| 919 | if (!gradient_checker.Probe(parameter_blocks.data(), 1e-9, &results) { |
| 920 | LOG(ERROR) << "An error has occurred:\n" << results.error_log; |
| 921 | } |
| 922 | |
| 923 | |
| 924 | :class:`NormalPrior` |
| 925 | ==================== |
| 926 | |
| 927 | .. class:: NormalPrior |
| 928 | |
| 929 | .. code-block:: c++ |
| 930 | |
| 931 | class NormalPrior: public CostFunction { |
| 932 | public: |
| 933 | // Check that the number of rows in the vector b are the same as the |
| 934 | // number of columns in the matrix A, crash otherwise. |
| 935 | NormalPrior(const Matrix& A, const Vector& b); |
| 936 | |
| 937 | virtual bool Evaluate(double const* const* parameters, |
| 938 | double* residuals, |
| 939 | double** jacobians) const; |
| 940 | }; |
| 941 | |
| 942 | Implements a cost function of the form |
| 943 | |
| 944 | .. math:: cost(x) = ||A(x - b)||^2 |
| 945 | |
| 946 | where, the matrix :math:`A` and the vector :math:`b` are fixed and :math:`x` |
| 947 | is the variable. In case the user is interested in implementing a cost |
| 948 | function of the form |
| 949 | |
| 950 | .. math:: cost(x) = (x - \mu)^T S^{-1} (x - \mu) |
| 951 | |
| 952 | where, :math:`\mu` is a vector and :math:`S` is a covariance matrix, |
| 953 | then, :math:`A = S^{-1/2}`, i.e the matrix :math:`A` is the square |
| 954 | root of the inverse of the covariance, also known as the stiffness |
| 955 | matrix. There are however no restrictions on the shape of |
| 956 | :math:`A`. It is free to be rectangular, which would be the case if |
| 957 | the covariance matrix :math:`S` is rank deficient. |
| 958 | |
| 959 | |
| 960 | |
| 961 | .. _`section-loss_function`: |
| 962 | |
| 963 | :class:`LossFunction` |
| 964 | ===================== |
| 965 | |
| 966 | .. class:: LossFunction |
| 967 | |
| 968 | For least squares problems where the minimization may encounter |
| 969 | input terms that contain outliers, that is, completely bogus |
| 970 | measurements, it is important to use a loss function that reduces |
| 971 | their influence. |
| 972 | |
| 973 | Consider a structure from motion problem. The unknowns are 3D |
| 974 | points and camera parameters, and the measurements are image |
| 975 | coordinates describing the expected reprojected position for a |
| 976 | point in a camera. For example, we want to model the geometry of a |
| 977 | street scene with fire hydrants and cars, observed by a moving |
| 978 | camera with unknown parameters, and the only 3D points we care |
| 979 | about are the pointy tippy-tops of the fire hydrants. Our magic |
| 980 | image processing algorithm, which is responsible for producing the |
| 981 | measurements that are input to Ceres, has found and matched all |
| 982 | such tippy-tops in all image frames, except that in one of the |
| 983 | frame it mistook a car's headlight for a hydrant. If we didn't do |
| 984 | anything special the residual for the erroneous measurement will |
| 985 | result in the entire solution getting pulled away from the optimum |
| 986 | to reduce the large error that would otherwise be attributed to the |
| 987 | wrong measurement. |
| 988 | |
| 989 | Using a robust loss function, the cost for large residuals is |
| 990 | reduced. In the example above, this leads to outlier terms getting |
| 991 | down-weighted so they do not overly influence the final solution. |
| 992 | |
| 993 | .. code-block:: c++ |
| 994 | |
| 995 | class LossFunction { |
| 996 | public: |
| 997 | virtual void Evaluate(double s, double out[3]) const = 0; |
| 998 | }; |
| 999 | |
| 1000 | |
| 1001 | The key method is :func:`LossFunction::Evaluate`, which given a |
| 1002 | non-negative scalar ``s``, computes |
| 1003 | |
| 1004 | .. math:: out = \begin{bmatrix}\rho(s), & \rho'(s), & \rho''(s)\end{bmatrix} |
| 1005 | |
| 1006 | Here the convention is that the contribution of a term to the cost |
| 1007 | function is given by :math:`\frac{1}{2}\rho(s)`, where :math:`s |
| 1008 | =\|f_i\|^2`. Calling the method with a negative value of :math:`s` |
| 1009 | is an error and the implementations are not required to handle that |
| 1010 | case. |
| 1011 | |
| 1012 | Most sane choices of :math:`\rho` satisfy: |
| 1013 | |
| 1014 | .. math:: |
| 1015 | |
| 1016 | \rho(0) &= 0\\ |
| 1017 | \rho'(0) &= 1\\ |
| 1018 | \rho'(s) &< 1 \text{ in the outlier region}\\ |
| 1019 | \rho''(s) &< 0 \text{ in the outlier region} |
| 1020 | |
| 1021 | so that they mimic the squared cost for small residuals. |
| 1022 | |
| 1023 | **Scaling** |
| 1024 | |
| 1025 | Given one robustifier :math:`\rho(s)` one can change the length |
| 1026 | scale at which robustification takes place, by adding a scale |
| 1027 | factor :math:`a > 0` which gives us :math:`\rho(s,a) = a^2 \rho(s / |
| 1028 | a^2)` and the first and second derivatives as :math:`\rho'(s / |
| 1029 | a^2)` and :math:`(1 / a^2) \rho''(s / a^2)` respectively. |
| 1030 | |
| 1031 | |
| 1032 | The reason for the appearance of squaring is that :math:`a` is in |
| 1033 | the units of the residual vector norm whereas :math:`s` is a squared |
| 1034 | norm. For applications it is more convenient to specify :math:`a` than |
| 1035 | its square. |
| 1036 | |
| 1037 | Instances |
| 1038 | --------- |
| 1039 | |
| 1040 | Ceres includes a number of predefined loss functions. For simplicity |
| 1041 | we described their unscaled versions. The figure below illustrates |
| 1042 | their shape graphically. More details can be found in |
| 1043 | ``include/ceres/loss_function.h``. |
| 1044 | |
| 1045 | .. figure:: loss.png |
| 1046 | :figwidth: 500px |
| 1047 | :height: 400px |
| 1048 | :align: center |
| 1049 | |
| 1050 | Shape of the various common loss functions. |
| 1051 | |
| 1052 | .. class:: TrivialLoss |
| 1053 | |
| 1054 | .. math:: \rho(s) = s |
| 1055 | |
| 1056 | .. class:: HuberLoss |
| 1057 | |
| 1058 | .. math:: \rho(s) = \begin{cases} s & s \le 1\\ 2 \sqrt{s} - 1 & s > 1 \end{cases} |
| 1059 | |
| 1060 | .. class:: SoftLOneLoss |
| 1061 | |
| 1062 | .. math:: \rho(s) = 2 (\sqrt{1+s} - 1) |
| 1063 | |
| 1064 | .. class:: CauchyLoss |
| 1065 | |
| 1066 | .. math:: \rho(s) = \log(1 + s) |
| 1067 | |
| 1068 | .. class:: ArctanLoss |
| 1069 | |
| 1070 | .. math:: \rho(s) = \arctan(s) |
| 1071 | |
| 1072 | .. class:: TolerantLoss |
| 1073 | |
| 1074 | .. math:: \rho(s,a,b) = b \log(1 + e^{(s - a) / b}) - b \log(1 + e^{-a / b}) |
| 1075 | |
Austin Schuh | 3de38b0 | 2024-06-25 18:25:10 -0700 | [diff] [blame^] | 1076 | .. class:: TukeyLoss |
| 1077 | |
| 1078 | .. math:: \rho(s) = \begin{cases} \frac{1}{3} (1 - (1 - s)^3) & s \le 1\\ \frac{1}{3} & s > 1 \end{cases} |
| 1079 | |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 1080 | .. class:: ComposedLoss |
| 1081 | |
| 1082 | Given two loss functions ``f`` and ``g``, implements the loss |
| 1083 | function ``h(s) = f(g(s))``. |
| 1084 | |
| 1085 | .. code-block:: c++ |
| 1086 | |
| 1087 | class ComposedLoss : public LossFunction { |
| 1088 | public: |
| 1089 | explicit ComposedLoss(const LossFunction* f, |
| 1090 | Ownership ownership_f, |
| 1091 | const LossFunction* g, |
| 1092 | Ownership ownership_g); |
| 1093 | }; |
| 1094 | |
| 1095 | .. class:: ScaledLoss |
| 1096 | |
| 1097 | Sometimes you want to simply scale the output value of the |
| 1098 | robustifier. For example, you might want to weight different error |
| 1099 | terms differently (e.g., weight pixel reprojection errors |
| 1100 | differently from terrain errors). |
| 1101 | |
| 1102 | Given a loss function :math:`\rho(s)` and a scalar :math:`a`, :class:`ScaledLoss` |
| 1103 | implements the function :math:`a \rho(s)`. |
| 1104 | |
Austin Schuh | 1d1e6ea | 2020-12-23 21:56:30 -0800 | [diff] [blame] | 1105 | Since we treat a ``nullptr`` Loss function as the Identity loss |
| 1106 | function, :math:`rho` = ``nullptr``: is a valid input and will result |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 1107 | in the input being scaled by :math:`a`. This provides a simple way |
| 1108 | of implementing a scaled ResidualBlock. |
| 1109 | |
| 1110 | .. class:: LossFunctionWrapper |
| 1111 | |
| 1112 | Sometimes after the optimization problem has been constructed, we |
| 1113 | wish to mutate the scale of the loss function. For example, when |
| 1114 | performing estimation from data which has substantial outliers, |
| 1115 | convergence can be improved by starting out with a large scale, |
| 1116 | optimizing the problem and then reducing the scale. This can have |
| 1117 | better convergence behavior than just using a loss function with a |
| 1118 | small scale. |
| 1119 | |
| 1120 | This templated class allows the user to implement a loss function |
| 1121 | whose scale can be mutated after an optimization problem has been |
| 1122 | constructed, e.g, |
| 1123 | |
| 1124 | .. code-block:: c++ |
| 1125 | |
| 1126 | Problem problem; |
| 1127 | |
| 1128 | // Add parameter blocks |
| 1129 | |
Austin Schuh | 3de38b0 | 2024-06-25 18:25:10 -0700 | [diff] [blame^] | 1130 | auto* cost_function = |
| 1131 | new AutoDiffCostFunction<UW_Camera_Mapper, 2, 9, 3>(feature_x, feature_y); |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 1132 | |
| 1133 | LossFunctionWrapper* loss_function(new HuberLoss(1.0), TAKE_OWNERSHIP); |
| 1134 | problem.AddResidualBlock(cost_function, loss_function, parameters); |
| 1135 | |
| 1136 | Solver::Options options; |
| 1137 | Solver::Summary summary; |
| 1138 | Solve(options, &problem, &summary); |
| 1139 | |
| 1140 | loss_function->Reset(new HuberLoss(1.0), TAKE_OWNERSHIP); |
| 1141 | Solve(options, &problem, &summary); |
| 1142 | |
| 1143 | |
| 1144 | Theory |
| 1145 | ------ |
| 1146 | |
Austin Schuh | 1d1e6ea | 2020-12-23 21:56:30 -0800 | [diff] [blame] | 1147 | Let us consider a problem with a single parameter block. |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 1148 | |
| 1149 | .. math:: |
| 1150 | |
| 1151 | \min_x \frac{1}{2}\rho(f^2(x)) |
| 1152 | |
| 1153 | |
| 1154 | Then, the robustified gradient and the Gauss-Newton Hessian are |
| 1155 | |
| 1156 | .. math:: |
| 1157 | |
| 1158 | g(x) &= \rho'J^\top(x)f(x)\\ |
| 1159 | H(x) &= J^\top(x)\left(\rho' + 2 \rho''f(x)f^\top(x)\right)J(x) |
| 1160 | |
| 1161 | where the terms involving the second derivatives of :math:`f(x)` have |
| 1162 | been ignored. Note that :math:`H(x)` is indefinite if |
| 1163 | :math:`\rho''f(x)^\top f(x) + \frac{1}{2}\rho' < 0`. If this is not |
| 1164 | the case, then its possible to re-weight the residual and the Jacobian |
Austin Schuh | 1d1e6ea | 2020-12-23 21:56:30 -0800 | [diff] [blame] | 1165 | matrix such that the robustified Gauss-Newton step corresponds to an |
| 1166 | ordinary linear least squares problem. |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 1167 | |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 1168 | Let :math:`\alpha` be a root of |
| 1169 | |
| 1170 | .. math:: \frac{1}{2}\alpha^2 - \alpha - \frac{\rho''}{\rho'}\|f(x)\|^2 = 0. |
| 1171 | |
| 1172 | |
| 1173 | Then, define the rescaled residual and Jacobian as |
| 1174 | |
| 1175 | .. math:: |
| 1176 | |
| 1177 | \tilde{f}(x) &= \frac{\sqrt{\rho'}}{1 - \alpha} f(x)\\ |
| 1178 | \tilde{J}(x) &= \sqrt{\rho'}\left(1 - \alpha |
| 1179 | \frac{f(x)f^\top(x)}{\left\|f(x)\right\|^2} \right)J(x) |
| 1180 | |
| 1181 | |
| 1182 | In the case :math:`2 \rho''\left\|f(x)\right\|^2 + \rho' \lesssim 0`, |
| 1183 | we limit :math:`\alpha \le 1- \epsilon` for some small |
| 1184 | :math:`\epsilon`. For more details see [Triggs]_. |
| 1185 | |
Austin Schuh | 1d1e6ea | 2020-12-23 21:56:30 -0800 | [diff] [blame] | 1186 | With this simple rescaling, one can apply any Jacobian based non-linear |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 1187 | least squares algorithm to robustified non-linear least squares |
| 1188 | problems. |
| 1189 | |
| 1190 | |
Austin Schuh | 3de38b0 | 2024-06-25 18:25:10 -0700 | [diff] [blame^] | 1191 | While the theory described above is elegant, in practice we observe |
| 1192 | that using the Triggs correction when :math:`\rho'' > 0` leads to poor |
| 1193 | performance, so we upper bound it by zero. For more details see |
| 1194 | `corrector.cc <https://github.com/ceres-solver/ceres-solver/blob/master/internal/ceres/corrector.cc#L51>`_ |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 1195 | |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 1196 | |
Austin Schuh | 3de38b0 | 2024-06-25 18:25:10 -0700 | [diff] [blame^] | 1197 | :class:`Manifold` |
| 1198 | ================== |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 1199 | |
Austin Schuh | 3de38b0 | 2024-06-25 18:25:10 -0700 | [diff] [blame^] | 1200 | .. class:: Manifold |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 1201 | |
Austin Schuh | 3de38b0 | 2024-06-25 18:25:10 -0700 | [diff] [blame^] | 1202 | In sensor fusion problems, we often have to model quantities that live |
| 1203 | in spaces known as `Manifolds |
| 1204 | <https://en.wikipedia.org/wiki/Manifold>`_, for example the |
| 1205 | rotation/orientation of a sensor that is represented by a `Quaternion |
| 1206 | <https://en.wikipedia.org/wiki/Quaternion>`_. |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 1207 | |
Austin Schuh | 3de38b0 | 2024-06-25 18:25:10 -0700 | [diff] [blame^] | 1208 | Manifolds are spaces which locally look like Euclidean spaces. More |
| 1209 | precisely, at each point on the manifold there is a linear space that |
| 1210 | is tangent to the manifold. It has dimension equal to the intrinsic |
| 1211 | dimension of the manifold itself, which is less than or equal to the |
| 1212 | ambient space in which the manifold is embedded. |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 1213 | |
Austin Schuh | 3de38b0 | 2024-06-25 18:25:10 -0700 | [diff] [blame^] | 1214 | For example, the tangent space to a point on a sphere in three |
| 1215 | dimensions is the two dimensional plane that is tangent to the sphere |
| 1216 | at that point. There are two reasons tangent spaces are interesting: |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 1217 | |
Austin Schuh | 3de38b0 | 2024-06-25 18:25:10 -0700 | [diff] [blame^] | 1218 | 1. They are Eucliean spaces so the usual vector space operations apply |
| 1219 | there, which makes numerical operations easy. |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 1220 | |
Austin Schuh | 3de38b0 | 2024-06-25 18:25:10 -0700 | [diff] [blame^] | 1221 | 2. Movements in the tangent space translate into movements along the |
| 1222 | manifold. Movements perpendicular to the tangent space do not |
| 1223 | translate into movements on the manifold. |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 1224 | |
Austin Schuh | 3de38b0 | 2024-06-25 18:25:10 -0700 | [diff] [blame^] | 1225 | However, moving along the 2 dimensional plane tangent to the sphere |
| 1226 | and projecting back onto the sphere will move you away from the point |
| 1227 | you started from but moving along the normal at the same point and the |
| 1228 | projecting back onto the sphere brings you back to the point. |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 1229 | |
Austin Schuh | 3de38b0 | 2024-06-25 18:25:10 -0700 | [diff] [blame^] | 1230 | Besides the mathematical niceness, modeling manifold valued |
| 1231 | quantities correctly and paying attention to their geometry has |
| 1232 | practical benefits too: |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 1233 | |
Austin Schuh | 3de38b0 | 2024-06-25 18:25:10 -0700 | [diff] [blame^] | 1234 | 1. It naturally constrains the quantity to the manifold throughout the |
| 1235 | optimization, freeing the user from hacks like *quaternion |
| 1236 | normalization*. |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 1237 | |
Austin Schuh | 3de38b0 | 2024-06-25 18:25:10 -0700 | [diff] [blame^] | 1238 | 2. It reduces the dimension of the optimization problem to its |
| 1239 | *natural* size. For example, a quantity restricted to a line is a |
| 1240 | one dimensional object regardless of the dimension of the ambient |
| 1241 | space in which this line lives. |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 1242 | |
Austin Schuh | 3de38b0 | 2024-06-25 18:25:10 -0700 | [diff] [blame^] | 1243 | Working in the tangent space reduces not just the computational |
| 1244 | complexity of the optimization algorithm, but also improves the |
| 1245 | numerical behaviour of the algorithm. |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 1246 | |
Austin Schuh | 3de38b0 | 2024-06-25 18:25:10 -0700 | [diff] [blame^] | 1247 | A basic operation one can perform on a manifold is the |
| 1248 | :math:`\boxplus` operation that computes the result of moving along |
| 1249 | :math:`\delta` in the tangent space at :math:`x`, and then projecting |
| 1250 | back onto the manifold that :math:`x` belongs to. Also known as a |
| 1251 | *Retraction*, :math:`\boxplus` is a generalization of vector addition |
| 1252 | in Euclidean spaces. |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 1253 | |
Austin Schuh | 3de38b0 | 2024-06-25 18:25:10 -0700 | [diff] [blame^] | 1254 | The inverse of :math:`\boxplus` is :math:`\boxminus`, which given two |
| 1255 | points :math:`y` and :math:`x` on the manifold computes the tangent |
| 1256 | vector :math:`\Delta` at :math:`x` s.t. :math:`\boxplus(x, \Delta) = |
| 1257 | y`. |
| 1258 | |
| 1259 | Let us now consider two examples. |
| 1260 | |
| 1261 | The `Euclidean space <https://en.wikipedia.org/wiki/Euclidean_space>`_ |
| 1262 | :math:`\mathbb{R}^n` is the simplest example of a manifold. It has |
| 1263 | dimension :math:`n` (and so does its tangent space) and |
| 1264 | :math:`\boxplus` and :math:`\boxminus` are the familiar vector sum and |
| 1265 | difference operations. |
| 1266 | |
| 1267 | .. math:: |
| 1268 | \begin{align*} |
| 1269 | \boxplus(x, \Delta) &= x + \Delta = y\\ |
| 1270 | \boxminus(y, x) &= y - x = \Delta. |
| 1271 | \end{align*} |
| 1272 | |
| 1273 | A more interesting case is the case :math:`SO(3)`, the `special |
| 1274 | orthogonal group <https://en.wikipedia.org/wiki/3D_rotation_group>`_ |
| 1275 | in three dimensions - the space of :math:`3\times3` rotation |
| 1276 | matrices. :math:`SO(3)` is a three dimensional manifold embedded in |
| 1277 | :math:`\mathbb{R}^9` or :math:`\mathbb{R}^{3\times 3}`. So points on :math:`SO(3)` are |
| 1278 | represented using 9 dimensional vectors or :math:`3\times 3` matrices, |
| 1279 | and points in its tangent spaces are represented by 3 dimensional |
| 1280 | vectors. |
| 1281 | |
| 1282 | For :math:`SO(3)`, :math:`\boxplus` and :math:`\boxminus` are defined |
| 1283 | in terms of the matrix :math:`\exp` and :math:`\log` operations as |
| 1284 | follows: |
| 1285 | |
| 1286 | Given a 3-vector :math:`\Delta = [\begin{matrix}p,&q,&r\end{matrix}]`, we have |
| 1287 | |
| 1288 | .. math:: |
| 1289 | |
| 1290 | \exp(\Delta) & = \left [ \begin{matrix} |
| 1291 | \cos \theta + cp^2 & -sr + cpq & sq + cpr \\ |
| 1292 | sr + cpq & \cos \theta + cq^2& -sp + cqr \\ |
| 1293 | -sq + cpr & sp + cqr & \cos \theta + cr^2 |
| 1294 | \end{matrix} \right ] |
| 1295 | |
| 1296 | where, |
| 1297 | |
| 1298 | .. math:: |
| 1299 | \begin{align} |
| 1300 | \theta &= \sqrt{p^2 + q^2 + r^2},\\ |
| 1301 | s &= \frac{\sin \theta}{\theta},\\ |
| 1302 | c &= \frac{1 - \cos \theta}{\theta^2}. |
| 1303 | \end{align} |
| 1304 | |
| 1305 | Given :math:`x \in SO(3)`, we have |
| 1306 | |
| 1307 | .. math:: |
| 1308 | |
| 1309 | \log(x) = 1/(2 \sin(\theta)/\theta)\left[\begin{matrix} x_{32} - x_{23},& x_{13} - x_{31},& x_{21} - x_{12}\end{matrix} \right] |
| 1310 | |
| 1311 | |
| 1312 | where, |
| 1313 | |
| 1314 | .. math:: \theta = \cos^{-1}((\operatorname{Trace}(x) - 1)/2) |
| 1315 | |
| 1316 | Then, |
| 1317 | |
| 1318 | .. math:: |
| 1319 | \begin{align*} |
| 1320 | \boxplus(x, \Delta) &= x \exp(\Delta) |
| 1321 | \\ |
| 1322 | \boxminus(y, x) &= \log(x^T y) |
| 1323 | \end{align*} |
| 1324 | |
| 1325 | For :math:`\boxplus` and :math:`\boxminus` to be mathematically |
| 1326 | consistent, the following identities must be satisfied at all points |
| 1327 | :math:`x` on the manifold: |
| 1328 | |
| 1329 | 1. :math:`\boxplus(x, 0) = x`. This ensures that the tangent space is |
| 1330 | *centered* at :math:`x`, and the zero vector is the identity |
| 1331 | element. |
| 1332 | 2. For all :math:`y` on the manifold, :math:`\boxplus(x, |
| 1333 | \boxminus(y,x)) = y`. This ensures that any :math:`y` can be |
| 1334 | reached from :math:`x`. |
| 1335 | 3. For all :math:`\Delta`, :math:`\boxminus(\boxplus(x, \Delta), x) = |
| 1336 | \Delta`. This ensures that :math:`\boxplus` is an injective |
| 1337 | (one-to-one) map. |
| 1338 | 4. For all :math:`\Delta_1, \Delta_2\ |\boxminus(\boxplus(x, \Delta_1), |
| 1339 | \boxplus(x, \Delta_2)) \leq |\Delta_1 - \Delta_2|`. Allows us to define |
| 1340 | a metric on the manifold. |
| 1341 | |
| 1342 | Additionally we require that :math:`\boxplus` and :math:`\boxminus` be |
| 1343 | sufficiently smooth. In particular they need to be differentiable |
| 1344 | everywhere on the manifold. |
| 1345 | |
| 1346 | For more details, please see [Hertzberg]_ |
| 1347 | |
| 1348 | The :class:`Manifold` interface allows the user to define a manifold |
| 1349 | for the purposes optimization by implementing ``Plus`` and ``Minus`` |
| 1350 | operations and their derivatives (corresponding naturally to |
| 1351 | :math:`\boxplus` and :math:`\boxminus`). |
| 1352 | |
| 1353 | .. code-block:: c++ |
| 1354 | |
| 1355 | class Manifold { |
| 1356 | public: |
| 1357 | virtual ~Manifold(); |
| 1358 | virtual int AmbientSize() const = 0; |
| 1359 | virtual int TangentSize() const = 0; |
| 1360 | virtual bool Plus(const double* x, |
| 1361 | const double* delta, |
| 1362 | double* x_plus_delta) const = 0; |
| 1363 | virtual bool PlusJacobian(const double* x, double* jacobian) const = 0; |
| 1364 | virtual bool RightMultiplyByPlusJacobian(const double* x, |
| 1365 | const int num_rows, |
| 1366 | const double* ambient_matrix, |
| 1367 | double* tangent_matrix) const; |
| 1368 | virtual bool Minus(const double* y, |
| 1369 | const double* x, |
| 1370 | double* y_minus_x) const = 0; |
| 1371 | virtual bool MinusJacobian(const double* x, double* jacobian) const = 0; |
| 1372 | }; |
| 1373 | |
| 1374 | |
| 1375 | .. function:: int Manifold::AmbientSize() const; |
| 1376 | |
| 1377 | Dimension of the ambient space in which the manifold is embedded. |
| 1378 | |
| 1379 | .. function:: int Manifold::TangentSize() const; |
| 1380 | |
| 1381 | Dimension of the manifold/tangent space. |
| 1382 | |
| 1383 | .. function:: bool Plus(const double* x, const double* delta, double* x_plus_delta) const; |
| 1384 | |
| 1385 | Implements the :math:`\boxplus(x,\Delta)` operation for the manifold. |
| 1386 | |
| 1387 | A generalization of vector addition in Euclidean space, ``Plus`` |
| 1388 | computes the result of moving along ``delta`` in the tangent space |
| 1389 | at ``x``, and then projecting back onto the manifold that ``x`` |
| 1390 | belongs to. |
| 1391 | |
| 1392 | ``x`` and ``x_plus_delta`` are :func:`Manifold::AmbientSize` vectors. |
| 1393 | ``delta`` is a :func:`Manifold::TangentSize` vector. |
| 1394 | |
| 1395 | Return value indicates if the operation was successful or not. |
| 1396 | |
| 1397 | .. function:: bool PlusJacobian(const double* x, double* jacobian) const; |
| 1398 | |
| 1399 | Compute the derivative of :math:`\boxplus(x, \Delta)` w.r.t |
| 1400 | :math:`\Delta` at :math:`\Delta = 0`, i.e. :math:`(D_2 |
| 1401 | \boxplus)(x, 0)`. |
| 1402 | |
| 1403 | ``jacobian`` is a row-major :func:`Manifold::AmbientSize` |
| 1404 | :math:`\times` :func:`Manifold::TangentSize` matrix. |
| 1405 | |
| 1406 | Return value indicates whether the operation was successful or not. |
| 1407 | |
| 1408 | .. function:: bool RightMultiplyByPlusJacobian(const double* x, const int num_rows, const double* ambient_matrix, double* tangent_matrix) const; |
| 1409 | |
| 1410 | ``tangent_matrix`` = ``ambient_matrix`` :math:`\times` plus_jacobian. |
| 1411 | |
| 1412 | |
| 1413 | ``ambient_matrix`` is a row-major ``num_rows`` :math:`\times` |
| 1414 | :func:`Manifold::AmbientSize` matrix. |
| 1415 | |
| 1416 | ``tangent_matrix`` is a row-major ``num_rows`` :math:`\times` |
| 1417 | :func:`Manifold::TangentSize` matrix. |
| 1418 | |
| 1419 | Return value indicates whether the operation was successful or not. |
| 1420 | |
| 1421 | This function is only used by the :class:`GradientProblemSolver`, |
| 1422 | where the dimension of the parameter block can be large and it may |
| 1423 | be more efficient to compute this product directly rather than |
| 1424 | first evaluating the Jacobian into a matrix and then doing a matrix |
| 1425 | vector product. |
| 1426 | |
| 1427 | Because this is not an often used function, we provide a default |
| 1428 | implementation for convenience. If performance becomes an issue |
| 1429 | then the user should consider implementing a specialization. |
| 1430 | |
| 1431 | .. function:: bool Minus(const double* y, const double* x, double* y_minus_x) const; |
| 1432 | |
| 1433 | Implements :math:`\boxminus(y,x)` operation for the manifold. |
| 1434 | |
| 1435 | A generalization of vector subtraction in Euclidean spaces, given |
| 1436 | two points ``x`` and ``y`` on the manifold, ``Minus`` computes the |
| 1437 | change to ``x`` in the tangent space at ``x``, that will take it to |
| 1438 | ``y``. |
| 1439 | |
| 1440 | ``x`` and ``y`` are :func:`Manifold::AmbientSize` vectors. |
| 1441 | ``y_minus_x`` is a ::func:`Manifold::TangentSize` vector. |
| 1442 | |
| 1443 | Return value indicates if the operation was successful or not. |
| 1444 | |
| 1445 | .. function:: bool MinusJacobian(const double* x, double* jacobian) const = 0; |
| 1446 | |
| 1447 | Compute the derivative of :math:`\boxminus(y, x)` w.r.t :math:`y` |
| 1448 | at :math:`y = x`, i.e :math:`(D_1 \boxminus) (x, x)`. |
| 1449 | |
| 1450 | ``jacobian`` is a row-major :func:`Manifold::TangentSize` |
| 1451 | :math:`\times` :func:`Manifold::AmbientSize` matrix. |
| 1452 | |
| 1453 | Return value indicates whether the operation was successful or not. |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 1454 | |
Austin Schuh | 1d1e6ea | 2020-12-23 21:56:30 -0800 | [diff] [blame] | 1455 | Ceres Solver ships with a number of commonly used instances of |
Austin Schuh | 3de38b0 | 2024-06-25 18:25:10 -0700 | [diff] [blame^] | 1456 | :class:`Manifold`. |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 1457 | |
Austin Schuh | 3de38b0 | 2024-06-25 18:25:10 -0700 | [diff] [blame^] | 1458 | For `Lie Groups <https://en.wikipedia.org/wiki/Lie_group>`_, a great |
| 1459 | place to find high quality implementations is the `Sophus |
| 1460 | <https://github.com/strasdat/Sophus>`_ library developed by Hauke |
| 1461 | Strasdat and his collaborators. |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 1462 | |
Austin Schuh | 3de38b0 | 2024-06-25 18:25:10 -0700 | [diff] [blame^] | 1463 | :class:`EuclideanManifold` |
| 1464 | -------------------------- |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 1465 | |
Austin Schuh | 3de38b0 | 2024-06-25 18:25:10 -0700 | [diff] [blame^] | 1466 | .. class:: EuclideanManifold |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 1467 | |
Austin Schuh | 3de38b0 | 2024-06-25 18:25:10 -0700 | [diff] [blame^] | 1468 | :class:`EuclideanManifold` as the name implies represents a Euclidean |
| 1469 | space, where the :math:`\boxplus` and :math:`\boxminus` operations are |
| 1470 | the usual vector addition and subtraction. |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 1471 | |
Austin Schuh | 3de38b0 | 2024-06-25 18:25:10 -0700 | [diff] [blame^] | 1472 | .. math:: |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 1473 | |
Austin Schuh | 3de38b0 | 2024-06-25 18:25:10 -0700 | [diff] [blame^] | 1474 | \begin{align*} |
| 1475 | \boxplus(x, \Delta) &= x + \Delta\\ |
| 1476 | \boxminus(y,x) &= y - x |
| 1477 | \end{align*} |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 1478 | |
Austin Schuh | 3de38b0 | 2024-06-25 18:25:10 -0700 | [diff] [blame^] | 1479 | By default parameter blocks are assumed to be Euclidean, so there is |
| 1480 | no need to use this manifold on its own. It is provided for the |
| 1481 | purpose of testing and for use in combination with other manifolds |
| 1482 | using :class:`ProductManifold`. |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 1483 | |
Austin Schuh | 3de38b0 | 2024-06-25 18:25:10 -0700 | [diff] [blame^] | 1484 | The class works with dynamic and static ambient space dimensions. If |
| 1485 | the ambient space dimensions is known at compile time use |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 1486 | |
Austin Schuh | 3de38b0 | 2024-06-25 18:25:10 -0700 | [diff] [blame^] | 1487 | .. code-block:: c++ |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 1488 | |
Austin Schuh | 3de38b0 | 2024-06-25 18:25:10 -0700 | [diff] [blame^] | 1489 | EuclideanManifold<3> manifold; |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 1490 | |
Austin Schuh | 3de38b0 | 2024-06-25 18:25:10 -0700 | [diff] [blame^] | 1491 | If the ambient space dimensions is not known at compile time the |
| 1492 | template parameter needs to be set to `ceres::DYNAMIC` and the actual |
| 1493 | dimension needs to be provided as a constructor argument: |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 1494 | |
Austin Schuh | 3de38b0 | 2024-06-25 18:25:10 -0700 | [diff] [blame^] | 1495 | .. code-block:: c++ |
| 1496 | |
| 1497 | EuclideanManifold<ceres::DYNAMIC> manifold(ambient_dim); |
| 1498 | |
| 1499 | :class:`SubsetManifold` |
| 1500 | ----------------------- |
| 1501 | |
| 1502 | .. class:: SubsetManifold |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 1503 | |
Austin Schuh | 1d1e6ea | 2020-12-23 21:56:30 -0800 | [diff] [blame] | 1504 | Suppose :math:`x` is a two dimensional vector, and the user wishes to |
| 1505 | hold the first coordinate constant. Then, :math:`\Delta` is a scalar |
| 1506 | and :math:`\boxplus` is defined as |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 1507 | |
Austin Schuh | 3de38b0 | 2024-06-25 18:25:10 -0700 | [diff] [blame^] | 1508 | .. math:: |
| 1509 | \boxplus(x, \Delta) = x + \left[ \begin{array}{c} 0 \\ 1 \end{array} \right] \Delta |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 1510 | |
Austin Schuh | 3de38b0 | 2024-06-25 18:25:10 -0700 | [diff] [blame^] | 1511 | and given two, two-dimensional vectors :math:`x` and :math:`y` with |
| 1512 | the same first coordinate, :math:`\boxminus` is defined as: |
| 1513 | |
| 1514 | .. math:: |
| 1515 | \boxminus(y, x) = y[1] - x[1] |
| 1516 | |
| 1517 | :class:`SubsetManifold` generalizes this construction to hold |
Austin Schuh | 1d1e6ea | 2020-12-23 21:56:30 -0800 | [diff] [blame] | 1518 | any part of a parameter block constant by specifying the set of |
| 1519 | coordinates that are held constant. |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 1520 | |
Austin Schuh | 1d1e6ea | 2020-12-23 21:56:30 -0800 | [diff] [blame] | 1521 | .. NOTE:: |
Austin Schuh | 3de38b0 | 2024-06-25 18:25:10 -0700 | [diff] [blame^] | 1522 | |
| 1523 | It is legal to hold *all* coordinates of a parameter block to |
| 1524 | constant using a :class:`SubsetManifold`. It is the same as calling |
Austin Schuh | 1d1e6ea | 2020-12-23 21:56:30 -0800 | [diff] [blame] | 1525 | :func:`Problem::SetParameterBlockConstant` on that parameter block. |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 1526 | |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 1527 | |
Austin Schuh | 3de38b0 | 2024-06-25 18:25:10 -0700 | [diff] [blame^] | 1528 | :class:`ProductManifold` |
| 1529 | ------------------------ |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 1530 | |
Austin Schuh | 3de38b0 | 2024-06-25 18:25:10 -0700 | [diff] [blame^] | 1531 | .. class:: ProductManifold |
Austin Schuh | 1d1e6ea | 2020-12-23 21:56:30 -0800 | [diff] [blame] | 1532 | |
| 1533 | In cases, where a parameter block is the Cartesian product of a number |
Austin Schuh | 3de38b0 | 2024-06-25 18:25:10 -0700 | [diff] [blame^] | 1534 | of manifolds and you have the manifold of the individual |
| 1535 | parameter blocks available, :class:`ProductManifold` can be used to |
| 1536 | construct a :class:`Manifold` of the Cartesian product. |
| 1537 | |
| 1538 | For the case of the rigid transformation, where say you have a |
| 1539 | parameter block of size 7, where the first four entries represent the |
| 1540 | rotation as a quaternion, and the next three the translation, a |
| 1541 | manifold can be constructed as: |
Austin Schuh | 1d1e6ea | 2020-12-23 21:56:30 -0800 | [diff] [blame] | 1542 | |
| 1543 | .. code-block:: c++ |
| 1544 | |
Austin Schuh | 3de38b0 | 2024-06-25 18:25:10 -0700 | [diff] [blame^] | 1545 | ProductManifold<QuaternionManifold, EuclideanManifold<3>> se3; |
| 1546 | |
| 1547 | Manifolds can be copied and moved to :class:`ProductManifold`: |
| 1548 | |
| 1549 | .. code-block:: c++ |
| 1550 | |
| 1551 | SubsetManifold manifold1(5, {2}); |
| 1552 | SubsetManifold manifold2(3, {0, 1}); |
| 1553 | ProductManifold<SubsetManifold, SubsetManifold> manifold(manifold1, |
| 1554 | manifold2); |
| 1555 | |
| 1556 | In advanced use cases, manifolds can be dynamically allocated and passed as (smart) pointers: |
| 1557 | |
| 1558 | .. code-block:: c++ |
| 1559 | |
| 1560 | ProductManifold<std::unique_ptr<QuaternionManifold>, EuclideanManifold<3>> se3 |
| 1561 | {std::make_unique<QuaternionManifold>(), EuclideanManifold<3>{}}; |
| 1562 | |
| 1563 | The template parameters can also be left out as they are deduced automatically |
| 1564 | making the initialization much simpler: |
| 1565 | |
| 1566 | .. code-block:: c++ |
| 1567 | |
| 1568 | ProductManifold se3{QuaternionManifold{}, EuclideanManifold<3>{}}; |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 1569 | |
| 1570 | |
Austin Schuh | 3de38b0 | 2024-06-25 18:25:10 -0700 | [diff] [blame^] | 1571 | :class:`QuaternionManifold` |
| 1572 | --------------------------- |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 1573 | |
Austin Schuh | 3de38b0 | 2024-06-25 18:25:10 -0700 | [diff] [blame^] | 1574 | .. class:: QuaternionManifold |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 1575 | |
Austin Schuh | 3de38b0 | 2024-06-25 18:25:10 -0700 | [diff] [blame^] | 1576 | .. NOTE:: |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 1577 | |
Austin Schuh | 3de38b0 | 2024-06-25 18:25:10 -0700 | [diff] [blame^] | 1578 | If you are using ``Eigen`` quaternions, then you should use |
| 1579 | :class:`EigenQuaternionManifold` instead because ``Eigen`` uses a |
| 1580 | different memory layout for its Quaternions. |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 1581 | |
Austin Schuh | 3de38b0 | 2024-06-25 18:25:10 -0700 | [diff] [blame^] | 1582 | Manifold for a Hamilton `Quaternion |
| 1583 | <https://en.wikipedia.org/wiki/Quaternion>`_. Quaternions are a three |
| 1584 | dimensional manifold represented as unit norm 4-vectors, i.e. |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 1585 | |
Austin Schuh | 3de38b0 | 2024-06-25 18:25:10 -0700 | [diff] [blame^] | 1586 | .. math:: q = \left [\begin{matrix}q_0,& q_1,& q_2,& q_3\end{matrix}\right], \quad \|q\| = 1 |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 1587 | |
Austin Schuh | 3de38b0 | 2024-06-25 18:25:10 -0700 | [diff] [blame^] | 1588 | is the ambient space representation. Here :math:`q_0` is the scalar |
| 1589 | part. :math:`q_1` is the coefficient of :math:`i`, :math:`q_2` is the |
| 1590 | coefficient of :math:`j`, and :math:`q_3` is the coefficient of |
| 1591 | :math:`k`. Where: |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 1592 | |
Austin Schuh | 3de38b0 | 2024-06-25 18:25:10 -0700 | [diff] [blame^] | 1593 | .. math:: |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 1594 | |
Austin Schuh | 3de38b0 | 2024-06-25 18:25:10 -0700 | [diff] [blame^] | 1595 | \begin{align*} |
| 1596 | i\times j &= k,\\ |
| 1597 | j\times k &= i,\\ |
| 1598 | k\times i &= j,\\ |
| 1599 | i\times i &= -1,\\ |
| 1600 | j\times j &= -1,\\ |
| 1601 | k\times k &= -1. |
| 1602 | \end{align*} |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 1603 | |
Austin Schuh | 3de38b0 | 2024-06-25 18:25:10 -0700 | [diff] [blame^] | 1604 | The tangent space is three dimensional and the :math:`\boxplus` and |
| 1605 | :math:`\boxminus` operators are defined in term of :math:`\exp` and |
| 1606 | :math:`\log` operations. |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 1607 | |
Austin Schuh | 3de38b0 | 2024-06-25 18:25:10 -0700 | [diff] [blame^] | 1608 | .. math:: |
| 1609 | \begin{align*} |
| 1610 | \boxplus(x, \Delta) &= \exp\left(\Delta\right) \otimes x \\ |
| 1611 | \boxminus(y,x) &= \log\left(y \otimes x^{-1}\right) |
| 1612 | \end{align*} |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 1613 | |
Austin Schuh | 3de38b0 | 2024-06-25 18:25:10 -0700 | [diff] [blame^] | 1614 | Where :math:`\otimes` is the `Quaternion product |
| 1615 | <https://en.wikipedia.org/wiki/Quaternion#Hamilton_product>`_ and |
| 1616 | since :math:`x` is a unit quaternion, :math:`x^{-1} = [\begin{matrix} |
| 1617 | q_0,& -q_1,& -q_2,& -q_3\end{matrix}]`. Given a vector :math:`\Delta |
| 1618 | \in \mathbb{R}^3`, |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 1619 | |
Austin Schuh | 3de38b0 | 2024-06-25 18:25:10 -0700 | [diff] [blame^] | 1620 | .. math:: |
| 1621 | \exp(\Delta) = \left[ \begin{matrix} |
| 1622 | \cos\left(\|\Delta\|\right)\\ |
| 1623 | \frac{\displaystyle \sin\left(|\Delta\|\right)}{\displaystyle \|\Delta\|} \Delta |
| 1624 | \end{matrix} \right] |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 1625 | |
Austin Schuh | 3de38b0 | 2024-06-25 18:25:10 -0700 | [diff] [blame^] | 1626 | and given a unit quaternion :math:`q = \left [\begin{matrix}q_0,& q_1,& q_2,& q_3\end{matrix}\right]` |
| 1627 | |
| 1628 | .. math:: |
| 1629 | |
| 1630 | \log(q) = \frac{\operatorname{atan2}\left(\sqrt{1-q_0^2},q_0\right)}{\sqrt{1-q_0^2}} \left [\begin{matrix}q_1,& q_2,& q_3\end{matrix}\right] |
| 1631 | |
| 1632 | |
| 1633 | :class:`EigenQuaternionManifold` |
| 1634 | -------------------------------- |
| 1635 | |
| 1636 | .. class:: EigenQuaternionManifold |
| 1637 | |
| 1638 | Implements the quaternion manifold for `Eigen's |
| 1639 | <http://eigen.tuxfamily.org/index.php?title=Main_Page>`_ |
| 1640 | representation of the Hamilton quaternion. Geometrically it is exactly |
| 1641 | the same as the :class:`QuaternionManifold` defined above. However, |
| 1642 | Eigen uses a different internal memory layout for the elements of the |
| 1643 | quaternion than what is commonly used. It stores the quaternion in |
| 1644 | memory as :math:`[q_1, q_2, q_3, q_0]` or :math:`[x, y, z, w]` where |
| 1645 | the real (scalar) part is last. |
| 1646 | |
| 1647 | Since Ceres operates on parameter blocks which are raw double pointers |
| 1648 | this difference is important and requires a different manifold. |
| 1649 | |
| 1650 | :class:`SphereManifold` |
| 1651 | ----------------------- |
| 1652 | |
| 1653 | .. class:: SphereManifold |
| 1654 | |
| 1655 | This provides a manifold on a sphere meaning that the norm of the |
| 1656 | vector stays the same. Such cases often arises in Structure for Motion |
| 1657 | problems. One example where they are used is in representing points |
| 1658 | whose triangulation is ill-conditioned. Here it is advantageous to use |
| 1659 | an over-parameterization since homogeneous vectors can represent |
| 1660 | points at infinity. |
| 1661 | |
| 1662 | The ambient space dimension is required to be greater than 1. |
| 1663 | |
| 1664 | The class works with dynamic and static ambient space dimensions. If |
| 1665 | the ambient space dimensions is known at compile time use |
| 1666 | |
| 1667 | .. code-block:: c++ |
| 1668 | |
| 1669 | SphereManifold<3> manifold; |
| 1670 | |
| 1671 | If the ambient space dimensions is not known at compile time the |
| 1672 | template parameter needs to be set to `ceres::DYNAMIC` and the actual |
| 1673 | dimension needs to be provided as a constructor argument: |
| 1674 | |
| 1675 | .. code-block:: c++ |
| 1676 | |
| 1677 | SphereManifold<ceres::DYNAMIC> manifold(ambient_dim); |
| 1678 | |
| 1679 | For more details, please see Section B.2 (p.25) in [Hertzberg]_ |
| 1680 | |
| 1681 | |
| 1682 | :class:`LineManifold` |
| 1683 | --------------------- |
| 1684 | |
| 1685 | .. class:: LineManifold |
| 1686 | |
| 1687 | This class provides a manifold for lines, where the line is defined |
| 1688 | using an origin point and a direction vector. So the ambient size |
| 1689 | needs to be two times the dimension of the space in which the line |
| 1690 | lives. The first half of the parameter block is interpreted as the |
| 1691 | origin point and the second half as the direction. This manifold is a |
| 1692 | special case of the `Affine Grassmannian manifold |
| 1693 | <https://en.wikipedia.org/wiki/Affine_Grassmannian_(manifold))>`_ for |
| 1694 | the case :math:`\operatorname{Graff}_1(R^n)`. |
| 1695 | |
| 1696 | Note that this is a manifold for a line, rather than a point |
| 1697 | constrained to lie on a line. It is useful when one wants to optimize |
| 1698 | over the space of lines. For example, given :math:`n` distinct points |
| 1699 | in 3D (measurements) we want to find the line that minimizes the sum |
| 1700 | of squared distances to all the points. |
| 1701 | |
| 1702 | :class:`AutoDiffManifold` |
| 1703 | ========================= |
| 1704 | |
| 1705 | .. class:: AutoDiffManifold |
| 1706 | |
| 1707 | Create a :class:`Manifold` with Jacobians computed via automatic |
| 1708 | differentiation. |
| 1709 | |
| 1710 | To get an auto differentiated manifold, you must define a Functor with |
| 1711 | templated ``Plus`` and ``Minus`` functions that compute: |
| 1712 | |
| 1713 | .. code-block:: c++ |
| 1714 | |
| 1715 | x_plus_delta = Plus(x, delta); |
| 1716 | y_minus_x = Minus(y, x); |
| 1717 | |
| 1718 | Where, ``x``, ``y`` and ``x_plus_delta`` are vectors on the manifold in |
| 1719 | the ambient space (so they are ``kAmbientSize`` vectors) and |
| 1720 | ``delta``, ``y_minus_x`` are vectors in the tangent space (so they are |
| 1721 | ``kTangentSize`` vectors). |
| 1722 | |
| 1723 | The Functor should have the signature: |
| 1724 | |
| 1725 | .. code-block:: c++ |
| 1726 | |
| 1727 | struct Functor { |
| 1728 | template <typename T> |
| 1729 | bool Plus(const T* x, const T* delta, T* x_plus_delta) const; |
| 1730 | |
| 1731 | template <typename T> |
| 1732 | bool Minus(const T* y, const T* x, T* y_minus_x) const; |
| 1733 | }; |
| 1734 | |
| 1735 | |
| 1736 | Observe that the ``Plus`` and ``Minus`` operations are templated on |
| 1737 | the parameter ``T``. The autodiff framework substitutes appropriate |
| 1738 | ``Jet`` objects for ``T`` in order to compute the derivative when |
| 1739 | necessary. This is the same mechanism that is used to compute |
| 1740 | derivatives when using :class:`AutoDiffCostFunction`. |
| 1741 | |
| 1742 | ``Plus`` and ``Minus`` should return true if the computation is |
| 1743 | successful and false otherwise, in which case the result will not be |
| 1744 | used. |
| 1745 | |
| 1746 | Given this Functor, the corresponding :class:`Manifold` can be constructed as: |
| 1747 | |
| 1748 | .. code-block:: c++ |
| 1749 | |
| 1750 | AutoDiffManifold<Functor, kAmbientSize, kTangentSize> manifold; |
| 1751 | |
| 1752 | .. NOTE:: |
| 1753 | |
| 1754 | The following is only used for illustration purposes. Ceres Solver |
| 1755 | ships with an optimized, production grade :class:`QuaternionManifold` |
| 1756 | implementation. |
| 1757 | |
| 1758 | As a concrete example consider the case of `Quaternions |
| 1759 | <https://en.wikipedia.org/wiki/Quaternion>`_. Quaternions form a three |
| 1760 | dimensional manifold embedded in :math:`\mathbb{R}^4`, i.e. they have |
| 1761 | an ambient dimension of 4 and their tangent space has dimension 3. The |
| 1762 | following Functor defines the ``Plus`` and ``Minus`` operations on the |
| 1763 | Quaternion manifold. It assumes that the quaternions are laid out as |
| 1764 | ``[w,x,y,z]`` in memory, i.e. the real or scalar part is the first |
| 1765 | coordinate. |
| 1766 | |
| 1767 | .. code-block:: c++ |
| 1768 | |
| 1769 | struct QuaternionFunctor { |
| 1770 | template <typename T> |
| 1771 | bool Plus(const T* x, const T* delta, T* x_plus_delta) const { |
| 1772 | const T squared_norm_delta = |
| 1773 | delta[0] * delta[0] + delta[1] * delta[1] + delta[2] * delta[2]; |
| 1774 | |
| 1775 | T q_delta[4]; |
| 1776 | if (squared_norm_delta > T(0.0)) { |
| 1777 | T norm_delta = sqrt(squared_norm_delta); |
| 1778 | const T sin_delta_by_delta = sin(norm_delta) / norm_delta; |
| 1779 | q_delta[0] = cos(norm_delta); |
| 1780 | q_delta[1] = sin_delta_by_delta * delta[0]; |
| 1781 | q_delta[2] = sin_delta_by_delta * delta[1]; |
| 1782 | q_delta[3] = sin_delta_by_delta * delta[2]; |
| 1783 | } else { |
| 1784 | // We do not just use q_delta = [1,0,0,0] here because that is a |
| 1785 | // constant and when used for automatic differentiation will |
| 1786 | // lead to a zero derivative. Instead we take a first order |
| 1787 | // approximation and evaluate it at zero. |
| 1788 | q_delta[0] = T(1.0); |
| 1789 | q_delta[1] = delta[0]; |
| 1790 | q_delta[2] = delta[1]; |
| 1791 | q_delta[3] = delta[2]; |
| 1792 | } |
| 1793 | |
| 1794 | QuaternionProduct(q_delta, x, x_plus_delta); |
| 1795 | return true; |
| 1796 | } |
| 1797 | |
| 1798 | template <typename T> |
| 1799 | bool Minus(const T* y, const T* x, T* y_minus_x) const { |
| 1800 | T minus_x[4] = {x[0], -x[1], -x[2], -x[3]}; |
| 1801 | T ambient_y_minus_x[4]; |
| 1802 | QuaternionProduct(y, minus_x, ambient_y_minus_x); |
| 1803 | T u_norm = sqrt(ambient_y_minus_x[1] * ambient_y_minus_x[1] + |
| 1804 | ambient_y_minus_x[2] * ambient_y_minus_x[2] + |
| 1805 | ambient_y_minus_x[3] * ambient_y_minus_x[3]); |
| 1806 | if (u_norm > 0.0) { |
| 1807 | T theta = atan2(u_norm, ambient_y_minus_x[0]); |
| 1808 | y_minus_x[0] = theta * ambient_y_minus_x[1] / u_norm; |
| 1809 | y_minus_x[1] = theta * ambient_y_minus_x[2] / u_norm; |
| 1810 | y_minus_x[2] = theta * ambient_y_minus_x[3] / u_norm; |
| 1811 | } else { |
| 1812 | We do not use [0,0,0] here because even though the value part is |
| 1813 | a constant, the derivative part is not. |
| 1814 | y_minus_x[0] = ambient_y_minus_x[1]; |
| 1815 | y_minus_x[1] = ambient_y_minus_x[2]; |
| 1816 | y_minus_x[2] = ambient_y_minus_x[3]; |
| 1817 | } |
| 1818 | return true; |
| 1819 | } |
| 1820 | }; |
| 1821 | |
| 1822 | |
| 1823 | Then given this struct, the auto differentiated Quaternion Manifold can now |
| 1824 | be constructed as |
| 1825 | |
| 1826 | .. code-block:: c++ |
| 1827 | |
| 1828 | Manifold* manifold = new AutoDiffManifold<QuaternionFunctor, 4, 3>; |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 1829 | |
| 1830 | :class:`Problem` |
| 1831 | ================ |
| 1832 | |
| 1833 | .. class:: Problem |
| 1834 | |
| 1835 | :class:`Problem` holds the robustified bounds constrained |
| 1836 | non-linear least squares problem :eq:`ceresproblem_modeling`. To |
| 1837 | create a least squares problem, use the |
Austin Schuh | 1d1e6ea | 2020-12-23 21:56:30 -0800 | [diff] [blame] | 1838 | :func:`Problem::AddResidalBlock` and |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 1839 | :func:`Problem::AddParameterBlock` methods. |
| 1840 | |
| 1841 | For example a problem containing 3 parameter blocks of sizes 3, 4 |
| 1842 | and 5 respectively and two residual blocks of size 2 and 6: |
| 1843 | |
| 1844 | .. code-block:: c++ |
| 1845 | |
| 1846 | double x1[] = { 1.0, 2.0, 3.0 }; |
| 1847 | double x2[] = { 1.0, 2.0, 3.0, 5.0 }; |
| 1848 | double x3[] = { 1.0, 2.0, 3.0, 6.0, 7.0 }; |
| 1849 | |
| 1850 | Problem problem; |
| 1851 | problem.AddResidualBlock(new MyUnaryCostFunction(...), x1); |
| 1852 | problem.AddResidualBlock(new MyBinaryCostFunction(...), x2, x3); |
| 1853 | |
| 1854 | :func:`Problem::AddResidualBlock` as the name implies, adds a |
| 1855 | residual block to the problem. It adds a :class:`CostFunction`, an |
| 1856 | optional :class:`LossFunction` and connects the |
| 1857 | :class:`CostFunction` to a set of parameter block. |
| 1858 | |
| 1859 | The cost function carries with it information about the sizes of |
| 1860 | the parameter blocks it expects. The function checks that these |
| 1861 | match the sizes of the parameter blocks listed in |
| 1862 | ``parameter_blocks``. The program aborts if a mismatch is |
Austin Schuh | 1d1e6ea | 2020-12-23 21:56:30 -0800 | [diff] [blame] | 1863 | detected. ``loss_function`` can be ``nullptr``, in which case the cost |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 1864 | of the term is just the squared norm of the residuals. |
| 1865 | |
| 1866 | The user has the option of explicitly adding the parameter blocks |
| 1867 | using :func:`Problem::AddParameterBlock`. This causes additional |
| 1868 | correctness checking; however, :func:`Problem::AddResidualBlock` |
| 1869 | implicitly adds the parameter blocks if they are not present, so |
| 1870 | calling :func:`Problem::AddParameterBlock` explicitly is not |
| 1871 | required. |
| 1872 | |
| 1873 | :func:`Problem::AddParameterBlock` explicitly adds a parameter |
| 1874 | block to the :class:`Problem`. Optionally it allows the user to |
Austin Schuh | 3de38b0 | 2024-06-25 18:25:10 -0700 | [diff] [blame^] | 1875 | associate a :class:`Manifold` object with the parameter block |
| 1876 | too. Repeated calls with the same arguments are ignored. Repeated |
| 1877 | calls with the same double pointer but a different size results in |
| 1878 | undefined behavior. |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 1879 | |
| 1880 | You can set any parameter block to be constant using |
| 1881 | :func:`Problem::SetParameterBlockConstant` and undo this using |
| 1882 | :func:`SetParameterBlockVariable`. |
| 1883 | |
| 1884 | In fact you can set any number of parameter blocks to be constant, |
| 1885 | and Ceres is smart enough to figure out what part of the problem |
| 1886 | you have constructed depends on the parameter blocks that are free |
| 1887 | to change and only spends time solving it. So for example if you |
| 1888 | constructed a problem with a million parameter blocks and 2 million |
| 1889 | residual blocks, but then set all but one parameter blocks to be |
| 1890 | constant and say only 10 residual blocks depend on this one |
| 1891 | non-constant parameter block. Then the computational effort Ceres |
| 1892 | spends in solving this problem will be the same if you had defined |
| 1893 | a problem with one parameter block and 10 residual blocks. |
| 1894 | |
| 1895 | **Ownership** |
| 1896 | |
| 1897 | :class:`Problem` by default takes ownership of the |
Austin Schuh | 3de38b0 | 2024-06-25 18:25:10 -0700 | [diff] [blame^] | 1898 | ``cost_function``, ``loss_function`` and ``manifold`` pointers. These |
| 1899 | objects remain live for the life of the :class:`Problem`. If the user wishes |
| 1900 | to keep control over the destruction of these objects, then they can do this |
| 1901 | by setting the corresponding enums in the :class:`Problem::Options` struct. |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 1902 | |
Austin Schuh | 3de38b0 | 2024-06-25 18:25:10 -0700 | [diff] [blame^] | 1903 | Note that even though the Problem takes ownership of objects, |
| 1904 | ``cost_function`` and ``loss_function``, it does not preclude the |
| 1905 | user from re-using them in another residual block. Similarly the |
| 1906 | same ``manifold`` object can be used with multiple parameter blocks. The |
| 1907 | destructor takes care to call delete on each owned object exactly once. |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 1908 | |
Austin Schuh | 1d1e6ea | 2020-12-23 21:56:30 -0800 | [diff] [blame] | 1909 | .. class:: Problem::Options |
| 1910 | |
| 1911 | Options struct that is used to control :class:`Problem`. |
| 1912 | |
| 1913 | .. member:: Ownership Problem::Options::cost_function_ownership |
| 1914 | |
| 1915 | Default: ``TAKE_OWNERSHIP`` |
| 1916 | |
| 1917 | This option controls whether the Problem object owns the cost |
| 1918 | functions. |
| 1919 | |
Austin Schuh | 3de38b0 | 2024-06-25 18:25:10 -0700 | [diff] [blame^] | 1920 | If set to ``TAKE_OWNERSHIP``, then the problem object will delete the |
Austin Schuh | 1d1e6ea | 2020-12-23 21:56:30 -0800 | [diff] [blame] | 1921 | cost functions on destruction. The destructor is careful to delete |
| 1922 | the pointers only once, since sharing cost functions is allowed. |
| 1923 | |
| 1924 | .. member:: Ownership Problem::Options::loss_function_ownership |
| 1925 | |
| 1926 | Default: ``TAKE_OWNERSHIP`` |
| 1927 | |
| 1928 | This option controls whether the Problem object owns the loss |
| 1929 | functions. |
| 1930 | |
Austin Schuh | 3de38b0 | 2024-06-25 18:25:10 -0700 | [diff] [blame^] | 1931 | If set to ``TAKE_OWNERSHIP``, then the problem object will delete the |
Austin Schuh | 1d1e6ea | 2020-12-23 21:56:30 -0800 | [diff] [blame] | 1932 | loss functions on destruction. The destructor is careful to delete |
| 1933 | the pointers only once, since sharing loss functions is allowed. |
| 1934 | |
Austin Schuh | 3de38b0 | 2024-06-25 18:25:10 -0700 | [diff] [blame^] | 1935 | .. member:: Ownership Problem::Options::manifold_ownership |
Austin Schuh | 1d1e6ea | 2020-12-23 21:56:30 -0800 | [diff] [blame] | 1936 | |
| 1937 | Default: ``TAKE_OWNERSHIP`` |
| 1938 | |
Austin Schuh | 3de38b0 | 2024-06-25 18:25:10 -0700 | [diff] [blame^] | 1939 | This option controls whether the Problem object owns the manifolds. |
Austin Schuh | 1d1e6ea | 2020-12-23 21:56:30 -0800 | [diff] [blame] | 1940 | |
Austin Schuh | 3de38b0 | 2024-06-25 18:25:10 -0700 | [diff] [blame^] | 1941 | If set to ``TAKE_OWNERSHIP``, then the problem object will delete the |
| 1942 | manifolds on destruction. The destructor is careful to delete the |
| 1943 | pointers only once, since sharing manifolds is allowed. |
Austin Schuh | 1d1e6ea | 2020-12-23 21:56:30 -0800 | [diff] [blame] | 1944 | |
| 1945 | .. member:: bool Problem::Options::enable_fast_removal |
| 1946 | |
| 1947 | Default: ``false`` |
| 1948 | |
| 1949 | If true, trades memory for faster |
| 1950 | :func:`Problem::RemoveResidualBlock` and |
| 1951 | :func:`Problem::RemoveParameterBlock` operations. |
| 1952 | |
| 1953 | By default, :func:`Problem::RemoveParameterBlock` and |
| 1954 | :func:`Problem::RemoveResidualBlock` take time proportional to |
| 1955 | the size of the entire problem. If you only ever remove |
| 1956 | parameters or residuals from the problem occasionally, this might |
| 1957 | be acceptable. However, if you have memory to spare, enable this |
| 1958 | option to make :func:`Problem::RemoveParameterBlock` take time |
| 1959 | proportional to the number of residual blocks that depend on it, |
| 1960 | and :func:`Problem::RemoveResidualBlock` take (on average) |
| 1961 | constant time. |
| 1962 | |
| 1963 | The increase in memory usage is twofold: an additional hash set |
| 1964 | per parameter block containing all the residuals that depend on |
| 1965 | the parameter block; and a hash set in the problem containing all |
| 1966 | residuals. |
| 1967 | |
| 1968 | .. member:: bool Problem::Options::disable_all_safety_checks |
| 1969 | |
| 1970 | Default: `false` |
| 1971 | |
| 1972 | By default, Ceres performs a variety of safety checks when |
| 1973 | constructing the problem. There is a small but measurable |
| 1974 | performance penalty to these checks, typically around 5% of |
| 1975 | construction time. If you are sure your problem construction is |
| 1976 | correct, and 5% of the problem construction time is truly an |
| 1977 | overhead you want to avoid, then you can set |
| 1978 | disable_all_safety_checks to true. |
| 1979 | |
Austin Schuh | 3de38b0 | 2024-06-25 18:25:10 -0700 | [diff] [blame^] | 1980 | .. warning:: |
| 1981 | Do not set this to true, unless you are absolutely sure of what you are |
| 1982 | doing. |
Austin Schuh | 1d1e6ea | 2020-12-23 21:56:30 -0800 | [diff] [blame] | 1983 | |
| 1984 | .. member:: Context* Problem::Options::context |
| 1985 | |
Austin Schuh | 3de38b0 | 2024-06-25 18:25:10 -0700 | [diff] [blame^] | 1986 | Default: ``nullptr`` |
Austin Schuh | 1d1e6ea | 2020-12-23 21:56:30 -0800 | [diff] [blame] | 1987 | |
| 1988 | A Ceres global context to use for solving this problem. This may |
| 1989 | help to reduce computation time as Ceres can reuse expensive |
| 1990 | objects to create. The context object can be `nullptr`, in which |
| 1991 | case Ceres may create one. |
| 1992 | |
| 1993 | Ceres does NOT take ownership of the pointer. |
| 1994 | |
| 1995 | .. member:: EvaluationCallback* Problem::Options::evaluation_callback |
| 1996 | |
Austin Schuh | 3de38b0 | 2024-06-25 18:25:10 -0700 | [diff] [blame^] | 1997 | Default: ``nullptr`` |
Austin Schuh | 1d1e6ea | 2020-12-23 21:56:30 -0800 | [diff] [blame] | 1998 | |
| 1999 | Using this callback interface, Ceres will notify you when it is |
| 2000 | about to evaluate the residuals or Jacobians. |
| 2001 | |
| 2002 | If an ``evaluation_callback`` is present, Ceres will update the |
| 2003 | user's parameter blocks to the values that will be used when |
| 2004 | calling :func:`CostFunction::Evaluate` before calling |
| 2005 | :func:`EvaluationCallback::PrepareForEvaluation`. One can then use |
| 2006 | this callback to share (or cache) computation between cost |
| 2007 | functions by doing the shared computation in |
| 2008 | :func:`EvaluationCallback::PrepareForEvaluation` before Ceres |
| 2009 | calls :func:`CostFunction::Evaluate`. |
| 2010 | |
| 2011 | Problem does NOT take ownership of the callback. |
| 2012 | |
| 2013 | .. NOTE:: |
| 2014 | |
| 2015 | Evaluation callbacks are incompatible with inner iterations. So |
| 2016 | calling Solve with |
Austin Schuh | 3de38b0 | 2024-06-25 18:25:10 -0700 | [diff] [blame^] | 2017 | :member:`Solver::Options::use_inner_iterations` set to ``true`` |
Austin Schuh | 1d1e6ea | 2020-12-23 21:56:30 -0800 | [diff] [blame] | 2018 | on a :class:`Problem` with a non-null evaluation callback is an |
| 2019 | error. |
| 2020 | |
Austin Schuh | 3de38b0 | 2024-06-25 18:25:10 -0700 | [diff] [blame^] | 2021 | .. function:: ResidualBlockId Problem::AddResidualBlock(CostFunction* cost_function, LossFunction* loss_function, const std::vector<double*> parameter_blocks) |
Austin Schuh | 1d1e6ea | 2020-12-23 21:56:30 -0800 | [diff] [blame] | 2022 | |
| 2023 | .. function:: template <typename Ts...> ResidualBlockId Problem::AddResidualBlock(CostFunction* cost_function, LossFunction* loss_function, double* x0, Ts... xs) |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 2024 | |
| 2025 | Add a residual block to the overall cost function. The cost |
| 2026 | function carries with it information about the sizes of the |
| 2027 | parameter blocks it expects. The function checks that these match |
| 2028 | the sizes of the parameter blocks listed in parameter_blocks. The |
| 2029 | program aborts if a mismatch is detected. loss_function can be |
Austin Schuh | 3de38b0 | 2024-06-25 18:25:10 -0700 | [diff] [blame^] | 2030 | ``nullptr``, in which case the cost of the term is just the squared |
Austin Schuh | 1d1e6ea | 2020-12-23 21:56:30 -0800 | [diff] [blame] | 2031 | norm of the residuals. |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 2032 | |
| 2033 | The parameter blocks may be passed together as a |
Austin Schuh | 1d1e6ea | 2020-12-23 21:56:30 -0800 | [diff] [blame] | 2034 | ``vector<double*>``, or ``double*`` pointers. |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 2035 | |
| 2036 | The user has the option of explicitly adding the parameter blocks |
| 2037 | using AddParameterBlock. This causes additional correctness |
| 2038 | checking; however, AddResidualBlock implicitly adds the parameter |
| 2039 | blocks if they are not present, so calling AddParameterBlock |
| 2040 | explicitly is not required. |
| 2041 | |
| 2042 | The Problem object by default takes ownership of the |
| 2043 | cost_function and loss_function pointers. These objects remain |
| 2044 | live for the life of the Problem object. If the user wishes to |
| 2045 | keep control over the destruction of these objects, then they can |
| 2046 | do this by setting the corresponding enums in the Options struct. |
| 2047 | |
Austin Schuh | 3de38b0 | 2024-06-25 18:25:10 -0700 | [diff] [blame^] | 2048 | .. note:: |
| 2049 | Even though the Problem takes ownership of ``cost_function`` |
| 2050 | and ``loss_function``, it does not preclude the user from re-using |
| 2051 | them in another residual block. The destructor takes care to call |
| 2052 | delete on each cost_function or loss_function pointer only once, |
| 2053 | regardless of how many residual blocks refer to them. |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 2054 | |
| 2055 | Example usage: |
| 2056 | |
| 2057 | .. code-block:: c++ |
| 2058 | |
| 2059 | double x1[] = {1.0, 2.0, 3.0}; |
| 2060 | double x2[] = {1.0, 2.0, 5.0, 6.0}; |
| 2061 | double x3[] = {3.0, 6.0, 2.0, 5.0, 1.0}; |
Austin Schuh | 3de38b0 | 2024-06-25 18:25:10 -0700 | [diff] [blame^] | 2062 | std::vector<double*> v1; |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 2063 | v1.push_back(x1); |
Austin Schuh | 3de38b0 | 2024-06-25 18:25:10 -0700 | [diff] [blame^] | 2064 | std::vector<double*> v2; |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 2065 | v2.push_back(x2); |
| 2066 | v2.push_back(x1); |
| 2067 | |
| 2068 | Problem problem; |
| 2069 | |
Austin Schuh | 1d1e6ea | 2020-12-23 21:56:30 -0800 | [diff] [blame] | 2070 | problem.AddResidualBlock(new MyUnaryCostFunction(...), nullptr, x1); |
| 2071 | problem.AddResidualBlock(new MyBinaryCostFunction(...), nullptr, x2, x1); |
| 2072 | problem.AddResidualBlock(new MyUnaryCostFunction(...), nullptr, v1); |
| 2073 | problem.AddResidualBlock(new MyBinaryCostFunction(...), nullptr, v2); |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 2074 | |
Austin Schuh | 3de38b0 | 2024-06-25 18:25:10 -0700 | [diff] [blame^] | 2075 | .. function:: void Problem::AddParameterBlock(double* values, int size, Manifold* manifold) |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 2076 | |
Austin Schuh | 3de38b0 | 2024-06-25 18:25:10 -0700 | [diff] [blame^] | 2077 | Add a parameter block with appropriate size and Manifold to the |
| 2078 | problem. It is okay for ``manifold`` to be ``nullptr``. |
| 2079 | |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 2080 | Repeated calls with the same arguments are ignored. Repeated calls |
Austin Schuh | 3de38b0 | 2024-06-25 18:25:10 -0700 | [diff] [blame^] | 2081 | with the same double pointer but a different size results in a crash |
| 2082 | (unless :member:`Solver::Options::disable_all_safety_checks` is set to true). |
| 2083 | |
| 2084 | Repeated calls with the same double pointer and size but different |
| 2085 | :class:`Manifold` is equivalent to calling `SetManifold(manifold)`, |
| 2086 | i.e., any previously associated :class:`Manifold` object will be replaced |
| 2087 | with the `manifold`. |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 2088 | |
| 2089 | .. function:: void Problem::AddParameterBlock(double* values, int size) |
| 2090 | |
| 2091 | Add a parameter block with appropriate size and parameterization to |
| 2092 | the problem. Repeated calls with the same arguments are |
| 2093 | ignored. Repeated calls with the same double pointer but a |
| 2094 | different size results in undefined behavior. |
| 2095 | |
| 2096 | .. function:: void Problem::RemoveResidualBlock(ResidualBlockId residual_block) |
| 2097 | |
Austin Schuh | 3de38b0 | 2024-06-25 18:25:10 -0700 | [diff] [blame^] | 2098 | Remove a residual block from the problem. |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 2099 | |
Austin Schuh | 3de38b0 | 2024-06-25 18:25:10 -0700 | [diff] [blame^] | 2100 | Since residual blocks are allowed to share cost function and loss |
| 2101 | function objects, Ceres Solver uses a reference counting |
| 2102 | mechanism. So when a residual block is deleted, the reference count |
| 2103 | for the corresponding cost function and loss function objects are |
| 2104 | decreased and when this count reaches zero, they are deleted. |
| 2105 | |
| 2106 | If :member:`Problem::Options::enable_fast_removal` is ``true``, then the removal |
| 2107 | is fast (almost constant time). Otherwise it is linear, requiring a |
| 2108 | scan of the entire problem. |
| 2109 | |
| 2110 | Removing a residual block has no effect on the parameter blocks |
| 2111 | that the problem depends on. |
| 2112 | |
| 2113 | .. warning:: |
| 2114 | Removing a residual or parameter block will destroy the implicit |
| 2115 | ordering, rendering the jacobian or residuals returned from the solver |
| 2116 | uninterpretable. If you depend on the evaluated jacobian, do not use |
| 2117 | remove! This may change in a future release. Hold the indicated parameter |
| 2118 | block constant during optimization. |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 2119 | |
Austin Schuh | 1d1e6ea | 2020-12-23 21:56:30 -0800 | [diff] [blame] | 2120 | .. function:: void Problem::RemoveParameterBlock(const double* values) |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 2121 | |
Austin Schuh | 3de38b0 | 2024-06-25 18:25:10 -0700 | [diff] [blame^] | 2122 | Remove a parameter block from the problem. Any residual blocks that |
| 2123 | depend on the parameter are also removed, as described above in |
| 2124 | :func:`RemoveResidualBlock()`. |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 2125 | |
Austin Schuh | 3de38b0 | 2024-06-25 18:25:10 -0700 | [diff] [blame^] | 2126 | The manifold of the parameter block, if it exists, will persist until the |
| 2127 | deletion of the problem. |
| 2128 | |
| 2129 | If :member:`Problem::Options::enable_fast_removal` is ``true``, then the removal |
| 2130 | is fast (almost constant time). Otherwise, removing a parameter |
| 2131 | block will scan the entire Problem. |
| 2132 | |
| 2133 | .. warning:: |
| 2134 | Removing a residual or parameter block will destroy the implicit |
| 2135 | ordering, rendering the jacobian or residuals returned from the solver |
| 2136 | uninterpretable. If you depend on the evaluated jacobian, do not use |
| 2137 | remove! This may change in a future release. |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 2138 | |
Austin Schuh | 1d1e6ea | 2020-12-23 21:56:30 -0800 | [diff] [blame] | 2139 | .. function:: void Problem::SetParameterBlockConstant(const double* values) |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 2140 | |
| 2141 | Hold the indicated parameter block constant during optimization. |
| 2142 | |
| 2143 | .. function:: void Problem::SetParameterBlockVariable(double* values) |
| 2144 | |
| 2145 | Allow the indicated parameter to vary during optimization. |
| 2146 | |
Austin Schuh | 1d1e6ea | 2020-12-23 21:56:30 -0800 | [diff] [blame] | 2147 | .. function:: bool Problem::IsParameterBlockConstant(const double* values) const |
| 2148 | |
| 2149 | Returns ``true`` if a parameter block is set constant, and false |
| 2150 | otherwise. A parameter block may be set constant in two ways: |
| 2151 | either by calling ``SetParameterBlockConstant`` or by associating a |
Austin Schuh | 3de38b0 | 2024-06-25 18:25:10 -0700 | [diff] [blame^] | 2152 | :class:`Manifold` with a zero dimensional tangent space with it. |
Austin Schuh | 1d1e6ea | 2020-12-23 21:56:30 -0800 | [diff] [blame] | 2153 | |
Austin Schuh | 3de38b0 | 2024-06-25 18:25:10 -0700 | [diff] [blame^] | 2154 | .. function:: void SetManifold(double* values, Manifold* manifold); |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 2155 | |
Austin Schuh | 3de38b0 | 2024-06-25 18:25:10 -0700 | [diff] [blame^] | 2156 | Set the :class:`Manifold` for the parameter block. Calling |
| 2157 | :func:`Problem::SetManifold` with ``nullptr`` will clear any |
| 2158 | previously set :class:`Manifold` for the parameter block. |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 2159 | |
Austin Schuh | 3de38b0 | 2024-06-25 18:25:10 -0700 | [diff] [blame^] | 2160 | Repeated calls will result in any previously associated |
| 2161 | :class:`Manifold` object to be replaced with ``manifold``. |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 2162 | |
Austin Schuh | 3de38b0 | 2024-06-25 18:25:10 -0700 | [diff] [blame^] | 2163 | ``manifold`` is owned by :class:`Problem` by default (See |
| 2164 | :class:`Problem::Options` to override this behaviour). |
| 2165 | |
| 2166 | It is acceptable to set the same :class:`Manifold` for multiple |
| 2167 | parameter blocks. |
| 2168 | |
| 2169 | .. function:: const Manifold* GetManifold(const double* values) const; |
| 2170 | |
| 2171 | Get the :class:`Manifold` object associated with this parameter block. |
| 2172 | |
| 2173 | If there is no :class:`Manifold` object associated with the parameter block, |
| 2174 | then ``nullptr`` is returned. |
| 2175 | |
| 2176 | .. function:: bool HasManifold(const double* values) const; |
| 2177 | |
| 2178 | Returns ``true`` if a :class:`Manifold` is associated with this parameter |
| 2179 | block, ``false`` otherwise. |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 2180 | |
| 2181 | .. function:: void Problem::SetParameterLowerBound(double* values, int index, double lower_bound) |
| 2182 | |
| 2183 | Set the lower bound for the parameter at position `index` in the |
| 2184 | parameter block corresponding to `values`. By default the lower |
| 2185 | bound is ``-std::numeric_limits<double>::max()``, which is treated |
| 2186 | by the solver as the same as :math:`-\infty`. |
| 2187 | |
| 2188 | .. function:: void Problem::SetParameterUpperBound(double* values, int index, double upper_bound) |
| 2189 | |
| 2190 | Set the upper bound for the parameter at position `index` in the |
| 2191 | parameter block corresponding to `values`. By default the value is |
| 2192 | ``std::numeric_limits<double>::max()``, which is treated by the |
| 2193 | solver as the same as :math:`\infty`. |
| 2194 | |
Austin Schuh | 1d1e6ea | 2020-12-23 21:56:30 -0800 | [diff] [blame] | 2195 | .. function:: double Problem::GetParameterLowerBound(const double* values, int index) |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 2196 | |
| 2197 | Get the lower bound for the parameter with position `index`. If the |
| 2198 | parameter is not bounded by the user, then its lower bound is |
| 2199 | ``-std::numeric_limits<double>::max()``. |
| 2200 | |
Austin Schuh | 1d1e6ea | 2020-12-23 21:56:30 -0800 | [diff] [blame] | 2201 | .. function:: double Problem::GetParameterUpperBound(const double* values, int index) |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 2202 | |
| 2203 | Get the upper bound for the parameter with position `index`. If the |
| 2204 | parameter is not bounded by the user, then its upper bound is |
| 2205 | ``std::numeric_limits<double>::max()``. |
| 2206 | |
| 2207 | .. function:: int Problem::NumParameterBlocks() const |
| 2208 | |
| 2209 | Number of parameter blocks in the problem. Always equals |
| 2210 | parameter_blocks().size() and parameter_block_sizes().size(). |
| 2211 | |
| 2212 | .. function:: int Problem::NumParameters() const |
| 2213 | |
| 2214 | The size of the parameter vector obtained by summing over the sizes |
| 2215 | of all the parameter blocks. |
| 2216 | |
| 2217 | .. function:: int Problem::NumResidualBlocks() const |
| 2218 | |
| 2219 | Number of residual blocks in the problem. Always equals |
| 2220 | residual_blocks().size(). |
| 2221 | |
| 2222 | .. function:: int Problem::NumResiduals() const |
| 2223 | |
| 2224 | The size of the residual vector obtained by summing over the sizes |
| 2225 | of all of the residual blocks. |
| 2226 | |
| 2227 | .. function:: int Problem::ParameterBlockSize(const double* values) const |
| 2228 | |
| 2229 | The size of the parameter block. |
| 2230 | |
Austin Schuh | 3de38b0 | 2024-06-25 18:25:10 -0700 | [diff] [blame^] | 2231 | .. function:: int Problem::ParameterBlockTangentSize(const double* values) const |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 2232 | |
Austin Schuh | 3de38b0 | 2024-06-25 18:25:10 -0700 | [diff] [blame^] | 2233 | The dimension of the tangent space of the :class:`Manifold` for the |
| 2234 | parameter block. If there is no :class:`Manifold` associated with this |
| 2235 | parameter block, then ``ParameterBlockTangentSize = ParameterBlockSize``. |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 2236 | |
| 2237 | .. function:: bool Problem::HasParameterBlock(const double* values) const |
| 2238 | |
| 2239 | Is the given parameter block present in the problem or not? |
| 2240 | |
Austin Schuh | 3de38b0 | 2024-06-25 18:25:10 -0700 | [diff] [blame^] | 2241 | .. function:: void Problem::GetParameterBlocks(std::vector<double*>* parameter_blocks) const |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 2242 | |
| 2243 | Fills the passed ``parameter_blocks`` vector with pointers to the |
| 2244 | parameter blocks currently in the problem. After this call, |
| 2245 | ``parameter_block.size() == NumParameterBlocks``. |
| 2246 | |
Austin Schuh | 3de38b0 | 2024-06-25 18:25:10 -0700 | [diff] [blame^] | 2247 | .. function:: void Problem::GetResidualBlocks(std::vector<ResidualBlockId>* residual_blocks) const |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 2248 | |
| 2249 | Fills the passed `residual_blocks` vector with pointers to the |
| 2250 | residual blocks currently in the problem. After this call, |
| 2251 | `residual_blocks.size() == NumResidualBlocks`. |
| 2252 | |
Austin Schuh | 3de38b0 | 2024-06-25 18:25:10 -0700 | [diff] [blame^] | 2253 | .. function:: void Problem::GetParameterBlocksForResidualBlock(const ResidualBlockId residual_block, std::vector<double*>* parameter_blocks) const |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 2254 | |
| 2255 | Get all the parameter blocks that depend on the given residual |
| 2256 | block. |
| 2257 | |
Austin Schuh | 3de38b0 | 2024-06-25 18:25:10 -0700 | [diff] [blame^] | 2258 | .. function:: void Problem::GetResidualBlocksForParameterBlock(const double* values, std::vector<ResidualBlockId>* residual_blocks) const |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 2259 | |
| 2260 | Get all the residual blocks that depend on the given parameter |
| 2261 | block. |
| 2262 | |
Austin Schuh | 3de38b0 | 2024-06-25 18:25:10 -0700 | [diff] [blame^] | 2263 | If :member:`Problem::Options::enable_fast_removal` is |
| 2264 | ``true``, then getting the residual blocks is fast and depends only |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 2265 | on the number of residual blocks. Otherwise, getting the residual |
Austin Schuh | 3de38b0 | 2024-06-25 18:25:10 -0700 | [diff] [blame^] | 2266 | blocks for a parameter block will scan the entire problem. |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 2267 | |
Austin Schuh | 1d1e6ea | 2020-12-23 21:56:30 -0800 | [diff] [blame] | 2268 | .. function:: const CostFunction* Problem::GetCostFunctionForResidualBlock(const ResidualBlockId residual_block) const |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 2269 | |
| 2270 | Get the :class:`CostFunction` for the given residual block. |
| 2271 | |
Austin Schuh | 1d1e6ea | 2020-12-23 21:56:30 -0800 | [diff] [blame] | 2272 | .. function:: const LossFunction* Problem::GetLossFunctionForResidualBlock(const ResidualBlockId residual_block) const |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 2273 | |
| 2274 | Get the :class:`LossFunction` for the given residual block. |
| 2275 | |
Austin Schuh | 1d1e6ea | 2020-12-23 21:56:30 -0800 | [diff] [blame] | 2276 | .. function:: bool EvaluateResidualBlock(ResidualBlockId residual_block_id, bool apply_loss_function, double* cost,double* residuals, double** jacobians) const |
| 2277 | |
| 2278 | Evaluates the residual block, storing the scalar cost in ``cost``, the |
| 2279 | residual components in ``residuals``, and the jacobians between the |
| 2280 | parameters and residuals in ``jacobians[i]``, in row-major order. |
| 2281 | |
| 2282 | If ``residuals`` is ``nullptr``, the residuals are not computed. |
| 2283 | |
| 2284 | If ``jacobians`` is ``nullptr``, no Jacobians are computed. If |
| 2285 | ``jacobians[i]`` is ``nullptr``, then the Jacobian for that |
| 2286 | parameter block is not computed. |
| 2287 | |
| 2288 | It is not okay to request the Jacobian w.r.t a parameter block |
| 2289 | that is constant. |
| 2290 | |
| 2291 | The return value indicates the success or failure. Even if the |
| 2292 | function returns false, the caller should expect the output |
| 2293 | memory locations to have been modified. |
| 2294 | |
Austin Schuh | 3de38b0 | 2024-06-25 18:25:10 -0700 | [diff] [blame^] | 2295 | The returned cost and jacobians have had robustification and |
| 2296 | :class:`Manifold` applied already; for example, the jacobian for a |
| 2297 | 4-dimensional quaternion parameter using the :class:`QuaternionManifold` is |
| 2298 | ``num_residuals x 3`` instead of ``num_residuals x 4``. |
Austin Schuh | 1d1e6ea | 2020-12-23 21:56:30 -0800 | [diff] [blame] | 2299 | |
| 2300 | ``apply_loss_function`` as the name implies allows the user to |
| 2301 | switch the application of the loss function on and off. |
| 2302 | |
| 2303 | .. NOTE:: If an :class:`EvaluationCallback` is associated with the |
| 2304 | problem, then its |
| 2305 | :func:`EvaluationCallback::PrepareForEvaluation` method will be |
| 2306 | called every time this method is called with `new_point = |
| 2307 | true`. This conservatively assumes that the user may have |
| 2308 | changed the parameter values since the previous call to evaluate |
| 2309 | / solve. For improved efficiency, and only if you know that the |
| 2310 | parameter values have not changed between calls, see |
| 2311 | :func:`Problem::EvaluateResidualBlockAssumingParametersUnchanged`. |
| 2312 | |
| 2313 | |
| 2314 | .. function:: bool EvaluateResidualBlockAssumingParametersUnchanged(ResidualBlockId residual_block_id, bool apply_loss_function, double* cost,double* residuals, double** jacobians) const |
| 2315 | |
| 2316 | Same as :func:`Problem::EvaluateResidualBlock` except that if an |
| 2317 | :class:`EvaluationCallback` is associated with the problem, then |
| 2318 | its :func:`EvaluationCallback::PrepareForEvaluation` method will |
| 2319 | be called every time this method is called with new_point = false. |
| 2320 | |
| 2321 | This means, if an :class:`EvaluationCallback` is associated with |
| 2322 | the problem then it is the user's responsibility to call |
| 2323 | :func:`EvaluationCallback::PrepareForEvaluation` before calling |
| 2324 | this method if necessary, i.e. iff the parameter values have been |
| 2325 | changed since the last call to evaluate / solve.' |
| 2326 | |
| 2327 | This is because, as the name implies, we assume that the parameter |
| 2328 | blocks did not change since the last time |
| 2329 | :func:`EvaluationCallback::PrepareForEvaluation` was called (via |
| 2330 | :func:`Solve`, :func:`Problem::Evaluate` or |
| 2331 | :func:`Problem::EvaluateResidualBlock`). |
| 2332 | |
| 2333 | |
Austin Schuh | 3de38b0 | 2024-06-25 18:25:10 -0700 | [diff] [blame^] | 2334 | .. function:: bool Problem::Evaluate(const Problem::EvaluateOptions& options, double* cost, std::vector<double>* residuals, std::vector<double>* gradient, CRSMatrix* jacobian) |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 2335 | |
| 2336 | Evaluate a :class:`Problem`. Any of the output pointers can be |
Austin Schuh | 3de38b0 | 2024-06-25 18:25:10 -0700 | [diff] [blame^] | 2337 | ``nullptr``. Which residual blocks and parameter blocks are used is |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 2338 | controlled by the :class:`Problem::EvaluateOptions` struct below. |
| 2339 | |
| 2340 | .. NOTE:: |
| 2341 | |
| 2342 | The evaluation will use the values stored in the memory |
| 2343 | locations pointed to by the parameter block pointers used at the |
| 2344 | time of the construction of the problem, for example in the |
| 2345 | following code: |
| 2346 | |
| 2347 | .. code-block:: c++ |
| 2348 | |
| 2349 | Problem problem; |
| 2350 | double x = 1; |
Austin Schuh | 1d1e6ea | 2020-12-23 21:56:30 -0800 | [diff] [blame] | 2351 | problem.Add(new MyCostFunction, nullptr, &x); |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 2352 | |
| 2353 | double cost = 0.0; |
Austin Schuh | 1d1e6ea | 2020-12-23 21:56:30 -0800 | [diff] [blame] | 2354 | problem.Evaluate(Problem::EvaluateOptions(), &cost, nullptr, nullptr, nullptr); |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 2355 | |
| 2356 | The cost is evaluated at `x = 1`. If you wish to evaluate the |
| 2357 | problem at `x = 2`, then |
| 2358 | |
| 2359 | .. code-block:: c++ |
| 2360 | |
| 2361 | x = 2; |
Austin Schuh | 1d1e6ea | 2020-12-23 21:56:30 -0800 | [diff] [blame] | 2362 | problem.Evaluate(Problem::EvaluateOptions(), &cost, nullptr, nullptr, nullptr); |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 2363 | |
| 2364 | is the way to do so. |
| 2365 | |
| 2366 | .. NOTE:: |
| 2367 | |
Austin Schuh | 3de38b0 | 2024-06-25 18:25:10 -0700 | [diff] [blame^] | 2368 | If no :class:`Manifold` are used, then the size of the gradient vector is |
| 2369 | the sum of the sizes of all the parameter blocks. If a parameter block has |
| 2370 | a manifold then it contributes "TangentSize" entries to the gradient |
| 2371 | vector. |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 2372 | |
| 2373 | .. NOTE:: |
| 2374 | |
| 2375 | This function cannot be called while the problem is being |
| 2376 | solved, for example it cannot be called from an |
| 2377 | :class:`IterationCallback` at the end of an iteration during a |
| 2378 | solve. |
| 2379 | |
Austin Schuh | 1d1e6ea | 2020-12-23 21:56:30 -0800 | [diff] [blame] | 2380 | .. NOTE:: |
| 2381 | |
| 2382 | If an EvaluationCallback is associated with the problem, then |
| 2383 | its PrepareForEvaluation method will be called everytime this |
| 2384 | method is called with ``new_point = true``. |
| 2385 | |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 2386 | .. class:: Problem::EvaluateOptions |
| 2387 | |
| 2388 | Options struct that is used to control :func:`Problem::Evaluate`. |
| 2389 | |
Austin Schuh | 3de38b0 | 2024-06-25 18:25:10 -0700 | [diff] [blame^] | 2390 | .. member:: std::vector<double*> Problem::EvaluateOptions::parameter_blocks |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 2391 | |
| 2392 | The set of parameter blocks for which evaluation should be |
| 2393 | performed. This vector determines the order in which parameter |
| 2394 | blocks occur in the gradient vector and in the columns of the |
| 2395 | jacobian matrix. If parameter_blocks is empty, then it is assumed |
| 2396 | to be equal to a vector containing ALL the parameter |
| 2397 | blocks. Generally speaking the ordering of the parameter blocks in |
| 2398 | this case depends on the order in which they were added to the |
| 2399 | problem and whether or not the user removed any parameter blocks. |
| 2400 | |
| 2401 | **NOTE** This vector should contain the same pointers as the ones |
| 2402 | used to add parameter blocks to the Problem. These parameter block |
| 2403 | should NOT point to new memory locations. Bad things will happen if |
| 2404 | you do. |
| 2405 | |
Austin Schuh | 3de38b0 | 2024-06-25 18:25:10 -0700 | [diff] [blame^] | 2406 | .. member:: std::vector<ResidualBlockId> Problem::EvaluateOptions::residual_blocks |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 2407 | |
| 2408 | The set of residual blocks for which evaluation should be |
| 2409 | performed. This vector determines the order in which the residuals |
| 2410 | occur, and how the rows of the jacobian are ordered. If |
| 2411 | residual_blocks is empty, then it is assumed to be equal to the |
| 2412 | vector containing all the residual blocks. |
| 2413 | |
| 2414 | .. member:: bool Problem::EvaluateOptions::apply_loss_function |
| 2415 | |
| 2416 | Even though the residual blocks in the problem may contain loss |
| 2417 | functions, setting apply_loss_function to false will turn off the |
| 2418 | application of the loss function to the output of the cost |
| 2419 | function. This is of use for example if the user wishes to analyse |
| 2420 | the solution quality by studying the distribution of residuals |
| 2421 | before and after the solve. |
| 2422 | |
| 2423 | .. member:: int Problem::EvaluateOptions::num_threads |
| 2424 | |
Austin Schuh | 3de38b0 | 2024-06-25 18:25:10 -0700 | [diff] [blame^] | 2425 | Number of threads to use. |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 2426 | |
Austin Schuh | 1d1e6ea | 2020-12-23 21:56:30 -0800 | [diff] [blame] | 2427 | |
| 2428 | :class:`EvaluationCallback` |
| 2429 | =========================== |
| 2430 | |
| 2431 | .. class:: EvaluationCallback |
| 2432 | |
| 2433 | Interface for receiving callbacks before Ceres evaluates residuals or |
| 2434 | Jacobians: |
| 2435 | |
| 2436 | .. code-block:: c++ |
| 2437 | |
| 2438 | class EvaluationCallback { |
| 2439 | public: |
Austin Schuh | 3de38b0 | 2024-06-25 18:25:10 -0700 | [diff] [blame^] | 2440 | virtual ~EvaluationCallback(); |
| 2441 | virtual void PrepareForEvaluation(bool evaluate_jacobians, |
| 2442 | bool new_evaluation_point) = 0; |
Austin Schuh | 1d1e6ea | 2020-12-23 21:56:30 -0800 | [diff] [blame] | 2443 | }; |
| 2444 | |
| 2445 | .. function:: void EvaluationCallback::PrepareForEvaluation(bool evaluate_jacobians, bool new_evaluation_point) |
| 2446 | |
| 2447 | Ceres will call :func:`EvaluationCallback::PrepareForEvaluation` |
| 2448 | every time, and once before it computes the residuals and/or the |
| 2449 | Jacobians. |
| 2450 | |
Austin Schuh | 3de38b0 | 2024-06-25 18:25:10 -0700 | [diff] [blame^] | 2451 | User parameters (the double* values provided by the user) are fixed |
Austin Schuh | 1d1e6ea | 2020-12-23 21:56:30 -0800 | [diff] [blame] | 2452 | until the next call to |
| 2453 | :func:`EvaluationCallback::PrepareForEvaluation`. If |
| 2454 | ``new_evaluation_point == true``, then this is a new point that is |
| 2455 | different from the last evaluated point. Otherwise, it is the same |
| 2456 | point that was evaluated previously (either Jacobian or residual) |
| 2457 | and the user can use cached results from previous evaluations. If |
Austin Schuh | 3de38b0 | 2024-06-25 18:25:10 -0700 | [diff] [blame^] | 2458 | ``evaluate_jacobians`` is ``true``, then Ceres will request Jacobians |
Austin Schuh | 1d1e6ea | 2020-12-23 21:56:30 -0800 | [diff] [blame] | 2459 | in the upcoming cost evaluation. |
| 2460 | |
| 2461 | Using this callback interface, Ceres can notify you when it is |
| 2462 | about to evaluate the residuals or Jacobians. With the callback, |
| 2463 | you can share computation between residual blocks by doing the |
| 2464 | shared computation in |
| 2465 | :func:`EvaluationCallback::PrepareForEvaluation` before Ceres calls |
| 2466 | :func:`CostFunction::Evaluate` on all the residuals. It also |
| 2467 | enables caching results between a pure residual evaluation and a |
| 2468 | residual & Jacobian evaluation, via the ``new_evaluation_point`` |
| 2469 | argument. |
| 2470 | |
| 2471 | One use case for this callback is if the cost function compute is |
| 2472 | moved to the GPU. In that case, the prepare call does the actual |
| 2473 | cost function evaluation, and subsequent calls from Ceres to the |
| 2474 | actual cost functions merely copy the results from the GPU onto the |
| 2475 | corresponding blocks for Ceres to plug into the solver. |
| 2476 | |
| 2477 | **Note**: Ceres provides no mechanism to share data other than the |
| 2478 | notification from the callback. Users must provide access to |
| 2479 | pre-computed shared data to their cost functions behind the scenes; |
| 2480 | this all happens without Ceres knowing. One approach is to put a |
| 2481 | pointer to the shared data in each cost function (recommended) or |
| 2482 | to use a global shared variable (discouraged; bug-prone). As far |
| 2483 | as Ceres is concerned, it is evaluating cost functions like any |
| 2484 | other; it just so happens that behind the scenes the cost functions |
Austin Schuh | 3de38b0 | 2024-06-25 18:25:10 -0700 | [diff] [blame^] | 2485 | reuse pre-computed data to execute faster. See |
| 2486 | `examples/evaluation_callback_example.cc |
| 2487 | <https://ceres-solver.googlesource.com/ceres-solver/+/master/examples/evaluation_callback_example.cc>`_ |
| 2488 | for an example. |
Austin Schuh | 1d1e6ea | 2020-12-23 21:56:30 -0800 | [diff] [blame] | 2489 | |
| 2490 | See ``evaluation_callback_test.cc`` for code that explicitly |
| 2491 | verifies the preconditions between |
| 2492 | :func:`EvaluationCallback::PrepareForEvaluation` and |
| 2493 | :func:`CostFunction::Evaluate`. |
| 2494 | |
| 2495 | |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 2496 | ``rotation.h`` |
| 2497 | ============== |
| 2498 | |
| 2499 | Many applications of Ceres Solver involve optimization problems where |
| 2500 | some of the variables correspond to rotations. To ease the pain of |
| 2501 | work with the various representations of rotations (angle-axis, |
| 2502 | quaternion and matrix) we provide a handy set of templated |
| 2503 | functions. These functions are templated so that the user can use them |
| 2504 | within Ceres Solver's automatic differentiation framework. |
| 2505 | |
| 2506 | .. function:: template <typename T> void AngleAxisToQuaternion(T const* angle_axis, T* quaternion) |
| 2507 | |
| 2508 | Convert a value in combined axis-angle representation to a |
| 2509 | quaternion. |
| 2510 | |
| 2511 | The value ``angle_axis`` is a triple whose norm is an angle in radians, |
| 2512 | and whose direction is aligned with the axis of rotation, and |
| 2513 | ``quaternion`` is a 4-tuple that will contain the resulting quaternion. |
| 2514 | |
| 2515 | .. function:: template <typename T> void QuaternionToAngleAxis(T const* quaternion, T* angle_axis) |
| 2516 | |
| 2517 | Convert a quaternion to the equivalent combined axis-angle |
| 2518 | representation. |
| 2519 | |
| 2520 | The value ``quaternion`` must be a unit quaternion - it is not |
| 2521 | normalized first, and ``angle_axis`` will be filled with a value |
| 2522 | whose norm is the angle of rotation in radians, and whose direction |
| 2523 | is the axis of rotation. |
| 2524 | |
| 2525 | .. function:: template <typename T, int row_stride, int col_stride> void RotationMatrixToAngleAxis(const MatrixAdapter<const T, row_stride, col_stride>& R, T * angle_axis) |
| 2526 | .. function:: template <typename T, int row_stride, int col_stride> void AngleAxisToRotationMatrix(T const * angle_axis, const MatrixAdapter<T, row_stride, col_stride>& R) |
| 2527 | .. function:: template <typename T> void RotationMatrixToAngleAxis(T const * R, T * angle_axis) |
| 2528 | .. function:: template <typename T> void AngleAxisToRotationMatrix(T const * angle_axis, T * R) |
| 2529 | |
Austin Schuh | 3de38b0 | 2024-06-25 18:25:10 -0700 | [diff] [blame^] | 2530 | Conversions between :math:`3\times3` rotation matrix with given column and row strides and |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 2531 | axis-angle rotation representations. The functions that take a pointer to T instead |
| 2532 | of a MatrixAdapter assume a column major representation with unit row stride and a column stride of 3. |
| 2533 | |
| 2534 | .. function:: template <typename T, int row_stride, int col_stride> void EulerAnglesToRotationMatrix(const T* euler, const MatrixAdapter<T, row_stride, col_stride>& R) |
| 2535 | .. function:: template <typename T> void EulerAnglesToRotationMatrix(const T* euler, int row_stride, T* R) |
| 2536 | |
Austin Schuh | 3de38b0 | 2024-06-25 18:25:10 -0700 | [diff] [blame^] | 2537 | Conversions between :math:`3\times3` rotation matrix with given column and row strides and |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 2538 | Euler angle (in degrees) rotation representations. |
| 2539 | |
| 2540 | The {pitch,roll,yaw} Euler angles are rotations around the {x,y,z} |
| 2541 | axes, respectively. They are applied in that same order, so the |
| 2542 | total rotation R is Rz * Ry * Rx. |
| 2543 | |
| 2544 | The function that takes a pointer to T as the rotation matrix assumes a row |
| 2545 | major representation with unit column stride and a row stride of 3. |
| 2546 | The additional parameter row_stride is required to be 3. |
| 2547 | |
| 2548 | .. function:: template <typename T, int row_stride, int col_stride> void QuaternionToScaledRotation(const T q[4], const MatrixAdapter<T, row_stride, col_stride>& R) |
| 2549 | .. function:: template <typename T> void QuaternionToScaledRotation(const T q[4], T R[3 * 3]) |
| 2550 | |
Austin Schuh | 3de38b0 | 2024-06-25 18:25:10 -0700 | [diff] [blame^] | 2551 | Convert a 4-vector to a :math:`3\times3` scaled rotation matrix. |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 2552 | |
| 2553 | The choice of rotation is such that the quaternion |
| 2554 | :math:`\begin{bmatrix} 1 &0 &0 &0\end{bmatrix}` goes to an identity |
| 2555 | matrix and for small :math:`a, b, c` the quaternion |
| 2556 | :math:`\begin{bmatrix}1 &a &b &c\end{bmatrix}` goes to the matrix |
| 2557 | |
| 2558 | .. math:: |
| 2559 | |
| 2560 | I + 2 \begin{bmatrix} 0 & -c & b \\ c & 0 & -a\\ -b & a & 0 |
| 2561 | \end{bmatrix} + O(q^2) |
| 2562 | |
| 2563 | which corresponds to a Rodrigues approximation, the last matrix |
| 2564 | being the cross-product matrix of :math:`\begin{bmatrix} a& b& |
Austin Schuh | 3de38b0 | 2024-06-25 18:25:10 -0700 | [diff] [blame^] | 2565 | c\end{bmatrix}`. Together with the property that :math:`R(q_1 \otimes q_2) |
| 2566 | = R(q_1) R(q_2)` this uniquely defines the mapping from :math:`q` to |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 2567 | :math:`R`. |
| 2568 | |
| 2569 | In the function that accepts a pointer to T instead of a MatrixAdapter, |
| 2570 | the rotation matrix ``R`` is a row-major matrix with unit column stride |
| 2571 | and a row stride of 3. |
| 2572 | |
| 2573 | No normalization of the quaternion is performed, i.e. |
| 2574 | :math:`R = \|q\|^2 Q`, where :math:`Q` is an orthonormal matrix |
Austin Schuh | 3de38b0 | 2024-06-25 18:25:10 -0700 | [diff] [blame^] | 2575 | such that :math:`\det(Q) = 1` and :math:`QQ' = I`. |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 2576 | |
| 2577 | |
| 2578 | .. function:: template <typename T> void QuaternionToRotation(const T q[4], const MatrixAdapter<T, row_stride, col_stride>& R) |
| 2579 | .. function:: template <typename T> void QuaternionToRotation(const T q[4], T R[3 * 3]) |
| 2580 | |
| 2581 | Same as above except that the rotation matrix is normalized by the |
| 2582 | Frobenius norm, so that :math:`R R' = I` (and :math:`\det(R) = 1`). |
| 2583 | |
| 2584 | .. function:: template <typename T> void UnitQuaternionRotatePoint(const T q[4], const T pt[3], T result[3]) |
| 2585 | |
| 2586 | Rotates a point pt by a quaternion q: |
| 2587 | |
| 2588 | .. math:: \text{result} = R(q) \text{pt} |
| 2589 | |
| 2590 | Assumes the quaternion is unit norm. If you pass in a quaternion |
| 2591 | with :math:`|q|^2 = 2` then you WILL NOT get back 2 times the |
| 2592 | result you get for a unit quaternion. |
| 2593 | |
| 2594 | |
| 2595 | .. function:: template <typename T> void QuaternionRotatePoint(const T q[4], const T pt[3], T result[3]) |
| 2596 | |
| 2597 | With this function you do not need to assume that :math:`q` has unit norm. |
| 2598 | It does assume that the norm is non-zero. |
| 2599 | |
| 2600 | .. function:: template <typename T> void QuaternionProduct(const T z[4], const T w[4], T zw[4]) |
| 2601 | |
Austin Schuh | 3de38b0 | 2024-06-25 18:25:10 -0700 | [diff] [blame^] | 2602 | .. math:: zw = z \otimes w |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 2603 | |
Austin Schuh | 3de38b0 | 2024-06-25 18:25:10 -0700 | [diff] [blame^] | 2604 | where :math:`\otimes` is the Quaternion product between 4-vectors. |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 2605 | |
| 2606 | |
| 2607 | .. function:: template <typename T> void CrossProduct(const T x[3], const T y[3], T x_cross_y[3]) |
| 2608 | |
| 2609 | .. math:: \text{x_cross_y} = x \times y |
| 2610 | |
| 2611 | .. function:: template <typename T> void AngleAxisRotatePoint(const T angle_axis[3], const T pt[3], T result[3]) |
| 2612 | |
| 2613 | .. math:: y = R(\text{angle_axis}) x |
| 2614 | |
| 2615 | |
| 2616 | Cubic Interpolation |
| 2617 | =================== |
| 2618 | |
| 2619 | Optimization problems often involve functions that are given in the |
| 2620 | form of a table of values, for example an image. Evaluating these |
| 2621 | functions and their derivatives requires interpolating these |
| 2622 | values. Interpolating tabulated functions is a vast area of research |
| 2623 | and there are a lot of libraries which implement a variety of |
| 2624 | interpolation schemes. However, using them within the automatic |
| 2625 | differentiation framework in Ceres is quite painful. To this end, |
| 2626 | Ceres provides the ability to interpolate one dimensional and two |
| 2627 | dimensional tabular functions. |
| 2628 | |
| 2629 | The one dimensional interpolation is based on the Cubic Hermite |
| 2630 | Spline, also known as the Catmull-Rom Spline. This produces a first |
| 2631 | order differentiable interpolating function. The two dimensional |
| 2632 | interpolation scheme is a generalization of the one dimensional scheme |
| 2633 | where the interpolating function is assumed to be separable in the two |
| 2634 | dimensions, |
| 2635 | |
| 2636 | More details of the construction can be found `Linear Methods for |
| 2637 | Image Interpolation <http://www.ipol.im/pub/art/2011/g_lmii/>`_ by |
| 2638 | Pascal Getreuer. |
| 2639 | |
| 2640 | .. class:: CubicInterpolator |
| 2641 | |
| 2642 | Given as input an infinite one dimensional grid, which provides the |
| 2643 | following interface. |
| 2644 | |
| 2645 | .. code:: |
| 2646 | |
| 2647 | struct Grid1D { |
| 2648 | enum { DATA_DIMENSION = 2; }; |
| 2649 | void GetValue(int n, double* f) const; |
| 2650 | }; |
| 2651 | |
| 2652 | Where, ``GetValue`` gives us the value of a function :math:`f` |
| 2653 | (possibly vector valued) for any integer :math:`n` and the enum |
| 2654 | ``DATA_DIMENSION`` indicates the dimensionality of the function being |
| 2655 | interpolated. For example if you are interpolating rotations in |
| 2656 | axis-angle format over time, then ``DATA_DIMENSION = 3``. |
| 2657 | |
| 2658 | :class:`CubicInterpolator` uses Cubic Hermite splines to produce a |
| 2659 | smooth approximation to it that can be used to evaluate the |
| 2660 | :math:`f(x)` and :math:`f'(x)` at any point on the real number |
| 2661 | line. For example, the following code interpolates an array of four |
| 2662 | numbers. |
| 2663 | |
| 2664 | .. code:: |
| 2665 | |
Austin Schuh | 1d1e6ea | 2020-12-23 21:56:30 -0800 | [diff] [blame] | 2666 | const double x[] = {1.0, 2.0, 5.0, 6.0}; |
Austin Schuh | 70cc955 | 2019-01-21 19:46:48 -0800 | [diff] [blame] | 2667 | Grid1D<double, 1> array(x, 0, 4); |
| 2668 | CubicInterpolator interpolator(array); |
| 2669 | double f, dfdx; |
| 2670 | interpolator.Evaluate(1.5, &f, &dfdx); |
| 2671 | |
| 2672 | |
| 2673 | In the above code we use ``Grid1D`` a templated helper class that |
| 2674 | allows easy interfacing between ``C++`` arrays and |
| 2675 | :class:`CubicInterpolator`. |
| 2676 | |
| 2677 | ``Grid1D`` supports vector valued functions where the various |
| 2678 | coordinates of the function can be interleaved or stacked. It also |
| 2679 | allows the use of any numeric type as input, as long as it can be |
| 2680 | safely cast to a double. |
| 2681 | |
| 2682 | .. class:: BiCubicInterpolator |
| 2683 | |
| 2684 | Given as input an infinite two dimensional grid, which provides the |
| 2685 | following interface: |
| 2686 | |
| 2687 | .. code:: |
| 2688 | |
| 2689 | struct Grid2D { |
| 2690 | enum { DATA_DIMENSION = 2 }; |
| 2691 | void GetValue(int row, int col, double* f) const; |
| 2692 | }; |
| 2693 | |
| 2694 | Where, ``GetValue`` gives us the value of a function :math:`f` |
| 2695 | (possibly vector valued) for any pair of integers :code:`row` and |
| 2696 | :code:`col` and the enum ``DATA_DIMENSION`` indicates the |
| 2697 | dimensionality of the function being interpolated. For example if you |
| 2698 | are interpolating a color image with three channels (Red, Green & |
| 2699 | Blue), then ``DATA_DIMENSION = 3``. |
| 2700 | |
| 2701 | :class:`BiCubicInterpolator` uses the cubic convolution interpolation |
| 2702 | algorithm of R. Keys [Keys]_, to produce a smooth approximation to it |
| 2703 | that can be used to evaluate the :math:`f(r,c)`, :math:`\frac{\partial |
| 2704 | f(r,c)}{\partial r}` and :math:`\frac{\partial f(r,c)}{\partial c}` at |
| 2705 | any any point in the real plane. |
| 2706 | |
| 2707 | For example the following code interpolates a two dimensional array. |
| 2708 | |
| 2709 | .. code:: |
| 2710 | |
| 2711 | const double data[] = {1.0, 3.0, -1.0, 4.0, |
| 2712 | 3.6, 2.1, 4.2, 2.0, |
| 2713 | 2.0, 1.0, 3.1, 5.2}; |
| 2714 | Grid2D<double, 1> array(data, 0, 3, 0, 4); |
| 2715 | BiCubicInterpolator interpolator(array); |
| 2716 | double f, dfdr, dfdc; |
| 2717 | interpolator.Evaluate(1.2, 2.5, &f, &dfdr, &dfdc); |
| 2718 | |
| 2719 | In the above code, the templated helper class ``Grid2D`` is used to |
| 2720 | make a ``C++`` array look like a two dimensional table to |
| 2721 | :class:`BiCubicInterpolator`. |
| 2722 | |
| 2723 | ``Grid2D`` supports row or column major layouts. It also supports |
| 2724 | vector valued functions where the individual coordinates of the |
| 2725 | function may be interleaved or stacked. It also allows the use of any |
| 2726 | numeric type as input, as long as it can be safely cast to double. |