Go to the documentation of this file.
18 #ifndef KARTO_SPASOLVER_H
19 #define KARTO_SPASOLVER_H
23 #ifndef EIGEN_USE_NEW_STDVECTOR
24 #define EIGEN_USE_NEW_STDVECTOR
25 #endif // EIGEN_USE_NEW_STDVECTOR
27 #include <Eigen/Eigen>
48 virtual void getGraph(std::vector<Eigen::Vector2d>& g);
50 virtual void ModifyNode(
const int& unique_id,
const Eigen::Vector3d& pose);
60 #endif // KARTO_SPASOLVER_H
virtual const karto::ScanSolver::IdPoseVector & GetCorrections() const
virtual void ModifyNode(const int &unique_id, const Eigen::Vector3d &pose)
virtual void AddNode(karto::Vertex< karto::LocalizedRangeScan > *pVertex)
std::vector< std::pair< kt_int32s, Pose2 > > IdPoseVector
virtual void AddConstraint(karto::Edge< karto::LocalizedRangeScan > *pEdge)
karto::ScanSolver::IdPoseVector corrections
virtual std::unordered_map< int, Eigen::Vector3d > * getGraph()
slam_toolbox
Author(s): Steve Macenski
autogenerated on Thu Jan 11 2024 03:37:56