MotionFX Software Library: algorithms/Middlewares/ST/STM32_MotionFX_Library/Inc/motion_fx.h Source File

Motion FX

MotionFX Software Library
MotionFX Software Library Documentation
motion_fx.h
Go to the documentation of this file.
1 
38 /* Define to prevent recursive inclusion -------------------------------------*/
39 #ifndef _MOTION_FX_H_
40 #define _MOTION_FX_H_
41 
42 #ifdef __cplusplus
43 extern "C" {
44 #endif
45 
46 /* Includes ------------------------------------------------------------------*/
47 #include <stdint.h>
48 
61 /* Exported constants --------------------------------------------------------*/
62 #define MFX_NUM_AXES 3
63 #define MFX_QNUM_AXES 4
64 
65 /* Exported types ------------------------------------------------------------*/
66 typedef enum
67 {
71 
72 typedef enum
73 {
77 
78 typedef struct
79 {
80  float ATime; /* merge rate to the accel */
81  float MTime; /* merge rate to the mag */
82  float FrTime; /* merge rate to the accel when external accelerations occours */
83  unsigned char LMode; /* gyro bias learn mode: 1-static learning, 2-dynamic learning */
84  float gbias_mag_th_sc_6X; /* 6 axes scaler for the gyro bias mag threshold nominal */
85  float gbias_acc_th_sc_6X; /* 6 axes scaler for the gyro bias acc threshold nominal */
86  float gbias_gyro_th_sc_6X; /* 6 axes scaler for the gyro bias gyro threshold nominal */
87  float gbias_mag_th_sc_9X; /* 9 axes scaler for the gyro bias mag threshold nominal */
88  float gbias_acc_th_sc_9X; /* 9 axes scaler for the gyro bias acc threshold nominal */
89  float gbias_gyro_th_sc_9X; /* 9 axes scaler for the gyro bias gyro threshold nominal */
90  unsigned char modx; /* setting to indicate the decimation, set to 1 in smartphone/tablet, set to >=1 in embedded solutions */
91  char acc_orientation[MFX_QNUM_AXES]; /* accelerometer data orientation */
92  char gyro_orientation[MFX_QNUM_AXES]; /* gyroscope data orientation */
93  char mag_orientation[MFX_QNUM_AXES]; /* magnetometer data orientation */
94  MFX_engine_output_ref_sys output_type; /* 0: NED, 1: ENU */
96 } MFX_knobs_t;
97 
98 typedef struct
99 {
100  float mag[MFX_NUM_AXES]; /* Calibrated mag [uT]/50 */
101  float acc[MFX_NUM_AXES]; /* Acceleration in [g] */
102  float gyro[MFX_NUM_AXES]; /* Angular rate [dps] */
103 } MFX_input_t;
104 
105 typedef struct
106 {
107  float rotation_9X[MFX_NUM_AXES]; /* 9 axes yaw, pitch and roll */
108  float quaternion_9X[MFX_QNUM_AXES]; /* 9 axes quaternion */
109  float gravity_9X[MFX_NUM_AXES]; /* 9 axes device frame gravity */
110  float linear_acceleration_9X[MFX_NUM_AXES]; /* 9 axes device frame linear acceleration */
111  float heading_9X; /* 9 axes heading */
112  float rotation_6X[MFX_NUM_AXES]; /* 6 axes yaw, pitch and roll */
113  float quaternion_6X[MFX_QNUM_AXES]; /* 6 axes quaternion */
114  float gravity_6X[MFX_NUM_AXES]; /* 6 axes device frame gravity */
115  float linear_acceleration_6X[MFX_NUM_AXES]; /* 6 axes device frame linear acceleration */
116  float heading_6X; /* 6 axes heading */
117 } MFX_output_t;
118 
119 typedef enum
120 {
126 
127 typedef struct {
128  float mag[MFX_NUM_AXES]; /* Uncalibrated mag [uT]/50 */
129  int time_stamp; /* Timestamp [ms] */
131 
132 typedef struct {
133  float hi_bias[3]; /* Hard iron offset array [uT]/50 */
134  MFX_MagCal_quality_t cal_quality; /* Calibration quality factor */
136 
141 /* Exported variables --------------------------------------------------------*/
142 /* Exported macro ------------------------------------------------------------*/
143 
148 /* Exported functions ------------------------------------------------------- */
149 
155 void MotionFX_initialize(void);
156 
162 void MotionFX_setKnobs(MFX_knobs_t *knobs);
163 
169 void MotionFX_getKnobs(MFX_knobs_t *knobs);
170 
176 
182 
189 
196 
202 void MotionFX_setGbias(float *gbias);
203 
209 void MotionFX_getGbias(float *gbias);
210 
219 void MotionFX_update(MFX_output_t *data_out, MFX_input_t *data_in, float eml_deltatime, float *eml_q_update);
220 
228 void MotionFX_propagate(MFX_output_t *data_out, MFX_input_t *data_in, float eml_deltatime);
229 
236 void MotionFX_MagCal_init(int sampletime, unsigned short int enable);
237 
244 
251 
257 uint8_t MotionFX_GetLibVersion(char *version);
258 
271 #ifdef __cplusplus
272 }
273 #endif
274 
275 #endif /* _MOTION_FX_H_ */
276 
277 /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
void MotionFX_propagate(MFX_output_t *data_out, MFX_input_t *data_in, float eml_deltatime)
Run the Kalman filter propagate.
void MotionFX_setKnobs(MFX_knobs_t *knobs)
Set the internal knobs.
void MotionFX_MagCal_init(int sampletime, unsigned short int enable)
Initialize the compass calibration library.
unsigned char modx
Definition: motion_fx.h:90
void MotionFX_MagCal_getParams(MFX_MagCal_output_t *data_out)
Get magnetic calibration parameters.
float gbias_gyro_th_sc_9X
Definition: motion_fx.h:89
void MotionFX_getGbias(float *gbias)
Get the initial gbias.
MFX_engine_state_t MotionFX_getStatus_6X(void)
Get the status of the 6 axes library.
float heading_9X
Definition: motion_fx.h:111
void MotionFX_enable_6X(MFX_engine_state_t enable)
Enable or disable the 6 axes function (ACC + GYRO)
int start_automatic_gbias_calculation
Definition: motion_fx.h:95
float heading_6X
Definition: motion_fx.h:116
MFX_engine_output_ref_sys
Definition: motion_fx.h:72
float MTime
Definition: motion_fx.h:81
void MotionFX_getKnobs(MFX_knobs_t *knobs)
Get the current internal knobs.
float gbias_mag_th_sc_6X
Definition: motion_fx.h:84
#define MFX_QNUM_AXES
Definition: motion_fx.h:63
uint8_t MotionFX_GetLibVersion(char *version)
Get the library version.
unsigned char LMode
Definition: motion_fx.h:83
float gbias_acc_th_sc_6X
Definition: motion_fx.h:85
MFX_engine_output_ref_sys output_type
Definition: motion_fx.h:94
float gbias_mag_th_sc_9X
Definition: motion_fx.h:87
MFX_MagCal_quality_t
Definition: motion_fx.h:119
#define MFX_NUM_AXES
Definition: motion_fx.h:62
MFX_MagCal_quality_t cal_quality
Definition: motion_fx.h:134
MFX_engine_state_t
Definition: motion_fx.h:66
float ATime
Definition: motion_fx.h:80
void MotionFX_initialize(void)
Initialize the MotionFX engine.
void MotionFX_enable_9X(MFX_engine_state_t enable)
Enable or disable the 9 axes function (ACC + GYRO + MAG)
float gbias_gyro_th_sc_6X
Definition: motion_fx.h:86
float FrTime
Definition: motion_fx.h:82
float gbias_acc_th_sc_9X
Definition: motion_fx.h:88
void MotionFX_update(MFX_output_t *data_out, MFX_input_t *data_in, float eml_deltatime, float *eml_q_update)
Run the Kalman filter update.
void MotionFX_MagCal_run(MFX_MagCal_input_t *data_in)
Run magnetic calibration algorithm.
MFX_engine_state_t MotionFX_getStatus_9X(void)
Get the status of the 9 axes library.
void MotionFX_setGbias(float *gbias)
Set the initial gbias.
Generated on Fri May 12 2017 11:19:25 for MotionFX Software Library by   doxygen 1.8.9.1