spa2d.h
Go to the documentation of this file.
00001 /*********************************************************************
00002 * Software License Agreement (BSD License)
00003 *
00004 *  Copyright (c) 2009, Willow Garage, Inc.
00005 *  All rights reserved.
00006 *
00007 *  Redistribution and use in source and binary forms, with or without
00008 *  modification, are permitted provided that the following conditions
00009 *  are met:
00010 *
00011 *   * Redistributions of source code must retain the above copyright
00012 *     notice, this list of conditions and the following disclaimer.
00013 *   * Redistributions in binary form must reproduce the above
00014 *     copyright notice, this list of conditions and the following
00015 *     disclaimer in the documentation and/or other materials provided
00016 *     with the distribution.
00017 *   * Neither the name of the Willow Garage nor the names of its
00018 *     contributors may be used to endorse or promote products derived
00019 *     from this software without specific prior written permission.
00020 *
00021 *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022 *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023 *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024 *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025 *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026 *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027 *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028 *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029 *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030 *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031 *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032 *  POSSIBILITY OF SUCH DAMAGE.
00033 *********************************************************************/
00034 
00035 //
00036 // Sparse pose adjustment, 2d version
00037 //
00038 
00039 #ifndef _SPA2D_H_
00040 #define _SPA2D_H_
00041 
00042 #ifndef EIGEN_USE_NEW_STDVECTOR
00043 #define EIGEN_USE_NEW_STDVECTOR
00044 #endif // EIGEN_USE_NEW_STDVECTOR
00045 
00046 #include <stdio.h>
00047 #include <iostream>
00048 #include <Eigen/Core>
00049 #include <Eigen/Geometry>
00050 #include <Eigen/LU>
00051 #ifndef EIGEN_USE_NEW_STDVECTOR
00052 #define EIGEN_USE_NEW_STDVECTOR
00053 #endif
00054 #include <Eigen/StdVector>
00055 #include <vector>
00056 
00057 // sparse Cholesky
00058 #include <sba/csparse.h>
00059 // block jacobian pcg
00060 #include <bpcg/bpcg.h>
00061 
00062 // Defines for methods to use with doSBA().
00063 #define SBA_DENSE_CHOLESKY 0
00064 #define SBA_SPARSE_CHOLESKY 1
00065 #define SBA_GRADIENT 2
00066 #define SBA_BLOCK_JACOBIAN_PCG 3
00067 
00068 
00069 // put things into a namespace
00070 namespace sba
00071 {
00072 
00075 
00093 
00094   class Node2d
00095   {
00096   public:
00097     EIGEN_MAKE_ALIGNED_OPERATOR_NEW // needed for 16B alignment
00098 
00100     int nodeId;
00101 
00103     Eigen::Matrix<double,3,1> trans;    // homogeneous coordinates, last element is 1.0
00104     double arot;                // angle in radians, normalized to [-pi,+pi]
00106     inline void normArot()
00107     { 
00108       if (arot > M_PI) arot -= 2.0*M_PI;
00109       if (arot < -M_PI) arot += 2.0*M_PI;
00110     }
00111 
00113     Eigen::Matrix<double,2,3> w2n;
00114     void setTransform();
00115 
00119     //    Eigen::Matrix<double,3,3> covar;
00120 
00123     Eigen::Matrix2d dRdx;
00124 
00125     void setDr();               // set local angle derivatives
00126 
00128     bool isFixed;
00129 
00132     Eigen::Matrix<double,3,1> oldtrans; // homogeneous coordinates, last element is 1.0
00133     double oldarot;             // angle
00134   };
00135 
00136 
00140 
00141   class Con2dP2
00142   {
00143   public:
00144     EIGEN_MAKE_ALIGNED_OPERATOR_NEW // needed for 16B alignment
00145 
00147     int ndr;
00148 
00150     int nd1;
00151 
00153     Eigen::Vector2d tmean;
00154     double amean;
00155     Eigen::Matrix<double,3,3> prec;
00156 
00158     Eigen::Matrix<double,3,1> err;
00160     inline double calcErr(const Node2d &nd0, const Node2d &nd1);
00161 
00163     double calcErrDist(const Node2d &nd0, const Node2d &nd1);
00164 
00165 
00167     Eigen::Matrix<double,3,3> J0,J0t,J1,J1t;
00168 
00171     const static double qScale = 1.0;
00172 
00175 
00178 
00182     void setJacobians(std::vector<Node2d,Eigen::aligned_allocator<Node2d> > &nodes);
00183 
00185     bool isValid;
00186   };
00187 
00188 
00189 
00191 
00192   class SysSPA2d
00193     {
00194     public:
00195       EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00196 
00198       SysSPA2d() { nFixed = 1; verbose = false; lambda = 1.0e-4, print_iros_stats=false; }
00199 
00202       int addNode(const Vector3d &pos, int id);
00203       void removeNode(int id);
00204 
00205       // add a constraint
00206       // <nd0>, <nd1> are node id's
00207       // <mean> is x,y,th, with th in radians
00208       // <prec> is a 3x3 precision matrix (inverse covariance
00209       bool addConstraint(int nd0, int nd1, const Vector3d &mean, const Matrix3d &prec);
00210       bool removeConstraint(int ndi0, int ndi1);
00211 
00212 
00214       std::vector<Node2d,Eigen::aligned_allocator<Node2d> > nodes;
00215       std::vector<Node2d,Eigen::aligned_allocator<Node2d> > getNodes()
00216         { return nodes; }
00217 
00219       std::vector< std::vector< Eigen::Vector2d, Eigen::aligned_allocator<Eigen::Vector2d> > > scans;
00220 
00222       int nFixed;               
00223 
00225       std::vector<Con2dP2,Eigen::aligned_allocator<Con2dP2> >  p2cons;
00226 
00229       double calcCost(bool tcost = false);
00231       double calcCost(double dist);
00232       double errcost;
00233 
00234 
00236       void printStats();
00237       void writeSparseA(char *fname, bool useCSparse = false); // save precision matrix in CSPARSE format
00238 
00241       void setupSys(double sLambda);
00242       void setupSparseSys(double sLambda, int iter, int sparseType);
00243 
00248       double lambda;
00249       int doSPA(int niter, double sLambda = 1.0e-4, int useCSparse = SBA_SPARSE_CHOLESKY, double initTol = 1.0e-8, int CGiters = 50);
00250       int doSPAwindowed(int window, int niter, double sLambda, int useCSparse);
00251 
00252 
00253 #ifdef SBA_DSIF
00254 
00255       void doDSIF(int newnode);
00256       void setupSparseDSIF(int newnode);
00257 #endif
00258 
00260       double sqMinDelta;
00261 
00263       Eigen::MatrixXd A;
00264       Eigen::VectorXd B;
00265 
00267       CSparse2d csp;
00268 
00270       void useCholmod(bool yes)
00271       { csp.useCholmod = yes; }
00272 
00274       bool verbose;
00275       bool print_iros_stats;
00276 
00279       void getGraph(std::vector<float> &graph);
00280     };
00281 
00282 
00283 
00284 
00286 
00288   bool read2dP2File(char *fname, SysSPA2d spa);
00289 
00290 
00291 } // ends namespace sba
00292 
00293 #endif  // _SPA2d_H_


sba
Author(s): Kurt Konolige, Helen Oleynikova
autogenerated on Thu Jan 2 2014 12:12:09