Port of http://dev.qu.tu-berlin.de/projects/sf-razor-9dof-ahrs to an mbed, tested with a 9DOF Sensor Stick, SEN-10724

Dependencies:   mbed

Committer:
lpetre
Date:
Wed Dec 28 18:09:14 2011 +0000
Revision:
2:5aa75c3d8cc3
Parent:
0:9a72d42c0da3

        

Who changed what in which revision?

UserRevisionLine numberNew contents of line
lpetre 0:9a72d42c0da3 1 /* This file is part of the Razor AHRS Firmware */
lpetre 0:9a72d42c0da3 2 #include "Razor_AHRS.h"
lpetre 0:9a72d42c0da3 3 #include <math.h>
lpetre 0:9a72d42c0da3 4
lpetre 0:9a72d42c0da3 5 void IMU::read_sensors() {
lpetre 0:9a72d42c0da3 6 Read_Gyro(); // Read gyroscope
lpetre 0:9a72d42c0da3 7 Read_Accel(); // Read accelerometer
lpetre 0:9a72d42c0da3 8 Read_Magn(); // Read magnetometer
lpetre 0:9a72d42c0da3 9 }
lpetre 0:9a72d42c0da3 10
lpetre 0:9a72d42c0da3 11 // Read every sensor and record a time stamp
lpetre 0:9a72d42c0da3 12 // Init DCM with unfiltered orientation
lpetre 0:9a72d42c0da3 13 // TODO re-init global vars?
lpetre 0:9a72d42c0da3 14 void IMU::reset_sensor_fusion() {
lpetre 0:9a72d42c0da3 15 float temp0[3] = { accel[0], accel[1], accel[2] };
lpetre 0:9a72d42c0da3 16 float temp1[3];
lpetre 0:9a72d42c0da3 17 float temp2[3];
lpetre 0:9a72d42c0da3 18 float xAxis[] = {1.0f, 0.0f, 0.0f};
lpetre 0:9a72d42c0da3 19
lpetre 0:9a72d42c0da3 20 read_sensors();
lpetre 0:9a72d42c0da3 21 timestamp = timer.read_ms();
lpetre 0:9a72d42c0da3 22
lpetre 0:9a72d42c0da3 23 // GET PITCH
lpetre 0:9a72d42c0da3 24 // Using y-z-plane-component/x-component of gravity vector
lpetre 0:9a72d42c0da3 25 pitch = -atan2(accel[0], sqrt((double)(accel[1] * accel[1] + accel[2] * accel[2])));
lpetre 0:9a72d42c0da3 26
lpetre 0:9a72d42c0da3 27 // GET ROLL
lpetre 0:9a72d42c0da3 28 // Compensate pitch of gravity vector
lpetre 2:5aa75c3d8cc3 29
lpetre 0:9a72d42c0da3 30 Vector_Cross_Product(temp1, temp0, xAxis);
lpetre 0:9a72d42c0da3 31 Vector_Cross_Product(temp2, xAxis, temp1);
lpetre 0:9a72d42c0da3 32 // Normally using x-z-plane-component/y-component of compensated gravity vector
lpetre 0:9a72d42c0da3 33 // roll = atan2(temp2[1], sqrt(temp2[0] * temp2[0] + temp2[2] * temp2[2]));
lpetre 0:9a72d42c0da3 34 // Since we compensated for pitch, x-z-plane-component equals z-component:
lpetre 0:9a72d42c0da3 35 roll = atan2(temp2[1], temp2[2]);
lpetre 0:9a72d42c0da3 36
lpetre 0:9a72d42c0da3 37 // GET YAW
lpetre 0:9a72d42c0da3 38 Compass_Heading();
lpetre 0:9a72d42c0da3 39 yaw = MAG_Heading;
lpetre 0:9a72d42c0da3 40
lpetre 0:9a72d42c0da3 41 // Init rotation matrix
lpetre 0:9a72d42c0da3 42 init_rotation_matrix(DCM_Matrix, yaw, pitch, roll);
lpetre 0:9a72d42c0da3 43 }
lpetre 0:9a72d42c0da3 44
lpetre 0:9a72d42c0da3 45 // Apply calibration to raw sensor readings
lpetre 0:9a72d42c0da3 46 void IMU::compensate_sensor_errors() {
lpetre 0:9a72d42c0da3 47 // Compensate accelerometer error
lpetre 0:9a72d42c0da3 48 accel[0] = (accel[0] - ACCEL_X_OFFSET) * ACCEL_X_SCALE;
lpetre 0:9a72d42c0da3 49 accel[1] = (accel[1] - ACCEL_Y_OFFSET) * ACCEL_Y_SCALE;
lpetre 0:9a72d42c0da3 50 accel[2] = (accel[2] - ACCEL_Z_OFFSET) * ACCEL_Z_SCALE;
lpetre 0:9a72d42c0da3 51
lpetre 0:9a72d42c0da3 52 // Compensate magnetometer error
lpetre 0:9a72d42c0da3 53 magnetom[0] = (magnetom[0] - MAGN_X_OFFSET) * MAGN_X_SCALE;
lpetre 0:9a72d42c0da3 54 magnetom[1] = (magnetom[1] - MAGN_Y_OFFSET) * MAGN_Y_SCALE;
lpetre 0:9a72d42c0da3 55 magnetom[2] = (magnetom[2] - MAGN_Z_OFFSET) * MAGN_Z_SCALE;
lpetre 0:9a72d42c0da3 56
lpetre 0:9a72d42c0da3 57 // Compensate gyroscope error
lpetre 0:9a72d42c0da3 58 gyro[0] -= GYRO_AVERAGE_OFFSET_X;
lpetre 0:9a72d42c0da3 59 gyro[1] -= GYRO_AVERAGE_OFFSET_Y;
lpetre 0:9a72d42c0da3 60 gyro[2] -= GYRO_AVERAGE_OFFSET_Z;
lpetre 0:9a72d42c0da3 61 }
lpetre 0:9a72d42c0da3 62
lpetre 0:9a72d42c0da3 63 // Reset calibration session if reset_calibration_session_flag is set
lpetre 0:9a72d42c0da3 64 void IMU::check_reset_calibration_session() {
lpetre 0:9a72d42c0da3 65 // Raw sensor values have to be read already, but no error compensation applied
lpetre 0:9a72d42c0da3 66
lpetre 0:9a72d42c0da3 67 // Reset this calibration session?
lpetre 0:9a72d42c0da3 68 if (!reset_calibration_session_flag) return;
lpetre 0:9a72d42c0da3 69
lpetre 0:9a72d42c0da3 70 // Reset acc and mag calibration variables
lpetre 0:9a72d42c0da3 71 for (int i = 0; i < 3; i++) {
lpetre 0:9a72d42c0da3 72 accel_min[i] = accel_max[i] = accel[i];
lpetre 0:9a72d42c0da3 73 magnetom_min[i] = magnetom_max[i] = magnetom[i];
lpetre 0:9a72d42c0da3 74 }
lpetre 0:9a72d42c0da3 75
lpetre 0:9a72d42c0da3 76 // Reset gyro calibration variables
lpetre 0:9a72d42c0da3 77 gyro_num_samples = 0; // Reset gyro calibration averaging
lpetre 0:9a72d42c0da3 78 gyro_average[0] = gyro_average[1] = gyro_average[2] = 0;
lpetre 0:9a72d42c0da3 79
lpetre 0:9a72d42c0da3 80 reset_calibration_session_flag = false;
lpetre 0:9a72d42c0da3 81 }
lpetre 0:9a72d42c0da3 82
lpetre 0:9a72d42c0da3 83 void IMU::turn_output_stream_on() {
lpetre 0:9a72d42c0da3 84 output_stream_on = true;
lpetre 0:9a72d42c0da3 85 statusLed = 1;
lpetre 0:9a72d42c0da3 86 }
lpetre 0:9a72d42c0da3 87
lpetre 0:9a72d42c0da3 88 void IMU::turn_output_stream_off() {
lpetre 0:9a72d42c0da3 89 output_stream_on = false;
lpetre 0:9a72d42c0da3 90 statusLed = 0;
lpetre 0:9a72d42c0da3 91 }
lpetre 0:9a72d42c0da3 92
lpetre 0:9a72d42c0da3 93 // Blocks until another byte is available on serial port
lpetre 0:9a72d42c0da3 94 char IMU::readChar() {
lpetre 0:9a72d42c0da3 95 while (pc.rxBufferGetCount() < 1) { } // Block
lpetre 0:9a72d42c0da3 96 return pc.getc();
lpetre 0:9a72d42c0da3 97 }
lpetre 0:9a72d42c0da3 98
lpetre 2:5aa75c3d8cc3 99 void IMU::readInput() {
lpetre 0:9a72d42c0da3 100 // Read incoming control messages
lpetre 0:9a72d42c0da3 101 if (pc.rxBufferGetCount() >= 2) {
lpetre 0:9a72d42c0da3 102 if (pc.getc() == '#') { // Start of new control message
lpetre 0:9a72d42c0da3 103 int command = pc.getc(); // Commands
lpetre 0:9a72d42c0da3 104 if (command == 'f') // request one output _f_rame
lpetre 0:9a72d42c0da3 105 output_single_on = true;
lpetre 0:9a72d42c0da3 106 else if (command == 's') { // _s_ynch request
lpetre 0:9a72d42c0da3 107 // Read ID
lpetre 0:9a72d42c0da3 108 char id[2];
lpetre 0:9a72d42c0da3 109 id[0] = readChar();
lpetre 0:9a72d42c0da3 110 id[1] = readChar();
lpetre 0:9a72d42c0da3 111
lpetre 0:9a72d42c0da3 112 // Reply with synch message
lpetre 0:9a72d42c0da3 113 pc.printf("#SYNCH");
lpetre 0:9a72d42c0da3 114 pc.putc(id[0]);
lpetre 0:9a72d42c0da3 115 pc.putc(id[1]);
lpetre 0:9a72d42c0da3 116 pc.printf(NEW_LINE);
lpetre 0:9a72d42c0da3 117 } else if (command == 'o') { // Set _o_utput mode
lpetre 0:9a72d42c0da3 118 char output_param = readChar();
lpetre 0:9a72d42c0da3 119 if (output_param == 'n') { // Calibrate _n_ext sensor
lpetre 0:9a72d42c0da3 120 curr_calibration_sensor = (curr_calibration_sensor + 1) % 3;
lpetre 0:9a72d42c0da3 121 reset_calibration_session_flag = true;
lpetre 0:9a72d42c0da3 122 } else if (output_param == 't') // Output angles as _t_ext
lpetre 0:9a72d42c0da3 123 output_mode = OUTPUT__MODE_ANGLES_TEXT;
lpetre 0:9a72d42c0da3 124 else if (output_param == 'b') // Output angles in _b_inary form
lpetre 0:9a72d42c0da3 125 output_mode = OUTPUT__MODE_ANGLES_BINARY;
lpetre 0:9a72d42c0da3 126 else if (output_param == 'c') { // Go to _c_alibration mode
lpetre 0:9a72d42c0da3 127 output_mode = OUTPUT__MODE_CALIBRATE_SENSORS;
lpetre 0:9a72d42c0da3 128 reset_calibration_session_flag = true;
lpetre 0:9a72d42c0da3 129 } else if (output_param == 's') // Output _s_ensor values as text
lpetre 0:9a72d42c0da3 130 output_mode = OUTPUT__MODE_SENSORS_TEXT;
lpetre 0:9a72d42c0da3 131 else if (output_param == '0') { // Disable continuous streaming output
lpetre 0:9a72d42c0da3 132 turn_output_stream_off();
lpetre 0:9a72d42c0da3 133 reset_calibration_session_flag = true;
lpetre 0:9a72d42c0da3 134 } else if (output_param == '1') { // Enable continuous streaming output
lpetre 0:9a72d42c0da3 135 reset_calibration_session_flag = true;
lpetre 0:9a72d42c0da3 136 turn_output_stream_on();
lpetre 0:9a72d42c0da3 137 } else if (output_param == 'e') { // _e_rror output settings
lpetre 0:9a72d42c0da3 138 char error_param = readChar();
lpetre 0:9a72d42c0da3 139 if (error_param == '0') output_errors = false;
lpetre 0:9a72d42c0da3 140 else if (error_param == '1') output_errors = true;
lpetre 0:9a72d42c0da3 141 else if (error_param == 'c') { // get error count
lpetre 0:9a72d42c0da3 142 pc.printf("#AMG-ERR:%d,%d,%d" NEW_LINE,num_accel_errors,num_magn_errors,num_gyro_errors);
lpetre 0:9a72d42c0da3 143 }
lpetre 0:9a72d42c0da3 144 }
lpetre 0:9a72d42c0da3 145 }
lpetre 0:9a72d42c0da3 146 #if OUTPUT__HAS_RN_BLUETOOTH == true
lpetre 0:9a72d42c0da3 147 // Read messages from bluetooth module
lpetre 0:9a72d42c0da3 148 // For this to work, the connect/disconnect message prefix of the module has to be set to "#".
lpetre 0:9a72d42c0da3 149 else if (command == 'C') // Bluetooth "#CONNECT" message (does the same as "#o1")
lpetre 0:9a72d42c0da3 150 turn_output_stream_on();
lpetre 0:9a72d42c0da3 151 else if (command == 'D') // Bluetooth "#DISCONNECT" message (does the same as "#o0")
lpetre 0:9a72d42c0da3 152 turn_output_stream_off();
lpetre 0:9a72d42c0da3 153 #endif // OUTPUT__HAS_RN_BLUETOOTH == true
lpetre 0:9a72d42c0da3 154 } else { } // Skip character
lpetre 0:9a72d42c0da3 155 }
lpetre 2:5aa75c3d8cc3 156 }
lpetre 0:9a72d42c0da3 157
lpetre 2:5aa75c3d8cc3 158 IMU::IMU()
lpetre 2:5aa75c3d8cc3 159 : gyro_num_samples(0)
lpetre 2:5aa75c3d8cc3 160 , yaw(0)
lpetre 2:5aa75c3d8cc3 161 , pitch(0)
lpetre 2:5aa75c3d8cc3 162 , roll(0)
lpetre 2:5aa75c3d8cc3 163 , MAG_Heading(0)
lpetre 2:5aa75c3d8cc3 164 , timestamp(0)
lpetre 2:5aa75c3d8cc3 165 , timestamp_old(0)
lpetre 2:5aa75c3d8cc3 166 , G_Dt(0)
lpetre 2:5aa75c3d8cc3 167 , output_mode(-1) // Select your startup output mode here!// Select your startup output mode here!
lpetre 2:5aa75c3d8cc3 168 , output_stream_on(false)
lpetre 2:5aa75c3d8cc3 169 , output_single_on(true)
lpetre 2:5aa75c3d8cc3 170 , curr_calibration_sensor(0)
lpetre 2:5aa75c3d8cc3 171 , reset_calibration_session_flag(true)
lpetre 2:5aa75c3d8cc3 172 , num_accel_errors(0)
lpetre 2:5aa75c3d8cc3 173 , num_magn_errors(0)
lpetre 2:5aa75c3d8cc3 174 , num_gyro_errors(0)
lpetre 2:5aa75c3d8cc3 175 , output_errors(true)
lpetre 2:5aa75c3d8cc3 176 , statusLed(LED1)
lpetre 2:5aa75c3d8cc3 177 , pc(USBTX, USBRX)
lpetre 2:5aa75c3d8cc3 178 , Wire(p28, p27) {
lpetre 2:5aa75c3d8cc3 179
lpetre 2:5aa75c3d8cc3 180 accel[0] = accel_min[0] = accel_max[0] = magnetom[0] = magnetom_min[0] = magnetom_max[0] = gyro[0] = gyro_average[0] = 0;
lpetre 2:5aa75c3d8cc3 181 accel[1] = accel_min[1] = accel_max[1] = magnetom[1] = magnetom_min[1] = magnetom_max[1] = gyro[1] = gyro_average[1] = 0;
lpetre 2:5aa75c3d8cc3 182 accel[2] = accel_min[2] = accel_max[2] = magnetom[2] = magnetom_min[2] = magnetom_max[2] = gyro[2] = gyro_average[2] = 0;
lpetre 2:5aa75c3d8cc3 183
lpetre 2:5aa75c3d8cc3 184 Accel_Vector[0] = Gyro_Vector[0] = Omega_Vector[0] = Omega_P[0] = Omega_I[0] = Omega[0] = errorRollPitch[0] = errorYaw[0] = 0;
lpetre 2:5aa75c3d8cc3 185 Accel_Vector[1] = Gyro_Vector[1] = Omega_Vector[1] = Omega_P[1] = Omega_I[1] = Omega[1] = errorRollPitch[1] = errorYaw[1] = 0;
lpetre 2:5aa75c3d8cc3 186 Accel_Vector[2] = Gyro_Vector[2] = Omega_Vector[2] = Omega_P[2] = Omega_I[2] = Omega[2] = errorRollPitch[2] = errorYaw[2] = 0;
lpetre 0:9a72d42c0da3 187
lpetre 2:5aa75c3d8cc3 188 DCM_Matrix[0][0] = 1;
lpetre 2:5aa75c3d8cc3 189 DCM_Matrix[0][1] = 0;
lpetre 2:5aa75c3d8cc3 190 DCM_Matrix[0][2] = 0;
lpetre 2:5aa75c3d8cc3 191 DCM_Matrix[1][0] = 0;
lpetre 2:5aa75c3d8cc3 192 DCM_Matrix[1][1] = 1;
lpetre 2:5aa75c3d8cc3 193 DCM_Matrix[1][2] = 0;
lpetre 2:5aa75c3d8cc3 194 DCM_Matrix[2][0] = 0;
lpetre 2:5aa75c3d8cc3 195 DCM_Matrix[2][1] = 0;
lpetre 2:5aa75c3d8cc3 196 DCM_Matrix[2][2] = 1;
lpetre 2:5aa75c3d8cc3 197
lpetre 2:5aa75c3d8cc3 198 Update_Matrix[0][0] = 0;
lpetre 2:5aa75c3d8cc3 199 Update_Matrix[0][1] = 1;
lpetre 2:5aa75c3d8cc3 200 Update_Matrix[0][2] = 2;
lpetre 2:5aa75c3d8cc3 201 Update_Matrix[1][0] = 3;
lpetre 2:5aa75c3d8cc3 202 Update_Matrix[1][1] = 4;
lpetre 2:5aa75c3d8cc3 203 Update_Matrix[1][2] = 5;
lpetre 2:5aa75c3d8cc3 204 Update_Matrix[2][0] = 6;
lpetre 2:5aa75c3d8cc3 205 Update_Matrix[2][1] = 7;
lpetre 2:5aa75c3d8cc3 206 Update_Matrix[2][2] = 8;
lpetre 2:5aa75c3d8cc3 207
lpetre 2:5aa75c3d8cc3 208 Temporary_Matrix[0][0] = 0;
lpetre 2:5aa75c3d8cc3 209 Temporary_Matrix[0][1] = 0;
lpetre 2:5aa75c3d8cc3 210 Temporary_Matrix[0][2] = 0;
lpetre 2:5aa75c3d8cc3 211 Temporary_Matrix[1][0] = 0;
lpetre 2:5aa75c3d8cc3 212 Temporary_Matrix[1][1] = 0;
lpetre 2:5aa75c3d8cc3 213 Temporary_Matrix[1][2] = 0;
lpetre 2:5aa75c3d8cc3 214 Temporary_Matrix[2][0] = 0;
lpetre 2:5aa75c3d8cc3 215 Temporary_Matrix[2][1] = 0;
lpetre 2:5aa75c3d8cc3 216 Temporary_Matrix[2][2] = 0;
lpetre 0:9a72d42c0da3 217
lpetre 2:5aa75c3d8cc3 218 timer.start();
lpetre 2:5aa75c3d8cc3 219 // Init serial output
lpetre 2:5aa75c3d8cc3 220 pc.baud(OUTPUT__BAUD_RATE);
lpetre 2:5aa75c3d8cc3 221
lpetre 2:5aa75c3d8cc3 222 // Init status LED
lpetre 2:5aa75c3d8cc3 223 statusLed = 0;
lpetre 2:5aa75c3d8cc3 224
lpetre 2:5aa75c3d8cc3 225 // Init sensors
lpetre 2:5aa75c3d8cc3 226 wait_ms(50); // Give sensors enough time to start
lpetre 2:5aa75c3d8cc3 227 I2C_Init();
lpetre 2:5aa75c3d8cc3 228 Accel_Init();
lpetre 2:5aa75c3d8cc3 229 Magn_Init();
lpetre 2:5aa75c3d8cc3 230 Gyro_Init();
lpetre 2:5aa75c3d8cc3 231
lpetre 2:5aa75c3d8cc3 232 // Read sensors, init DCM algorithm
lpetre 2:5aa75c3d8cc3 233 wait_ms(20); // Give sensors enough time to collect data
lpetre 2:5aa75c3d8cc3 234 reset_sensor_fusion();
lpetre 2:5aa75c3d8cc3 235
lpetre 2:5aa75c3d8cc3 236 // Init output
lpetre 2:5aa75c3d8cc3 237 #if (OUTPUT__HAS_RN_BLUETOOTH == true) || (OUTPUT__STARTUP_STREAM_ON == false)
lpetre 2:5aa75c3d8cc3 238 turn_output_stream_off();
lpetre 2:5aa75c3d8cc3 239 #else
lpetre 2:5aa75c3d8cc3 240 turn_output_stream_on();
lpetre 2:5aa75c3d8cc3 241 #endif
lpetre 2:5aa75c3d8cc3 242 }
lpetre 0:9a72d42c0da3 243
lpetre 2:5aa75c3d8cc3 244 // Main loop
lpetre 2:5aa75c3d8cc3 245 void IMU::loop() {
lpetre 2:5aa75c3d8cc3 246 timestamp_old = timestamp;
lpetre 2:5aa75c3d8cc3 247 timestamp = timer.read_ms();
lpetre 2:5aa75c3d8cc3 248 if (timestamp > timestamp_old)
lpetre 2:5aa75c3d8cc3 249 G_Dt = (float) (timestamp - timestamp_old) / 1000.0f; // Real time of loop run. We use this on the DCM algorithm (gyro integration time)
lpetre 2:5aa75c3d8cc3 250 else
lpetre 2:5aa75c3d8cc3 251 G_Dt = 0;
lpetre 2:5aa75c3d8cc3 252
lpetre 2:5aa75c3d8cc3 253 // Update sensor readings
lpetre 2:5aa75c3d8cc3 254 read_sensors();
lpetre 0:9a72d42c0da3 255
lpetre 2:5aa75c3d8cc3 256 if (output_mode == OUTPUT__MODE_CALIBRATE_SENSORS) { // We're in calibration mode
lpetre 2:5aa75c3d8cc3 257 check_reset_calibration_session(); // Check if this session needs a reset
lpetre 2:5aa75c3d8cc3 258 if (output_stream_on || output_single_on)
lpetre 2:5aa75c3d8cc3 259 output_calibration(curr_calibration_sensor);
lpetre 2:5aa75c3d8cc3 260 } else if (output_mode == OUTPUT__MODE_SENSORS_TEXT) {
lpetre 2:5aa75c3d8cc3 261 // Apply sensor calibration
lpetre 2:5aa75c3d8cc3 262 compensate_sensor_errors();
lpetre 0:9a72d42c0da3 263
lpetre 2:5aa75c3d8cc3 264 if (output_stream_on || output_single_on)
lpetre 2:5aa75c3d8cc3 265 output_sensors();
lpetre 2:5aa75c3d8cc3 266 } else if (output_mode == OUTPUT__MODE_ANGLES_TEXT || output_mode == OUTPUT__MODE_ANGLES_BINARY) {
lpetre 2:5aa75c3d8cc3 267 // Apply sensor calibration
lpetre 2:5aa75c3d8cc3 268 compensate_sensor_errors();
lpetre 0:9a72d42c0da3 269
lpetre 2:5aa75c3d8cc3 270 // Run DCM algorithm
lpetre 2:5aa75c3d8cc3 271 Compass_Heading(); // Calculate magnetic heading
lpetre 2:5aa75c3d8cc3 272 Matrix_update();
lpetre 2:5aa75c3d8cc3 273 Normalize();
lpetre 2:5aa75c3d8cc3 274 Drift_correction();
lpetre 2:5aa75c3d8cc3 275 Euler_angles();
lpetre 2:5aa75c3d8cc3 276
lpetre 2:5aa75c3d8cc3 277 if (output_stream_on || output_single_on)
lpetre 2:5aa75c3d8cc3 278 output_angles();
lpetre 2:5aa75c3d8cc3 279 }
lpetre 2:5aa75c3d8cc3 280
lpetre 2:5aa75c3d8cc3 281 output_single_on = false;
lpetre 0:9a72d42c0da3 282
lpetre 0:9a72d42c0da3 283 #if DEBUG__PRINT_LOOP_TIME == true
lpetre 2:5aa75c3d8cc3 284 pc.printf("loop time (ms) = %f" NEW_LINE, timer.read_ms() - timestamp);
lpetre 0:9a72d42c0da3 285 #endif
lpetre 0:9a72d42c0da3 286 }
lpetre 2:5aa75c3d8cc3 287
lpetre 2:5aa75c3d8cc3 288 int main() {
lpetre 2:5aa75c3d8cc3 289 IMU imu;
lpetre 2:5aa75c3d8cc3 290
lpetre 2:5aa75c3d8cc3 291 Ticker looper;
lpetre 2:5aa75c3d8cc3 292 looper.attach(&imu, &IMU::loop, (float)OUTPUT__DATA_INTERVAL / 1000.0f); // 50Hz update
lpetre 2:5aa75c3d8cc3 293
lpetre 2:5aa75c3d8cc3 294 while (1)
lpetre 2:5aa75c3d8cc3 295 {
lpetre 2:5aa75c3d8cc3 296 imu.readInput();
lpetre 2:5aa75c3d8cc3 297 wait_ms(5);
lpetre 2:5aa75c3d8cc3 298 }
lpetre 2:5aa75c3d8cc3 299
lpetre 2:5aa75c3d8cc3 300 return 0;
lpetre 2:5aa75c3d8cc3 301 }