mad-location-manager-lib 1.0
Library for fusing GPS and ENU accelerometer data
Loading...
Searching...
No Matches
Public Member Functions | Public Attributes | Friends | List of all members
kf_state Struct Reference

Kalman filter state vector (X matrix) for 2D tracking. More...

#include <gps_acc_fusion_filter.h>

Public Member Functions

 kf_state ()
 velocity pointing north
 
 kf_state (double x_, double y_, double x_vel_, double y_vel_)
 

Public Attributes

double x
 
double y
 EAST -> longitude in meters.
 
double x_vel
 NORTH -> latitude in meters.
 
double y_vel
 velocity pointing east
 

Friends

std::ostream & operator<< (std::ostream &os, const kf_state &obj)
 

Detailed Description

Kalman filter state vector (X matrix) for 2D tracking.

Constructor & Destructor Documentation

◆ kf_state() [1/2]

kf_state::kf_state ( )
inline

velocity pointing north

◆ kf_state() [2/2]

kf_state::kf_state ( double  x_,
double  y_,
double  x_vel_,
double  y_vel_ 
)
inline

Friends And Related Symbol Documentation

◆ operator<<

std::ostream & operator<< ( std::ostream &  os,
const kf_state obj 
)
friend

Member Data Documentation

◆ x

double kf_state::x

◆ x_vel

double kf_state::x_vel

NORTH -> latitude in meters.

◆ y

double kf_state::y

EAST -> longitude in meters.

◆ y_vel

double kf_state::y_vel

velocity pointing east


The documentation for this struct was generated from the following file: