AHRS
Dependencies: Eigen
AHRS.cpp
- Committer:
- altb2
- Date:
- 2019-06-14
- Revision:
- 6:5824bd96b6cf
- Parent:
- 5:eee47600b772
- Child:
- 7:bfde7bd5fe31
File content as of revision 6:5824bd96b6cf:
#include "AHRS.h" #include "Mahony.h" #include "MadgwickAHRS.h" #include "ekf.h" #define PI 3.141592653589793 using namespace std; //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){ AHRS::AHRS(uint8_t filtertype,float TS) : imu(PC_9, PA_8, 0xD6, 0x3C), RPY_filter(TS), thread(osPriorityBelowNormal, 4096){ thread.start(callback(this, &AHRS::update)); ticker.attach(callback(this, &AHRS::sendSignal), TS); /* LinearCharacteristics raw_ax2ax(40.0/65536.0,-418.0); // use gain and offset here LinearCharacteristics raw_ay2ay(-40.0/65536.0,-307.0); // y-axis reversed LinearCharacteristics raw_az2az(-16350.0,16350,-10.0, 10.0); LinearCharacteristics raw_gx2gx(-32767,32768,-500*PI/180.0, 500*PI/180.0); LinearCharacteristics raw_gy2gy(-32767,32768, 500*PI/180.0,-500*PI/180.0); // y-axis reversed (lefthanded system) LinearCharacteristics raw_gz2gz(-32767,32768,-500*PI/180.0, 500*PI/180.0); LinearCharacteristics int2magx( -32767,32768,100.0,-100.0); // x-axis reversed LinearCharacteristics int2magy( -32767,32768,100.0,-100.0); // y-axis reversed*/ LinearCharacteristics raw_ax2ax( 1.0,0.0); // use gain and offset here LinearCharacteristics raw_ay2ay(-1.0,0.0); // y-axis reversed LinearCharacteristics raw_az2az( 1.0,0.0); LinearCharacteristics raw_gx2gx( 1.0,0.0); LinearCharacteristics raw_gy2gy(-1.0,0.0); // y-axis reversed (lefthanded system) LinearCharacteristics raw_gz2gz( 1.0,0.0); LinearCharacteristics int2magx( -1.0,0.0); // x-axis reversed LinearCharacteristics int2magy( -1.0,0.0); // y-axis reversed LinearCharacteristics int2magz( 1.0,0.0); //matrix measurement(6,1,0.0); while (!imu.begin()) { wait(1); printf("Failed to communicate with LSM9DS1.\r\n"); } } AHRS::~AHRS() {} void AHRS::update(void) { while(1){ thread.signal_wait(signal); imu.readAccel(); //imu.readMag_calibrated(); imu.readMag(); imu.readGyro(); matrix measurement(6,1,0.0); //Perform filter update //RPY_filter.update(raw_gx2gx(imu.gx), raw_gy2gy(imu.gy), raw_gz2gz(imu.gz) , // raw_ax2ax(imu.ax), raw_ay2ay(imu.ay), raw_az2az(imu.az), // int2magx(imu.mx), int2magy(imu.my), int2magz(imu.mz)); measurement.put_entry(0,0,raw_gx2gx(imu.gyroX)); measurement.put_entry(1,0,raw_gy2gy(imu.gyroY)); measurement.put_entry(3,0,raw_ax2ax(imu.accX)); measurement.put_entry(4,0,raw_ay2ay(imu.accY)); RPY_filter.loop(&measurement); my_logger.data_vector[0] = raw_gx2gx(imu.gyroX); my_logger.data_vector[1] = raw_gy2gy(imu.gyroY); my_logger.data_vector[2] = raw_gz2gz(imu.gyroZ); my_logger.data_vector[3] = raw_ax2ax(imu.accX); my_logger.data_vector[4] = raw_ay2ay(imu.accY); my_logger.data_vector[5] = raw_az2az(imu.accZ); my_logger.data_vector[6] = RPY_filter.get_est_state(1); my_logger.data_vector[7] = RPY_filter.get_est_state(2); } // while(1) (the thread) } void AHRS::sendSignal() { thread.signal_set(signal); }