Jafar
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Defines
Classes | Public Member Functions | Static Public Member Functions | Protected Member Functions | Private Attributes
jafar::rtslam::RobotOdometry Class Reference

Odometry motion model robot class. More...


Detailed Description

Odometry motion model robot class.

This class implements a rigid frame in 3D moving with an odometry motion model. This model performs one step on the pose F of a vehicle, given odometry increments U=[dx,dv] given by the robot frame.

This model is the following:
-p += dx <- position -q += v2q(dv) <- quaternion dx : position increment <- given by odometry sensors dv : orientation increment <- given by odometry sensors

This model is embedded into the system variables as follows:

See also:
Explore the comments in file robotOdometry.cpp for full algebraic details.

Definition at line 52 of file robotOdometry.hpp.

#include <robotOdometry.hpp>

Inheritance diagram for jafar::rtslam::RobotOdometry:
Inheritance graph
[legend]

List of all members.

Classes

struct  TempVariables

Public Member Functions

 RobotOdometry (const map_ptr_t _mapPtr)
 Remote constructor from remote map.
virtual std::string typeName () const
void move_func (const vec &_x, const vec &_u, const vec &_n, const double _dt, vec &_xnew, mat &_XNEW_x, mat &_XNEW_u, unsigned tempSet=0) const
 Move one step ahead.
bool move (double time)
void init_func (const vec &_x, const vec &_u, vec &_xnew)
virtual size_t mySize ()
virtual size_t mySize_control ()
virtual size_t mySize_perturbation ()
virtual void writeLogHeader (kernel::DataLogger &log) const
 Implements this method calling repeatidly log methods.
virtual void writeLogData (kernel::DataLogger &log) const
 Implements this method calling repeatidly log methods.

Static Public Member Functions

static size_t size ()
static size_t size_control ()
static size_t size_perturbation ()

Protected Member Functions

template<class Vx , class Vp , class Vq >
void splitState (const Vx x, Vp &p, Vq &q) const
 Split state vector.
template<class Vp , class Vq , class Vx >
void unsplitState (const Vp &p, const Vq &q, Vx &x) const
 Compose state vector.
template<class Vu , class V >
void splitControl (Vu &u, V &dx, V &dv) const
 Split control vector.

Private Attributes

TempVariables tempvars0
TempVariables tempvars1

Constructor & Destructor Documentation

jafar::rtslam::RobotOdometry::RobotOdometry ( const map_ptr_t  _mapPtr)

Remote constructor from remote map.

Parameters:
_mapthe remote map

Member Function Documentation

void jafar::rtslam::RobotOdometry::move_func ( const vec _x,
const vec _u,
const vec _n,
const double  _dt,
vec _xnew,
mat _XNEW_x,
mat _XNEW_u,
unsigned  tempSet = 0 
) const [virtual]

Move one step ahead.

This function predicts the robot state one step of length dt ahead in time, according to the control input control.x and the time interval control.dt.

Parameters:
_xthe current state vector
_uthe odometry input vector
_dtthe sampling time
_xnewthe new state vector
_XNEW_xthe Jacobian of xnew wrt x
_XNEW_pertthe Jacobian of xnew wrt u

Implements jafar::rtslam::RobotAbstract.

template<class Vu , class V >
void jafar::rtslam::RobotOdometry::splitControl ( Vu &  u,
V &  dx,
V &  dv 
) const [inline, protected]

Split control vector.

Extracts odometry datas dx and dv from the odometry vector.

Parameters:
dxthe position increment.
dvthe orientation increment.

Definition at line 151 of file robotOdometry.hpp.

template<class Vx , class Vp , class Vq >
void jafar::rtslam::RobotOdometry::splitState ( const Vx  x,
Vp &  p,
Vq &  q 
) const [inline, protected]

Split state vector.

Extracts p and q from the state vector, x = [p, q].

Parameters:
xthe state vector
pthe position
qthe quaternion

Definition at line 124 of file robotOdometry.hpp.

template<class Vp , class Vq , class Vx >
void jafar::rtslam::RobotOdometry::unsplitState ( const Vp &  p,
const Vq &  q,
Vx &  x 
) const [inline, protected]

Compose state vector.

Composes the state vector with p and q, x = [p, q].

Parameters:
pthe position
qthe quaternion
xthe state vector

Definition at line 138 of file robotOdometry.hpp.

virtual void jafar::rtslam::RobotOdometry::writeLogData ( kernel::DataLogger log) const [virtual]

Implements this method calling repeatidly log methods.

You should use writeData() or writeDataVector().

Reimplemented from jafar::rtslam::RobotAbstract.

virtual void jafar::rtslam::RobotOdometry::writeLogHeader ( kernel::DataLogger log) const [virtual]

Implements this method calling repeatidly log methods.

You should use writeComment(), writeLegend() or writeLegendTokens().

Reimplemented from jafar::rtslam::RobotAbstract.


The documentation for this class was generated from the following file:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Defines

Generated on Wed Oct 15 2014 00:37:46 for Jafar by doxygen 1.7.6.1
LAAS-CNRS