AHRS
Dependencies: Eigen
AHRS.cpp@5:eee47600b772, 2019-05-03 (annotated)
- Committer:
- altb2
- Date:
- Fri May 03 14:43:47 2019 +0000
- Revision:
- 5:eee47600b772
- Parent:
- 4:3c21fb0c9e84
- Child:
- 6:5824bd96b6cf
EKF running
Who changed what in which revision?
User | Revision | Line number | New contents of line |
---|---|---|---|
altb | 3:6811c0ce95f6 | 1 | #include "AHRS.h" |
altb | 3:6811c0ce95f6 | 2 | #include "Mahony.h" |
altb | 3:6811c0ce95f6 | 3 | #include "MadgwickAHRS.h" |
altb2 | 4:3c21fb0c9e84 | 4 | #include "ekf.h" |
altb2 | 4:3c21fb0c9e84 | 5 | |
altb | 3:6811c0ce95f6 | 6 | #define PI 3.141592653589793 |
altb | 3:6811c0ce95f6 | 7 | |
altb | 3:6811c0ce95f6 | 8 | using namespace std; |
altb | 3:6811c0ce95f6 | 9 | |
altb2 | 4:3c21fb0c9e84 | 10 | //OLD: AHRS::AHRS(uint8_t filtertype,float TS) : RPY_filter(TS), csAG(PA_15),csM(PD_2), spi(PC_12, PC_11, PC_10), imu(&spi, &csM, &csAG), thread(osPriorityBelowNormal, 4096){ |
altb2 | 4:3c21fb0c9e84 | 11 | AHRS::AHRS(uint8_t filtertype,float TS) : imu(PC_9, PA_8, 0xD6, 0x3C), RPY_filter(TS), thread(osPriorityBelowNormal, 4096){ |
altb2 | 4:3c21fb0c9e84 | 12 | |
altb | 3:6811c0ce95f6 | 13 | thread.start(callback(this, &AHRS::update)); |
altb | 3:6811c0ce95f6 | 14 | ticker.attach(callback(this, &AHRS::sendSignal), TS); |
altb2 | 4:3c21fb0c9e84 | 15 | /* LinearCharacteristics raw_ax2ax(40.0/65536.0,-418.0); // use gain and offset here |
altb | 3:6811c0ce95f6 | 16 | LinearCharacteristics raw_ay2ay(-40.0/65536.0,-307.0); // y-axis reversed |
altb | 3:6811c0ce95f6 | 17 | LinearCharacteristics raw_az2az(-16350.0,16350,-10.0, 10.0); |
altb | 3:6811c0ce95f6 | 18 | LinearCharacteristics raw_gx2gx(-32767,32768,-500*PI/180.0, 500*PI/180.0); |
altb | 3:6811c0ce95f6 | 19 | LinearCharacteristics raw_gy2gy(-32767,32768, 500*PI/180.0,-500*PI/180.0); // y-axis reversed (lefthanded system) |
altb | 3:6811c0ce95f6 | 20 | LinearCharacteristics raw_gz2gz(-32767,32768,-500*PI/180.0, 500*PI/180.0); |
altb | 3:6811c0ce95f6 | 21 | LinearCharacteristics int2magx( -32767,32768,100.0,-100.0); // x-axis reversed |
altb2 | 4:3c21fb0c9e84 | 22 | LinearCharacteristics int2magy( -32767,32768,100.0,-100.0); // y-axis reversed*/ |
altb2 | 4:3c21fb0c9e84 | 23 | LinearCharacteristics raw_ax2ax( 1.0,0.0); // use gain and offset here |
altb2 | 4:3c21fb0c9e84 | 24 | LinearCharacteristics raw_ay2ay(-1.0,0.0); // y-axis reversed |
altb2 | 4:3c21fb0c9e84 | 25 | LinearCharacteristics raw_az2az( 1.0,0.0); |
altb2 | 4:3c21fb0c9e84 | 26 | LinearCharacteristics raw_gx2gx( 1.0,0.0); |
altb2 | 4:3c21fb0c9e84 | 27 | LinearCharacteristics raw_gy2gy(-1.0,0.0); // y-axis reversed (lefthanded system) |
altb2 | 4:3c21fb0c9e84 | 28 | LinearCharacteristics raw_gz2gz( 1.0,0.0); |
altb2 | 4:3c21fb0c9e84 | 29 | LinearCharacteristics int2magx( -1.0,0.0); // x-axis reversed |
altb2 | 4:3c21fb0c9e84 | 30 | LinearCharacteristics int2magy( -1.0,0.0); // y-axis reversed |
altb2 | 4:3c21fb0c9e84 | 31 | LinearCharacteristics int2magz( 1.0,0.0); |
altb2 | 5:eee47600b772 | 32 | //matrix measurement(6,1,0.0); |
altb | 3:6811c0ce95f6 | 33 | while (!imu.begin()) { |
altb | 3:6811c0ce95f6 | 34 | wait(1); |
altb | 3:6811c0ce95f6 | 35 | printf("Failed to communicate with LSM9DS1.\r\n"); |
altb | 3:6811c0ce95f6 | 36 | } |
altb | 3:6811c0ce95f6 | 37 | |
altb | 3:6811c0ce95f6 | 38 | } |
altb | 3:6811c0ce95f6 | 39 | |
altb | 3:6811c0ce95f6 | 40 | AHRS::~AHRS() {} |
altb | 3:6811c0ce95f6 | 41 | |
altb | 3:6811c0ce95f6 | 42 | void AHRS::update(void) |
altb | 3:6811c0ce95f6 | 43 | { |
altb | 3:6811c0ce95f6 | 44 | while(1){ |
altb | 3:6811c0ce95f6 | 45 | thread.signal_wait(signal); |
altb | 3:6811c0ce95f6 | 46 | imu.readAccel(); |
altb2 | 4:3c21fb0c9e84 | 47 | //imu.readMag_calibrated(); |
altb2 | 4:3c21fb0c9e84 | 48 | imu.readMag(); |
altb | 3:6811c0ce95f6 | 49 | imu.readGyro(); |
altb2 | 5:eee47600b772 | 50 | matrix measurement(6,1,0.0); |
altb | 3:6811c0ce95f6 | 51 | //Perform Madgwick-filter update |
altb2 | 4:3c21fb0c9e84 | 52 | //RPY_filter.update(raw_gx2gx(imu.gx), raw_gy2gy(imu.gy), raw_gz2gz(imu.gz) , |
altb2 | 4:3c21fb0c9e84 | 53 | // raw_ax2ax(imu.ax), raw_ay2ay(imu.ay), raw_az2az(imu.az), |
altb2 | 5:eee47600b772 | 54 | // int2magx(imu.mx), int2magy(imu.my), int2magz(imu.mz)); |
altb2 | 4:3c21fb0c9e84 | 55 | measurement.put_entry(1,1,raw_gx2gx(imu.gyroX)); |
altb2 | 4:3c21fb0c9e84 | 56 | measurement.put_entry(2,1,raw_gy2gy(imu.gyroY)); |
altb2 | 4:3c21fb0c9e84 | 57 | measurement.put_entry(3,1,raw_ax2ax(imu.accX)); |
altb2 | 4:3c21fb0c9e84 | 58 | measurement.put_entry(4,1,raw_ay2ay(imu.accY)); |
altb2 | 5:eee47600b772 | 59 | RPY_filter.loop(&measurement); |
altb | 3:6811c0ce95f6 | 60 | } // while(1) |
altb | 3:6811c0ce95f6 | 61 | } |
altb | 3:6811c0ce95f6 | 62 | void AHRS::sendSignal() { |
altb | 3:6811c0ce95f6 | 63 | |
altb | 3:6811c0ce95f6 | 64 | thread.signal_set(signal); |
altb | 3:6811c0ce95f6 | 65 | } |