43 #ifndef POSITION_ESTIMATION_H__
44 #define POSITION_ESTIMATION_H__
54 #include "gps_ublox.h"
55 #include "coord_conventions.h"
58 #include "constants.h"
62 #define VEL_DECAY 0.0f
63 #define POS_DECAY 0.0f
148 #endif // POSITION_ESTIMATION_H__
Structure containing the Attitude and Heading Reference System.
Definition: ahrs.h:58
uint32_t time_last_gps_msg
The time at which we received the last GPS message in ms.
Definition: position_estimation.h:86
bool init_gps_position
The boolean flag ensuring that the GPS was initialized.
Definition: position_estimation.h:88
The position estimator structure.
Definition: position_estimation.h:69
global_position_t origin
Global coordinates of the local frame's origin (ie. local (0, 0, 0) expressed in the global frame) ...
Definition: position_estimation.h:71
const imu_t * imu
The pointer to the IMU structure.
Definition: position_estimation.h:105
local_coordinates_t last_gps_pos
The coordinates of the last GPS position.
Definition: position_estimation.h:98
bool init_barometer
The boolean flag ensuring that the barometer was initialized.
Definition: position_estimation.h:89
const gps_t * gps
The pointer to the GPS structure.
Definition: position_estimation.h:103
uint32_t time_last_barometer_msg
The time at which we received the last barometer message in ms.
Definition: position_estimation.h:87
state_t * state
The pointer to the state structure.
Definition: position_estimation.h:106
float kp_vel_baro
The gain to correct the position estimation from the barometer.
Definition: position_estimation.h:84
float last_alt
The value of the last altitude estimation.
Definition: position_estimation.h:94
Type definition for GPS data.
Definition: gps_ublox.h:635
The IMU structure.
Definition: imu.h:108
barometer_t * barometer
The pointer to the barometer structure.
Definition: position_estimation.h:102
The state structure.
Definition: state.h:79
bool * nav_plan_active
The pointer to the waypoint set flag.
Definition: position_estimation.h:108
local_coordinates_t local_position
The local position.
Definition: position_estimation.h:97
Global position structure.
Definition: coord_conventions.h:60
Define the barometer structure.
Definition: barometer.h:60
float gravity
value of the Gravity for position estimation correction
Definition: position_estimation.h:72
float gravity
The value of the gravity.
Definition: position_estimation.h:100
Local coordinates structure.
Definition: coord_conventions.h:73
The position estimator structure.
Definition: position_estimation.h:79
const ahrs_t * ahrs
The pointer to the attitude estimation structure.
Definition: position_estimation.h:104
float kp_alt_baro
The gain to correct the Z position estimation from the barometer.
Definition: position_estimation.h:83