32 #ifndef _MOTION_MODEL_H_
33 #define _MOTION_MODEL_H_
35 #include <kfilter/ekfilter.hpp>
constant_velocity_nh(double _l, double _dt, scan_matching_method _method)
Constructor.
double dt
Iteration interval.
void makeA()
Make the process Jacobian matrix.
void updateDt(double _dt)
Update the iteration interval.
void makeMeasure()
Make measurement, used when measurement is not possible (i'm not using it now)
double l
Wheel base of the nonholonomic vehicle.
Nonholonomic constant velocity motion model.
void makeQ()
Make process noise covariance matrix.
void makeH()
Make measurement sensitivity matrix.
void makeR()
Make measurement noise covariance matrix.
constant_velocity_nh::Vector Vector
constant_velocity_nh::Matrix Matrix
void makeProcess()
Make process, model iteration.
void makeW()
Make process noise sensitivity matrix.
scan_matching_method method
Scan matching method used, this will influence the errors.
void makeV()
Make measurement noise sensitivity matrix.