Go to the documentation of this file.
11 #ifndef KARTO_GTSAMSolver_H
12 #define KARTO_GTSAMSolver_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>
78 virtual void getGraph(std::vector<Eigen::Vector2d>& nodes);
80 virtual void ModifyNode(
const int& unique_id,
const Eigen::Vector3d& pose);
85 gtsam::NonlinearFactorGraph
graph_;
92 #endif // KARTO_GTSAMSolver_H
virtual const karto::ScanSolver::IdPoseVector & GetCorrections() const
Get the vector of corrections.
virtual void AddConstraint(karto::Edge< karto::LocalizedRangeScan > *pEdge)
Add an edge constraint to pose-graph.
gtsam::NonlinearFactorGraph graph_
std::vector< std::pair< kt_int32s, Pose2 > > IdPoseVector
std::vector< Eigen::Vector2d > graphNodes_
virtual void AddNode(karto::Vertex< karto::LocalizedRangeScan > *pVertex)
Add a node to pose-graph.
virtual void ModifyNode(const int &unique_id, const Eigen::Vector3d &pose)
karto::ScanSolver::IdPoseVector corrections_
virtual std::unordered_map< int, Eigen::Vector3d > * getGraph()
virtual void Compute()
Solve the SLAM back-end.
gtsam::Values initialGuess_
virtual void Clear()
Clear the vector of corrections.
slam_toolbox
Author(s): Steve Macenski
autogenerated on Thu Jan 11 2024 03:37:55