Public Member Functions | Public Attributes | Protected Member Functions | Protected Attributes | List of all members
constant_velocity_nh Class Reference

Nonholonomic constant velocity motion model. More...

#include <motion_model.h>

Inheritance diagram for constant_velocity_nh:
Inheritance graph
[legend]

Public Member Functions

 constant_velocity_nh (double _l, double _dt, scan_matching_method _method)
 Constructor. More...
 
void updateDt (double _dt)
 Update the iteration interval. More...
 

Public Attributes

double dt
 Iteration interval. More...
 
double l
 Wheel base of the nonholonomic vehicle. More...
 

Protected Member Functions

void makeA ()
 Make the process Jacobian matrix. More...
 
void makeH ()
 Make measurement sensitivity matrix. More...
 
void makeMeasure ()
 Make measurement, used when measurement is not possible (i'm not using it now) More...
 
void makeProcess ()
 Make process, model iteration. More...
 
void makeQ ()
 Make process noise covariance matrix. More...
 
void makeR ()
 Make measurement noise covariance matrix. More...
 
void makeV ()
 Make measurement noise sensitivity matrix. More...
 
void makeW ()
 Make process noise sensitivity matrix. More...
 

Protected Attributes

scan_matching_method method
 Scan matching method used, this will influence the errors. More...
 

Detailed Description

Nonholonomic constant velocity motion model.

Extended Kalman Filter using a nonholonomic constant velocity motion model, by other works a simplistic non-linear car model.

Definition at line 47 of file motion_model.h.

Constructor & Destructor Documentation

constant_velocity_nh::constant_velocity_nh ( double  _l,
double  _dt,
scan_matching_method  _method 
)

Constructor.

Definition at line 34 of file motion_model.cpp.

Member Function Documentation

void constant_velocity_nh::makeA ( )
protected

Make the process Jacobian matrix.

Definition at line 71 of file motion_model.cpp.

void constant_velocity_nh::makeH ( )
protected

Make measurement sensitivity matrix.

Definition at line 123 of file motion_model.cpp.

void constant_velocity_nh::makeMeasure ( )
protected

Make measurement, used when measurement is not possible (i'm not using it now)

Definition at line 209 of file motion_model.cpp.

void constant_velocity_nh::makeProcess ( )
protected

Make process, model iteration.

Definition at line 185 of file motion_model.cpp.

void constant_velocity_nh::makeQ ( )
protected

Make process noise covariance matrix.

Definition at line 313 of file motion_model.cpp.

void constant_velocity_nh::makeR ( )
protected

Make measurement noise covariance matrix.

Definition at line 223 of file motion_model.cpp.

void constant_velocity_nh::makeV ( )
protected

Make measurement noise sensitivity matrix.

Definition at line 215 of file motion_model.cpp.

void constant_velocity_nh::makeW ( )
protected

Make process noise sensitivity matrix.

Definition at line 140 of file motion_model.cpp.

void constant_velocity_nh::updateDt ( double  _dt)

Update the iteration interval.

Definition at line 66 of file motion_model.cpp.

Member Data Documentation

double constant_velocity_nh::dt

Iteration interval.

Definition at line 58 of file motion_model.h.

double constant_velocity_nh::l

Wheel base of the nonholonomic vehicle.

Definition at line 56 of file motion_model.h.

scan_matching_method constant_velocity_nh::method
protected

Scan matching method used, this will influence the errors.

Definition at line 108 of file motion_model.h.


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


lidar_egomotion
Author(s): Jorge Almeida
autogenerated on Mon Mar 2 2015 01:32:10