Public Types | Public Member Functions | Static Public Member Functions | Protected Member Functions | Private Attributes
rtabmap::graph::Optimizer Class Reference

#include <Graph.h>

Inheritance diagram for rtabmap::graph::Optimizer:
Inheritance graph
[legend]

List of all members.

Public Types

enum  Type { kTypeUndef = -1, kTypeTORO = 0, kTypeG2O = 1 }

Public Member Functions

bool isCovarianceIgnored () const
bool isSlam2d () const
int iterations () const
virtual std::map< int, Transformoptimize (int rootId, const std::map< int, Transform > &poses, const std::multimap< int, Link > &constraints, std::list< std::map< int, Transform > > *intermediateGraphes=0)=0
virtual void parseParameters (const ParametersMap &parameters)
virtual Type type () const =0
virtual ~Optimizer ()

Static Public Member Functions

static Optimizercreate (const ParametersMap &parameters)
static Optimizercreate (Optimizer::Type &type, const ParametersMap &parameters=ParametersMap())
static void getConnectedGraph (int fromId, const std::map< int, Transform > &posesIn, const std::multimap< int, Link > &linksIn, std::map< int, Transform > &posesOut, std::multimap< int, Link > &linksOut, int depth=0)

Protected Member Functions

 Optimizer (int iterations=100, bool slam2d=false, bool covarianceIgnored=false)
 Optimizer (const ParametersMap &parameters)

Private Attributes

bool covarianceIgnored_
int iterations_
bool slam2d_

Detailed Description

Definition at line 45 of file Graph.h.


Member Enumeration Documentation

Enumerator:
kTypeUndef 
kTypeTORO 
kTypeG2O 

Definition at line 48 of file Graph.h.


Constructor & Destructor Documentation

virtual rtabmap::graph::Optimizer::~Optimizer ( ) [inline, virtual]

Definition at line 66 of file Graph.h.

rtabmap::graph::Optimizer::Optimizer ( int  iterations = 100,
bool  slam2d = false,
bool  covarianceIgnored = false 
) [protected]

Definition at line 113 of file Graph.cpp.

rtabmap::graph::Optimizer::Optimizer ( const ParametersMap parameters) [protected]

Definition at line 120 of file Graph.cpp.


Member Function Documentation

Optimizer * rtabmap::graph::Optimizer::create ( const ParametersMap parameters) [static]

Definition at line 63 of file Graph.cpp.

Optimizer * rtabmap::graph::Optimizer::create ( Optimizer::Type type,
const ParametersMap parameters = ParametersMap() 
) [static]

Definition at line 90 of file Graph.cpp.

void rtabmap::graph::Optimizer::getConnectedGraph ( int  fromId,
const std::map< int, Transform > &  posesIn,
const std::multimap< int, Link > &  linksIn,
std::map< int, Transform > &  posesOut,
std::multimap< int, Link > &  linksOut,
int  depth = 0 
) [static]

Definition at line 135 of file Graph.cpp.

Definition at line 72 of file Graph.h.

bool rtabmap::graph::Optimizer::isSlam2d ( ) const [inline]

Definition at line 71 of file Graph.h.

int rtabmap::graph::Optimizer::iterations ( ) const [inline]

Definition at line 70 of file Graph.h.

virtual std::map<int, Transform> rtabmap::graph::Optimizer::optimize ( int  rootId,
const std::map< int, Transform > &  poses,
const std::multimap< int, Link > &  constraints,
std::list< std::map< int, Transform > > *  intermediateGraphes = 0 
) [pure virtual]
void rtabmap::graph::Optimizer::parseParameters ( const ParametersMap parameters) [virtual]

Definition at line 128 of file Graph.cpp.

virtual Type rtabmap::graph::Optimizer::type ( ) const [pure virtual]

Member Data Documentation

Definition at line 89 of file Graph.h.

Definition at line 87 of file Graph.h.

Definition at line 88 of file Graph.h.


The documentation for this class was generated from the following files:


rtabmap
Author(s): Mathieu Labbe
autogenerated on Fri Aug 28 2015 12:51:44