MAV'RIC
position_estimation.h
1 /*******************************************************************************
2  * Copyright (c) 2009-2014, MAV'RIC Development Team
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * 1. Redistributions of source code must retain the above copyright notice,
9  * this list of conditions and the following disclaimer.
10  *
11  * 2. Redistributions in binary form must reproduce the above copyright notice,
12  * this list of conditions and the following disclaimer in the documentation
13  * and/or other materials provided with the distribution.
14  *
15  * 3. Neither the name of the copyright holder nor the names of its contributors
16  * may be used to endorse or promote products derived from this software without
17  * specific prior written permission.
18  *
19  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
20  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
21  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
22  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
23  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
24  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
25  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
26  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
27  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
28  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
29  * POSSIBILITY OF SUCH DAMAGE.
30  ******************************************************************************/
31 
32 /*******************************************************************************
33  * \file position_estimation.h
34  *
35  * \author MAV'RIC Team
36  *
37  * \brief This file performs the 3D position estimation, either by direct
38  * integration or with correction with the GPS and pos_est->barometer
39  *
40  ******************************************************************************/
41 
42 
43 #ifndef POSITION_ESTIMATION_H__
44 #define POSITION_ESTIMATION_H__
45 
46 #ifdef __cplusplus
47 extern "C" {
48 #endif
49 
50 #include <stdbool.h>
51 #include "imu.h"
52 #include "ahrs.h"
53 #include "bmp085.h"
54 #include "gps_ublox.h"
55 #include "coord_conventions.h"
56 #include "state.h"
57 #include "tasks.h"
58 #include "constants.h"
59 
60 
61 // leaky velocity integration as a simple trick to emulate drag and avoid too large deviations (loss per 1 second)
62 #define VEL_DECAY 0.0f
63 #define POS_DECAY 0.0f
64 
65 
69 typedef struct
70 {
72  float gravity;
74 
75 
79 typedef struct
80 {
81  float kp_vel_gps[3];
82  float kp_pos_gps[3];
83  float kp_alt_baro;
84  float kp_vel_baro;
85 
86  uint32_t time_last_gps_msg;
90 
91  float vel_bf[3];
92  float vel[3];
93 
94  float last_alt;
95  float last_vel[3];
96 
99 
100  float gravity;
101 
103  const gps_t* gps;
104  const ahrs_t* ahrs;
105  const imu_t* imu;
107 
110 
111 
125 bool position_estimation_init(position_estimation_t* pos_est, const position_estimation_conf_t* config, state_t* state, barometer_t* barometer, const gps_t *gps, const ahrs_t *ahrs, const imu_t *imu);
126 
127 
133 void position_estimation_reset_home_altitude(position_estimation_t *pos_est);
134 
135 
141 void position_estimation_update(position_estimation_t *pos_est);
142 
143 
144 #ifdef __cplusplus
145 }
146 #endif
147 
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