#include <constraint_generator.h>
Public Member Functions | |
virtual NodeConstraintVector | getConstraints (const pg::PoseGraph &graph, pg::NodeId new_node, const NodePoseMap &optimized_poses)=0 |
Return a set of constraints given the current state of the graph the identity of the new node, and current optimized poses. | |
virtual void | initializeFromGraph (const pg::PoseGraph &g, const std::vector< pg::NodeId > &node_sequence)=0 |
Initialize from existing graph. | |
virtual void | updateLocalization (const graph_slam::GraphLocalization &loc)=0 |
virtual | ~ConstraintGenerator () |
Subclasses of this must define a method for getConstraints They may assume getConstraints is called once each time a new node is added during normal operation, and that updateLocalization is called whenever we switch to a new reference node If the graph is loaded at initialization in graph_mapper, then instead initializeFromGraph will be called
Definition at line 85 of file constraint_generator.h.
virtual graph_slam::ConstraintGenerator::~ConstraintGenerator | ( | ) | [inline, virtual] |
Definition at line 88 of file constraint_generator.h.
virtual NodeConstraintVector graph_slam::ConstraintGenerator::getConstraints | ( | const pg::PoseGraph & | graph, |
pg::NodeId | new_node, | ||
const NodePoseMap & | optimized_poses | ||
) | [pure virtual] |
Return a set of constraints given the current state of the graph the identity of the new node, and current optimized poses.
Implemented in graph_slam::KartoLaserConstraints, graph_slam::OdomConstraintGenerator, and graph_slam::FakeLoopClosureGenerator.
virtual void graph_slam::ConstraintGenerator::initializeFromGraph | ( | const pg::PoseGraph & | g, |
const std::vector< pg::NodeId > & | node_sequence | ||
) | [pure virtual] |
Initialize from existing graph.
node_sequence | is a suffix of the order in which nodes were seen; can have repeats |
Implemented in graph_slam::KartoLaserConstraints, and graph_slam::OdomConstraintGenerator.
virtual void graph_slam::ConstraintGenerator::updateLocalization | ( | const graph_slam::GraphLocalization & | loc | ) | [pure virtual] |