Home | History | Annotate | Download | only in examples
      1 // Ceres Solver - A fast non-linear least squares minimizer
      2 // Copyright 2010, 2011, 2012 Google Inc. All rights reserved.
      3 // http://code.google.com/p/ceres-solver/
      4 //
      5 // Redistribution and use in source and binary forms, with or without
      6 // modification, are permitted provided that the following conditions are met:
      7 //
      8 // * Redistributions of source code must retain the above copyright notice,
      9 //   this list of conditions and the following disclaimer.
     10 // * Redistributions in binary form must reproduce the above copyright notice,
     11 //   this list of conditions and the following disclaimer in the documentation
     12 //   and/or other materials provided with the distribution.
     13 // * Neither the name of Google Inc. nor the names of its contributors may be
     14 //   used to endorse or promote products derived from this software without
     15 //   specific prior written permission.
     16 //
     17 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
     18 // AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
     19 // IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
     20 // ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
     21 // LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
     22 // CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
     23 // SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
     24 // INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
     25 // CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
     26 // ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
     27 // POSSIBILITY OF SUCH DAMAGE.
     28 //
     29 // Author: sameeragarwal (at) google.com (Sameer Agarwal)
     30 //
     31 // Templated struct implementing the camera model and residual
     32 // computation for bundle adjustment used by Noah Snavely's Bundler
     33 // SfM system. This is also the camera model/residual for the bundle
     34 // adjustment problems in the BAL dataset. It is templated so that we
     35 // can use Ceres's automatic differentiation to compute analytic
     36 // jacobians.
     37 //
     38 // For details see: http://phototour.cs.washington.edu/bundler/
     39 // and http://grail.cs.washington.edu/projects/bal/
     40 
     41 #ifndef CERES_EXAMPLES_SNAVELY_REPROJECTION_ERROR_H_
     42 #define CERES_EXAMPLES_SNAVELY_REPROJECTION_ERROR_H_
     43 
     44 #include "ceres/rotation.h"
     45 
     46 namespace ceres {
     47 namespace examples {
     48 
     49 // Templated pinhole camera model for used with Ceres.  The camera is
     50 // parameterized using 9 parameters: 3 for rotation, 3 for translation, 1 for
     51 // focal length and 2 for radial distortion. The principal point is not modeled
     52 // (i.e. it is assumed be located at the image center).
     53 struct SnavelyReprojectionError {
     54   SnavelyReprojectionError(double observed_x, double observed_y)
     55       : observed_x(observed_x), observed_y(observed_y) {}
     56 
     57   template <typename T>
     58   bool operator()(const T* const camera,
     59                   const T* const point,
     60                   T* residuals) const {
     61     // camera[0,1,2] are the angle-axis rotation.
     62     T p[3];
     63     ceres::AngleAxisRotatePoint(camera, point, p);
     64 
     65     // camera[3,4,5] are the translation.
     66     p[0] += camera[3];
     67     p[1] += camera[4];
     68     p[2] += camera[5];
     69 
     70     // Compute the center of distortion. The sign change comes from
     71     // the camera model that Noah Snavely's Bundler assumes, whereby
     72     // the camera coordinate system has a negative z axis.
     73     const T& focal = camera[6];
     74     T xp = - p[0] / p[2];
     75     T yp = - p[1] / p[2];
     76 
     77     // Apply second and fourth order radial distortion.
     78     const T& l1 = camera[7];
     79     const T& l2 = camera[8];
     80     T r2 = xp*xp + yp*yp;
     81     T distortion = T(1.0) + r2  * (l1 + l2  * r2);
     82 
     83     // Compute final projected point position.
     84     T predicted_x = focal * distortion * xp;
     85     T predicted_y = focal * distortion * yp;
     86 
     87     // The error is the difference between the predicted and observed position.
     88     residuals[0] = predicted_x - T(observed_x);
     89     residuals[1] = predicted_y - T(observed_y);
     90 
     91     return true;
     92   }
     93 
     94   double observed_x;
     95   double observed_y;
     96 };
     97 
     98 // Templated pinhole camera model for used with Ceres.  The camera is
     99 // parameterized using 10 parameters. 4 for rotation, 3 for
    100 // translation, 1 for focal length and 2 for radial distortion. The
    101 // principal point is not modeled (i.e. it is assumed be located at
    102 // the image center).
    103 struct SnavelyReprojectionErrorWithQuaternions {
    104   // (u, v): the position of the observation with respect to the image
    105   // center point.
    106   SnavelyReprojectionErrorWithQuaternions(double observed_x, double observed_y)
    107       : observed_x(observed_x), observed_y(observed_y) {}
    108 
    109   template <typename T>
    110   bool operator()(const T* const camera_rotation,
    111                   const T* const camera_translation_and_intrinsics,
    112                   const T* const point,
    113                   T* residuals) const {
    114     const T& focal = camera_translation_and_intrinsics[3];
    115     const T& l1 = camera_translation_and_intrinsics[4];
    116     const T& l2 = camera_translation_and_intrinsics[5];
    117 
    118     // Use a quaternion rotation that doesn't assume the quaternion is
    119     // normalized, since one of the ways to run the bundler is to let Ceres
    120     // optimize all 4 quaternion parameters unconstrained.
    121     T p[3];
    122     QuaternionRotatePoint(camera_rotation, point, p);
    123 
    124     p[0] += camera_translation_and_intrinsics[0];
    125     p[1] += camera_translation_and_intrinsics[1];
    126     p[2] += camera_translation_and_intrinsics[2];
    127 
    128     // Compute the center of distortion. The sign change comes from
    129     // the camera model that Noah Snavely's Bundler assumes, whereby
    130     // the camera coordinate system has a negative z axis.
    131     T xp = - p[0] / p[2];
    132     T yp = - p[1] / p[2];
    133 
    134     // Apply second and fourth order radial distortion.
    135     T r2 = xp*xp + yp*yp;
    136     T distortion = T(1.0) + r2  * (l1 + l2  * r2);
    137 
    138     // Compute final projected point position.
    139     T predicted_x = focal * distortion * xp;
    140     T predicted_y = focal * distortion * yp;
    141 
    142     // The error is the difference between the predicted and observed position.
    143     residuals[0] = predicted_x - T(observed_x);
    144     residuals[1] = predicted_y - T(observed_y);
    145 
    146     return true;
    147   }
    148 
    149   double observed_x;
    150   double observed_y;
    151 };
    152 
    153 }  // namespace examples
    154 }  // namespace ceres
    155 
    156 #endif  // CERES_EXAMPLES_SNAVELY_REPROJECTION_ERROR_H_
    157