Class KeyFrameGraph¶
- Defined in File KeyFrameGraph.h
Class Documentation¶
-
class
KeyFrameGraph¶ Graph consisting of KeyFrames and constraints, performing optimization.
Public Functions
-
KeyFrameGraph()¶ Constructs an empty pose graph.
-
~KeyFrameGraph()¶ Deletes the g2o graph.
Adds a new KeyFrame to the graph.
-
void
dumpMap(std::string folder)¶ Adds a new Frame to the graph. Doesnt actually keep the frame, but only it’s pose-struct.
-
void
insertConstraint(KFConstraintStruct *constraint)¶ Adds a new constraint to the graph.
The transformation must map world points such that they move as if attached to a frame which moves from firstFrame to secondFrame: second->camToWorld * first->worldToCam * point
If isOdometryConstraint is set, scaleInformation is ignored.
-
int
size() const¶
-
int
optimize(int num_iterations)¶ Optimizes the graph. Does not update the keyframe poses, only the vertex poses. You must call updateKeyFramePoses() afterwards.
-
bool
addElementsFromBuffer()¶
Creates a hash map of keyframe -> distance to given frame.
Public Members
-
int
totalPoints¶
-
int
totalEdges¶
-
int
totalVertices¶
-
boost::shared_mutex
keyframesAllMutex¶
-
boost::shared_mutex
idToKeyFrameMutex¶ Maps frame ids to keyframes. Contains ALL Keyframes allocated, including the one that currently being created.
-
boost::shared_mutex
edgesListsMutex¶
-
std::vector<KFConstraintStruct *>
edgesAll¶
-
std::mutex
keyframesForRetrackMutex¶
-
std::mutex
newKeyFrameMutex¶
-