Home | History | Annotate | Download | only in examples
      1 // Ceres Solver - A fast non-linear least squares minimizer
      2 // Copyright 2014 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: joydeepb (at) ri.cmu.edu (Joydeep Biswas)
     30 //
     31 // This example demonstrates how to use the DynamicAutoDiffCostFunction
     32 // variant of CostFunction. The DynamicAutoDiffCostFunction is meant to
     33 // be used in cases where the number of parameter blocks or the sizes are not
     34 // known at compile time.
     35 //
     36 // This example simulates a robot traversing down a 1-dimension hallway with
     37 // noise odometry readings and noisy range readings of the end of the hallway.
     38 // By fusing the noisy odometry and sensor readings this example demonstrates
     39 // how to compute the maximum likelihood estimate (MLE) of the robot's pose at
     40 // each timestep.
     41 //
     42 // The robot starts at the origin, and it is travels to the end of a corridor of
     43 // fixed length specified by the "--corridor_length" flag. It executes a series
     44 // of motion commands to move forward a fixed length, specified by the
     45 // "--pose_separation" flag, at which pose it receives relative odometry
     46 // measurements as well as a range reading of the distance to the end of the
     47 // hallway. The odometry readings are drawn with Gaussian noise and standard
     48 // deviation specified by the "--odometry_stddev" flag, and the range readings
     49 // similarly with standard deviation specified by the "--range-stddev" flag.
     50 //
     51 // There are two types of residuals in this problem:
     52 // 1) The OdometryConstraint residual, that accounts for the odometry readings
     53 //    between successive pose estimatess of the robot.
     54 // 2) The RangeConstraint residual, that accounts for the errors in the observed
     55 //    range readings from each pose.
     56 //
     57 // The OdometryConstraint residual is modeled as an AutoDiffCostFunction with
     58 // a fixed parameter block size of 1, which is the relative odometry being
     59 // solved for, between a pair of successive poses of the robot. Differences
     60 // between observed and computed relative odometry values are penalized weighted
     61 // by the known standard deviation of the odometry readings.
     62 //
     63 // The RangeConstraint residual is modeled as a DynamicAutoDiffCostFunction
     64 // which sums up the relative odometry estimates to compute the estimated
     65 // global pose of the robot, and then computes the expected range reading.
     66 // Differences between the observed and expected range readings are then
     67 // penalized weighted by the standard deviation of readings of the sensor.
     68 // Since the number of poses of the robot is not known at compile time, this
     69 // cost function is implemented as a DynamicAutoDiffCostFunction.
     70 //
     71 // The outputs of the example are the initial values of the odometry and range
     72 // readings, and the range and odometry errors for every pose of the robot.
     73 // After computing the MLE, the computed poses and corrected odometry values
     74 // are printed out, along with the corresponding range and odometry errors. Note
     75 // that as an MLE of a noisy system the errors will not be reduced to zero, but
     76 // the odometry estimates will be updated to maximize the joint likelihood of
     77 // all odometry and range readings of the robot.
     78 //
     79 // Mathematical Formulation
     80 // ======================================================
     81 //
     82 // Let p_0, .., p_N be (N+1) robot poses, where the robot moves down the
     83 // corridor starting from p_0 and ending at p_N. We assume that p_0 is the
     84 // origin of the coordinate system.
     85 // Odometry u_i is the observed relative odometry between pose p_(i-1) and p_i,
     86 // and range reading y_i is the range reading of the end of the corridor from
     87 // pose p_i. Both odometry as well as range readings are noisy, but we wish to
     88 // compute the maximum likelihood estimate (MLE) of corrected odometry values
     89 // u*_0 to u*_(N-1), such that the Belief is optimized:
     90 //
     91 // Belief(u*_(0:N-1) | u_(0:N-1), y_(0:N-1))                                  1.
     92 //   =        P(u*_(0:N-1) | u_(0:N-1), y_(0:N-1))                            2.
     93 //   \propto  P(y_(0:N-1) | u*_(0:N-1), u_(0:N-1)) P(u*_(0:N-1) | u_(0:N-1))  3.
     94 //   =       \prod_i{ P(y_i | u*_(0:i)) P(u*_i | u_i) }                       4.
     95 //
     96 // Here, the subscript "(0:i)" is used as shorthand to indicate entries from all
     97 // timesteps 0 to i for that variable, both inclusive.
     98 //
     99 // Bayes' rule is used to derive eq. 3 from 2, and the independence of
    100 // odometry observations and range readings is expolited to derive 4 from 3.
    101 //
    102 // Thus, the Belief, up to scale, is factored as a product of a number of
    103 // terms, two for each pose, where for each pose term there is one term for the
    104 // range reading, P(y_i | u*_(0:i) and one term for the odometry reading,
    105 // P(u*_i | u_i) . Note that the term for the range reading is dependent on all
    106 // odometry values u*_(0:i), while the odometry term, P(u*_i | u_i) depends only
    107 // on a single value, u_i. Both the range reading as well as odoemtry
    108 // probability terms are modeled as the Normal distribution, and have the form:
    109 //
    110 // p(x) \propto \exp{-((x - x_mean) / x_stddev)^2}
    111 //
    112 // where x refers to either the MLE odometry u* or range reading y, and x_mean
    113 // is the corresponding mean value, u for the odometry terms, and y_expected,
    114 // the expected range reading based on all the previous odometry terms.
    115 // The MLE is thus found by finding those values x* which minimize:
    116 //
    117 // x* = \arg\min{((x - x_mean) / x_stddev)^2}
    118 //
    119 // which is in the nonlinear least-square form, suited to being solved by Ceres.
    120 // The non-linear component arise from the computation of x_mean. The residuals
    121 // ((x - x_mean) / x_stddev) for the residuals that Ceres will optimize. As
    122 // mentioned earlier, the odometry term for each pose depends only on one
    123 // variable, and will be computed by an AutoDiffCostFunction, while the term
    124 // for the range reading will depend on all previous odometry observations, and
    125 // will be computed by a DynamicAutoDiffCostFunction since the number of
    126 // odoemtry observations will only be known at run time.
    127 
    128 #include <cstdio>
    129 #include <math.h>
    130 #include <vector>
    131 
    132 #include "ceres/ceres.h"
    133 #include "ceres/dynamic_autodiff_cost_function.h"
    134 #include "gflags/gflags.h"
    135 #include "glog/logging.h"
    136 #include "random.h"
    137 
    138 using ceres::AutoDiffCostFunction;
    139 using ceres::DynamicAutoDiffCostFunction;
    140 using ceres::CauchyLoss;
    141 using ceres::CostFunction;
    142 using ceres::LossFunction;
    143 using ceres::Problem;
    144 using ceres::Solve;
    145 using ceres::Solver;
    146 using ceres::examples::RandNormal;
    147 using std::min;
    148 using std::vector;
    149 
    150 DEFINE_double(corridor_length, 30.0, "Length of the corridor that the robot is "
    151               "travelling down.");
    152 
    153 DEFINE_double(pose_separation, 0.5, "The distance that the robot traverses "
    154               "between successive odometry updates.");
    155 
    156 DEFINE_double(odometry_stddev, 0.1, "The standard deviation of "
    157               "odometry error of the robot.");
    158 
    159 DEFINE_double(range_stddev, 0.01, "The standard deviation of range readings of "
    160               "the robot.");
    161 
    162 // The stride length of the dynamic_autodiff_cost_function evaluator.
    163 static const int kStride = 10;
    164 
    165 struct OdometryConstraint {
    166   typedef AutoDiffCostFunction<OdometryConstraint, 1, 1> OdometryCostFunction;
    167 
    168   OdometryConstraint(double odometry_mean, double odometry_stddev) :
    169       odometry_mean(odometry_mean), odometry_stddev(odometry_stddev) {}
    170 
    171   template <typename T>
    172   bool operator()(const T* const odometry, T* residual) const {
    173     *residual = (*odometry - T(odometry_mean)) / T(odometry_stddev);
    174     return true;
    175   }
    176 
    177   static OdometryCostFunction* Create(const double odometry_value) {
    178     return new OdometryCostFunction(
    179         new OdometryConstraint(odometry_value, FLAGS_odometry_stddev));
    180   }
    181 
    182   const double odometry_mean;
    183   const double odometry_stddev;
    184 };
    185 
    186 struct RangeConstraint {
    187   typedef DynamicAutoDiffCostFunction<RangeConstraint, kStride>
    188       RangeCostFunction;
    189 
    190   RangeConstraint(
    191       int pose_index,
    192       double range_reading,
    193       double range_stddev,
    194       double corridor_length) :
    195       pose_index(pose_index), range_reading(range_reading),
    196       range_stddev(range_stddev), corridor_length(corridor_length) {}
    197 
    198   template <typename T>
    199   bool operator()(T const* const* relative_poses, T* residuals) const {
    200     T global_pose(0);
    201     for (int i = 0; i <= pose_index; ++i) {
    202       global_pose += relative_poses[i][0];
    203     }
    204     residuals[0] = (global_pose + T(range_reading) - T(corridor_length)) /
    205         T(range_stddev);
    206     return true;
    207   }
    208 
    209   // Factory method to create a CostFunction from a RangeConstraint to
    210   // conveniently add to a ceres problem.
    211   static RangeCostFunction* Create(const int pose_index,
    212                                    const double range_reading,
    213                                    vector<double>* odometry_values,
    214                                    vector<double*>* parameter_blocks) {
    215     RangeConstraint* constraint = new RangeConstraint(
    216         pose_index, range_reading, FLAGS_range_stddev, FLAGS_corridor_length);
    217     RangeCostFunction* cost_function = new RangeCostFunction(constraint);
    218     // Add all the parameter blocks that affect this constraint.
    219     parameter_blocks->clear();
    220     for (int i = 0; i <= pose_index; ++i) {
    221       parameter_blocks->push_back(&((*odometry_values)[i]));
    222       cost_function->AddParameterBlock(1);
    223     }
    224     cost_function->SetNumResiduals(1);
    225     return (cost_function);
    226   }
    227 
    228   const int pose_index;
    229   const double range_reading;
    230   const double range_stddev;
    231   const double corridor_length;
    232 };
    233 
    234 void SimulateRobot(vector<double>* odometry_values,
    235                    vector<double>* range_readings) {
    236   const int num_steps = static_cast<int>(
    237       ceil(FLAGS_corridor_length / FLAGS_pose_separation));
    238 
    239   // The robot starts out at the origin.
    240   double robot_location = 0.0;
    241   for (int i = 0; i < num_steps; ++i) {
    242     const double actual_odometry_value = min(
    243         FLAGS_pose_separation, FLAGS_corridor_length - robot_location);
    244     robot_location += actual_odometry_value;
    245     const double actual_range = FLAGS_corridor_length - robot_location;
    246     const double observed_odometry =
    247         RandNormal() * FLAGS_odometry_stddev + actual_odometry_value;
    248     const double observed_range =
    249         RandNormal() * FLAGS_range_stddev + actual_range;
    250     odometry_values->push_back(observed_odometry);
    251     range_readings->push_back(observed_range);
    252   }
    253 }
    254 
    255 void PrintState(const vector<double>& odometry_readings,
    256                 const vector<double>& range_readings) {
    257   CHECK_EQ(odometry_readings.size(), range_readings.size());
    258   double robot_location = 0.0;
    259   printf("pose: location     odom    range  r.error  o.error\n");
    260   for (int i = 0; i < odometry_readings.size(); ++i) {
    261     robot_location += odometry_readings[i];
    262     const double range_error =
    263         robot_location + range_readings[i] - FLAGS_corridor_length;
    264     const double odometry_error =
    265         FLAGS_pose_separation - odometry_readings[i];
    266     printf("%4d: %8.3f %8.3f %8.3f %8.3f %8.3f\n",
    267            static_cast<int>(i), robot_location, odometry_readings[i],
    268            range_readings[i], range_error, odometry_error);
    269   }
    270 }
    271 
    272 int main(int argc, char** argv) {
    273   google::InitGoogleLogging(argv[0]);
    274   google::ParseCommandLineFlags(&argc, &argv, true);
    275   // Make sure that the arguments parsed are all positive.
    276   CHECK_GT(FLAGS_corridor_length, 0.0);
    277   CHECK_GT(FLAGS_pose_separation, 0.0);
    278   CHECK_GT(FLAGS_odometry_stddev, 0.0);
    279   CHECK_GT(FLAGS_range_stddev, 0.0);
    280 
    281   vector<double> odometry_values;
    282   vector<double> range_readings;
    283   SimulateRobot(&odometry_values, &range_readings);
    284 
    285   printf("Initial values:\n");
    286   PrintState(odometry_values, range_readings);
    287   ceres::Problem problem;
    288 
    289   for (int i = 0; i < odometry_values.size(); ++i) {
    290     // Create and add a DynamicAutoDiffCostFunction for the RangeConstraint from
    291     // pose i.
    292     vector<double*> parameter_blocks;
    293     RangeConstraint::RangeCostFunction* range_cost_function =
    294         RangeConstraint::Create(
    295             i, range_readings[i], &odometry_values, &parameter_blocks);
    296     problem.AddResidualBlock(range_cost_function, NULL, parameter_blocks);
    297 
    298     // Create and add an AutoDiffCostFunction for the OdometryConstraint for
    299     // pose i.
    300     problem.AddResidualBlock(OdometryConstraint::Create(odometry_values[i]),
    301                              NULL,
    302                              &(odometry_values[i]));
    303   }
    304 
    305   ceres::Solver::Options solver_options;
    306   solver_options.minimizer_progress_to_stdout = true;
    307 
    308   Solver::Summary summary;
    309   printf("Solving...\n");
    310   Solve(solver_options, &problem, &summary);
    311   printf("Done.\n");
    312   std::cout << summary.FullReport() << "\n";
    313   printf("Final values:\n");
    314   PrintState(odometry_values, range_readings);
    315   return 0;
    316 }
    317