Public Types | Public Member Functions | Protected Member Functions | Protected Attributes | Static Protected Attributes | Private Attributes | List of all members
tuw::SLAMTechnique Class Referenceabstract

#include <slam_technique.h>

Inheritance diagram for tuw::SLAMTechnique:
Inheritance graph
[legend]

Public Types

enum  Type { EKF = 0 }
 

Public Member Functions

virtual void cycle (std::vector< Pose2D > &yt, cv::Mat_< double > &C_Yt, const Command &ut, const MeasurementConstPtr &zt)=0
 
Type getType () const
 
const std::string getTypeName () const
 
void reset ()
 
virtual void setConfig (const void *config)=0
 
 SLAMTechnique (Type type)
 
const boost::posix_time::ptime & time_last_update () const
 

Protected Member Functions

virtual void init ()=0
 map of type enum to human readable names More...
 
bool updateTimestamp (const boost::posix_time::ptime &t)
 

Protected Attributes

boost::posix_time::time_duration duration_last_update_
 time of the last processed measurment More...
 
bool reset_
 
boost::posix_time::ptime timestamp_last_update_
 on true the system should be reseted on the next loop More...
 

Static Protected Attributes

static std::map< Type, std::string > TypeName_
 

Private Attributes

Type type_
 time since the previous processed measurment More...
 

Detailed Description

Definition at line 17 of file slam_technique.h.

Member Enumeration Documentation

Different supported slam techniques

Enumerator
EKF 

Definition at line 22 of file slam_technique.h.

Constructor & Destructor Documentation

SLAMTechnique::SLAMTechnique ( Type  type)

Constructor

Parameters
typeused to identify the SLAM technique

Definition at line 9 of file slam_technique.cpp.

Member Function Documentation

virtual void tuw::SLAMTechnique::cycle ( std::vector< Pose2D > &  yt,
cv::Mat_< double > &  C_Yt,
const Command &  ut,
const MeasurementConstPtr &  zt 
)
pure virtual

starts the SLAM cycle and predicts the vehicles and landmark poses at the timestamp encoded into the measurement

Parameters
ytimplicit return of the combined state yt = (xt, mt_1, ..., mt_n) with xt = (x, y, alpha), mt_i = (x_i, y_i, alpha_i)
C_Ytimplicit return of the combined covariance matrix of combined state
utcurrent control command
ztmeasurments at time t

Implemented in tuw::EKFSLAM.

SLAMTechnique::Type SLAMTechnique::getType ( ) const

Returns the SLAM technique as enum

Returns
type enum
See also
SLAMTechnique::Type

Definition at line 19 of file slam_technique.cpp.

const std::string SLAMTechnique::getTypeName ( ) const

Returns the SLAM technique as name

Returns
type name
See also
SLAMTechnique::Type

Definition at line 23 of file slam_technique.cpp.

virtual void tuw::SLAMTechnique::init ( )
protectedpure virtual

map of type enum to human readable names

Inits the system

Implemented in tuw::EKFSLAM.

void SLAMTechnique::reset ( )

Set a reset flag to reset the system on the next loop

See also
SLAMTechnique::reset_

Definition at line 15 of file slam_technique.cpp.

virtual void tuw::SLAMTechnique::setConfig ( const void *  config)
pure virtual

virtual function to set the config parameters

Parameters
configpoint to a autogenerated ros reconfiguration config

Implemented in tuw::EKFSLAM.

const boost::posix_time::ptime & SLAMTechnique::time_last_update ( ) const

Time of the last processed measurment

Returns
time

Definition at line 27 of file slam_technique.cpp.

bool SLAMTechnique::updateTimestamp ( const boost::posix_time::ptime &  t)
protected

updates the timestamp_last_update_ and the duration_last_update_ on the first call it will set the timestamp_last_update_ to t and the duration_last_update_ to zero the duration_last_update_ will be used for the prediction step

Returns
true on succsessful update, false on first use and if t is in the past

Definition at line 31 of file slam_technique.cpp.

Member Data Documentation

boost::posix_time::time_duration tuw::SLAMTechnique::duration_last_update_
protected

time of the last processed measurment

Definition at line 99 of file slam_technique.h.

bool tuw::SLAMTechnique::reset_
protected

Definition at line 97 of file slam_technique.h.

boost::posix_time::ptime tuw::SLAMTechnique::timestamp_last_update_
protected

on true the system should be reseted on the next loop

Definition at line 98 of file slam_technique.h.

Type tuw::SLAMTechnique::type_
private

time since the previous processed measurment

Definition at line 101 of file slam_technique.h.

std::map< SLAMTechnique::Type, std::string > SLAMTechnique::TypeName_
staticprotected
Initial value:
= {
{EKF, "EKF"},
}

Definition at line 81 of file slam_technique.h.


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


tuw_marker_slam
Author(s): Markus Macsek
autogenerated on Mon Jun 10 2019 15:39:09