Mired in code
Check-in [1885651ed3]
Not logged in
Public Repositories
mwm's Repositories

Many hyperlinks are disabled.
Use anonymous login to enable hyperlinks.

Overview
Comment:Move calibration to a separate sketch.
Timelines: family | ancestors | descendants | both | trunk
Files: files | file ages | folders
SHA1:1885651ed3536c46ed4088e3e11ae9f682db1cc1
User & Date: mwm 2015-08-28 14:15:47
Context
2015-08-28
14:34
Add a note about running Calibrate to the calibration load failure message. check-in: bd54efccc5 user: mwm tags: trunk
14:15
Move calibration to a separate sketch. check-in: 1885651ed3 user: mwm tags: trunk
13:31
Save calibration data to eeprom after calibrating. check-in: 2c269f1a5e user: mwm tags: trunk
Changes
Hide Diffs Unified Diffs Ignore Whitespace Patch

Added Arduino/FloatController/Calibrate/Calibrate.ino.































































































































































































































































































































































































































































































































































































































































































>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
>
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
#define SERIAL_DEBUG
// I2C device class (I2Cdev) demonstration Arduino sketch for MPU6050 class using DMP (MotionApps v2.0)
// 6/21/2012 by Jeff Rowberg <jeff@rowberg.net>
// Updates should (hopefully) always be available at https://github.com/jrowberg/i2cdevlib
//
// Modified 2015 as initial version of FloatController by Mike Meyer <mwm@mired.org>
//

/* ============================================
I2Cdev device library code is placed under the MIT license
Copyright (c) 2012 Jeff Rowberg
Copyright (c) 2015 Mike Meyer

===============================================
*/

// I2Cdev and MPU6050 must be installed as libraries, or else the .cpp/.h files
// for both classes must be in the include path of your project
#include "I2Cdev.h"

#include "MPU6050_6Axis_MotionApps20.h"

// Arduino Wire library is required if I2Cdev I2CDEV_ARDUINO_WIRE implementation
// is used in I2Cdev.h
#if I2CDEV_IMPLEMENTATION == I2CDEV_ARDUINO_WIRE
    #include <Wire.h>
#endif

#include <EEPROM.h>

// class default I2C address is 0x68
// specific I2C addresses may be passed as a parameter here
// AD0 low = 0x68 (default for SparkFun breakout and InvenSense evaluation board)
// AD0 high = 0x69
MPU6050 mpu;
//MPU6050 mpu(0x69); // <-- use for AD0 high


#define LED_PIN 13  // We turn the LED on if everything is OK, off otherwise
#define ROLL_PIN 5  // PWM output for roll value

// MPU control/status vars
bool dmpReady = false;  // set true if DMP init was successful
uint8_t mpuIntStatus;   // holds actual interrupt status byte from MPU
uint8_t devStatus;      // return status after each device operation (0 = success, !0 = error)
uint16_t packetSize;    // expected DMP packet size (default is 42 bytes)
uint16_t fifoCount;     // count of all bytes currently in FIFO
uint8_t fifoBuffer[64]; // FIFO storage buffer

// orientation/motion vars
Quaternion q;           // [w, x, y, z]         quaternion container
VectorFloat gravity;    // [x, y, z]            gravity vector
float ypr[3];           // [yaw, pitch, roll]   yaw/pitch/roll container and gravity vector


// ================================================================
// ===               INTERRUPT DETECTION ROUTINE                ===
// ================================================================

volatile bool mpuInterrupt = false;     // indicates whether MPU interrupt pin has gone high
void dmpDataReady() {
    mpuInterrupt = true;
}


// ================================================================
// ===                      INITIAL SETUP                       ===
// ================================================================
bool calibrated;
void calibrate();

void setup() {
    // join I2C bus (I2Cdev library doesn't do this automatically)
    #if I2CDEV_IMPLEMENTATION == I2CDEV_ARDUINO_WIRE
        Wire.begin();
        TWBR = 24; // 400kHz I2C clock (200kHz if CPU is 8MHz)
    #elif I2CDEV_IMPLEMENTATION == I2CDEV_BUILTIN_FASTWIRE
        Fastwire::setup(400, true);
    #endif

    // Set up the output pins.
    pinMode(LED_PIN, OUTPUT);
    pinMode(ROLL_PIN, OUTPUT);

#ifdef	SERIAL_DEBUG
    // initialize serial communication
    Serial.begin(115200);
    while (!Serial); // wait for Leonardo enumeration, others continue immediately
#endif

    // initialize device
#ifdef	SERIAL_DEBUG
    Serial.println(F("Initializing I2C devices..."));
#endif
    mpu.initialize();

    // verify connection
#ifdef	SERIAL_DEBUG
    Serial.println(F("Testing device connections..."));
    Serial.println(mpu.testConnection() ? F("MPU6050 connection successful") : F("MPU6050 connection failed"));
#else
    mpu.testConnection();
#endif

    // wait for ready
#ifdef	SERIAL_DEBUG
    Serial.println(F("\nSend any character to begin DMP programming and demo: "));
    while (Serial.available() && Serial.read()); // empty buffer
    while (!Serial.available());                 // wait for data
    while (Serial.available() && Serial.read()); // empty buffer again

    // load and configure the DMPf
    Serial.println(F("Initializing DMP..."));
#endif
    devStatus = mpu.dmpInitialize();

    // make sure it worked (returns 0 if so)
    if (devStatus == 0) {
        // turn on the DMP, now that it's ready
#ifdef	SERIAL_DEBUG
        Serial.println(F("Enabling DMP..."));
#endif
        mpu.setDMPEnabled(true);

        // enable Arduino interrupt detection
#ifdef	SERIAL_DEBUG
        Serial.println(F("Enabling interrupt detection (Arduino external interrupt 0)..."));
#endif
        attachInterrupt(0, dmpDataReady, RISING);
        mpuIntStatus = mpu.getIntStatus();

        // set our DMP Ready flag so the main loop() function knows it's okay to use it
#ifdef	SERIAL_DEBUG
        Serial.println(F("DMP ready! Waiting for first interrupt..."));
#endif
        dmpReady = true;

        // get expected DMP packet size for later comparison
        packetSize = mpu.dmpGetFIFOPacketSize();
        calibrate();
        digitalWrite(LED_PIN, HIGH);
    } else {
        // ERROR!
        // 1 = initial memory load failed
        // 2 = DMP configuration updates failed
        // (if it's going to break, usually the code will be 1)
#ifdef	SERIAL_DEBUG
        Serial.print(F("DMP Initialization failed (code "));
        Serial.print(devStatus);
        Serial.println(F(")"));
#endif
        digitalWrite(LED_PIN, LOW);
    }
}

void loop() { }

/**********************************************
 * Additional calibration code by luisrodenas *
 **********************************************/
// Change this 3 variables if you want to fine tune the skecth to your needs.
int buffersize = 1000;   //Amount of readings used to average, make it higher to get more precision but sketch will be slower  (default:1000)
int acel_deadzone = 8;   //Acelerometer error allowed, make it lower to get more precision, but sketch may not converge  (default:8)
int giro_deadzone = 1;   //Giro error allowed, make it lower to get more precision, but sketch may not converge  (default:1)
int16_t ax, ay, az, gx, gy, gz;

int mean_ax, mean_ay, mean_az, mean_gx, mean_gy, mean_gz;
int ax_offset, ay_offset, az_offset, gx_offset, gy_offset, gz_offset;

void calibrate()
{
  void calibration(), meansensors(), saveCalibration(), setCalibration();

#ifdef SERIAL_DEBUG
  Serial.print(F("Calibrating..."));
#endif

  // Shut things down.
  mpu.setDMPEnabled(false);
  detachInterrupt(0);

  // Reset offsets
  mpu.setXAccelOffset(0);
  mpu.setYAccelOffset(0);
  mpu.setZAccelOffset(0);
  mpu.setXGyroOffset(0);
  mpu.setYGyroOffset(0);
  mpu.setZGyroOffset(0);

  delay(100);

#ifdef SERIAL_DEBUG
  Serial.print(F("state 0..."));
#endif
  meansensors();
  delay(1000);

#ifdef SERIAL_DEBUG
  Serial.print(F("state 1..."));
#endif
  calibration();
  delay(1000);

  meansensors();
  setCalibration();
  calibrated = true;
  saveCalibration();

#ifdef SERIAL_DEBUG
  Serial.println("done!");
  Serial.print("\nSensor readings with offsets:\t");
  Serial.print(mean_ax); 
  Serial.print("\t");
  Serial.print(mean_ay); 
  Serial.print("\t");
  Serial.print(mean_az); 
  Serial.print("\t");
  Serial.print(mean_gx); 
  Serial.print("\t");
  Serial.print(mean_gy); 
  Serial.print("\t");
  Serial.println(mean_gz);
  Serial.println("Values should be close to 0 0 16384 0 0 0");
#endif

  // Start us up again.
  mpu.setDMPEnabled(true);
  attachInterrupt(0, dmpDataReady, RISING);
  mpuIntStatus = mpu.getIntStatus();

  digitalWrite(LED_PIN, HIGH);
}

///////////////////////////////////   FUNCTIONS   ////////////////////////////////////
void meansensors() {
  long i = 0, buff_ax = 0, buff_ay = 0, buff_az = 0, buff_gx = 0, buff_gy = 0, buff_gz = 0;
  static int blinkstate = 0 ;

  while (i < (buffersize + 101)) {
    analogWrite(LED_PIN, blinkstate += 1);
    if (blinkstate > 255) blinkstate = 0;

    // read raw accel/gyro measurements from device
    mpu.getMotion6(&ax, &ay, &az, &gx, &gy, &gz);

    if (i > 100 && i <= (buffersize + 100)) { //First 100 measures are discarded
      buff_ax = buff_ax + ax;
      buff_ay = buff_ay + ay;
      buff_az = buff_az + az;
      buff_gx = buff_gx + gx;
      buff_gy = buff_gy + gy;
      buff_gz = buff_gz + gz;
    }
    if (i == (buffersize + 100)) {
      mean_ax = buff_ax / buffersize;
      mean_ay = buff_ay / buffersize;
      mean_az = buff_az / buffersize;
      mean_gx = buff_gx / buffersize;
      mean_gy = buff_gy / buffersize;
      mean_gz = buff_gz / buffersize;
    }
    i++;
    delay(2); //Needed so we don't get repeated measures
  }
}

void calibration() {
  ax_offset = -mean_ax / 8;
  ay_offset = -mean_ay / 8;
  az_offset = (16384 - mean_az) / 8;

  gx_offset = -mean_gx / 4;
  gy_offset = -mean_gy / 4;
  gz_offset = -mean_gz / 4;
  while (1) {
    int ready = 0;
    mpu.setXAccelOffset(ax_offset);
    mpu.setYAccelOffset(ay_offset);
    mpu.setZAccelOffset(az_offset);

    mpu.setXGyroOffset(gx_offset);
    mpu.setYGyroOffset(gy_offset);
    mpu.setZGyroOffset(gz_offset);

    meansensors();

    if (abs(mean_ax) <= acel_deadzone) ready++;
    else ax_offset = ax_offset - mean_ax / acel_deadzone;

    if (abs(mean_ay) <= acel_deadzone) ready++;
    else ay_offset = ay_offset - mean_ay / acel_deadzone;

    if (abs(16384 - mean_az) <= acel_deadzone) ready++;
    else az_offset = az_offset + (16384 - mean_az) / acel_deadzone;

    if (abs(mean_gx) <= giro_deadzone) ready++;
    else gx_offset = gx_offset - mean_gx / (giro_deadzone + 1);

    if (abs(mean_gy) <= giro_deadzone) ready++;
    else gy_offset = gy_offset - mean_gy / (giro_deadzone + 1);

    if (abs(mean_gz) <= giro_deadzone) ready++;
    else gz_offset = gz_offset - mean_gz / (giro_deadzone + 1);

    if (ready == 6) break;
  }
}

// Save/restore our EEPROM values.
void
saveCalibration() {
  EEPROM.write(0, 0x01);	// Version number
  EEPROM.write(1, ax_offset & 0xFF);
  EEPROM.write(2, ax_offset >> 8);
  EEPROM.write(3, ay_offset & 0xFF);
  EEPROM.write(4, ay_offset >> 8);
  EEPROM.write(5, az_offset & 0xFF);
  EEPROM.write(6, az_offset >> 8);
  EEPROM.write(7, gx_offset & 0xFF);
  EEPROM.write(8, gx_offset >> 8);
  EEPROM.write(9, gy_offset & 0xFF);
  EEPROM.write(10, gy_offset >> 8);
  EEPROM.write(11, gz_offset & 0xFF);
  EEPROM.write(12, gz_offset >> 8);
}

void
setCalibration() {
  mpu.setXGyroOffset(gx_offset);
  mpu.setYGyroOffset(gy_offset);
  mpu.setZGyroOffset(gz_offset);
  mpu.setXAccelOffset(ax_offset);
  mpu.setYAccelOffset(ay_offset);
  mpu.setZAccelOffset(az_offset);
}

Added Arduino/FloatController/Calibrate/Makefile.







>
>
>
1
2
3
ARDUINO_LIBS = I2Cdev MPU6050 Wire Wire/utility EEPROM

include ../../Makefile

Changes to Arduino/FloatController/FloatController.ino.

1
2
3
4
5
6
7
8
..
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
...
113
114
115
116
117
118
119






120
121
122
123











124
125
126
127
128
129
130
...
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156

157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
...
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404

405
406
407
408
409
410
411
412

413
414
415
416
417
418
419
420
421
422
423
// #define SERIAL_DEBUG
// I2C device class (I2Cdev) demonstration Arduino sketch for MPU6050 class using DMP (MotionApps v2.0)
// 6/21/2012 by Jeff Rowberg <jeff@rowberg.net>
// Updates should (hopefully) always be available at https://github.com/jrowberg/i2cdevlib
//
// Modified 2015 as initial version of FloatController by Mike Meyer <mwm@mired.org>
//

................................................................................
// ================================================================

volatile bool mpuInterrupt = false;     // indicates whether MPU interrupt pin has gone high
void dmpDataReady() {
    mpuInterrupt = true;
}


// ================================================================
// ===                      INITIAL SETUP                       ===
// ================================================================
bool calibrated;

void setup() {
    void loadCalibration(), setCalibration();

    loadCalibration();

    // join I2C bus (I2Cdev library doesn't do this automatically)
    #if I2CDEV_IMPLEMENTATION == I2CDEV_ARDUINO_WIRE
        Wire.begin();
        TWBR = 24; // 400kHz I2C clock (200kHz if CPU is 8MHz)
    #elif I2CDEV_IMPLEMENTATION == I2CDEV_BUILTIN_FASTWIRE
        Fastwire::setup(400, true);
    #endif

    // Set up the output pins.
    pinMode(LED_PIN, OUTPUT);
    pinMode(ROLL_PIN, OUTPUT);

#ifdef	SERIAL_DEBUG
    // initialize serial communication
................................................................................
    while (Serial.available() && Serial.read()); // empty buffer again

    // load and configure the DMPf
    Serial.println(F("Initializing DMP..."));
#endif
    devStatus = mpu.dmpInitialize();







    setCalibration();

    // make sure it worked (returns 0 if so)
    if (devStatus == 0) {











        // turn on the DMP, now that it's ready
#ifdef	SERIAL_DEBUG
        Serial.println(F("Enabling DMP..."));
#endif
        mpu.setDMPEnabled(true);

        // enable Arduino interrupt detection
................................................................................
        Serial.println(F("DMP ready! Waiting for first interrupt..."));
#endif
        dmpReady = true;

        // get expected DMP packet size for later comparison
        packetSize = mpu.dmpGetFIFOPacketSize();
        digitalWrite(LED_PIN, HIGH);
    } else {
        // ERROR!
        // 1 = initial memory load failed
        // 2 = DMP configuration updates failed
        // (if it's going to break, usually the code will be 1)
#ifdef	SERIAL_DEBUG
        Serial.print(F("DMP Initialization failed (code "));
        Serial.print(devStatus);
        Serial.println(F(")"));
#endif
        digitalWrite(LED_PIN, LOW);

    }
}



// ================================================================
// ===                    MAIN PROGRAM LOOP                     ===
// ================================================================
void loop() {
    void calibrate();

    // For now, we just do this at install time. Add some way to control it later.
    if (!calibrated) calibrate();

    // if programming failed, don't try to do anything
    if (!dmpReady) return;

    // wait for MPU interrupt or extra packet(s) available
    while (!mpuInterrupt && fifoCount < packetSize) {
        // other program behavior stuff here
        // .
................................................................................
        Serial.print("\t");
        Serial.println(min(abs(ypr[1]) * 510 / M_PI, 1023));
        /* Serial.println(ypr[2] * 180/M_PI); */
#endif
    }
}

/**********************************************
 * Additional calibration code by luisrodenas *
 **********************************************/
// Change this 3 variables if you want to fine tune the skecth to your needs.
int buffersize = 1000;   //Amount of readings used to average, make it higher to get more precision but sketch will be slower  (default:1000)
int acel_deadzone = 8;   //Acelerometer error allowed, make it lower to get more precision, but sketch may not converge  (default:8)
int giro_deadzone = 1;   //Giro error allowed, make it lower to get more precision, but sketch may not converge  (default:1)
int16_t ax, ay, az, gx, gy, gz;

int mean_ax, mean_ay, mean_az, mean_gx, mean_gy, mean_gz;
int ax_offset, ay_offset, az_offset, gx_offset, gy_offset, gz_offset;

void calibrate()
{
  void calibration(), meansensors(), saveCalibration(), setCalibration();

#ifdef SERIAL_DEBUG
  Serial.print(F("Calibrating..."));
#endif

  // Shut things down.
  mpu.setDMPEnabled(false);
  detachInterrupt(0);

  // Reset offsets
  mpu.setXAccelOffset(0);
  mpu.setYAccelOffset(0);
  mpu.setZAccelOffset(0);
  mpu.setXGyroOffset(0);
  mpu.setYGyroOffset(0);
  mpu.setZGyroOffset(0);

  delay(100);

#ifdef SERIAL_DEBUG
  Serial.print(F("state 0..."));
#endif
  meansensors();
  delay(1000);

#ifdef SERIAL_DEBUG
  Serial.print(F("state 1..."));
#endif
  calibration();
  delay(1000);

  meansensors();
  setCalibration();
  calibrated = true;
  saveCalibration();

#ifdef SERIAL_DEBUG
  Serial.println("done!");
  Serial.print("\nSensor readings with offsets:\t");
  Serial.print(mean_ax); 
  Serial.print("\t");
  Serial.print(mean_ay); 
  Serial.print("\t");
  Serial.print(mean_az); 
  Serial.print("\t");
  Serial.print(mean_gx); 
  Serial.print("\t");
  Serial.print(mean_gy); 
  Serial.print("\t");
  Serial.println(mean_gz);
  Serial.println("Values should be close to 0 0 16384 0 0 0");
#endif

  // Start us up again.
  mpu.setDMPEnabled(true);
  attachInterrupt(0, dmpDataReady, RISING);
  mpuIntStatus = mpu.getIntStatus();

  digitalWrite(LED_PIN, HIGH);
}

///////////////////////////////////   FUNCTIONS   ////////////////////////////////////
void meansensors() {
  long i = 0, buff_ax = 0, buff_ay = 0, buff_az = 0, buff_gx = 0, buff_gy = 0, buff_gz = 0;
  static int blinkstate = 0 ;

  while (i < (buffersize + 101)) {
    analogWrite(LED_PIN, blinkstate += 1);
    if (blinkstate > 255) blinkstate = 0;

    // read raw accel/gyro measurements from device
    mpu.getMotion6(&ax, &ay, &az, &gx, &gy, &gz);

    if (i > 100 && i <= (buffersize + 100)) { //First 100 measures are discarded
      buff_ax = buff_ax + ax;
      buff_ay = buff_ay + ay;
      buff_az = buff_az + az;
      buff_gx = buff_gx + gx;
      buff_gy = buff_gy + gy;
      buff_gz = buff_gz + gz;
    }
    if (i == (buffersize + 100)) {
      mean_ax = buff_ax / buffersize;
      mean_ay = buff_ay / buffersize;
      mean_az = buff_az / buffersize;
      mean_gx = buff_gx / buffersize;
      mean_gy = buff_gy / buffersize;
      mean_gz = buff_gz / buffersize;
    }
    i++;
    delay(2); //Needed so we don't get repeated measures
  }
}

void calibration() {
  ax_offset = -mean_ax / 8;
  ay_offset = -mean_ay / 8;
  az_offset = (16384 - mean_az) / 8;

  gx_offset = -mean_gx / 4;
  gy_offset = -mean_gy / 4;
  gz_offset = -mean_gz / 4;
  while (1) {
    int ready = 0;
    mpu.setXAccelOffset(ax_offset);
    mpu.setYAccelOffset(ay_offset);
    mpu.setZAccelOffset(az_offset);

    mpu.setXGyroOffset(gx_offset);
    mpu.setYGyroOffset(gy_offset);
    mpu.setZGyroOffset(gz_offset);

    meansensors();

    if (abs(mean_ax) <= acel_deadzone) ready++;
    else ax_offset = ax_offset - mean_ax / acel_deadzone;

    if (abs(mean_ay) <= acel_deadzone) ready++;
    else ay_offset = ay_offset - mean_ay / acel_deadzone;

    if (abs(16384 - mean_az) <= acel_deadzone) ready++;
    else az_offset = az_offset + (16384 - mean_az) / acel_deadzone;

    if (abs(mean_gx) <= giro_deadzone) ready++;
    else gx_offset = gx_offset - mean_gx / (giro_deadzone + 1);

    if (abs(mean_gy) <= giro_deadzone) ready++;
    else gy_offset = gy_offset - mean_gy / (giro_deadzone + 1);

    if (abs(mean_gz) <= giro_deadzone) ready++;
    else gz_offset = gz_offset - mean_gz / (giro_deadzone + 1);

    if (ready == 6) break;
  }
}

// Save/restore our EEPROM values.
void
saveCalibration() {
  EEPROM.write(0, calibrated);
  EEPROM.write(1, ax_offset & 0xFF);
  EEPROM.write(2, ax_offset >> 8);
  EEPROM.write(3, ay_offset & 0xFF);
  EEPROM.write(4, ay_offset >> 8);
  EEPROM.write(5, az_offset & 0xFF);
  EEPROM.write(6, az_offset >> 8);
  EEPROM.write(7, gx_offset & 0xFF);
  EEPROM.write(8, gx_offset >> 8);
  EEPROM.write(9, gy_offset & 0xFF);
  EEPROM.write(10, gy_offset >> 8);
  EEPROM.write(11, gz_offset & 0xFF);
  EEPROM.write(12, gz_offset >> 8);
}

void

loadCalibration() {
  calibrated = EEPROM.read(0);
  ax_offset = EEPROM.read(1) | (EEPROM.read(2) << 8);
  ay_offset = EEPROM.read(3) | (EEPROM.read(4) << 8);
  az_offset = EEPROM.read(5) | (EEPROM.read(6) << 8);
  gx_offset = EEPROM.read(7) | (EEPROM.read(8) << 8);
  gy_offset = EEPROM.read(9) | (EEPROM.read(10) << 8);
  gz_offset = EEPROM.read(11) | (EEPROM.read(12) << 8);

}

void
setCalibration() {
  mpu.setXGyroOffset(gx_offset);
  mpu.setYGyroOffset(gy_offset);
  mpu.setZGyroOffset(gz_offset);
  mpu.setXAccelOffset(ax_offset);
  mpu.setYAccelOffset(ay_offset);
  mpu.setZAccelOffset(az_offset);
}
|







 







<



<
<

|
<
|


|
|
|
|
|
|







 







>
>
>
>
>
>
|

|
|
>
>
>
>
>
>
>
>
>
>
>







 







<
<
<
<
<
<
<
<
<
<
<
>









<
<
<
<
<







 







<
<
<
<
<
<
<
<
<
<
|
<
<
<
<
<
<
<
<
<
<
<
<
<
<
<
<
<
<
<
<
<
<
<
<
<
<
<
<
<
<
<
<
<
<
<
<
<
<
<
<
<
<
<
<
<
<
<
<
<
<
<
<
<
<
<
<
<
<
<
<
<
<
<
<
<
<
<
<
<
<
<
<
<
<
<
<
<
<
<
<
<
<
<
<
<
<
<
<
<
<
<
<
<
<
<
<
<
<
<
<
<
<
<
<
<
<
<
<
<
<
<
<
<
<
<
<
<
<
<
<
<
<
<
<
<
<
<
<
<
<
<
<
<
<
<
<
<
<
<
<
<
<
<
<
<
<
<
<
<
<
<
<
<
<
<
<
<
<
<
>

|






>











1
2
3
4
5
6
7
8
..
58
59
60
61
62
63
64

65
66
67


68
69

70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
...
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
...
152
153
154
155
156
157
158











159
160
161
162
163
164
165
166
167
168





169
170
171
172
173
174
175
...
226
227
228
229
230
231
232










233































































































































































234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
#define SERIAL_DEBUG
// I2C device class (I2Cdev) demonstration Arduino sketch for MPU6050 class using DMP (MotionApps v2.0)
// 6/21/2012 by Jeff Rowberg <jeff@rowberg.net>
// Updates should (hopefully) always be available at https://github.com/jrowberg/i2cdevlib
//
// Modified 2015 as initial version of FloatController by Mike Meyer <mwm@mired.org>
//

................................................................................
// ================================================================

volatile bool mpuInterrupt = false;     // indicates whether MPU interrupt pin has gone high
void dmpDataReady() {
    mpuInterrupt = true;
}


// ================================================================
// ===                      INITIAL SETUP                       ===
// ================================================================


void setup() {
    bool loadCalibration();

    void setCalibration();

    // join I2C bus (I2Cdev library doesn't do this automatically)
#if I2CDEV_IMPLEMENTATION == I2CDEV_ARDUINO_WIRE
    Wire.begin();
    TWBR = 24; // 400kHz I2C clock (200kHz if CPU is 8MHz)
#elif I2CDEV_IMPLEMENTATION == I2CDEV_BUILTIN_FASTWIRE
    Fastwire::setup(400, true);
#endif

    // Set up the output pins.
    pinMode(LED_PIN, OUTPUT);
    pinMode(ROLL_PIN, OUTPUT);

#ifdef	SERIAL_DEBUG
    // initialize serial communication
................................................................................
    while (Serial.available() && Serial.read()); // empty buffer again

    // load and configure the DMPf
    Serial.println(F("Initializing DMP..."));
#endif
    devStatus = mpu.dmpInitialize();

    if (!loadCalibration()) {
#ifdef SERIAL_DEBUG
      Serial.println(F("MPU not calibrated, or calibrated for wrong firmware."));
#endif
      digitalWrite(LED_PIN, LOW);
    } else {
      setCalibration();

      // make sure it worked (returns 0 if so)
      if (devStatus != 0) {
        // ERROR!
        // 1 = initial memory load failed
        // 2 = DMP configuration updates failed
        // (if it's going to break, usually the code will be 1)
#ifdef	SERIAL_DEBUG
        Serial.print(F("DMP Initialization failed (code "));
        Serial.print(devStatus);
        Serial.println(F(")"));
#endif
        digitalWrite(LED_PIN, LOW);
      } else {
        // turn on the DMP, now that it's ready
#ifdef	SERIAL_DEBUG
        Serial.println(F("Enabling DMP..."));
#endif
        mpu.setDMPEnabled(true);

        // enable Arduino interrupt detection
................................................................................
        Serial.println(F("DMP ready! Waiting for first interrupt..."));
#endif
        dmpReady = true;

        // get expected DMP packet size for later comparison
        packetSize = mpu.dmpGetFIFOPacketSize();
        digitalWrite(LED_PIN, HIGH);











      }
    }
}



// ================================================================
// ===                    MAIN PROGRAM LOOP                     ===
// ================================================================
void loop() {





    // if programming failed, don't try to do anything
    if (!dmpReady) return;

    // wait for MPU interrupt or extra packet(s) available
    while (!mpuInterrupt && fifoCount < packetSize) {
        // other program behavior stuff here
        // .
................................................................................
        Serial.print("\t");
        Serial.println(min(abs(ypr[1]) * 510 / M_PI, 1023));
        /* Serial.println(ypr[2] * 180/M_PI); */
#endif
    }
}











static int ax_offset, ay_offset, az_offset, gx_offset, gy_offset, gz_offset;































































































































































bool
loadCalibration() {
  if (EEPROM.read(0) != 0x01) return false;
  ax_offset = EEPROM.read(1) | (EEPROM.read(2) << 8);
  ay_offset = EEPROM.read(3) | (EEPROM.read(4) << 8);
  az_offset = EEPROM.read(5) | (EEPROM.read(6) << 8);
  gx_offset = EEPROM.read(7) | (EEPROM.read(8) << 8);
  gy_offset = EEPROM.read(9) | (EEPROM.read(10) << 8);
  gz_offset = EEPROM.read(11) | (EEPROM.read(12) << 8);
  return true;
}

void
setCalibration() {
  mpu.setXGyroOffset(gx_offset);
  mpu.setYGyroOffset(gy_offset);
  mpu.setZGyroOffset(gz_offset);
  mpu.setXAccelOffset(ax_offset);
  mpu.setYAccelOffset(ay_offset);
  mpu.setZAccelOffset(az_offset);
}

Changes to Arduino/FloatController/Makefile.

1
2
3
ARDUINO_LIBS = I2Cdev MPU6050 Wire Wire/utility EEPROM

include ../Makefile


|
1
2
3
ARDUINO_LIBS = I2Cdev MPU6050 Wire Wire/utility EEPROM

include ../../Makefile