#include <mapper.hpp>
◆ Mapper()
arx_mapper::Mapper::Mapper |
( |
double |
relinearize_thresh, |
|
|
int |
relinearize_skip |
|
) |
| |
◆ AddFactors()
void arx_mapper::Mapper::AddFactors |
( |
const std::vector< Marker > & |
markers | ) |
|
◆ AddLandmarks()
void arx_mapper::Mapper::AddLandmarks |
( |
const std::vector< Marker > & |
markers | ) |
|
◆ AddPose()
void arx_mapper::Mapper::AddPose |
( |
const ARdouble |
trans[3][4] | ) |
|
◆ Clear()
void arx_mapper::Mapper::Clear |
( |
| ) |
|
◆ inited()
bool arx_mapper::Mapper::inited |
( |
| ) |
const |
|
inline |
◆ Initialize()
void arx_mapper::Mapper::Initialize |
( |
int |
uid, |
|
|
ARdouble |
width |
|
) |
| |
◆ Optimize()
void arx_mapper::Mapper::Optimize |
( |
int |
num_iterations = 1 | ) |
|
◆ Update()
◆ pose_cnt
int arx_mapper::Mapper::pose_cnt |
|
static |
The documentation for this class was generated from the following file: