g2o_solver.hpp
Go to the documentation of this file.
1 /*********************************************************************
2 *
3 * Copyright (c) 2017, Saurav Agarwal
4 * All rights reserved.
5 *
6 *********************************************************************/
7 
8 
9 #ifndef KARTO_G2OSolver_H
10 #define KARTO_G2OSolver_H
11 
12 #include <karto_sdk/Mapper.h>
13 #include "g2o/core/sparse_optimizer.h"
14 
15 namespace solver_plugins
16 {
17 
22 {
23  public:
24 
25  G2OSolver();
26 
27  virtual ~G2OSolver();
28 
29  public:
30 
35  virtual void Clear();
36 
41  virtual void Compute();
42 
48  virtual const karto::ScanSolver::IdPoseVector& GetCorrections() const;
49 
57 
65 
72  void getGraph(std::vector<Eigen::Vector2d>& nodes); // std::vector<std::pair<Eigen::Vector2d, Eigen::Vector2d> > &edges);
73 
80  void useRobustKernel(bool flag)
81  {
82  useRobustKernel_ = flag;
83  }
84 
85  virtual void ModifyNode(const int& unique_id, const Eigen::Vector3d& pose); // change a node's pose
86 
87  private:
88 
90 
91  g2o::SparseOptimizer optimizer_;
92 
93  int latestNodeID_; // ID of the latest added node, this is used internally in AddHeadingConstraint
94 
96 
97 };
98 
99 }
100 
101 #endif // KARTO_G2OSolver_H
102 
virtual const karto::ScanSolver::IdPoseVector & GetCorrections() const
Get the vector of corrections.
Definition: g2o_solver.cpp:65
virtual void ModifyNode(const int &unique_id, const Eigen::Vector3d &pose)
virtual void AddConstraint(karto::Edge< karto::LocalizedRangeScan > *pEdge)
Add an edge constraint to pose-graph.
Definition: g2o_solver.cpp:135
virtual std::unordered_map< int, Eigen::Vector3d > * getGraph()
Definition: Mapper.h:1026
Wrapper for G2O to interface with Open Karto.
Definition: g2o_solver.hpp:21
virtual void Clear()
Clear the vector of corrections.
Definition: g2o_solver.cpp:59
void useRobustKernel(bool flag)
Use robust kernel in back-end.
Definition: g2o_solver.hpp:80
virtual void AddNode(karto::Vertex< karto::LocalizedRangeScan > *pVertex)
Add a node to pose-graph.
Definition: g2o_solver.cpp:119
std::vector< std::pair< kt_int32s, Pose2 > > IdPoseVector
Definition: Mapper.h:953
g2o::SparseOptimizer optimizer_
Definition: g2o_solver.hpp:91
virtual void Compute()
Solve the SLAM back-end.
Definition: g2o_solver.cpp:71
karto::ScanSolver::IdPoseVector corrections_
Definition: g2o_solver.hpp:89


slam_toolbox
Author(s): Steve Macenski
autogenerated on Mon Feb 28 2022 23:46:48