Class KeyFrameGraph

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.

void addKeyFrame(const KeyFrame::SharedPtr &keyframe)

Adds a new KeyFrame to the graph.

void dropKeyFrame(const KeyFrame::SharedPtr &keyframe)
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()
void calculateGraphDistancesToFrame(const KeyFrame::SharedPtr &frame, std::unordered_map<KeyFrame::SharedPtr, int> &distanceMap)

Creates a hash map of keyframe -> distance to given frame.

Public Members

int totalPoints
int totalEdges
int totalVertices
std::vector<KeyFrame::SharedPtr> _keyFrames
boost::shared_mutex keyframesAllMutex
std::vector<KeyFrame::SharedPtr> keyframesAll
boost::shared_mutex idToKeyFrameMutex

Maps frame ids to keyframes. Contains ALL Keyframes allocated, including the one that currently being created.

std::unordered_map<int, KeyFrame::SharedPtr> idToKeyFrame
boost::shared_mutex edgesListsMutex
std::vector<KFConstraintStruct *> edgesAll
std::mutex keyframesForRetrackMutex
std::deque<KeyFrame::SharedPtr> keyframesForRetrack
std::mutex newKeyFrameMutex