GTSAM_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 /* Authors: Saurav Agarwal */
9 /* Modified: Steve Macenski */
10 
11 #ifndef KARTO_GTSAMSolver_H
12 #define KARTO_GTSAMSolver_H
13 
14 #include <karto_sdk/Mapper.h>
15 #include <gtsam/slam/PriorFactor.h>
16 #include <gtsam/slam/BetweenFactor.h>
17 #include <gtsam/geometry/Pose2.h>
18 #include <gtsam/nonlinear/LevenbergMarquardtOptimizer.h>
19 #include <gtsam/nonlinear/Marginals.h>
20 
21 namespace solver_plugins
22 {
23 
27 class GTSAMSolver : public karto::ScanSolver
28 {
29  public:
30 
31  GTSAMSolver();
32 
33  virtual ~GTSAMSolver();
34 
35  public:
36 
41  virtual void Clear();
42 
47  virtual void Compute();
48 
54  virtual const karto::ScanSolver::IdPoseVector& GetCorrections() const;
55 
63 
71 
78  virtual void getGraph(std::vector<Eigen::Vector2d>& nodes); // std::vector<std::pair<Eigen::Vector2d, Eigen::Vector2d> > &edges);
79 
80  virtual void ModifyNode(const int& unique_id, const Eigen::Vector3d& pose); // change a node's pose
81 
82  private:
83 
85  gtsam::NonlinearFactorGraph graph_;
86  gtsam::Values initialGuess_;
87  std::vector<Eigen::Vector2d> graphNodes_;
88 };
89 
90 } // end namespace
91 
92 #endif // KARTO_GTSAMSolver_H
93 
solver_plugins::GTSAMSolver::GetCorrections
virtual const karto::ScanSolver::IdPoseVector & GetCorrections() const
Get the vector of corrections.
Definition: GTSAM_solver.cpp:56
karto::ScanSolver
Definition: Mapper.h:947
solver_plugins::GTSAMSolver::AddConstraint
virtual void AddConstraint(karto::Edge< karto::LocalizedRangeScan > *pEdge)
Add an edge constraint to pose-graph.
Definition: GTSAM_solver.cpp:120
solver_plugins::GTSAMSolver::GTSAMSolver
GTSAMSolver()
Definition: GTSAM_solver.cpp:28
solver_plugins::GTSAMSolver::graph_
gtsam::NonlinearFactorGraph graph_
Definition: GTSAM_solver.hpp:95
karto::ScanSolver::IdPoseVector
std::vector< std::pair< kt_int32s, Pose2 > > IdPoseVector
Definition: Mapper.h:953
solver_plugins::GTSAMSolver::graphNodes_
std::vector< Eigen::Vector2d > graphNodes_
Definition: GTSAM_solver.hpp:97
solver_plugins::GTSAMSolver::AddNode
virtual void AddNode(karto::Vertex< karto::LocalizedRangeScan > *pVertex)
Add a node to pose-graph.
Definition: GTSAM_solver.cpp:103
solver_plugins::GTSAMSolver::ModifyNode
virtual void ModifyNode(const int &unique_id, const Eigen::Vector3d &pose)
solver_plugins::GTSAMSolver::~GTSAMSolver
virtual ~GTSAMSolver()
Definition: GTSAM_solver.cpp:42
karto::Vertex< karto::LocalizedRangeScan >
Mapper.h
solver_plugins::GTSAMSolver::corrections_
karto::ScanSolver::IdPoseVector corrections_
Definition: GTSAM_solver.hpp:94
solver_plugins
Definition: ceres_solver.cpp:14
karto::ScanSolver::getGraph
virtual std::unordered_map< int, Eigen::Vector3d > * getGraph()
Definition: Mapper.h:1026
solver_plugins::GTSAMSolver::Compute
virtual void Compute()
Solve the SLAM back-end.
Definition: GTSAM_solver.cpp:63
karto::Edge
Definition: Mapper.h:247
solver_plugins::GTSAMSolver::initialGuess_
gtsam::Values initialGuess_
Definition: GTSAM_solver.hpp:96
solver_plugins::GTSAMSolver::Clear
virtual void Clear()
Clear the vector of corrections.
Definition: GTSAM_solver.cpp:49


slam_toolbox
Author(s): Steve Macenski
autogenerated on Thu Jan 11 2024 03:37:55