AHRS
Dependencies: Eigen
AHRS.cpp@8:51062bb877f0, 2019-07-05 (annotated)
- Committer:
- altb2
- Date:
- Fri Jul 05 06:56:19 2019 +0000
- Revision:
- 8:51062bb877f0
- Parent:
- 7:bfde7bd5fe31
- Child:
- 9:644266463f5f
Anpassungen Parameter fuer QK2, Alg. unveraendert
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 | 8:51062bb877f0 | 11 | AHRS::AHRS(uint8_t filtertype,float TS) : imu(PC_9, PA_8, 0xD6, 0x3C), RPY_filter(TS), Mahony_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 | 8:51062bb877f0 | 23 | raw_ax2ax.setup( 1.0,0.15); // use gain and offset here |
altb2 | 7:bfde7bd5fe31 | 24 | raw_ay2ay.setup(-1.0,-0.31); // y-axis reversed // was -1,0.0 |
altb2 | 7:bfde7bd5fe31 | 25 | raw_az2az.setup( 1.0,0.0); |
altb2 | 7:bfde7bd5fe31 | 26 | raw_gx2gx.setup( 1.0,0.0); |
altb2 | 7:bfde7bd5fe31 | 27 | raw_gy2gy.setup(-1.0,0.0); // y-axis reversed (lefthanded system) |
altb2 | 7:bfde7bd5fe31 | 28 | raw_gz2gz.setup( 1.0,0.0); |
altb2 | 8:51062bb877f0 | 29 | int2magx.setup( -1.0,0.0); // x-axis reversed |
altb2 | 8:51062bb877f0 | 30 | int2magy.setup( -1.0,0.0); // y-axis reversed |
altb2 | 7:bfde7bd5fe31 | 31 | int2magz.setup( 1.0,0.0); |
altb2 | 7:bfde7bd5fe31 | 32 | local_time = 0.0; |
altb2 | 7:bfde7bd5fe31 | 33 | // |
altb2 | 7:bfde7bd5fe31 | 34 | |
altb2 | 5:eee47600b772 | 35 | //matrix measurement(6,1,0.0); |
altb | 3:6811c0ce95f6 | 36 | while (!imu.begin()) { |
altb | 3:6811c0ce95f6 | 37 | wait(1); |
altb | 3:6811c0ce95f6 | 38 | printf("Failed to communicate with LSM9DS1.\r\n"); |
altb | 3:6811c0ce95f6 | 39 | } |
altb | 3:6811c0ce95f6 | 40 | |
altb | 3:6811c0ce95f6 | 41 | } |
altb | 3:6811c0ce95f6 | 42 | |
altb | 3:6811c0ce95f6 | 43 | AHRS::~AHRS() {} |
altb | 3:6811c0ce95f6 | 44 | |
altb | 3:6811c0ce95f6 | 45 | void AHRS::update(void) |
altb | 3:6811c0ce95f6 | 46 | { |
altb2 | 7:bfde7bd5fe31 | 47 | while(1){ |
altb | 3:6811c0ce95f6 | 48 | thread.signal_wait(signal); |
altb | 3:6811c0ce95f6 | 49 | imu.readAccel(); |
altb2 | 4:3c21fb0c9e84 | 50 | //imu.readMag_calibrated(); |
altb2 | 8:51062bb877f0 | 51 | imu.readMag(); |
altb | 3:6811c0ce95f6 | 52 | imu.readGyro(); |
altb2 | 5:eee47600b772 | 53 | matrix measurement(6,1,0.0); |
altb2 | 6:5824bd96b6cf | 54 | //Perform filter update |
altb2 | 8:51062bb877f0 | 55 | Mahony_filter.update(raw_gx2gx(imu.gyroX), raw_gy2gy(imu.gyroY), raw_gz2gz(imu.gyroZ) , |
altb2 | 8:51062bb877f0 | 56 | raw_ax2ax(imu.accX), raw_ay2ay(imu.accY), raw_az2az(imu.accZ), |
altb2 | 8:51062bb877f0 | 57 | int2magx(imu.magX), int2magy(imu.magY), int2magz(imu.magZ)); |
altb2 | 6:5824bd96b6cf | 58 | measurement.put_entry(0,0,raw_gx2gx(imu.gyroX)); |
altb2 | 6:5824bd96b6cf | 59 | measurement.put_entry(1,0,raw_gy2gy(imu.gyroY)); |
altb2 | 6:5824bd96b6cf | 60 | measurement.put_entry(3,0,raw_ax2ax(imu.accX)); |
altb2 | 6:5824bd96b6cf | 61 | measurement.put_entry(4,0,raw_ay2ay(imu.accY)); |
altb2 | 5:eee47600b772 | 62 | RPY_filter.loop(&measurement); |
altb2 | 8:51062bb877f0 | 63 | |
altb2 | 6:5824bd96b6cf | 64 | my_logger.data_vector[0] = raw_gx2gx(imu.gyroX); |
altb2 | 6:5824bd96b6cf | 65 | my_logger.data_vector[1] = raw_gy2gy(imu.gyroY); |
altb2 | 6:5824bd96b6cf | 66 | my_logger.data_vector[2] = raw_gz2gz(imu.gyroZ); |
altb2 | 6:5824bd96b6cf | 67 | my_logger.data_vector[3] = raw_ax2ax(imu.accX); |
altb2 | 6:5824bd96b6cf | 68 | my_logger.data_vector[4] = raw_ay2ay(imu.accY); |
altb2 | 6:5824bd96b6cf | 69 | my_logger.data_vector[5] = raw_az2az(imu.accZ); |
altb2 | 7:bfde7bd5fe31 | 70 | my_logger.data_vector[6] = RPY_filter.get_est_state(0); |
altb2 | 7:bfde7bd5fe31 | 71 | my_logger.data_vector[7] = RPY_filter.get_est_state(1); |
altb2 | 8:51062bb877f0 | 72 | my_logger.data_vector[8] = Mahony_filter.getRollRadians(); |
altb2 | 8:51062bb877f0 | 73 | my_logger.data_vector[9] = Mahony_filter.getPitchRadians(); |
altb2 | 7:bfde7bd5fe31 | 74 | |
altb2 | 7:bfde7bd5fe31 | 75 | //printf("R %1.5f P %1.5f gx: %1.5f gy: %1.5f\r\n",my_logger.data_vector[6],my_logger.data_vector[7],my_logger.data_vector[0],my_logger.data_vector[1]); |
altb2 | 7:bfde7bd5fe31 | 76 | //printf("%1.6f %1.6f %1.6f %1.6f %1.6f %1.6f %1.6f %1.6f\r\n",my_logger.data_vector[6],my_logger.data_vector[7],raw_gx2gx(imu.gyroX),raw_gy2gy(imu.gyroY),raw_gz2gz(imu.gyroZ),raw_ax2ax(imu.accX),raw_ay2ay(imu.accY),raw_az2az(imu.accZ)); |
altb2 | 7:bfde7bd5fe31 | 77 | //printf("ax: %1.4f ay: %1.4f az: %1.4f\r\n",raw_ax2ax(imu.accX),raw_ay2ay(imu.accY),raw_az2az(imu.accZ)); |
altb2 | 7:bfde7bd5fe31 | 78 | //printf("gx: %1.4f gy: %1.4f gz: %1.4f\r\n",raw_gx2gx(imu.gyroX),raw_gy2gy(imu.gyroY),raw_gz2gz(imu.gyroZ)); |
altb2 | 7:bfde7bd5fe31 | 79 | //printf("ax: %1.4f ay: %1.4f az: %1.4f\r\n",raw_ax2ax(imu.accX),raw_ay2ay(imu.accY),raw_az2az(imu.accZ)); |
altb2 | 6:5824bd96b6cf | 80 | } // while(1) (the thread) |
altb2 | 7:bfde7bd5fe31 | 81 | |
altb | 3:6811c0ce95f6 | 82 | } |
altb | 3:6811c0ce95f6 | 83 | void AHRS::sendSignal() { |
altb | 3:6811c0ce95f6 | 84 | |
altb | 3:6811c0ce95f6 | 85 | thread.signal_set(signal); |
altb | 3:6811c0ce95f6 | 86 | } |