spa2d.h
Go to the documentation of this file.
1 /*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2009, Willow Garage, Inc.
5 * All rights reserved.
6 *
7 * Redistribution and use in source and binary forms, with or without
8 * modification, are permitted provided that the following conditions
9 * are met:
10 *
11 * * Redistributions of source code must retain the above copyright
12 * notice, this list of conditions and the following disclaimer.
13 * * Redistributions in binary form must reproduce the above
14 * copyright notice, this list of conditions and the following
15 * disclaimer in the documentation and/or other materials provided
16 * with the distribution.
17 * * Neither the name of the Willow Garage nor the names of its
18 * contributors may be used to endorse or promote products derived
19 * from this software without specific prior written permission.
20 *
21 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32 * POSSIBILITY OF SUCH DAMAGE.
33 *********************************************************************/
34 
35 //
36 // Sparse pose adjustment, 2d version
37 //
38 
39 #ifndef _SPA2D_H_
40 #define _SPA2D_H_
41 
42 #ifndef EIGEN_USE_NEW_STDVECTOR
43 #define EIGEN_USE_NEW_STDVECTOR
44 #endif // EIGEN_USE_NEW_STDVECTOR
45 
46 #include <stdio.h>
47 #include <iostream>
48 
49 #include <Eigen/Core>
50 #include <Eigen/Geometry>
51 #include <Eigen/LU>
52 #include <Eigen/StdVector>
53 
54 #include <vector>
55 
56 // sparse Cholesky
57 #include <nav2d_karto/csparse.h>
58 // block jacobian pcg
59 // #include <bpcg/bpcg.h>
60 
61 // Defines for methods to use with doSBA().
62 #define SBA_DENSE_CHOLESKY 0
63 #define SBA_SPARSE_CHOLESKY 1
64 #define SBA_GRADIENT 2
65 #define SBA_BLOCK_JACOBIAN_PCG 3
66 
67 
70 
88 
89  class Node2d
90  {
91  public:
92  EIGEN_MAKE_ALIGNED_OPERATOR_NEW // needed for 16B alignment
93 
95  int nodeId;
96 
98  Eigen::Matrix<double,3,1> trans; // homogeneous coordinates, last element is 1.0
99  double arot; // angle in radians, normalized to [-pi,+pi]
101  inline void normArot()
102  {
103  if (arot > M_PI) arot -= 2.0*M_PI;
104  if (arot < -M_PI) arot += 2.0*M_PI;
105  }
106 
108  Eigen::Matrix<double,2,3> w2n;
109  void setTransform();
110 
114  // Eigen::Matrix<double,3,3> covar;
115 
118  Eigen::Matrix2d dRdx;
119 
120  void setDr(); // set local angle derivatives
121 
123  bool isFixed;
124 
127  Eigen::Matrix<double,3,1> oldtrans; // homogeneous coordinates, last element is 1.0
128  double oldarot; // angle
129  };
130 
131 
135 
136  class Con2dP2
137  {
138  public:
139  EIGEN_MAKE_ALIGNED_OPERATOR_NEW // needed for 16B alignment
140 
142  int ndr;
143 
145  int nd1;
146 
149  double amean;
150  Eigen::Matrix<double,3,3> prec;
151 
153  Eigen::Matrix<double,3,1> err;
155  inline double calcErr(const Node2d &nd0, const Node2d &nd1);
156 
158  double calcErrDist(const Node2d &nd0, const Node2d &nd1);
159 
160 
162  Eigen::Matrix<double,3,3> J0,J0t,J1,J1t;
163 
166 
169 
173  void setJacobians(std::vector<Node2d,Eigen::aligned_allocator<Node2d> > &nodes);
174 
176  bool isValid;
177  };
178 
179 
180 
182 
183  class SysSPA2d
184  {
185  public:
186  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
187 
189  SysSPA2d() { nFixed = 1; verbose = false; lambda = 1.0e-4, print_iros_stats=false; }
190 
193  int addNode(const Vector3d &pos, int id);
194  void removeNode(int id);
195 
196  // add a constraint
197  // <nd0>, <nd1> are node id's
198  // <mean> is x,y,th, with th in radians
199  // <prec> is a 3x3 precision matrix (inverse covariance
200  bool addConstraint(int nd0, int nd1, const Vector3d &mean, const Matrix3d &prec);
201  bool removeConstraint(int ndi0, int ndi1);
202 
203 
205  std::vector<Node2d,Eigen::aligned_allocator<Node2d> > nodes;
206  std::vector<Node2d,Eigen::aligned_allocator<Node2d> > getNodes()
207  { return nodes; }
208 
210  std::vector< std::vector< Eigen::Vector2d, Eigen::aligned_allocator<Eigen::Vector2d> > > scans;
211 
213  int nFixed;
214 
216  std::vector<Con2dP2,Eigen::aligned_allocator<Con2dP2> > p2cons;
217 
220  double calcCost(bool tcost = false);
222  double calcCost(double dist);
223  double errcost;
224 
225 
227  void printStats();
228  void writeSparseA(char *fname, bool useCSparse = false); // save precision matrix in CSPARSE format
229 
232  void setupSys(double sLambda);
233  void setupSparseSys(double sLambda, int iter, int sparseType);
234 
239  double lambda;
240  int doSPA(int niter, double sLambda = 1.0e-4, int useCSparse = SBA_SPARSE_CHOLESKY, double initTol = 1.0e-8, int CGiters = 50);
241  int doSPAwindowed(int window, int niter, double sLambda, int useCSparse);
242 
243 
244 #ifdef SBA_DSIF
245  void doDSIF(int newnode);
247  void setupSparseDSIF(int newnode);
248 #endif
249 
251  double sqMinDelta;
252 
254  Eigen::MatrixXd A;
255  Eigen::VectorXd B;
256 
259 
261  void useCholmod(bool yes)
262  { csp.useCholmod = yes; }
263 
265  bool verbose;
267 
270  void getGraph(std::vector<float> &graph);
271  };
272 
273 
274 
275 
277 
279  bool read2dP2File(char *fname, SysSPA2d spa);
280 
281 
282 #endif // _SPA2d_H_
int nFixed
Number of fixed nodes.
Definition: spa2d.h:213
Definition: spa2d.h:89
bool isValid
valid or not (could be out of bounds)
Definition: spa2d.h:176
Eigen::Matrix< double, 3, 1 > trans
6DOF pose as a unit quaternion and translation vector
Definition: spa2d.h:98
Eigen::Matrix< double, 2, 3 > w2n
Resultant transform from world to node coordinates;.
Definition: spa2d.h:108
bool print_iros_stats
Definition: spa2d.h:266
bool useCholmod
Definition: csparse.h:123
EIGEN_MAKE_ALIGNED_OPERATOR_NEW SysSPA2d()
constructor
Definition: spa2d.h:189
bool verbose
if we want statistics
Definition: spa2d.h:265
double arot
Definition: spa2d.h:99
EIGEN_MAKE_ALIGNED_OPERATOR_NEW int ndr
Reference pose index.
Definition: spa2d.h:142
void setTransform()
Definition: spa2d.cpp:64
void setDr()
Definition: spa2d.cpp:77
SysSPA2d holds a set of nodes and constraints for sparse pose adjustment.
Definition: spa2d.h:183
void normArot()
Normalize to [-pi,+pi].
Definition: spa2d.h:101
EIGEN_MAKE_ALIGNED_OPERATOR_NEW int nodeId
node id - somewhat redundant, but can be useful, e.g., in KARTO links
Definition: spa2d.h:95
CSparse2d csp
sparse matrix object
Definition: spa2d.h:258
Definition: spa2d.h:136
#define SBA_SPARSE_CHOLESKY
Definition: spa2d.h:63
double sqMinDelta
Convergence bound (square of minimum acceptable delta change)
Definition: spa2d.h:251
bool read2dP2File(char *fname, SysSPA2d spa)
constraint files
Eigen::Matrix< double, 3, 3 > prec
Definition: spa2d.h:150
std::vector< Node2d, Eigen::aligned_allocator< Node2d > > getNodes()
Definition: spa2d.h:206
Eigen::Matrix< double, 3, 3 > J1t
Definition: spa2d.h:162
double amean
Definition: spa2d.h:149
int nd1
Node2d index for the second node.
Definition: spa2d.h:145
Eigen::Matrix< double, 3, 1 > err
error
Definition: spa2d.h:153
std::vector< Node2d, Eigen::aligned_allocator< Node2d > > nodes
set of nodes (camera frames) for SPA system, indexed by position;
Definition: spa2d.h:205
std::vector< Con2dP2, Eigen::aligned_allocator< Con2dP2 > > p2cons
Set of P2 constraints.
Definition: spa2d.h:216
Vector3< kt_double > Vector3d
Definition: Geometry.h:1046
double oldarot
Definition: spa2d.h:128
Eigen::MatrixXd A
linear system matrix and vector
Definition: spa2d.h:254
Vector2< kt_double > Vector2d
Definition: Geometry.h:610
bool isFixed
For SPA, is this camera fixed or free?
Definition: spa2d.h:123
Eigen::VectorXd B
Definition: spa2d.h:255
std::vector< std::vector< Eigen::Vector2d, Eigen::aligned_allocator< Eigen::Vector2d > > > scans
set of point scans, corresponding to nodes
Definition: spa2d.h:210
double errcost
Definition: spa2d.h:223
Eigen::Matrix< double, 3, 1 > oldtrans
Definition: spa2d.h:127
Eigen::Vector2d tmean
Mean vector, quaternion (inverse) and precision matrix for this constraint.
Definition: spa2d.h:148
void useCholmod(bool yes)
use CHOLMOD or CSparse
Definition: spa2d.h:261
Eigen::Matrix2d dRdx
Definition: spa2d.h:118
double lambda
Definition: spa2d.h:239


nav2d_karto
Author(s): Sebastian Kasperski
autogenerated on Thu Jun 6 2019 19:20:24