spa_solver.h
Go to the documentation of this file.
1 /*
2  * Copyright 2010 SRI International
3  *
4  * This program is free software: you can redistribute it and/or modify
5  * it under the terms of the GNU Lesser General Public License as published by
6  * the Free Software Foundation, either version 3 of the License, or
7  * (at your option) any later version.
8  *
9  * This program is distributed in the hope that it will be useful,
10  * but WITHOUT ANY WARRANTY; without even the implied warranty of
11  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
12  * GNU Lesser General Public License for more details.
13  *
14  * You should have received a copy of the GNU Lesser General Public License
15  * along with this program. If not, see <http://www.gnu.org/licenses/>.
16  */
17 
18 #ifndef KARTO_SPASOLVER_H
19 #define KARTO_SPASOLVER_H
20 
21 #include <open_karto/Mapper.h>
22 
23 #ifndef EIGEN_USE_NEW_STDVECTOR
24 #define EIGEN_USE_NEW_STDVECTOR
25 #endif // EIGEN_USE_NEW_STDVECTOR
26 
27 #define EIGEN_DEFAULT_IO_FORMAT Eigen::IOFormat(10)
28 #include <Eigen/Eigen>
29 
31 
32 typedef std::vector<karto::Matrix3> CovarianceVector;
33 
34 class SpaSolver : public karto::ScanSolver
35 {
36 public:
37  SpaSolver();
38  virtual ~SpaSolver();
39 
40 public:
41  virtual void Clear();
42  virtual void Compute();
43  virtual const karto::ScanSolver::IdPoseVector& GetCorrections() const;
44 
47 
48  // Get the underlying graph from SBA
49  // return the graph of constraints
51  void getGraph(std::vector<float> &g) { m_Spa.getGraph(g); }
52 
53 private:
55 
57 };
58 
59 #endif // KARTO_SPASOLVER_H
60 
virtual const karto::ScanSolver::IdPoseVector & GetCorrections() const
Definition: spa_solver.cpp:38
void getGraph(std::vector< float > &graph)
virtual void AddNode(karto::Vertex< karto::LocalizedRangeScan > *pVertex)
Definition: spa_solver.cpp:60
std::vector< karto::Matrix3 > CovarianceVector
Definition: spa_solver.h:32
sba::SysSPA2d m_Spa
Definition: spa_solver.h:56
virtual void Clear()
Definition: spa_solver.cpp:33
karto::ScanSolver::IdPoseVector corrections
Definition: spa_solver.h:54
virtual void Compute()
Definition: spa_solver.cpp:43
std::vector< std::pair< kt_int32s, Pose2 > > IdPoseVector
virtual void AddConstraint(karto::Edge< karto::LocalizedRangeScan > *pEdge)
Definition: spa_solver.cpp:67
virtual ~SpaSolver()
Definition: spa_solver.cpp:28


slam_karto
Author(s): Brian Gerkey
autogenerated on Mon Jun 10 2019 15:08:17