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::RobotConstantVelocity Class Reference

Constant velocity model robot class. More...


Detailed Description

Constant velocity model robot class.

The SLAM origin is the camera origin.

Author:
jsola

This class implements a rigid frame in 3D moving with a constant velocity motion model. This model is the following:

where vi and wi are linear and angular velocity random impulses, and ** is the quaternion product.

This model is embedded into the system variables as follows:

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

Definition at line 54 of file robotConstantVelocity.hpp.

#include <robotConstantVelocity.hpp>

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

List of all members.

Classes

struct  TempVariables

Public Member Functions

 RobotConstantVelocity (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_pert, unsigned tempSet=0) const
 Move one step ahead.
void computePertJacobian ()
virtual size_t mySize ()
virtual size_t mySize_control ()
virtual size_t mySize_perturbation ()
void setVelocityStd (double velLinStd, double velAngStd)
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 , class Vv , class Vw >
void splitState (const Vx x, Vp &p, Vq &q, Vv &v, Vw &w) const
 Split state vector.
template<class Vp , class Vq , class Vv , class Vw , class Vx >
void unsplitState (const Vp &p, const Vq &q, const Vv &v, const Vw &w, Vx &x) const
 Compose state vector.
template<class Vu , class V >
void splitControl (const Vu &u, V &vi, V &wi) const
 Split control vector.

Private Attributes

TempVariables tempvars0
TempVariables tempvars1

Constructor & Destructor Documentation

Remote constructor from remote map.

Parameters:
_mapthe remote map

Member Function Documentation

void jafar::rtslam::RobotConstantVelocity::move_func ( const vec _x,
const vec _u,
const vec _n,
const double  _dt,
vec _xnew,
mat _XNEW_x,
mat _XNEW_pert,
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 vecto
_pthe perturbation vector
_dtthe sampling time
_xnewthe new state vector
_XNEW_xthe Jacobian of xnew wrt x
_XNEW_pertthe Jacobian of xnew wrt p

Implements jafar::rtslam::RobotAbstract.

template<class Vu , class V >
void jafar::rtslam::RobotConstantVelocity::splitControl ( const Vu &  u,
V &  vi,
V &  wi 
) const [inline, protected]

Split control vector.

Extracts impulses vi and wi from the control vector.

Parameters:
vithe linear impulse.
withe angular impulse.

Definition at line 163 of file robotConstantVelocity.hpp.

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

Split state vector.

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

Parameters:
xthe state vector
pthe position
qthe quaternion
vthe linear velocity
wthe angular velocity

Definition at line 128 of file robotConstantVelocity.hpp.

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

Compose state vector.

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

Parameters:
pthe position
qthe quaternion
vthe linear velocity
wthe angular velocity
xthe state vector

Definition at line 147 of file robotConstantVelocity.hpp.

Implements this method calling repeatidly log methods.

You should use writeData() or writeDataVector().

Reimplemented from jafar::rtslam::RobotAbstract.

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