Paparazzi UAS  v5.12_stable-4-g9b43e9b
Paparazzi is a free software Unmanned Aircraft System.
 All Data Structures Namespaces Files Functions Variables Typedefs Enumerations Enumerator Macros Modules Pages
ahrs_int_cmpl_quat.h
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2008-2013 The Paparazzi Team
3  *
4  * This file is part of paparazzi.
5  *
6  * paparazzi is free software; you can redistribute it and/or modify
7  * it under the terms of the GNU General Public License as published by
8  * the Free Software Foundation; either version 2, or (at your option)
9  * any later version.
10  *
11  * paparazzi is distributed in the hope that it will be useful,
12  * but WITHOUT ANY WARRANTY; without even the implied warranty of
13  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
14  * GNU General Public License for more details.
15  *
16  * You should have received a copy of the GNU General Public License
17  * along with paparazzi; see the file COPYING. If not, write to
18  * the Free Software Foundation, 59 Temple Place - Suite 330,
19  * Boston, MA 02111-1307, USA.
20  */
21 
31 #ifndef AHRS_INT_CMPL_QUAT_H
32 #define AHRS_INT_CMPL_QUAT_H
33 
34 #include "subsystems/ahrs.h"
35 #include "subsystems/gps.h"
36 #include "std.h"
37 #include "math/pprz_algebra_int.h"
39 
43 };
44 
55  struct Int32Vect3 mag_h;
56 
60  float weight;
61  float accel_inv_kp;
62  float accel_inv_ki;
63  float mag_kp;
64  float mag_ki;
65 
66  /* parameters/options that can be changed */
69 
74 
79  float accel_omega;
80 
85  float accel_zeta;
86 
90  float mag_omega;
91 
95  float mag_zeta;
96 
97  /* internal counters for the gains */
100 
102 
105 };
106 
107 extern struct AhrsIntCmplQuat ahrs_icq;
108 
109 extern void ahrs_icq_init(void);
111 extern void ahrs_icq_set_body_to_imu_quat(struct FloatQuat *q_b2i);
112 extern bool ahrs_icq_align(struct Int32Rates *lp_gyro, struct Int32Vect3 *lp_accel,
113  struct Int32Vect3 *lp_mag);
114 extern void ahrs_icq_propagate(struct Int32Rates *gyro, float dt);
115 extern void ahrs_icq_update_accel(struct Int32Vect3 *accel, float dt);
116 extern void ahrs_icq_update_mag(struct Int32Vect3 *mag, float dt);
117 extern void ahrs_icq_update_gps(struct GpsState *gps_s);
118 
124 
131 
132 
134 extern void ahrs_icq_set_accel_gains(void);
135 
136 static inline void ahrs_int_cmpl_quat_SetAccelOmega(float omega)
137 {
138  ahrs_icq.accel_omega = omega;
140 }
141 
142 static inline void ahrs_int_cmpl_quat_SetAccelZeta(float zeta)
143 {
144  ahrs_icq.accel_zeta = zeta;
146 }
147 
149 extern void ahrs_icq_set_mag_gains(void);
150 
151 static inline void ahrs_int_cmpl_quat_SetMagOmega(float omega)
152 {
153  ahrs_icq.mag_omega = omega;
155 }
156 
157 static inline void ahrs_int_cmpl_quat_SetMagZeta(float zeta)
158 {
159  ahrs_icq.mag_zeta = zeta;
161 }
162 
163 
164 #endif /* AHRS_INT_CMPL_QUAT_H */
unsigned short uint16_t
Definition: types.h:16
angular rates
float accel_omega
filter cut-off frequency for correcting the attitude from accels.
struct OrientationReps body_to_imu
Dispatcher to register actual AHRS implementations.
struct Int32Vect3 mag_h
void ahrs_icq_update_heading(int32_t heading)
Update yaw based on a heading measurement.
void ahrs_icq_realign_heading(int32_t heading)
Hard reset yaw to a heading.
void ahrs_icq_set_body_to_imu_quat(struct FloatQuat *q_b2i)
struct Int32Rates rate_correction
uint16_t accel_cnt
number of propagations since last accel update
struct AhrsIntCmplQuat ahrs_icq
Default Rate filter Low pass.
void ahrs_icq_update_mag(struct Int32Vect3 *mag, float dt)
static void ahrs_int_cmpl_quat_SetAccelOmega(float omega)
uint8_t gravity_heuristic_factor
sets how strongly the gravity heuristic reduces accel correction.
uint16_t mag_cnt
number of propagations since last mag update
AhrsICQStatus
void ahrs_icq_set_mag_gains(void)
update pre-computed kp and ki gains from mag_omega and mag_zeta
Roation quaternion.
bool ahrs_icq_align(struct Int32Rates *lp_gyro, struct Int32Vect3 *lp_accel, struct Int32Vect3 *lp_mag)
void ahrs_icq_update_gps(struct GpsState *gps_s)
static float heading
Definition: ahrs_infrared.c:45
struct Int32Rates gyro_bias
float mag_zeta
filter damping for correcting the gyro bias from magnetometer.
struct Int32Quat ltp_to_imu_quat
data structure for GPS information
Definition: gps.h:81
Device independent GPS code (interface)
float accel_zeta
filter damping for correcting the gyro-bias from accels.
Ahrs implementation specifc values.
void ahrs_icq_set_body_to_imu(struct OrientationReps *body_to_imu)
float mag_omega
filter cut-off frequency for correcting the attitude (heading) from magnetometer. ...
signed long int32_t
Definition: types.h:19
struct Int64Rates high_rez_bias
bool correct_gravity
enable gravity vector correction by removing centrifugal acceleration
unsigned char uint8_t
Definition: types.h:14
void ahrs_icq_update_accel(struct Int32Vect3 *accel, float dt)
static void ahrs_int_cmpl_quat_SetAccelZeta(float zeta)
struct Int64Quat high_rez_quat
void ahrs_icq_propagate(struct Int32Rates *gyro, float dt)
static void ahrs_int_cmpl_quat_SetMagZeta(float zeta)
struct Int32Rates imu_rate
void ahrs_icq_set_accel_gains(void)
update pre-computed inv_kp and inv_ki gains from acc_omega and acc_zeta
static struct OrientationReps body_to_imu
Definition: ins_alt_float.c:93
Generic orientation representation and conversions.
Rotation quaternion.
void ahrs_icq_init(void)
enum AhrsICQStatus status
status of the AHRS, AHRS_ICQ_UNINIT or AHRS_ICQ_RUNNING
Paparazzi fixed point algebra.
static void ahrs_int_cmpl_quat_SetMagOmega(float omega)