sba_setup.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 // Functions defined in various test setup files
37 //
38 
39 #ifndef _SBA_SETUP_H_
40 #define _SBA_SETUP_H_
41 
44 using namespace Eigen;
45 using namespace sba;
46 using namespace frame_common;
47 
48 #include <iostream>
49 #include <fstream>
50 #include <vector>
51 #include <sys/time.h>
52 
53 using namespace std;
54 
55 // elapsed time in microseconds
56 long long utime();
57 // set up spiral system
58 void
59 spiral_setup(SysSBA &sba, CamParams &cpars, vector<Matrix<double,6,1>,Eigen::aligned_allocator<Matrix<double,6,1> > > &cps,
60  double s_near, double s_far,
61  double ptsize, double kfang, double initang, double cycles,
62  double inoise, double pnoise, double qnoise);
63 
64 void
65 sphere_setup(SysSBA &sba, CamParams &cpars, vector<Matrix<double,6,1>, Eigen::aligned_allocator<Matrix<double,6,1> > > &cps,
66  int ncams, // number of cameras
67  int ncpts, // number of new pts per camera
68  int nccs, // number of camera connections per camera
69  double inoise, double pnoise, double qnoise);
70 
71 
72 void
73 spa_spiral_setup(SysSPA &spa, bool use_cross_links,
74  vector<Matrix<double,6,1>, Eigen::aligned_allocator<Matrix<double,6,1> > > &cps,
75  Matrix<double,6,6> prec, Matrix<double,6,6> vprec,
76  Matrix<double,6,6> a10prec, Matrix<double,6,6> a15prec,
77  double kfang, double initang, double cycles,
78  double pnoise, double qnoise, double snoise, // measurement noise (m,deg), scale noise (percent)
79  double mpnoise, double mqnoise); // initial displacement (m,deg)
80 
81 
82 void
84  vector<Matrix<double,3,1>, Eigen::aligned_allocator<Matrix<double,3,1> > > &cps,
85  Matrix<double,3,3> prec, Matrix<double,3,3> vprec,
86  Matrix<double,3,3> a10prec, Matrix<double,3,3> a15prec,
87  double kfang, double initang, double cycles,
88  double pnoise, double qnoise, double snoise, double dpnoise, double dqnoise);
89 
90 
91 #endif // _VO_SETUP_H_
SysSPA holds a set of nodes and constraints for sparse pose adjustment.
Definition: sba.h:440
void sphere_setup(SysSBA &sba, CamParams &cpars, vector< Matrix< double, 6, 1 >, Eigen::aligned_allocator< Matrix< double, 6, 1 > > > &cps, int ncams, int ncpts, int nccs, double inoise, double pnoise, double qnoise)
SysSBA holds a set of nodes and points for sparse bundle adjustment.
Definition: sba.h:75
void spiral_setup(SysSBA &sba, CamParams &cpars, vector< Matrix< double, 6, 1 >, Eigen::aligned_allocator< Matrix< double, 6, 1 > > > &cps, double s_near, double s_far, double ptsize, double kfang, double initang, double cycles, double inoise, double pnoise, double qnoise)
void spa_spiral_setup(SysSPA &spa, bool use_cross_links, vector< Matrix< double, 6, 1 >, Eigen::aligned_allocator< Matrix< double, 6, 1 > > > &cps, Matrix< double, 6, 6 > prec, Matrix< double, 6, 6 > vprec, Matrix< double, 6, 6 > a10prec, Matrix< double, 6, 6 > a15prec, double kfang, double initang, double cycles, double pnoise, double qnoise, double snoise, double mpnoise, double mqnoise)
Definition: bpcg.h:60
long long utime()
SysSPA2d holds a set of nodes and constraints for sparse pose adjustment.
Definition: spa2d.h:192
void spa2d_spiral_setup(SysSPA2d &spa, vector< Matrix< double, 3, 1 >, Eigen::aligned_allocator< Matrix< double, 3, 1 > > > &cps, Matrix< double, 3, 3 > prec, Matrix< double, 3, 3 > vprec, Matrix< double, 3, 3 > a10prec, Matrix< double, 3, 3 > a15prec, double kfang, double initang, double cycles, double pnoise, double qnoise, double snoise, double dpnoise, double dqnoise)


sparse_bundle_adjustment
Author(s):
autogenerated on Fri Apr 3 2020 03:30:53