AHRS

Dependencies:   Eigen

Dependents:   IndNav_QK3_T265

Committer:
altb2
Date:
Wed Sep 18 09:57:53 2019 +0000
Revision:
14:c357be9a3fc8
Parent:
10:fd4e2436b311
Child:
17:f9eed26536d9
minor changes

Who changed what in which revision?

UserRevisionLine numberNew 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 9:644266463f5f 11 AHRS::AHRS(uint8_t filtertype,float TS,bool calib) : imu(PC_9, PA_8, 0xD6, 0x3C), RPY_filter(TS), Mahony_filter(TS), thread(osPriorityBelowNormal, 4096){
altb2 9:644266463f5f 12 float g[3];
altb2 9:644266463f5f 13 g[0]=0.0;g[1]=0.0;g[2]=0.0;
altb2 9:644266463f5f 14 float a[3];
altb2 9:644266463f5f 15 a[0]=0.0;a[1]=0.0;a[2]=0.0;
altb2 9:644266463f5f 16 uint8_t N = 100;
altb2 9:644266463f5f 17 while (!imu.begin()) {
altb2 9:644266463f5f 18 wait(1);
altb2 9:644266463f5f 19 printf("Failed to communicate with LSM9DS1.\r\n");
altb2 9:644266463f5f 20 }
altb2 9:644266463f5f 21 if(calib){
altb2 9:644266463f5f 22 wait_ms(500);
altb2 9:644266463f5f 23 for(int k=0;k < N;k++)
altb2 9:644266463f5f 24 {
altb2 9:644266463f5f 25 imu.readGyro();
altb2 9:644266463f5f 26 imu.readAccel();
altb2 9:644266463f5f 27 g[0]+= imu.gyroX;
altb2 9:644266463f5f 28 g[1]+= imu.gyroY;
altb2 9:644266463f5f 29 g[2]+= imu.gyroZ;
altb2 9:644266463f5f 30 a[0]+= imu.accX;
altb2 9:644266463f5f 31 a[1]+= imu.accY;
altb2 9:644266463f5f 32 a[2]+= imu.accZ;
altb2 9:644266463f5f 33 wait_ms(10);
altb2 9:644266463f5f 34 }
altb2 9:644266463f5f 35 for(int k = 0;k<3;k++){
altb2 9:644266463f5f 36 g[k] /= (float)N;
altb2 9:644266463f5f 37 a[k] /= (float)N;
altb2 9:644266463f5f 38 }
altb2 9:644266463f5f 39 printf("Correct g: %1.5f %1.5f %1.5f a: %1.5f %1.5f %1.5f\r\n",g[0],g[1],g[2],a[0],a[1],a[2]);
altb2 9:644266463f5f 40 }
altb2 9:644266463f5f 41 raw_gx2gx.setup( 1.0,g[0]);
altb2 9:644266463f5f 42 raw_gy2gy.setup(-1.0,g[1]); // y-axis reversed (lefthanded system)
altb2 9:644266463f5f 43 raw_gz2gz.setup( 1.0,g[2]);
altb2 9:644266463f5f 44 raw_ax2ax.setup( 1.0,a[0]); // use gain and offset here
altb2 9:644266463f5f 45 raw_ay2ay.setup(-1.0,a[1]); // y-axis reversed // was -1,0.0
altb2 7:bfde7bd5fe31 46 raw_az2az.setup( 1.0,0.0);
altb2 8:51062bb877f0 47 int2magx.setup( -1.0,0.0); // x-axis reversed
altb2 8:51062bb877f0 48 int2magy.setup( -1.0,0.0); // y-axis reversed
altb2 7:bfde7bd5fe31 49 int2magz.setup( 1.0,0.0);
altb2 7:bfde7bd5fe31 50 local_time = 0.0;
altb2 9:644266463f5f 51 // The Thread starts
altb2 9:644266463f5f 52 thread.start(callback(this, &AHRS::update));
altb2 9:644266463f5f 53 ticker.attach(callback(this, &AHRS::sendSignal), TS);
altb2 9:644266463f5f 54
altb2 7:bfde7bd5fe31 55
altb 3:6811c0ce95f6 56
altb 3:6811c0ce95f6 57 }
altb 3:6811c0ce95f6 58
altb 3:6811c0ce95f6 59 AHRS::~AHRS() {}
altb 3:6811c0ce95f6 60
altb2 9:644266463f5f 61
altb 3:6811c0ce95f6 62 void AHRS::update(void)
altb 3:6811c0ce95f6 63 {
altb2 7:bfde7bd5fe31 64 while(1){
altb 3:6811c0ce95f6 65 thread.signal_wait(signal);
altb 3:6811c0ce95f6 66 imu.readAccel();
altb2 4:3c21fb0c9e84 67 //imu.readMag_calibrated();
altb2 8:51062bb877f0 68 imu.readMag();
altb 3:6811c0ce95f6 69 imu.readGyro();
altb2 5:eee47600b772 70 matrix measurement(6,1,0.0);
altb2 6:5824bd96b6cf 71 //Perform filter update
altb2 9:644266463f5f 72 //Mahony_filter.update(raw_gx2gx(imu.gyroX), raw_gy2gy(imu.gyroY), raw_gz2gz(imu.gyroZ) ,
altb2 9:644266463f5f 73 // raw_ax2ax(imu.accX), raw_ay2ay(imu.accY), raw_az2az(imu.accZ),
altb2 9:644266463f5f 74 // int2magx(imu.magX), int2magy(imu.magY), int2magz(imu.magZ));
altb2 6:5824bd96b6cf 75 measurement.put_entry(0,0,raw_gx2gx(imu.gyroX));
altb2 6:5824bd96b6cf 76 measurement.put_entry(1,0,raw_gy2gy(imu.gyroY));
altb2 6:5824bd96b6cf 77 measurement.put_entry(3,0,raw_ax2ax(imu.accX));
altb2 6:5824bd96b6cf 78 measurement.put_entry(4,0,raw_ay2ay(imu.accY));
altb2 5:eee47600b772 79 RPY_filter.loop(&measurement);
altb2 8:51062bb877f0 80
altb2 6:5824bd96b6cf 81 my_logger.data_vector[0] = raw_gx2gx(imu.gyroX);
altb2 6:5824bd96b6cf 82 my_logger.data_vector[1] = raw_gy2gy(imu.gyroY);
altb2 6:5824bd96b6cf 83 my_logger.data_vector[2] = raw_gz2gz(imu.gyroZ);
altb2 14:c357be9a3fc8 84 my_logger.data_vector[3] = raw_ax2ax(imu.accX);
altb2 6:5824bd96b6cf 85 my_logger.data_vector[4] = raw_ay2ay(imu.accY);
altb2 14:c357be9a3fc8 86 my_logger.data_vector[5] = raw_az2az(imu.accZ);
altb2 14:c357be9a3fc8 87 my_logger.data_vector[6] = RPY_filter.get_est_state(0);
altb2 14:c357be9a3fc8 88 my_logger.data_vector[7] = RPY_filter.get_est_state(1);
altb2 14:c357be9a3fc8 89 my_logger.data_vector[8] = RPY_filter.get_est_state(4);
altb2 14:c357be9a3fc8 90 my_logger.data_vector[9] = RPY_filter.get_est_state(5);
altb2 6:5824bd96b6cf 91 } // while(1) (the thread)
altb2 7:bfde7bd5fe31 92
altb 3:6811c0ce95f6 93 }
altb 3:6811c0ce95f6 94 void AHRS::sendSignal() {
altb 3:6811c0ce95f6 95
altb 3:6811c0ce95f6 96 thread.signal_set(signal);
altb 3:6811c0ce95f6 97 }