AHRS

Dependencies:   Eigen

Dependents:   IndNav_QK3_T265

Committer:
altb2
Date:
Fri Jan 10 16:00:47 2020 +0000
Revision:
26:1da7c6204775
Parent:
25:fe14dbcef82d
Child:
28:21dfb161c67c
recalib MAgnetometer

Who changed what in which revision?

UserRevisionLine numberNew contents of line
altb 3:6811c0ce95f6 1 #include "AHRS.h"
altb2 4:3c21fb0c9e84 2
altb 3:6811c0ce95f6 3 #define PI 3.141592653589793
altb 3:6811c0ce95f6 4
altb 3:6811c0ce95f6 5 using namespace std;
altb 3:6811c0ce95f6 6
pmic 17:f9eed26536d9 7 //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 25:fe14dbcef82d 8 AHRS::AHRS(uint8_t filtertype, float TS, bool calib, I2C &i2c) : ekf(TS), Mahony_filter(TS), cf_yaw(1.0f,TS), ekf_rp(TS), ekf_rpy(TS), imu(i2c), dout3(PA_10)
pmic 17:f9eed26536d9 9 {
pmic 17:f9eed26536d9 10 /* setup storage */
altb2 20:1182bc29c195 11 this->Ts = TS;
altb2 25:fe14dbcef82d 12 this->filtertype = filtertype;
altb2 25:fe14dbcef82d 13 #if _LSM9DS
altb2 25:fe14dbcef82d 14 imu_setup_LSM9DS(calib);
altb2 25:fe14dbcef82d 15 #else
altb2 25:fe14dbcef82d 16 imu_setup_BMX055(calib);
altb2 25:fe14dbcef82d 17 #endif
altb2 25:fe14dbcef82d 18 }
altb2 26:1da7c6204775 19 // -----------------------------------------------------------------------------
altb2 25:fe14dbcef82d 20 void AHRS::imu_setup_LSM9DS(bool calib){
pmic 17:f9eed26536d9 21 float gyro[3], accel[3], magnet[3];
altb2 20:1182bc29c195 22 for(uint8_t i = 0; i < 3; i++)
altb2 20:1182bc29c195 23 {
pmic 17:f9eed26536d9 24 gyro[i] = 0.0f;
pmic 17:f9eed26536d9 25 accel[i] = 0.0f;
pmic 17:f9eed26536d9 26 magnet[i] = 0.0f;
altb2 20:1182bc29c195 27 }
pmic 17:f9eed26536d9 28
pmic 17:f9eed26536d9 29 /* inform user if imu is not responsive */
altb2 20:1182bc29c195 30 while (!imu.begin())
altb2 20:1182bc29c195 31 {
altb2 9:644266463f5f 32 wait(1);
altb2 9:644266463f5f 33 printf("Failed to communicate with LSM9DS1.\r\n");
altb2 20:1182bc29c195 34 }
pmic 17:f9eed26536d9 35
pmic 17:f9eed26536d9 36 /* take mean value of N samples */
pmic 17:f9eed26536d9 37 uint8_t N = 200;
altb2 20:1182bc29c195 38 if(calib)
altb2 20:1182bc29c195 39 {
altb2 9:644266463f5f 40 wait_ms(500);
pmic 17:f9eed26536d9 41 /* read and cumsum data */
pmic 17:f9eed26536d9 42 for(uint16_t i = 0; i < N; i++) {
pmic 17:f9eed26536d9 43 imu.readGyro();
pmic 17:f9eed26536d9 44 imu.readAccel();
pmic 17:f9eed26536d9 45 imu.readMag();
pmic 17:f9eed26536d9 46 gyro[0] += imu.gyroX;
pmic 17:f9eed26536d9 47 gyro[1] += imu.gyroY;
pmic 17:f9eed26536d9 48 gyro[2] += imu.gyroZ;
pmic 17:f9eed26536d9 49 accel[0] += imu.accX;
pmic 17:f9eed26536d9 50 accel[1] += imu.accY;
pmic 17:f9eed26536d9 51 accel[2] += imu.accZ;
pmic 17:f9eed26536d9 52 magnet[0] += imu.magX;
pmic 17:f9eed26536d9 53 magnet[1] += imu.magY;
pmic 17:f9eed26536d9 54 magnet[2] += imu.magZ;
pmic 17:f9eed26536d9 55 wait_ms(10);
pmic 17:f9eed26536d9 56 }
pmic 17:f9eed26536d9 57 /* calculate mean value */
pmic 17:f9eed26536d9 58 for(uint16_t i = 0; i < 3; i++) {
pmic 17:f9eed26536d9 59 gyro[i] /= (float)N;
pmic 17:f9eed26536d9 60 accel[i] /= (float)N;
pmic 17:f9eed26536d9 61 magnet[i] /= (float)N;
altb2 20:1182bc29c195 62 }
pmic 17:f9eed26536d9 63 printf("Correct gyro: %1.5f %1.5f %1.5f accel: %1.5f %1.5f %1.5f magnet: %1.5f %1.5f %1.5f\r\n", gyro[0], gyro[1], gyro[2], accel[0], accel[1], accel[2], magnet[0], magnet[1], magnet[2]);
pmic 17:f9eed26536d9 64 }
pmic 17:f9eed26536d9 65
pmic 17:f9eed26536d9 66 /* gyro */
altb2 26:1da7c6204775 67 // ========== ACHTUNG HIER LSM9DS SENSOR
pmic 17:f9eed26536d9 68 raw_gx2gx.setup( 1.0, gyro[0]);
pmic 17:f9eed26536d9 69 raw_gy2gy.setup(-1.0, gyro[1]); // y-axis reversed (lefthanded system)
pmic 17:f9eed26536d9 70 raw_gz2gz.setup( 1.0, gyro[2]);
pmic 17:f9eed26536d9 71
pmic 17:f9eed26536d9 72 // pmic, 23.09.2019
pmic 17:f9eed26536d9 73 // calibration for acc and mag needs to be redone on real copter pes board with power on and spinning motors (no propellers)
pmic 17:f9eed26536d9 74 /* accel */
altb2 19:42ea6dd68185 75 raw_ax2ax.setup( 1.0f, accel[0]); // use gain and offset here
altb2 19:42ea6dd68185 76 raw_ay2ay.setup(-1.0f, accel[1]); // y-axis reversed // was -1,0.0
altb2 19:42ea6dd68185 77 raw_az2az.setup( 1.0, 0.0f); // do not remove gravity!
altb2 26:1da7c6204775 78 // ========== ACHTUNG HIER LSM9DS SENSOR
pmic 17:f9eed26536d9 79 /* magnet */
altb2 21:31e01d3e0143 80 /* Caibration on 21.10.2019 QK2 delivers:
altb2 19:42ea6dd68185 81 A=[ 0.9904 0 0; 0.0605 1.0158 0;0.0397 -0.0199 0.9938]
altb2 21:31e01d3e0143 82 b0= [0.4160 0.1587 -0.0998], //see T:\T-IMS-IndNav\01_Technisches\09_PES_Board_IMU\meas_mag_aFMA\calib_magn_Okt19_aFMA.m
altb2 19:42ea6dd68185 83 */
altb2 23:71996bfe68eb 84 raw_mx2mx.setup( 0.9837f,0.252f);
altb2 23:71996bfe68eb 85 raw_my2my.setup( 1.0298f,0.1675f);
altb2 23:71996bfe68eb 86 raw_mz2mz.setup(-0.9864f,-0.1392f); // achtung, bei gain(3) Vorzeichen drehen, b0 beibehalten!!!
altb2 23:71996bfe68eb 87 // raw_mx2mx.setup( 1.0f,0.0f);
altb2 23:71996bfe68eb 88 // raw_my2my.setup( 1.0f,0.0f);
altb2 23:71996bfe68eb 89 // raw_mz2mz.setup( 1.0f,0.0f); // achtung, bei b0(3) Vorzeichen drehen!!!
altb2 23:71996bfe68eb 90
pmic 17:f9eed26536d9 91 this->magnet_cal_0[0] = raw_mx2mx(magnet[0]);
pmic 17:f9eed26536d9 92 this->magnet_cal_0[1] = raw_my2my(magnet[1]);
pmic 17:f9eed26536d9 93 this->magnet_cal_0[2] = raw_mz2mz(magnet[2]);
altb2 21:31e01d3e0143 94 // set EKF_RPY magnet values now:
altb2 23:71996bfe68eb 95 ekf_rpy.set_m0(this->magnet_cal_0[0],this->magnet_cal_0[1],this->magnet_cal_0[2]);
altb2 7:bfde7bd5fe31 96 local_time = 0.0;
altb2 19:42ea6dd68185 97
pmic 17:f9eed26536d9 98 // the thread starts
altb2 9:644266463f5f 99
altb 3:6811c0ce95f6 100 }
altb2 25:fe14dbcef82d 101 //------------------------------------------------------------------------------
altb2 25:fe14dbcef82d 102 void AHRS::imu_setup_BMX055(bool calib){
altb2 25:fe14dbcef82d 103 float gyro[3], accel[3], magnet[3];
altb2 25:fe14dbcef82d 104 for(uint8_t i = 0; i < 3; i++)
altb2 25:fe14dbcef82d 105 {
altb2 25:fe14dbcef82d 106 gyro[i] = 0.0f;
altb2 25:fe14dbcef82d 107 accel[i] = 0.0f;
altb2 25:fe14dbcef82d 108 magnet[i] = 0.0f;
altb2 25:fe14dbcef82d 109 }
altb2 25:fe14dbcef82d 110
altb2 25:fe14dbcef82d 111 /* take mean value of N samples */
altb2 25:fe14dbcef82d 112 uint8_t N = 200;
altb2 25:fe14dbcef82d 113 if(calib)
altb2 25:fe14dbcef82d 114 {
altb2 25:fe14dbcef82d 115 wait_ms(500);
altb2 25:fe14dbcef82d 116 /* read and cumsum data */
altb2 25:fe14dbcef82d 117 for(uint16_t i = 0; i < N; i++) {
altb2 25:fe14dbcef82d 118 imu.readGyro();
altb2 25:fe14dbcef82d 119 imu.readAccel();
altb2 25:fe14dbcef82d 120 imu.readMag();
altb2 25:fe14dbcef82d 121 gyro[0] += imu.gyroX;
altb2 25:fe14dbcef82d 122 gyro[1] += imu.gyroY;
altb2 25:fe14dbcef82d 123 gyro[2] += imu.gyroZ;
altb2 25:fe14dbcef82d 124 accel[0] += imu.accX;
altb2 25:fe14dbcef82d 125 accel[1] += imu.accY;
altb2 25:fe14dbcef82d 126 accel[2] += imu.accZ;
altb2 25:fe14dbcef82d 127 magnet[0] += imu.magX;
altb2 25:fe14dbcef82d 128 magnet[1] += imu.magY;
altb2 25:fe14dbcef82d 129 magnet[2] += imu.magZ;
altb2 25:fe14dbcef82d 130 wait_ms(10);
altb2 25:fe14dbcef82d 131 }
altb2 25:fe14dbcef82d 132 /* calculate mean value */
altb2 25:fe14dbcef82d 133 for(uint16_t i = 0; i < 3; i++) {
altb2 25:fe14dbcef82d 134 gyro[i] /= (float)N;
altb2 25:fe14dbcef82d 135 accel[i] /= (float)N;
altb2 25:fe14dbcef82d 136 magnet[i] /= (float)N;
altb2 25:fe14dbcef82d 137 }
altb2 25:fe14dbcef82d 138 }
altb2 26:1da7c6204775 139 // ========== ACHTUNG HIER BMX055 SENSOR
altb2 25:fe14dbcef82d 140 /* gyro */
altb2 25:fe14dbcef82d 141 raw_gx2gx.setup( 1.0, gyro[0]);
altb2 25:fe14dbcef82d 142 raw_gy2gy.setup( 1.0, gyro[1]); // y-axis reversed (lefthanded system)
altb2 25:fe14dbcef82d 143 raw_gz2gz.setup( 1.0, gyro[2]);
altb2 25:fe14dbcef82d 144
altb2 25:fe14dbcef82d 145 /* accel */
altb2 25:fe14dbcef82d 146 raw_ax2ax.setup( 1.0f, accel[0]); // use gain and offset here
altb2 25:fe14dbcef82d 147 raw_ay2ay.setup( 1.0f, accel[1]); // y-axis reversed // was -1,0.0
altb2 25:fe14dbcef82d 148 raw_az2az.setup( 1.0, 0.0f); // do not remove gravity!
altb2 25:fe14dbcef82d 149
altb2 26:1da7c6204775 150 // ========== ACHTUNG HIER BMX055 SENSOR
altb2 25:fe14dbcef82d 151 /* magnet */
altb2 25:fe14dbcef82d 152 // diag(A0) = 0.8047 0.8447 0.8474
altb2 26:1da7c6204775 153 // diag(A0) = 0.7485 0.8074 0.8892 //10.1.2020
altb2 25:fe14dbcef82d 154 // b0 = -0.1195 0.2009 -0.3133, calibration at desk 19.12.2019
altb2 26:1da7c6204775 155 // b0 = 0.2656 0.4564 0.9155 // 10.1.20
altb2 26:1da7c6204775 156 // 1.0150 1.0843 1.1814, 0.2826 0.4353 0.9392 aFMA 10.1.2020
altb2 26:1da7c6204775 157 raw_mx2mx.setup(1.0150f,0.2826f);
altb2 26:1da7c6204775 158 raw_my2my.setup(1.0843f,0.4353f);
altb2 26:1da7c6204775 159 raw_mz2mz.setup(1.1814f,0.9392f); // */
altb2 25:fe14dbcef82d 160 /* raw_mx2mx.setup( 1.0f,0.0f);
altb2 25:fe14dbcef82d 161 raw_my2my.setup( 1.0f,0.0f);
altb2 26:1da7c6204775 162 raw_mz2mz.setup( 1.0f,0.0f); // */
altb2 25:fe14dbcef82d 163 this->magnet_cal_0[0] = raw_mx2mx(magnet[0]);
altb2 25:fe14dbcef82d 164 this->magnet_cal_0[1] = raw_my2my(magnet[1]);
altb2 25:fe14dbcef82d 165 this->magnet_cal_0[2] = raw_mz2mz(magnet[2]);
altb2 25:fe14dbcef82d 166 // set EKF_RPY magnet values now:
altb2 25:fe14dbcef82d 167 ekf_rpy.set_m0(this->magnet_cal_0[0],this->magnet_cal_0[1],this->magnet_cal_0[2]);
altb2 25:fe14dbcef82d 168 local_time = 0.0;
altb2 25:fe14dbcef82d 169
altb2 25:fe14dbcef82d 170 // the thread starts
altb2 25:fe14dbcef82d 171
altb2 25:fe14dbcef82d 172 }
altb2 25:fe14dbcef82d 173
altb 3:6811c0ce95f6 174
altb 3:6811c0ce95f6 175 AHRS::~AHRS() {}
altb 3:6811c0ce95f6 176
altb 3:6811c0ce95f6 177 void AHRS::update(void)
altb2 20:1182bc29c195 178 {
altb2 20:1182bc29c195 179 //dout3.write(1);
altb2 21:31e01d3e0143 180 switch(filtertype){
altb2 21:31e01d3e0143 181 case 1:
altb2 21:31e01d3e0143 182 ekf.update(data.sens_gyr[0],data.sens_gyr[1],data.sens_gyr[2],data.sens_acc[0],data.sens_acc[1],data.sens_acc[2]);
altb2 22:495a419e474c 183 cf_yaw.update(data.sens_gyr[2],data.sens_mag[0],data.sens_mag[1],data.sens_mag[2]);
altb2 21:31e01d3e0143 184 data.est_RPY[0] = ekf.get_est_state(0);
altb2 21:31e01d3e0143 185 data.est_RPY[1] = ekf.get_est_state(1);
altb2 23:71996bfe68eb 186 //data.est_Vxyz[0] = ekf.get_est_state(4);
altb2 23:71996bfe68eb 187 //data.est_Vxyz[1] = ekf.get_est_state(5);
altb2 21:31e01d3e0143 188 break;
altb2 21:31e01d3e0143 189 case 2:
altb2 21:31e01d3e0143 190 Mahony_filter.update(data.sens_gyr[0],data.sens_gyr[1],data.sens_gyr[2],data.sens_acc[0],data.sens_acc[1],data.sens_acc[2],0.0f,0.0f,0.0f);
altb2 21:31e01d3e0143 191 data.est_RPY[0] = Mahony_filter.getRollRadians();
altb2 21:31e01d3e0143 192 data.est_RPY[1] = Mahony_filter.getPitchRadians();
altb2 21:31e01d3e0143 193 break;
altb2 21:31e01d3e0143 194 case 3:
altb2 21:31e01d3e0143 195 ekf_rp.update(data.sens_gyr[0],data.sens_gyr[1],data.sens_acc[0],data.sens_acc[1]);
altb2 23:71996bfe68eb 196
altb2 23:71996bfe68eb 197 cf_yaw.update(data.sens_gyr[2],data.sens_mag[0],data.sens_mag[1],data.sens_mag[2]);
altb2 21:31e01d3e0143 198 data.est_RPY[0] = ekf_rp.get_est_state(0);
altb2 21:31e01d3e0143 199 data.est_RPY[1] = ekf_rp.get_est_state(1);
altb2 21:31e01d3e0143 200 break;
altb2 21:31e01d3e0143 201 case 4:
altb2 21:31e01d3e0143 202 ekf_rpy.update(data.sens_gyr[0],data.sens_gyr[1],data.sens_gyr[2],data.sens_acc[0],data.sens_acc[1],data.sens_mag[0],data.sens_mag[1]);
altb2 21:31e01d3e0143 203 data.est_RPY[0] = ekf_rpy.get_est_state(0);
altb2 21:31e01d3e0143 204 data.est_RPY[1] = ekf_rpy.get_est_state(1);
altb2 23:71996bfe68eb 205 data.est_RPY[2] = ekf_rpy.get_est_state(2);
altb2 23:71996bfe68eb 206 data.est_RPY[3] = ekf_rpy.get_est_state(3);
altb2 23:71996bfe68eb 207 data.est_RPY[4] = ekf_rpy.get_est_state(4);
altb2 23:71996bfe68eb 208 data.est_RPY[5] = ekf_rpy.get_est_state(5);
altb2 23:71996bfe68eb 209 data.est_RPY[6] = ekf_rpy.get_est_state(6);
altb2 23:71996bfe68eb 210 data.est_RPY[7] = ekf_rpy.get_est_state(7);
altb2 21:31e01d3e0143 211 break;
altb2 20:1182bc29c195 212 }
altb2 20:1182bc29c195 213 // dout3.write(0);
altb2 20:1182bc29c195 214 }
altb2 20:1182bc29c195 215 void AHRS::update_as_thread(void)
altb2 20:1182bc29c195 216 {
altb2 20:1182bc29c195 217 while(1)
altb2 20:1182bc29c195 218 {
altb2 20:1182bc29c195 219 thread.signal_wait(signal);
altb2 20:1182bc29c195 220 // dout3.write(1);
altb2 20:1182bc29c195 221 if(filtertype !=1)
altb2 20:1182bc29c195 222 {
altb2 20:1182bc29c195 223 Mahony_filter.update(data.sens_gyr[0],data.sens_gyr[1],data.sens_gyr[2],data.sens_acc[0],data.sens_acc[1],data.sens_acc[2],0.0f,0.0f,0.0f);
altb2 20:1182bc29c195 224 data.est_RPY[0] = Mahony_filter.getRollRadians();
altb2 20:1182bc29c195 225 data.est_RPY[1] = Mahony_filter.getPitchRadians();
altb2 20:1182bc29c195 226 }
altb2 20:1182bc29c195 227 else
altb2 20:1182bc29c195 228 {
altb2 20:1182bc29c195 229 ekf.update(data.sens_gyr[0],data.sens_gyr[1],data.sens_gyr[2],data.sens_acc[0],data.sens_acc[1],data.sens_acc[2]);
altb2 20:1182bc29c195 230 data.est_RPY[0] = ekf.get_est_state(0);
altb2 20:1182bc29c195 231 data.est_RPY[1] = ekf.get_est_state(1);
altb2 20:1182bc29c195 232 }
altb2 20:1182bc29c195 233 // dout3.write(0);
altb2 20:1182bc29c195 234 }
altb2 20:1182bc29c195 235 }
altb2 20:1182bc29c195 236 void AHRS::read_imu_sensors(void){
altb2 25:fe14dbcef82d 237 mutex.lock();
altb2 25:fe14dbcef82d 238 dout3.write(1);
altb2 20:1182bc29c195 239 imu.readGyro();
altb2 20:1182bc29c195 240 imu.readAccel();
altb2 20:1182bc29c195 241 imu.readMag();
altb2 25:fe14dbcef82d 242 dout3.write(0);
altb2 25:fe14dbcef82d 243 mutex.unlock();
altb2 20:1182bc29c195 244 data.sens_gyr[0] = raw_gx2gx(imu.gyroX);
altb2 20:1182bc29c195 245 data.sens_gyr[1] = raw_gy2gy(imu.gyroY);
altb2 20:1182bc29c195 246 data.sens_gyr[2] = raw_gz2gz(imu.gyroZ);
altb2 20:1182bc29c195 247 data.sens_acc[0] = raw_ax2ax(imu.accX);
altb2 20:1182bc29c195 248 data.sens_acc[1] = raw_ay2ay(imu.accY);
altb2 20:1182bc29c195 249 data.sens_acc[2] = raw_az2az(imu.accZ);
altb2 20:1182bc29c195 250 data.sens_mag[0] = raw_mx2mx(imu.magX);
altb2 20:1182bc29c195 251 data.sens_mag[1] = raw_my2my(imu.magY);
altb2 20:1182bc29c195 252 data.sens_mag[2] = raw_mz2mz(imu.magZ);
altb2 20:1182bc29c195 253 }
altb2 20:1182bc29c195 254 // ------------------- start controllers ----------------
altb2 20:1182bc29c195 255 void AHRS::start_loop(void){
altb2 20:1182bc29c195 256 thread.start(callback(this, &AHRS::update_as_thread));
altb2 20:1182bc29c195 257 ticker.attach(callback(this, &AHRS::sendSignal), Ts);
altb2 20:1182bc29c195 258 }
pmic 17:f9eed26536d9 259
altb2 20:1182bc29c195 260 // this is for realtime OS
altb2 20:1182bc29c195 261 void AHRS::sendSignal() {
altb2 20:1182bc29c195 262 thread.signal_set(signal);
altb2 20:1182bc29c195 263 }