Zephyr Scientific Library (zscilib)
calibration.h
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2021 Marti Riba Pons
3  *
4  * SPDX-License-Identifier: Apache-2.0
5  */
6 
21 #ifndef ZEPHYR_INCLUDE_ZSL_FUSION_CALIBRATION_H_
22 #define ZEPHYR_INCLUDE_ZSL_FUSION_CALIBRATION_H_
23 
24 #include <zsl/zsl.h>
25 #include <zsl/vectors.h>
26 #include <zsl/matrices.h>
28 #include <zsl/orientation/ahrs.h>
29 #include <zsl/statistics.h>
30 
31 #ifdef __cplusplus
32 extern "C" {
33 #endif
34 
45 int zsl_fus_cal_rot_mtx(struct zsl_vec *v, struct zsl_mtx *m,
46  struct zsl_vec *v_rot);
47 
59 int zsl_fus_cal_rot_axis_angle(struct zsl_vec *v, struct zsl_vec *a,
60  zsl_real_t *b, struct zsl_vec *v_rot);
61 
62 #ifndef CONFIG_ZSL_SINGLE_PRECISION
63 
82 int zsl_fus_cal_magn(struct zsl_mtx *m, zsl_real_t *l, zsl_real_t *mu,
83  struct zsl_mtx *K, struct zsl_vec *b);
84 #endif
85 
86 #ifndef CONFIG_ZSL_SINGLE_PRECISION
87 
121 int zsl_fus_cal_magn_fast(struct zsl_mtx *m, zsl_real_t *me, struct zsl_mtx *K,
122  struct zsl_vec *b);
123 #endif
124 
137  zsl_real_t *d_out);
138 
151 int zsl_fus_cal_corr_vec(struct zsl_vec *v, struct zsl_mtx *K,
152  struct zsl_vec *b, struct zsl_vec *v_out);
153 
171 int zsl_fus_cal_madg(struct zsl_mtx *g, struct zsl_mtx *a,
172  struct zsl_mtx *m, zsl_real_t sampleFreq, zsl_real_t *incl,
173  zsl_real_t *beta);
174 
193 int zsl_fus_cal_mahn(struct zsl_mtx *g, struct zsl_mtx *a,
194  struct zsl_mtx *m, zsl_real_t sampleFreq, zsl_real_t *incl,
195  zsl_real_t *kp);
196 
197 #ifdef __cplusplus
198 }
199 #endif
200 
201 #endif /* ZEPHYR_INCLUDE_ZSL_FUSION_CALIBRATION_H_ */
202  /* End of calibration group */
zsl_fus_cal_rot_axis_angle
int zsl_fus_cal_rot_axis_angle(struct zsl_vec *v, struct zsl_vec *a, zsl_real_t *b, struct zsl_vec *v_rot)
Rotates accel/mag/gyro data using a given axis and angle.
zsl_mtx
Represents a m x n matrix, with data stored in row-major order.
Definition: matrices.h:46
zsl_fus_cal_mahn
int zsl_fus_cal_mahn(struct zsl_mtx *g, struct zsl_mtx *a, struct zsl_mtx *m, zsl_real_t sampleFreq, zsl_real_t *incl, zsl_real_t *kp)
Calculates the optimal value of the variable kp in the Mahony filter, given a set of magnetometer,...
statistics.h
API header file for statistics in zscilib.
zsl_fus_cal_magn_fast
int zsl_fus_cal_magn_fast(struct zsl_mtx *m, zsl_real_t *me, struct zsl_mtx *K, struct zsl_vec *b)
This function calculates the soft iron ('K') and the hard iron ('b') errors in the magnetometer data,...
zsl_fus_cal_madg
int zsl_fus_cal_madg(struct zsl_mtx *g, struct zsl_mtx *a, struct zsl_mtx *m, zsl_real_t sampleFreq, zsl_real_t *incl, zsl_real_t *beta)
Calculates the optimal value of the variable beta in the Madgwick filter, given a set of magnetometer...
quaternions.h
API header file for quaternions in zscilib.
zsl_fus_cal_corr_vec
int zsl_fus_cal_corr_vec(struct zsl_vec *v, struct zsl_mtx *K, struct zsl_vec *b, struct zsl_vec *v_out)
Corrects the supplied vector data by adding a vector the same size ('b') and then multiplying by a ma...
vectors.h
API header file for vectors in zscilib.
zsl_fus_cal_corr_scalar
int zsl_fus_cal_corr_scalar(zsl_real_t *d, zsl_real_t *k, zsl_real_t *b, zsl_real_t *d_out)
Corrects the supplied scalar number by adding another number ('b') and multiplying the sum by a scala...
ahrs.h
API header file for attitude and AHRS in zscilib.
zsl_fus_cal_rot_mtx
int zsl_fus_cal_rot_mtx(struct zsl_vec *v, struct zsl_mtx *m, struct zsl_vec *v_rot)
Rotates accel/mag/gyro data using a given rotation matrix.
matrices.h
API header file for matrices in zscilib.
zsl.h
API header file for zscilib.
zsl_fus_cal_magn
int zsl_fus_cal_magn(struct zsl_mtx *m, zsl_real_t *l, zsl_real_t *mu, struct zsl_mtx *K, struct zsl_vec *b)
This function calculates the soft iron ('K') and the hard iron ('b') errors in the magnetometer data,...
zsl_vec
Represents a vector.
Definition: vectors.h:40
zsl_real_t
double zsl_real_t
Definition: zsl.h:51