sba_setup.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 // Functions defined in various test setup files
00037 //
00038 
00039 #ifndef _SBA_SETUP_H_
00040 #define _SBA_SETUP_H_
00041 
00042 #include "sba/sba.h"
00043 #include "sba/spa2d.h"
00044 using namespace Eigen;
00045 using namespace sba;
00046 using namespace frame_common;
00047 
00048 #include <iostream>
00049 #include <fstream>
00050 #include <vector>
00051 #include <sys/time.h>
00052 
00053 using namespace std;
00054 
00055 // elapsed time in microseconds
00056 long long utime();
00057 // set up spiral system
00058 void 
00059 spiral_setup(SysSBA &sba, CamParams &cpars, vector<Matrix<double,6,1>,Eigen::aligned_allocator<Matrix<double,6,1> > > &cps,
00060              double s_near, double s_far,
00061              double ptsize, double kfang, double initang, double cycles, 
00062              double inoise, double pnoise, double qnoise);
00063 
00064 void
00065 sphere_setup(SysSBA &sba, CamParams &cpars, vector<Matrix<double,6,1>, Eigen::aligned_allocator<Matrix<double,6,1> > > &cps,
00066              int ncams,         // number of cameras
00067              int ncpts,         // number of new pts per camera
00068              int nccs,          // number of camera connections per camera
00069              double inoise, double pnoise, double qnoise);
00070 
00071 
00072 void
00073 spa_spiral_setup(SysSPA &spa, bool use_cross_links,
00074                  vector<Matrix<double,6,1>, Eigen::aligned_allocator<Matrix<double,6,1> > > &cps,
00075                  Matrix<double,6,6> prec, Matrix<double,6,6> vprec,
00076                  Matrix<double,6,6> a10prec, Matrix<double,6,6> a15prec,
00077                  double kfang, double initang, double cycles, 
00078                  double pnoise, double qnoise, double snoise, // measurement noise (m,deg), scale noise (percent)
00079                  double mpnoise, double mqnoise); // initial displacement (m,deg)
00080 
00081 
00082 void
00083 spa2d_spiral_setup(SysSPA2d &spa, 
00084                  vector<Matrix<double,3,1>, Eigen::aligned_allocator<Matrix<double,3,1> > > &cps,
00085                  Matrix<double,3,3> prec, Matrix<double,3,3> vprec,
00086                  Matrix<double,3,3> a10prec, Matrix<double,3,3> a15prec,
00087                  double kfang, double initang, double cycles, 
00088                  double pnoise, double qnoise, double snoise, double dpnoise, double dqnoise);
00089 
00090 
00091 #endif  // _VO_SETUP_H_


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