AHRS

Dependencies:   Eigen

Dependents:   IndNav_QK3_T265

Committer:
altb
Date:
Tue Dec 04 15:49:48 2018 +0000
Revision:
3:6811c0ce95f6
Child:
4:3c21fb0c9e84
AHRS Klasse mit Mahony filter etc

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"
altb 3:6811c0ce95f6 4 #define PI 3.141592653589793
altb 3:6811c0ce95f6 5
altb 3:6811c0ce95f6 6 using namespace std;
altb 3:6811c0ce95f6 7
altb 3:6811c0ce95f6 8 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){
altb 3:6811c0ce95f6 9
altb 3:6811c0ce95f6 10 thread.start(callback(this, &AHRS::update));
altb 3:6811c0ce95f6 11 ticker.attach(callback(this, &AHRS::sendSignal), TS);
altb 3:6811c0ce95f6 12 LinearCharacteristics raw_ax2ax(40.0/65536.0,-418.0); // use gain and offset here
altb 3:6811c0ce95f6 13 LinearCharacteristics raw_ay2ay(-40.0/65536.0,-307.0); // y-axis reversed
altb 3:6811c0ce95f6 14 LinearCharacteristics raw_az2az(-16350.0,16350,-10.0, 10.0);
altb 3:6811c0ce95f6 15 LinearCharacteristics raw_gx2gx(-32767,32768,-500*PI/180.0, 500*PI/180.0);
altb 3:6811c0ce95f6 16 LinearCharacteristics raw_gy2gy(-32767,32768, 500*PI/180.0,-500*PI/180.0); // y-axis reversed (lefthanded system)
altb 3:6811c0ce95f6 17 LinearCharacteristics raw_gz2gz(-32767,32768,-500*PI/180.0, 500*PI/180.0);
altb 3:6811c0ce95f6 18 LinearCharacteristics int2magx( -32767,32768,100.0,-100.0); // x-axis reversed
altb 3:6811c0ce95f6 19 LinearCharacteristics int2magy( -32767,32768,100.0,-100.0); // y-axis reversed
altb 3:6811c0ce95f6 20 LinearCharacteristics int2magz( -32767,32768,-100.0,100.0);
altb 3:6811c0ce95f6 21 while (!imu.begin()) {
altb 3:6811c0ce95f6 22 wait(1);
altb 3:6811c0ce95f6 23 printf("Failed to communicate with LSM9DS1.\r\n");
altb 3:6811c0ce95f6 24 }
altb 3:6811c0ce95f6 25
altb 3:6811c0ce95f6 26 }
altb 3:6811c0ce95f6 27
altb 3:6811c0ce95f6 28 AHRS::~AHRS() {}
altb 3:6811c0ce95f6 29
altb 3:6811c0ce95f6 30 void AHRS::update(void)
altb 3:6811c0ce95f6 31 {
altb 3:6811c0ce95f6 32 while(1){
altb 3:6811c0ce95f6 33 thread.signal_wait(signal);
altb 3:6811c0ce95f6 34 imu.readAccel();
altb 3:6811c0ce95f6 35 imu.readMag_calibrated();
altb 3:6811c0ce95f6 36 imu.readGyro();
altb 3:6811c0ce95f6 37
altb 3:6811c0ce95f6 38 //Perform Madgwick-filter update
altb 3:6811c0ce95f6 39 RPY_filter.update(raw_gx2gx(imu.gx), raw_gy2gy(imu.gy), raw_gz2gz(imu.gz) ,
altb 3:6811c0ce95f6 40 raw_ax2ax(imu.ax), raw_ay2ay(imu.ay), raw_az2az(imu.az),
altb 3:6811c0ce95f6 41 int2magx(imu.mx), int2magy(imu.my), int2magz(imu.mz));
altb 3:6811c0ce95f6 42
altb 3:6811c0ce95f6 43
altb 3:6811c0ce95f6 44 } // while(1)
altb 3:6811c0ce95f6 45 }
altb 3:6811c0ce95f6 46 void AHRS::sendSignal() {
altb 3:6811c0ce95f6 47
altb 3:6811c0ce95f6 48 thread.signal_set(signal);
altb 3:6811c0ce95f6 49 }