Paparazzi UAS  v5.8.2_stable-0-g6260b7c
Paparazzi is a free software Unmanned Aircraft System.
 All Data Structures Namespaces Files Functions Variables Typedefs Enumerations Enumerator Macros Modules Pages
ahrs_float_cmpl.c
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2010-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 
33 #include "math/pprz_algebra_int.h"
35 #include "generated/airframe.h"
36 #if USE_GPS
37 #include "subsystems/gps.h"
38 #endif
39 
40 //#include "../../test/pprz_algebra_print.h"
41 
42 #if AHRS_PROPAGATE_RMAT && AHRS_PROPAGATE_QUAT
43 #error "You can only define either AHRS_PROPAGATE_RMAT or AHRS_PROPAGATE_QUAT, not both!"
44 #endif
45 #if !AHRS_PROPAGATE_RMAT && !AHRS_PROPAGATE_QUAT
46 #error "You have to define either AHRS_PROPAGATE_RMAT or AHRS_PROPAGATE_QUAT"
47 #endif
48 
49 #ifdef AHRS_MAG_UPDATE_YAW_ONLY
50 #warning "AHRS_MAG_UPDATE_YAW_ONLY is deprecated, please remove it. This is the default behaviour. Define AHRS_MAG_UPDATE_ALL_AXES to use mag for all axes and not only yaw."
51 #endif
52 
53 #if USE_MAGNETOMETER && AHRS_USE_GPS_HEADING
54 #warning "Using magnetometer _and_ GPS course to update heading. Probably better to <configure name="USE_MAGNETOMETER" value="0"/> if you want to use GPS course."
55 #endif
56 
57 /*
58  * default gains for correcting attitude and bias from accel/mag
59  */
60 #ifndef AHRS_ACCEL_OMEGA
61 #define AHRS_ACCEL_OMEGA 0.063
62 #endif
63 #ifndef AHRS_ACCEL_ZETA
64 #define AHRS_ACCEL_ZETA 0.9
65 #endif
66 
67 #ifndef AHRS_MAG_OMEGA
68 #define AHRS_MAG_OMEGA 0.04
69 #endif
70 #ifndef AHRS_MAG_ZETA
71 #define AHRS_MAG_ZETA 0.9
72 #endif
73 
75 #ifndef AHRS_GRAVITY_HEURISTIC_FACTOR
76 #define AHRS_GRAVITY_HEURISTIC_FACTOR 30
77 #endif
78 
79 
80 void ahrs_fc_update_mag_full(struct Int32Vect3 *mag, float dt);
81 void ahrs_fc_update_mag_2d(struct Int32Vect3 *mag, float dt);
82 void ahrs_fc_update_mag_2d_dumb(struct Int32Vect3 *mag);
83 
85 
86 void ahrs_fc_init(void)
87 {
90 
93 
94  /* init ltp_to_imu quaternion as zero/identity rotation */
96 
99 
101 
102  /* set default filter cut-off frequency and damping */
107 
108 #if AHRS_GRAVITY_UPDATE_COORDINATED_TURN
110 #else
112 #endif
113 
115 
116  VECT3_ASSIGN(ahrs_fc.mag_h, AHRS_H_X, AHRS_H_Y, AHRS_H_Z);
117 
118  ahrs_fc.accel_cnt = 0;
119  ahrs_fc.mag_cnt = 0;
120 }
121 
122 bool_t ahrs_fc_align(struct Int32Rates *lp_gyro, struct Int32Vect3 *lp_accel,
123  struct Int32Vect3 *lp_mag)
124 {
125 
126 #if USE_MAGNETOMETER
127  /* Compute an initial orientation from accel and mag directly as quaternion */
130 #else
131  /* Compute an initial orientation from accel and just set heading to zero */
134 #endif
135 
136  /* Convert initial orientation from quat to rotation matrix representations. */
138 
139  /* used averaged gyro as initial value for bias */
140  struct Int32Rates bias0;
141  RATES_COPY(bias0, *lp_gyro);
143 
146 
147  return TRUE;
148 }
149 
150 
151 void ahrs_fc_propagate(struct Int32Rates *gyro, float dt)
152 {
153 
154  /* converts gyro to floating point */
155  struct FloatRates gyro_float;
156  RATES_FLOAT_OF_BFP(gyro_float, *gyro);
157  /* unbias measurement */
158  RATES_SUB(gyro_float, ahrs_fc.gyro_bias);
159 
160 #ifdef AHRS_PROPAGATE_LOW_PASS_RATES
161  const float alpha = 0.1;
162  FLOAT_RATES_LIN_CMB(ahrs_fc.imu_rate, ahrs_fc.imu_rate, (1. - alpha), gyro_float, alpha);
163 #else
164  RATES_COPY(ahrs_fc.imu_rate, gyro_float);
165 #endif
166 
167  /* add correction */
168  struct FloatRates omega;
169  RATES_SUM(omega, gyro_float, ahrs_fc.rate_correction);
170  /* and zeros it */
172 
173 #if AHRS_PROPAGATE_RMAT
177 #endif
178 #if AHRS_PROPAGATE_QUAT
182 #endif
183 
184  // increase accel and mag propagation counters
185  ahrs_fc.accel_cnt++;
186  ahrs_fc.mag_cnt++;
187 }
188 
189 void ahrs_fc_update_accel(struct Int32Vect3 *accel, float dt)
190 {
191  // check if we had at least one propagation since last update
192  if (ahrs_fc.accel_cnt == 0) {
193  return;
194  }
195 
196  /* last column of roation matrix = ltp z-axis in imu-frame */
197  struct FloatVect3 c2 = { RMAT_ELMT(ahrs_fc.ltp_to_imu_rmat, 0, 2),
200  };
201 
202  struct FloatVect3 imu_accel_float;
203  ACCELS_FLOAT_OF_BFP(imu_accel_float, *accel);
204 
205  struct FloatVect3 residual;
206 
207  struct FloatVect3 pseudo_gravity_measurement;
208 
210  /*
211  * centrifugal acceleration in body frame
212  * a_c_body = omega x (omega x r)
213  * (omega x r) = tangential velocity in body frame
214  * a_c_body = omega x vel_tangential_body
215  * assumption: tangential velocity only along body x-axis
216  */
217  const struct FloatVect3 vel_tangential_body = {ahrs_fc.ltp_vel_norm, 0.0, 0.0};
218  struct FloatRMat *body_to_imu_rmat = orientationGetRMat_f(&ahrs_fc.body_to_imu);
219  struct FloatRates body_rate;
220  float_rmat_transp_ratemult(&body_rate, body_to_imu_rmat, &ahrs_fc.imu_rate);
221  struct FloatVect3 acc_c_body;
222  VECT3_RATES_CROSS_VECT3(acc_c_body, body_rate, vel_tangential_body);
223 
224  /* convert centrifugal acceleration from body to imu frame */
225  struct FloatVect3 acc_c_imu;
226  float_rmat_vmult(&acc_c_imu, body_to_imu_rmat, &acc_c_body);
227 
228  /* and subtract it from imu measurement to get a corrected measurement of the gravity vector */
229  VECT3_DIFF(pseudo_gravity_measurement, imu_accel_float, acc_c_imu);
230 
231  } else {
232  VECT3_COPY(pseudo_gravity_measurement, imu_accel_float);
233  }
234 
235  VECT3_CROSS_PRODUCT(residual, pseudo_gravity_measurement, c2);
236 
237  /* FIR filtered pseudo_gravity_measurement */
238 #define FIR_FILTER_SIZE 8
239  static struct FloatVect3 filtered_gravity_measurement = {0., 0., 0.};
240  VECT3_SMUL(filtered_gravity_measurement, filtered_gravity_measurement, FIR_FILTER_SIZE - 1);
241  VECT3_ADD(filtered_gravity_measurement, pseudo_gravity_measurement);
242  VECT3_SDIV(filtered_gravity_measurement, filtered_gravity_measurement, FIR_FILTER_SIZE);
243 
245  /* heuristic on acceleration (gravity estimate) norm */
246  /* Factor how strongly to change the weight.
247  * e.g. for gravity_heuristic_factor 30:
248  * <0.66G = 0, 1G = 1.0, >1.33G = 0
249  */
250 
251  const float g_meas_norm = float_vect3_norm(&filtered_gravity_measurement) / 9.81;
252  ahrs_fc.weight = 1.0 - ahrs_fc.gravity_heuristic_factor * fabs(1.0 - g_meas_norm) / 10.0;
253  Bound(ahrs_fc.weight, 0.15, 1.0);
254  } else {
255  ahrs_fc.weight = 1.0;
256  }
257 
258  /* Complementary filter proportional gain.
259  * Kp = 2 * zeta * omega * weight * ahrs_fc.accel_cnt
260  * with ahrs_fc.accel_cnt beeing the number of propagations since last update
261  */
262  const float gravity_rate_update_gain = -2 * ahrs_fc.accel_zeta * ahrs_fc.accel_omega *
263  ahrs_fc.weight * ahrs_fc.accel_cnt / 9.81;
264  RATES_ADD_SCALED_VECT(ahrs_fc.rate_correction, residual, gravity_rate_update_gain);
265 
266  // reset accel propagation counter
267  ahrs_fc.accel_cnt = 0;
268 
269  /* Complementary filter integral gain
270  * Correct the gyro bias.
271  * Ki = (omega*weight)^2 * dt
272  */
273  const float gravity_bias_update_gain = ahrs_fc.accel_omega * ahrs_fc.accel_omega *
274  ahrs_fc.weight * ahrs_fc.weight * dt / 9.81;
275  RATES_ADD_SCALED_VECT(ahrs_fc.gyro_bias, residual, gravity_bias_update_gain);
276 
277  /* FIXME: saturate bias */
278 }
279 
280 
281 void ahrs_fc_update_mag(struct Int32Vect3 *mag, float dt)
282 {
283 #if USE_MAGNETOMETER
284  // check if we had at least one propagation since last update
285  if (ahrs_fc.mag_cnt == 0) {
286  return;
287  }
288 #if AHRS_MAG_UPDATE_ALL_AXES
289  ahrs_fc_update_mag_full(mag, dt);
290 #else
291  ahrs_fc_update_mag_2d(mag, dt);
292 #endif
293  // reset mag propagation counter
294  ahrs_fc.mag_cnt = 0;
295 #endif
296 }
297 
298 void ahrs_fc_update_mag_full(struct Int32Vect3 *mag, float dt)
299 {
300 
301  struct FloatVect3 expected_imu;
303 
304  struct FloatVect3 measured_imu;
305  MAGS_FLOAT_OF_BFP(measured_imu, *mag);
306 
307  struct FloatVect3 residual_imu;
308  VECT3_CROSS_PRODUCT(residual_imu, measured_imu, expected_imu);
309  // DISPLAY_FLOAT_VECT3("# expected", expected_imu);
310  // DISPLAY_FLOAT_VECT3("# measured", measured_imu);
311  // DISPLAY_FLOAT_VECT3("# residual", residual);
312 
313  /* Complementary filter proportional gain.
314  * Kp = 2 * zeta * omega * weight * ahrs_fc.mag_cnt
315  * with ahrs_fc.mag_cnt beeing the number of propagations since last update
316  */
317 
318  const float mag_rate_update_gain = 2 * ahrs_fc.mag_zeta * ahrs_fc.mag_omega * ahrs_fc.mag_cnt;
319  RATES_ADD_SCALED_VECT(ahrs_fc.rate_correction, residual_imu, mag_rate_update_gain);
320 
321  /* Complementary filter integral gain
322  * Correct the gyro bias.
323  * Ki = (omega*weight)^2 * dt
324  */
325  const float mag_bias_update_gain = -(ahrs_fc.mag_omega * ahrs_fc.mag_omega) * dt;
326  RATES_ADD_SCALED_VECT(ahrs_fc.gyro_bias, residual_imu, mag_bias_update_gain);
327 
328 }
329 
330 void ahrs_fc_update_mag_2d(struct Int32Vect3 *mag, float dt)
331 {
332 
333  struct FloatVect2 expected_ltp;
334  VECT2_COPY(expected_ltp, ahrs_fc.mag_h);
335  // normalize expected ltp in 2D (x,y)
336  float_vect2_normalize(&expected_ltp);
337 
338  struct FloatVect3 measured_imu;
339  MAGS_FLOAT_OF_BFP(measured_imu, *mag);
340  struct FloatVect3 measured_ltp;
341  float_rmat_transp_vmult(&measured_ltp, &ahrs_fc.ltp_to_imu_rmat, &measured_imu);
342 
343  struct FloatVect2 measured_ltp_2d = {measured_ltp.x, measured_ltp.y};
344 
345  // normalize measured ltp in 2D (x,y)
346  float_vect2_normalize(&measured_ltp_2d);
347 
348  struct FloatVect3 residual_ltp = {
349  0,
350  0,
351  measured_ltp_2d.x *expected_ltp.y - measured_ltp_2d.y * expected_ltp.x
352  };
353 
354  // printf("res : %f\n", residual_ltp.z);
355 
356  struct FloatVect3 residual_imu;
357  float_rmat_vmult(&residual_imu, &ahrs_fc.ltp_to_imu_rmat, &residual_ltp);
358 
359 
360  /* Complementary filter proportional gain.
361  * Kp = 2 * zeta * omega * weight * ahrs_fc.mag_cnt
362  * with ahrs_fc.mag_cnt beeing the number of propagations since last update
363  */
364  const float mag_rate_update_gain = 2 * ahrs_fc.mag_zeta * ahrs_fc.mag_omega * ahrs_fc.mag_cnt;
365  RATES_ADD_SCALED_VECT(ahrs_fc.rate_correction, residual_imu, mag_rate_update_gain);
366 
367  /* Complementary filter integral gain
368  * Correct the gyro bias.
369  * Ki = (omega*weight)^2 * dt
370  */
371  const float mag_bias_update_gain = -(ahrs_fc.mag_omega * ahrs_fc.mag_omega) * dt;
372  RATES_ADD_SCALED_VECT(ahrs_fc.gyro_bias, residual_imu, mag_bias_update_gain);
373 }
374 
375 
377 {
378 
379  /* project mag on local tangeant plane */
380  struct FloatEulers ltp_to_imu_euler;
381  float_eulers_of_rmat(&ltp_to_imu_euler, &ahrs_fc.ltp_to_imu_rmat);
382  struct FloatVect3 magf;
383  MAGS_FLOAT_OF_BFP(magf, *mag);
384  const float cphi = cosf(ltp_to_imu_euler.phi);
385  const float sphi = sinf(ltp_to_imu_euler.phi);
386  const float ctheta = cosf(ltp_to_imu_euler.theta);
387  const float stheta = sinf(ltp_to_imu_euler.theta);
388  const float mn = ctheta * magf.x + sphi * stheta * magf.y + cphi * stheta * magf.z;
389  const float me = 0. * magf.x + cphi * magf.y - sphi * magf.z;
390 
391  const float res_norm = -RMAT_ELMT(ahrs_fc.ltp_to_imu_rmat, 0, 0) * me +
392  RMAT_ELMT(ahrs_fc.ltp_to_imu_rmat, 1, 0) * mn;
393  const struct FloatVect3 r2 = {RMAT_ELMT(ahrs_fc.ltp_to_imu_rmat, 2, 0),
396  };
397  const float mag_rate_update_gain = 2.5;
398  RATES_ADD_SCALED_VECT(ahrs_fc.rate_correction, r2, (mag_rate_update_gain * res_norm));
399  const float mag_bias_update_gain = -2.5e-4;
400  RATES_ADD_SCALED_VECT(ahrs_fc.gyro_bias, r2, (mag_bias_update_gain * res_norm));
401 
402 }
403 
404 void ahrs_fc_update_gps(struct GpsState *gps_s __attribute__((unused)))
405 {
406 #if AHRS_GRAVITY_UPDATE_COORDINATED_TURN && USE_GPS
407  if (gps_s->fix >= GPS_FIX_3D) {
408  ahrs_fc.ltp_vel_norm = gps_s->speed_3d / 100.;
410  } else {
412  }
413 #endif
414 
415 #if AHRS_USE_GPS_HEADING && USE_GPS
416  //got a 3d fix, ground speed > 0.5 m/s and course accuracy is better than 10deg
417  if (gps_s->fix >= GPS_FIX_3D && gps_s->gspeed >= 500 &&
418  gps_s->cacc <= RadOfDeg(10 * 1e7)) {
419 
420  // gps_s->course is in rad * 1e7, we need it in rad
421  float course = gps_s->course / 1e7;
422 
423  if (ahrs_fc.heading_aligned) {
424  /* the assumption here is that there is no side-slip, so heading=course */
425  ahrs_fc_update_heading(course);
426  } else {
427  /* hard reset the heading if this is the first measurement */
428  ahrs_fc_realign_heading(course);
429  }
430  }
431 #endif
432 }
433 
434 
436 {
437 
438  FLOAT_ANGLE_NORMALIZE(heading);
439 
441  struct FloatRMat *ltp_to_body_rmat = orientationGetRMat_f(&ahrs_fc.ltp_to_body);
442 
443  // row 0 of ltp_to_body_rmat = body x-axis in ltp frame
444  // we only consider x and y
445  struct FloatVect2 expected_ltp = {
446  RMAT_ELMT(*ltp_to_body_rmat, 0, 0),
447  RMAT_ELMT(*ltp_to_body_rmat, 0, 1)
448  };
449 
450  // expected_heading cross measured_heading
451  struct FloatVect3 residual_ltp = {
452  0,
453  0,
454  expected_ltp.x * sinf(heading) - expected_ltp.y * cosf(heading)
455  };
456 
457  struct FloatVect3 residual_imu;
458  float_rmat_vmult(&residual_imu, &ahrs_fc.ltp_to_imu_rmat, &residual_ltp);
459 
460  const float heading_rate_update_gain = 2.5;
461  RATES_ADD_SCALED_VECT(ahrs_fc.rate_correction, residual_imu, heading_rate_update_gain);
462 
463  float heading_bias_update_gain;
464  /* crude attempt to only update bias if deviation is small
465  * e.g. needed when you only have gps providing heading
466  * and the inital heading is totally different from
467  * the gps course information you get once you have a gps fix.
468  * Otherwise the bias will be falsely "corrected".
469  */
470  if (fabs(residual_ltp.z) < sinf(RadOfDeg(5.))) {
471  heading_bias_update_gain = -2.5e-4;
472  } else {
473  heading_bias_update_gain = 0.0;
474  }
475  RATES_ADD_SCALED_VECT(ahrs_fc.gyro_bias, residual_imu, heading_bias_update_gain);
476 }
477 
478 
480 {
481  FLOAT_ANGLE_NORMALIZE(heading);
482 
483  /* quaternion representing only the heading rotation from ltp to body */
484  struct FloatQuat q_h_new;
485  q_h_new.qx = 0.0;
486  q_h_new.qy = 0.0;
487  q_h_new.qz = sinf(heading / 2.0);
488  q_h_new.qi = cosf(heading / 2.0);
489 
491  struct FloatQuat *ltp_to_body_quat = orientationGetQuat_f(&ahrs_fc.ltp_to_body);
492 
493  /* quaternion representing current heading only */
494  struct FloatQuat q_h = *ltp_to_body_quat;
495  q_h.qx = 0.;
496  q_h.qy = 0.;
497  float_quat_normalize(&q_h);
498 
499  /* quaternion representing rotation from current to new heading */
500  struct FloatQuat q_c;
501  float_quat_inv_comp_norm_shortest(&q_c, &q_h, &q_h_new);
502 
503  /* correct current heading in body frame */
504  struct FloatQuat q;
505  float_quat_comp_norm_shortest(&q, &q_c, ltp_to_body_quat);
506 
507  /* compute ltp to imu rotation quaternion and matrix */
508  struct FloatQuat *body_to_imu_quat = orientationGetQuat_f(&ahrs_fc.body_to_imu);
509  float_quat_comp(&ahrs_fc.ltp_to_imu_quat, &q, body_to_imu_quat);
511 
513 }
514 
516 {
518 }
519 
521 {
523 
524  if (!ahrs_fc.is_aligned) {
525  /* Set ltp_to_imu so that body is zero */
528  }
529 }
530 
532 {
533  struct FloatQuat *body_to_imu_quat = orientationGetQuat_f(&ahrs_fc.body_to_imu);
534  struct FloatQuat ltp_to_body_quat;
535  float_quat_comp_inv(&ltp_to_body_quat, &ahrs_fc.ltp_to_imu_quat, body_to_imu_quat);
536  orientationSetQuat_f(&ahrs_fc.ltp_to_body, &ltp_to_body_quat);
537 }
#define VECT3_CROSS_PRODUCT(_vo, _v1, _v2)
Definition: pprz_algebra.h:243
void ahrs_fc_set_body_to_imu(struct OrientationReps *body_to_imu)
#define FLOAT_ANGLE_NORMALIZE(_a)
void float_quat_comp_inv(struct FloatQuat *a2b, struct FloatQuat *a2c, struct FloatQuat *b2c)
Composition (multiplication) of two quaternions.
angular rates
static void orientationSetQuat_f(struct OrientationReps *orientation, struct FloatQuat *quat)
Set vehicle body attitude from quaternion (float).
#define VECT3_ADD(_a, _b)
Definition: pprz_algebra.h:146
uint16_t mag_cnt
number of propagations since last mag update
float accel_omega
filter cut-off frequency for correcting the attitude from accels (pseudo-gravity measurement) ...
bool_t ltp_vel_norm_valid
Simple matrix helper macros.
float phi
in radians
struct FloatRates gyro_bias
static void orientationSetIdentity(struct OrientationReps *orientation)
Set to identity orientation.
#define AHRS_MAG_OMEGA
#define AHRS_MAG_ZETA
void ahrs_fc_update_mag_2d_dumb(struct Int32Vect3 *mag)
struct FloatRMat ltp_to_imu_rmat
void float_quat_comp(struct FloatQuat *a2c, struct FloatQuat *a2b, struct FloatQuat *b2c)
Composition (multiplication) of two quaternions.
void float_eulers_of_rmat(struct FloatEulers *e, struct FloatRMat *rm)
static void float_quat_identity(struct FloatQuat *q)
initialises a quaternion to identity
#define VECT3_COPY(_a, _b)
Definition: pprz_algebra.h:139
static struct FloatRMat * orientationGetRMat_f(struct OrientationReps *orientation)
Get vehicle body attitude rotation matrix (float).
#define VECT3_DIFF(_c, _a, _b)
Definition: pprz_algebra.h:181
#define VECT3_ASSIGN(_a, _x, _y, _z)
Definition: pprz_algebra.h:124
static void float_vect2_normalize(struct FloatVect2 *v)
normalize 2D vector in place
Utility functions for floating point AHRS implementations.
#define FLOAT_RATES_ZERO(_r)
#define VECT2_COPY(_a, _b)
Definition: pprz_algebra.h:67
void ahrs_fc_update_heading(float heading)
Update yaw based on a heading measurement.
#define RATES_SUB(_a, _b)
Definition: pprz_algebra.h:350
#define GPS_FIX_3D
3D GPS fix
Definition: gps.h:43
#define AHRS_GRAVITY_HEURISTIC_FACTOR
by default use the gravity heuristic to reduce gain
void ahrs_fc_init(void)
#define FALSE
Definition: std.h:5
struct FloatQuat ltp_to_imu_quat
euler angles
Roation quaternion.
void float_rmat_integrate_fi(struct FloatRMat *rm, struct FloatRates *omega, float dt)
in place first order integration of a rotation matrix
static float float_vect3_norm(struct FloatVect3 *v)
float theta
in radians
uint8_t gravity_heuristic_factor
sets how strongly the gravity heuristic reduces accel correction.
#define TRUE
Definition: std.h:4
void float_rmat_vmult(struct FloatVect3 *vb, struct FloatRMat *m_a2b, struct FloatVect3 *va)
rotate 3D vector by rotation matrix.
bool_t ahrs_fc_align(struct Int32Rates *lp_gyro, struct Int32Vect3 *lp_accel, struct Int32Vect3 *lp_mag)
static float heading
Definition: ahrs_infrared.c:45
void float_rmat_transp_vmult(struct FloatVect3 *vb, struct FloatRMat *m_b2a, struct FloatVect3 *va)
rotate 3D vector by transposed rotation matrix.
#define FLOAT_RATES_LIN_CMB(_ro, _r1, _s1, _r2, _s2)
#define RATES_FLOAT_OF_BFP(_rf, _ri)
Definition: pprz_algebra.h:692
Paparazzi floating point algebra.
data structure for GPS information
Definition: gps.h:67
void float_rmat_of_quat(struct FloatRMat *rm, struct FloatQuat *q)
Device independent GPS code (interface)
void float_quat_integrate(struct FloatQuat *q, struct FloatRates *omega, float dt)
in place quaternion integration with constant rotational velocity
#define RATES_SUM(_c, _a, _b)
Definition: pprz_algebra.h:357
#define VECT3_SDIV(_vo, _vi, _s)
Definition: pprz_algebra.h:195
#define RATES_ADD_SCALED_VECT(_ro, _v, _s)
Definition: pprz_algebra.h:418
static void ahrs_float_get_quat_from_accel_mag(struct FloatQuat *q, struct Int32Vect3 *accel, struct Int32Vect3 *mag)
static void float_quat_normalize(struct FloatQuat *q)
float mag_omega
filter cut-off frequency for correcting the attitude (heading) from magnetometer
void float_quat_of_rmat(struct FloatQuat *q, struct FloatRMat *rm)
Quaternion from rotation matrix.
bool_t correct_gravity
enable gravity correction during coordinated turns
void ahrs_fc_update_mag(struct Int32Vect3 *mag, float dt)
float accel_zeta
filter damping for correcting the gyro-bias from accels (pseudo-gravity measurement) ...
bool_t heading_aligned
#define AHRS_ACCEL_OMEGA
struct FloatVect3 mag_h
void ahrs_fc_set_body_to_imu_quat(struct FloatQuat *q_b2i)
#define ACCELS_FLOAT_OF_BFP(_ef, _ei)
Definition: pprz_algebra.h:728
void ahrs_fc_realign_heading(float heading)
Hard reset yaw to a heading.
float float_rmat_reorthogonalize(struct FloatRMat *rm)
void ahrs_fc_update_mag_full(struct Int32Vect3 *mag, float dt)
static void ahrs_float_get_quat_from_accel(struct FloatQuat *q, struct Int32Vect3 *accel)
Compute a quaternion representing roll and pitch from an accelerometer measurement.
#define VECT3_SMUL(_vo, _vi, _s)
Definition: pprz_algebra.h:188
void float_rmat_transp_ratemult(struct FloatRates *rb, struct FloatRMat *m_b2a, struct FloatRates *ra)
rotate anglular rates by transposed rotation matrix.
struct FloatRates imu_rate
#define FIR_FILTER_SIZE
#define RMAT_ELMT(_rm, _row, _col)
Definition: pprz_algebra.h:593
void float_quat_comp_norm_shortest(struct FloatQuat *a2c, struct FloatQuat *a2b, struct FloatQuat *b2c)
Composition (multiplication) of two quaternions with normalization.
void ahrs_fc_update_gps(struct GpsState *gps_s)
void float_quat_inv_comp_norm_shortest(struct FloatQuat *b2c, struct FloatQuat *a2b, struct FloatQuat *a2c)
Composition (multiplication) of two quaternions with normalization.
Complementary filter in float to estimate the attitude, heading and gyro bias.
struct OrientationReps body_to_imu
void ahrs_fc_recompute_ltp_to_body(void)
rotation matrix
void ahrs_fc_update_accel(struct Int32Vect3 *accel, float dt)
void ahrs_fc_update_mag_2d(struct Int32Vect3 *mag, float dt)
#define MAGS_FLOAT_OF_BFP(_ef, _ei)
Definition: pprz_algebra.h:740
uint16_t accel_cnt
number of propagations since last accel update
float ltp_vel_norm
velocity norm for gravity correction during coordinated turns
static struct OrientationReps body_to_imu
Definition: ins_alt_float.c:77
#define RATES_COPY(_a, _b)
Definition: pprz_algebra.h:336
struct FloatRates rate_correction
enum AhrsFCStatus status
void ahrs_fc_propagate(struct Int32Rates *gyro, float dt)
float mag_zeta
filter damping for correcting the gyro bias from magnetometer
#define AHRS_ACCEL_ZETA
struct AhrsFloatCmpl ahrs_fc
angular rates
static struct FloatQuat * orientationGetQuat_f(struct OrientationReps *orientation)
Get vehicle body attitude quaternion (float).
Paparazzi fixed point algebra.
struct OrientationReps ltp_to_body
#define VECT3_RATES_CROSS_VECT3(_vo, _r1, _v2)
Definition: pprz_algebra.h:253