AHRS
Dependencies: Eigen
AHRS.h@11:b010622c0748, 2019-08-19 (annotated)
- Committer:
- altb2
- Date:
- Mon Aug 19 14:16:31 2019 +0000
- Revision:
- 11:b010622c0748
- Parent:
- 10:fd4e2436b311
- Child:
- 17:f9eed26536d9
minor changes
Who changed what in which revision?
User | Revision | Line number | New contents of line |
---|---|---|---|
altb | 3:6811c0ce95f6 | 1 | #include "Mahony.h" |
altb | 3:6811c0ce95f6 | 2 | #include "MadgwickAHRS.h" |
altb | 3:6811c0ce95f6 | 3 | #include "LinearCharacteristics.h" |
altb2 | 4:3c21fb0c9e84 | 4 | #include "LSM9DS1_i2c.h" |
altb | 3:6811c0ce95f6 | 5 | #include "Signal.h" |
altb2 | 4:3c21fb0c9e84 | 6 | #include "ekf.h" |
altb2 | 4:3c21fb0c9e84 | 7 | #include "matrix.h" |
altb2 | 6:5824bd96b6cf | 8 | #include "data_logger.h" |
altb2 | 4:3c21fb0c9e84 | 9 | |
altb2 | 6:5824bd96b6cf | 10 | extern data_logger my_logger; |
altb | 3:6811c0ce95f6 | 11 | |
altb | 3:6811c0ce95f6 | 12 | class AHRS{ |
altb | 3:6811c0ce95f6 | 13 | public: |
altb2 | 9:644266463f5f | 14 | AHRS(uint8_t,float,bool); |
altb | 3:6811c0ce95f6 | 15 | virtual ~AHRS(); |
altb | 3:6811c0ce95f6 | 16 | |
altb2 | 8:51062bb877f0 | 17 | float getRoll(uint8_t ft) { |
altb2 | 8:51062bb877f0 | 18 | if(ft ==1) |
altb2 | 8:51062bb877f0 | 19 | return RPY_filter.get_est_state(0); |
altb2 | 8:51062bb877f0 | 20 | else |
altb2 | 8:51062bb877f0 | 21 | return Mahony_filter.getRollRadians(); |
altb | 3:6811c0ce95f6 | 22 | } |
altb2 | 8:51062bb877f0 | 23 | float getPitch(uint8_t ft) { |
altb2 | 8:51062bb877f0 | 24 | if(ft ==1) |
altb2 | 8:51062bb877f0 | 25 | return RPY_filter.get_est_state(1); |
altb2 | 8:51062bb877f0 | 26 | else |
altb2 | 8:51062bb877f0 | 27 | return Mahony_filter.getPitchRadians(); |
altb | 3:6811c0ce95f6 | 28 | } |
altb2 | 4:3c21fb0c9e84 | 29 | float getYaw() { |
altb2 | 6:5824bd96b6cf | 30 | return 0.0; |
altb | 3:6811c0ce95f6 | 31 | } |
altb | 3:6811c0ce95f6 | 32 | LSM9DS1 imu; |
altb2 | 8:51062bb877f0 | 33 | Mahony Mahony_filter; |
altb2 | 4:3c21fb0c9e84 | 34 | ekf RPY_filter; |
altb | 3:6811c0ce95f6 | 35 | LinearCharacteristics raw_gx2gx; |
altb | 3:6811c0ce95f6 | 36 | LinearCharacteristics raw_gy2gy; |
altb | 3:6811c0ce95f6 | 37 | LinearCharacteristics raw_gz2gz; |
altb2 | 4:3c21fb0c9e84 | 38 | LinearCharacteristics raw_ax2ax; |
altb2 | 4:3c21fb0c9e84 | 39 | LinearCharacteristics raw_ay2ay; |
altb2 | 4:3c21fb0c9e84 | 40 | LinearCharacteristics raw_az2az; |
altb2 | 4:3c21fb0c9e84 | 41 | LinearCharacteristics int2magx; |
altb2 | 4:3c21fb0c9e84 | 42 | LinearCharacteristics int2magy; |
altb2 | 4:3c21fb0c9e84 | 43 | LinearCharacteristics int2magz; |
altb2 | 9:644266463f5f | 44 | float xyzUS[3]; |
altb2 | 10:fd4e2436b311 | 45 | float xyzAS[3]; |
altb2 | 9:644266463f5f | 46 | float rxryrzUS[3]; |
altb2 | 10:fd4e2436b311 | 47 | float v_xyzOF[2]; |
altb2 | 10:fd4e2436b311 | 48 | float xyzOF[3]; |
altb2 | 11:b010622c0748 | 49 | float xyzLIDAR[3]; |
altb | 3:6811c0ce95f6 | 50 | private: |
altb | 3:6811c0ce95f6 | 51 | Signal signal; |
altb | 3:6811c0ce95f6 | 52 | Thread thread; |
altb | 3:6811c0ce95f6 | 53 | Ticker ticker; |
altb | 3:6811c0ce95f6 | 54 | Mutex mutex; // mutex to lock critical sections |
altb | 3:6811c0ce95f6 | 55 | void sendSignal(); |
altb2 | 7:bfde7bd5fe31 | 56 | float local_time; |
altb | 3:6811c0ce95f6 | 57 | void update(); |
altb2 | 4:3c21fb0c9e84 | 58 | matrix measurement; |
altb2 | 4:3c21fb0c9e84 | 59 | //SPI spi; % old board with spi |
altb2 | 4:3c21fb0c9e84 | 60 | |
altb2 | 4:3c21fb0c9e84 | 61 | // PinName csAG; // for spi |
altb2 | 4:3c21fb0c9e84 | 62 | // PinName csM; // " |
altb | 3:6811c0ce95f6 | 63 | }; |