
UCR Robosub manual control / PID tuning interface
Revision 0:048a74dd7c3a, committed 2017-07-22
- Comitter:
- roger_wee
- Date:
- Sat Jul 22 05:58:03 2017 +0000
- Child:
- 1:3f291f2f80d3
- Commit message:
- UCR Robosub Manual Control / PID tuning interface
Changed in this revision
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/PID.cpp Sat Jul 22 05:58:03 2017 +0000 @@ -0,0 +1,203 @@ +/********************************************************************************************** + * Arduino PID Library - Version 1.0.1 + * by Brett Beauregard <br3ttb@gmail.com> brettbeauregard.com + * + * This Library is licensed under a GPLv3 License + **********************************************************************************************/ +#include <PID.h> +//Serial cp(USBTX, USBRX); // tx, rx + +/*Constructor (...)********************************************************* + * The parameters specified here are those for for which we can't set up + * reliable defaults, so we need to have the user set them. + ***************************************************************************/ +PID::PID(double* Input, double* Output, double* Setpoint, + double Kp, double Ki, double Kd, int ControllerDirection) +{ + + myOutput = Output; + myInput = Input; + mySetpoint = Setpoint; + inAuto = false; + + PID::SetOutputLimits(0, 255); //default output limit corresponds to + //the arduino pwm limits + + SampleTime = 100; //default Controller Sample Time is 0.1 seconds + + PID::SetControllerDirection(ControllerDirection); + PID::SetTunings(Kp, Ki, Kd); + + lastTime = t.read_us()-SampleTime; +} + + +/* Compute() ********************************************************************** + * This, as they say, is where the magic happens. this function should be called + * every time "void loop()" executes. the function will decide for itself whether a new + * pid Output needs to be computed. returns true when the output is computed, + * false when nothing has been done. + **********************************************************************************/ + +Serial pt(USBTX, USBRX); // tx, rx + +bool PID::Compute() +{ + if(!inAuto) return false; + unsigned long now = t.read_us(); + unsigned long timeChange = (now - lastTime); + + //cp.printf("%f, %f, %f\n\r", timeChange, SampleTime, lastTime); + if(timeChange>=SampleTime) + { + /*Compute all the working error variables*/ + double input = *myInput; + + + double error = *mySetpoint - input; + //pt.printf("pid1: %f, %f, %f, %f\n\r", error, error, *mySetpoint, input); + + ITerm+= (ki * error); + if(ITerm > outMax) ITerm= outMax; + else if(ITerm < outMin) ITerm= outMin; + double dInput = (input - lastInput); + + /*Compute PID Output*/ + double output = kp * error + ITerm - kd * dInput; + + //pt.printf("pid2: %f, %f, %f, %f, %f\n\r", error, output, *mySetpoint, input, ITerm); + + if(output > outMax) output = outMax; + else if(output < outMin) output = outMin; + *myOutput = output; + + //pt.printf("pid3: %f, %f, %f, %f, %f\n\r", error, output, *mySetpoint, input, ki); + + /*Remember some variables for next time*/ + lastInput = input; + lastTime = now; + return true; + } + else return false; +} + + +/* SetTunings(...)************************************************************* + * This function allows the controller's dynamic performance to be adjusted. + * it's called automatically from the constructor, but tunings can also + * be adjusted on the fly during normal operation + ******************************************************************************/ +void PID::SetTunings(double Kp, double Ki, double Kd) +{ + if (Kp<0 || Ki<0 || Kd<0) return; + + dispKp = Kp; dispKi = Ki; dispKd = Kd; + + double SampleTimeInSec = ((double)SampleTime)/1000; + kp = Kp; + ki = Ki * SampleTimeInSec; + kd = Kd / SampleTimeInSec; + + if(controllerDirection ==REVERSE) + { + kp = (0 - kp); + ki = (0 - ki); + kd = (0 - kd); + } + ITerm = 0.0; +} + +/* SetSampleTime(...) ********************************************************* + * sets the period, in Milliseconds, at which the calculation is performed + ******************************************************************************/ +void PID::SetSampleTime(int NewSampleTime) +{ + if (NewSampleTime > 0) + { + double ratio = (double)NewSampleTime + / (double)SampleTime; + ki *= ratio; + kd /= ratio; + SampleTime = (unsigned long)NewSampleTime; + } +} + +/* SetOutputLimits(...)**************************************************** + * This function will be used far more often than SetInputLimits. while + * the input to the controller will generally be in the 0-1023 range (which is + * the default already,) the output will be a little different. maybe they'll + * be doing a time window and will need 0-8000 or something. or maybe they'll + * want to clamp it from 0-125. who knows. at any rate, that can all be done + * here. + **************************************************************************/ +void PID::SetOutputLimits(double Min, double Max) +{ + if(Min >= Max) return; + outMin = Min; + outMax = Max; + + if(inAuto) + { + if(*myOutput > outMax) *myOutput = outMax; + else if(*myOutput < outMin) *myOutput = outMin; + + if(ITerm > outMax) ITerm= outMax; + else if(ITerm < outMin) ITerm= outMin; + } +} + +/* SetMode(...)**************************************************************** + * Allows the controller Mode to be set to manual (0) or Automatic (non-zero) + * when the transition from manual to auto occurs, the controller is + * automatically initialized + ******************************************************************************/ +void PID::SetMode(int Mode) +{ + bool newAuto = (Mode == AUTOMATIC); + if(newAuto == !inAuto) + { /*we just went from manual to auto*/ + PID::Initialize(); + } + inAuto = newAuto; +} + +/* Initialize()**************************************************************** + * does all the things that need to happen to ensure a bumpless transfer + * from manual to automatic mode. + ******************************************************************************/ +void PID::Initialize() +{ + ITerm = *myOutput; + lastInput = *myInput; + t.start(); + if(ITerm > outMax) ITerm = outMax; + else if(ITerm < outMin) ITerm = outMin; +} + +/* SetControllerDirection(...)************************************************* + * The PID will either be connected to a DIRECT acting process (+Output leads + * to +Input) or a REVERSE acting process(+Output leads to -Input.) we need to + * know which one, because otherwise we may increase the output when we should + * be decreasing. This is called from the constructor. + ******************************************************************************/ +void PID::SetControllerDirection(int Direction) +{ + if(inAuto && Direction !=controllerDirection) + { + kp = (0 - kp); + ki = (0 - ki); + kd = (0 - kd); + } + controllerDirection = Direction; +} + +/* Status Funcions************************************************************* + * Just because you set the Kp=-1 doesn't mean it actually happened. these + * functions query the internal state of the PID. they're here for display + * purposes. this are the functions the PID Front-end uses for example + ******************************************************************************/ +double PID::GetKp(){ return dispKp; } +double PID::GetKi(){ return dispKi;} +double PID::GetKd(){ return dispKd;} +int PID::GetMode(){ return inAuto ? AUTOMATIC : MANUAL;} +int PID::GetDirection(){ return controllerDirection;} \ No newline at end of file
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/PID.h Sat Jul 22 05:58:03 2017 +0000 @@ -0,0 +1,79 @@ +#include "mbed.h" +#ifndef PID_H_ +#define PID_H_ + +class PID +{ + public: + + //Constants used in some of the functions below + #define AUTOMATIC 1 + #define MANUAL 0 + #define DIRECT 0 + #define REVERSE 1 + + //commonly used functions ************************************************************************** + PID(double*, double*, double*, // * constructor. links the PID to the Input, Output, and + double, double, double, int); // Setpoint. Initial tuning parameters are also set here + + void SetMode(int Mode); // * sets PID to either Manual (0) or Auto (non-0) + + bool Compute(); // * performs the PID calculation. it should be + // called every time loop() cycles. ON/OFF and + // calculation frequency can be set using SetMode + // SetSampleTime respectively + + void SetOutputLimits(double, double); //clamps the output to a specific range. 0-255 by default, but + //it's likely the user will want to change this depending on + //the application + + + + //available but not commonly used functions ******************************************************** + void SetTunings(double, double, // * While most users will set the tunings once in the + double); // constructor, this function gives the user the option + // of changing tunings during runtime for Adaptive control + void SetControllerDirection(int); // * Sets the Direction, or "Action" of the controller. DIRECT + // means the output will increase when error is positive. REVERSE + // means the opposite. it's very unlikely that this will be needed + // once it is set in the constructor. + void SetSampleTime(int); // * sets the frequency, in Milliseconds, with which + // the PID calculation is performed. default is 100 + + // void changeSetpoint(*double); // changes system setpoint + + //Display functions **************************************************************** + double GetKp(); // These functions query the pid for interal values. + double GetKi(); // they were created mainly for the pid front-end, + double GetKd(); // where it's important to know what is actually + int GetMode(); // inside the PID. + int GetDirection(); // + + private: + void Initialize(); + + double dispKp; // * we'll hold on to the tuning parameters in user-entered + double dispKi; // format for display purposes + double dispKd; // + + double kp; // * (P)roportional Tuning Parameter + double ki; // * (I)ntegral Tuning Parameter + double kd; // * (D)erivative Tuning Parameter + + int controllerDirection; + + double *myInput; // * Pointers to the Input, Output, and Setpoint variables + double *myOutput; // This creates a hard link between the variables and the + double *mySetpoint; // PID, freeing the user from having to constantly tell us + // what these values are. with pointers we'll just know. + + unsigned long lastTime; + double ITerm, lastInput; + + unsigned long SampleTime; + double outMin, outMax; + bool inAuto; + Timer t; +}; + +#endif \ No newline at end of file
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/Sensors/HMC5883L.lib Sat Jul 22 05:58:03 2017 +0000 @@ -0,0 +1,1 @@ +https://developer.mbed.org/users/roger_wee/code/HMC5883L/#f5f6aaf24be0
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/Sensors/IMU.h Sat Jul 22 05:58:03 2017 +0000 @@ -0,0 +1,229 @@ +#include "MPU6050.h" +#include "HMC5883L.h" + +float sum = 0; +uint32_t sumCount = 0; +Timer t; +Serial pc(USBTX, USBRX); + +void IMUinit(MPU6050 &mpu6050) +{ + //start timer/clock + t.start(); + + // Read the WHO_AM_I register, this is a good test of communication + uint8_t whoami = mpu6050.readByte(MPU6050_ADDRESS, WHO_AM_I_MPU6050); // Read WHO_AM_I register for MPU-6050 + pc.printf("I AM 0x%x\n\r", whoami); + pc.printf("I SHOULD BE 0x68\n\r"); + + if (whoami == 0x68) { // WHO_AM_I should always be 0x68 + pc.printf("MPU6050 is online..."); + wait(1); + //lcd.clear(); + //lcd.printString("MPU6050 OK", 0, 0); + + mpu6050.MPU6050SelfTest(SelfTest); // Start by performing self test and reporting values + pc.printf("x-axis self test: acceleration trim within : "); + pc.printf("%f", SelfTest[0]); + pc.printf("% of factory value \n\r"); + pc.printf("y-axis self test: acceleration trim within : "); + pc.printf("%f", SelfTest[1]); + pc.printf("% of factory value \n\r"); + pc.printf("z-axis self test: acceleration trim within : "); + pc.printf("%f", SelfTest[2]); + pc.printf("% of factory value \n\r"); + pc.printf("x-axis self test: gyration trim within : "); + pc.printf("%f", SelfTest[3]); + pc.printf("% of factory value \n\r"); + pc.printf("y-axis self test: gyration trim within : "); + pc.printf("%f", SelfTest[4]); + pc.printf("% of factory value \n\r"); + pc.printf("z-axis self test: gyration trim within : "); + pc.printf("%f", SelfTest[5]); + pc.printf("% of factory value \n\r"); + wait(1); + + if(SelfTest[0] < 1.0f && SelfTest[1] < 1.0f && SelfTest[2] < 1.0f && SelfTest[3] < 1.0f && SelfTest[4] < 1.0f && SelfTest[5] < 1.0f) { + mpu6050.resetMPU6050(); // Reset registers to default in preparation for device calibration + + mpu6050.calibrateMPU6050(gyroBias, accelBias); // Calibrate gyro and accelerometers, load biases in bias registers + + mpu6050.resetMPU6050(); + + mpu6050.initMPU6050(); + pc.printf("MPU6050 initialized for active data mode....\n\r"); // Initialize device for active mode read of acclerometer, gyroscope, and temperature + wait(2); + + } else { + pc.printf("Device did not the pass self-test!\n\r"); + } + } else { + pc.printf("Could not connect to MPU6050: \n\r"); + pc.printf("%#x \n", whoami); + + while(1) ; // Loop forever if communication doesn't happen + } +} + + +void IMUPrintData(MPU6050 &mpu6050, HMC5883L &compass) +{ + + // pc.printf("Beginning IMU read\n"); +// If data ready bit set, all data registers have new data + if(mpu6050.readByte(MPU6050_ADDRESS, INT_STATUS) & 0x01) { // check if data ready interrupt + + mpu6050.readAccelData(accelCount); // Read the x/y/z adc values + mpu6050.getAres(); + + // Now we'll calculate the accleration value into actual g's + ax = (float)accelCount[0] *aRes - accelBias[0]; // get actual g value, this depends on scale being set + ay = (float)accelCount[1] *aRes - accelBias[1]; + az = (float)accelCount[2] *aRes - accelBias[2]; + + mpu6050.readGyroData(gyroCount); // Read the x/y/z adc values + mpu6050.getGres(); + + // Calculate the gyro value into actual degrees per second + gx = (float)gyroCount[0]*gRes - gyroBias[0]; // get actual gyro value, this depends on scale being set + gy = (float)gyroCount[1]*gRes - gyroBias[1]; + gz = (float)gyroCount[2]*gRes - gyroBias[2]; + + tempCount = mpu6050.readTempData(); // Read the x/y/z adc values + temperature = (tempCount) / 340. + 36.53; // Temperature in degrees Centigrade + + } + + //get magdata + compass.readMagData(magdata); + heading = compass.getHeading(); + + Now = t.read_us(); + deltat = (float)((Now - lastUpdate)/1000000.0f) ; // set integration time by time elapsed since last filter update + //sampleFreq = 1/deltat; + lastUpdate = Now; + + sum += deltat; + sumCount++; + + if(lastUpdate - firstUpdate > 10000000.0f) { + beta = 0.04; // decrease filter gain after stabilized + zeta = 0.015; // increasey bias drift gain after stabilized + } + + // Convert gyro rate as rad/s + gx *= PI/180.0f; + gy *= PI/180.0f; + gz *= PI/180.0f; + + // Calculate position if time + mpu6050.getDisplacement(ax,ay); + + // Pass gyro rate as rad/s + mpu6050.MadgwickQuaternionUpdate(ax, ay, az, gx, gy, gz, magdata[0], magdata[1], magdata[2]); + + // Serial print and/or display at 0.5 s rate independent of data rates + delt_t = t.read_ms() - count; + if (delt_t > 0) { // update LCD once per half-second independent of read rate + + + // Define output variables from updated quaternion---these are Tait-Bryan angles, commonly used in aircraft orientation. + // In this coordinate system, the positive z-axis is down toward Earth. + // Yaw is the angle between Sensor x-axis and Earth magnetic North (or true North if corrected for local declination, looking down on the sensor positive yaw is counterclockwise. + // Pitch is angle between sensor x-axis and Earth ground plane, toward the Earth is positive, up toward the sky is negative. + // Roll is angle between sensor y-axis and Earth ground plane, y-axis up is positive roll. + // These arise from the definition of the homogeneous rotation matrix constructed from quaternions. + // Tait-Bryan angles as well as Euler angles are non-commutative; that is, the get the correct orientation the rotations must be + // applied in the correct order which for this configuration is yaw, pitch, and then roll. + // For more see http://en.wikipedia.org/wiki/Conversion_between_quaternions_and_Euler_angles which has additional links. + yaw = atan2(2.0f * (q[1] * q[2] + q[0] * q[3]), q[0] * q[0] + q[1] * q[1] - q[2] * q[2] - q[3] * q[3]); + pitch = -asin(2.0f * (q[1] * q[3] - q[0] * q[2])); + roll = atan2(2.0f * (q[0] * q[1] + q[2] * q[3]), q[0] * q[0] - q[1] * q[1] - q[2] * q[2] + q[3] * q[3]); + + pitch *= 180.0f / PI; + yaw *= 180.0f / PI; + roll *= 180.0f / PI; + +// pc.printf("Yaw, Pitch, Roll: \n\r"); +// pc.printf("%f", yaw); +// pc.printf(", "); +// pc.printf("%f", pitch); +// pc.printf(", "); +// pc.printf("%f\n\r", roll); +// pc.printf("average rate = "); pc.printf("%f", (sumCount/sum)); pc.printf(" Hz\n\r"); + + //pc.printf("average rate = %f\n\r", (float) sumCount/sum); + + //myled= !myled; + count = t.read_ms(); + sum = 0; + sumCount = 0; + } +} + +void IMUUpdate(MPU6050 &mpu6050) +{ + // If data ready bit set, all data registers have new data + if(mpu6050.readByte(MPU6050_ADDRESS, INT_STATUS) & 0x01) { // check if data ready interrupt + mpu6050.readAccelData(accelCount); // Read the x/y/z adc values + mpu6050.getAres(); + + // Now we'll calculate the accleration value into actual g's + ax = (float)accelCount[0]*aRes - accelBias[0]; // get actual g value, this depends on scale being set + ay = (float)accelCount[1]*aRes - accelBias[1]; + az = (float)accelCount[2]*aRes - accelBias[2]; + + mpu6050.readGyroData(gyroCount); // Read the x/y/z adc values + mpu6050.getGres(); + + // Calculate the gyro value into actual degrees per second + gx = (float)gyroCount[0]*gRes; // - gyroBias[0]; // get actual gyro value, this depends on scale being set + gy = (float)gyroCount[1]*gRes; // - gyroBias[1]; + gz = (float)gyroCount[2]*gRes; // - gyroBias[2]; + + tempCount = mpu6050.readTempData(); // Read the x/y/z adc values + temperature = (tempCount) / 340. + 36.53; // Temperature in degrees Centigrade + } + + Now = t.read_us(); + deltat = (float)((Now - lastUpdate)/1000000.0f) ; // set integration time by time elapsed since last filter update + lastUpdate = Now; + + sum += deltat; + sumCount++; + + if(lastUpdate - firstUpdate > 10000000.0f) { + beta = 0.04; // decrease filter gain after stabilized + zeta = 0.015; // increasey bias drift gain after stabilized + } + + // Pass gyro rate as rad/s + mpu6050.MadgwickQuaternionUpdate(ax, ay, az, gx*PI/180.0f, gy*PI/180.0f, gz*PI/180.0f); + + // Serial print and/or display at 0.5 s rate independent of data rates + delt_t = t.read_ms() - count; + + // Define output variables from updated quaternion---these are Tait-Bryan angles, commonly used in aircraft orientation. + // In this coordinate system, the positive z-axis is down toward Earth. + // Yaw is the angle between Sensor x-axis and Earth magnetic North (or true North if corrected for local declination, looking down on the sensor positive yaw is counterclockwise. + // Pitch is angle between sensor x-axis and Earth ground plane, toward the Earth is positive, up toward the sky is negative. + // Roll is angle between sensor y-axis and Earth ground plane, y-axis up is positive roll. + // These arise from the definition of the homogeneous rotation matrix constructed from quaternions. + // Tait-Bryan angles as well as Euler angles are non-commutative; that is, the get the correct orientation the rotations must be + // applied in the correct order which for this configuration is yaw, pitch, and then roll. + // For more see http://en.wikipedia.org/wiki/Conversion_between_quaternions_and_Euler_angles which has additional links. + yaw = atan2(2.0f * (q[1] * q[2] + q[0] * q[3]), q[0] * q[0] + q[1] * q[1] - q[2] * q[2] - q[3] * q[3]); + pitch = -asin(2.0f * (q[1] * q[3] - q[0] * q[2])); + roll = atan2(2.0f * (q[0] * q[1] + q[2] * q[3]), q[0] * q[0] - q[1] * q[1] - q[2] * q[2] + q[3] * q[3]); + pitch *= 180.0f / PI; + yaw *= 180.0f / PI; + roll *= 180.0f / PI; + + //update timer for filter + count = t.read_ms(); + sum = 0; + sumCount = 0; + +} + +
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/Sensors/MPU6050.h Sat Jul 22 05:58:03 2017 +0000 @@ -0,0 +1,891 @@ +#ifndef MPU6050_H +#define MPU6050_H + +#include "mbed.h" +#include "math.h" + +// Define registers per MPU6050, Register Map and Descriptions, Rev 4.2, 08/19/2013 6 DOF Motion sensor fusion device +// Invensense Inc., www.invensense.com +// See also MPU-6050 Register Map and Descriptions, Revision 4.0, RM-MPU-6050A-00, 9/12/2012 for registers not listed in +// above document; the MPU6050 and MPU 9150 are virtually identical but the latter has an on-board magnetic sensor +// +#define XGOFFS_TC 0x00 // Bit 7 PWR_MODE, bits 6:1 XG_OFFS_TC, bit 0 OTP_BNK_VLD +#define YGOFFS_TC 0x01 +#define ZGOFFS_TC 0x02 +#define X_FINE_GAIN 0x03 // [7:0] fine gain +#define Y_FINE_GAIN 0x04 +#define Z_FINE_GAIN 0x05 +#define XA_OFFSET_H 0x06 // User-defined trim values for accelerometer +#define XA_OFFSET_L_TC 0x07 +#define YA_OFFSET_H 0x08 +#define YA_OFFSET_L_TC 0x09 +#define ZA_OFFSET_H 0x0A +#define ZA_OFFSET_L_TC 0x0B +#define SELF_TEST_X 0x0D +#define SELF_TEST_Y 0x0E +#define SELF_TEST_Z 0x0F +#define SELF_TEST_A 0x10 +#define XG_OFFS_USRH 0x13 // User-defined trim values for gyroscope; supported in MPU-6050? +#define XG_OFFS_USRL 0x14 +#define YG_OFFS_USRH 0x15 +#define YG_OFFS_USRL 0x16 +#define ZG_OFFS_USRH 0x17 +#define ZG_OFFS_USRL 0x18 +#define SMPLRT_DIV 0x19 +#define CONFIG 0x1A +#define GYRO_CONFIG 0x1B +#define ACCEL_CONFIG 0x1C +#define FF_THR 0x1D // Free-fall +#define FF_DUR 0x1E // Free-fall +#define MOT_THR 0x1F // Motion detection threshold bits [7:0] +#define MOT_DUR 0x20 // Duration counter threshold for motion interrupt generation, 1 kHz rate, LSB = 1 ms +#define ZMOT_THR 0x21 // Zero-motion detection threshold bits [7:0] +#define ZRMOT_DUR 0x22 // Duration counter threshold for zero motion interrupt generation, 16 Hz rate, LSB = 64 ms +#define FIFO_EN 0x23 +#define I2C_MST_CTRL 0x24 +#define I2C_SLV0_ADDR 0x25 +#define I2C_SLV0_REG 0x26 +#define I2C_SLV0_CTRL 0x27 +#define I2C_SLV1_ADDR 0x28 +#define I2C_SLV1_REG 0x29 +#define I2C_SLV1_CTRL 0x2A +#define I2C_SLV2_ADDR 0x2B +#define I2C_SLV2_REG 0x2C +#define I2C_SLV2_CTRL 0x2D +#define I2C_SLV3_ADDR 0x2E +#define I2C_SLV3_REG 0x2F +#define I2C_SLV3_CTRL 0x30 +#define I2C_SLV4_ADDR 0x31 +#define I2C_SLV4_REG 0x32 +#define I2C_SLV4_DO 0x33 +#define I2C_SLV4_CTRL 0x34 +#define I2C_SLV4_DI 0x35 +#define I2C_MST_STATUS 0x36 +#define INT_PIN_CFG 0x37 +#define INT_ENABLE 0x38 +#define DMP_INT_STATUS 0x39 // Check DMP interrupt +#define INT_STATUS 0x3A +#define ACCEL_XOUT_H 0x3B +#define ACCEL_XOUT_L 0x3C +#define ACCEL_YOUT_H 0x3D +#define ACCEL_YOUT_L 0x3E +#define ACCEL_ZOUT_H 0x3F +#define ACCEL_ZOUT_L 0x40 +#define TEMP_OUT_H 0x41 +#define TEMP_OUT_L 0x42 +#define GYRO_XOUT_H 0x43 +#define GYRO_XOUT_L 0x44 +#define GYRO_YOUT_H 0x45 +#define GYRO_YOUT_L 0x46 +#define GYRO_ZOUT_H 0x47 +#define GYRO_ZOUT_L 0x48 +#define EXT_SENS_DATA_00 0x49 +#define EXT_SENS_DATA_01 0x4A +#define EXT_SENS_DATA_02 0x4B +#define EXT_SENS_DATA_03 0x4C +#define EXT_SENS_DATA_04 0x4D +#define EXT_SENS_DATA_05 0x4E +#define EXT_SENS_DATA_06 0x4F +#define EXT_SENS_DATA_07 0x50 +#define EXT_SENS_DATA_08 0x51 +#define EXT_SENS_DATA_09 0x52 +#define EXT_SENS_DATA_10 0x53 +#define EXT_SENS_DATA_11 0x54 +#define EXT_SENS_DATA_12 0x55 +#define EXT_SENS_DATA_13 0x56 +#define EXT_SENS_DATA_14 0x57 +#define EXT_SENS_DATA_15 0x58 +#define EXT_SENS_DATA_16 0x59 +#define EXT_SENS_DATA_17 0x5A +#define EXT_SENS_DATA_18 0x5B +#define EXT_SENS_DATA_19 0x5C +#define EXT_SENS_DATA_20 0x5D +#define EXT_SENS_DATA_21 0x5E +#define EXT_SENS_DATA_22 0x5F +#define EXT_SENS_DATA_23 0x60 +#define MOT_DETECT_STATUS 0x61 +#define I2C_SLV0_DO 0x63 +#define I2C_SLV1_DO 0x64 +#define I2C_SLV2_DO 0x65 +#define I2C_SLV3_DO 0x66 +#define I2C_MST_DELAY_CTRL 0x67 +#define SIGNAL_PATH_RESET 0x68 +#define MOT_DETECT_CTRL 0x69 +#define USER_CTRL 0x6A // Bit 7 enable DMP, bit 3 reset DMP +#define PWR_MGMT_1 0x6B // Device defaults to the SLEEP mode +#define PWR_MGMT_2 0x6C +#define DMP_BANK 0x6D // Activates a specific bank in the DMP +#define DMP_RW_PNT 0x6E // Set read/write pointer to a specific start address in specified DMP bank +#define DMP_REG 0x6F // Register in DMP from which to read or to which to write +#define DMP_REG_1 0x70 +#define DMP_REG_2 0x71 +#define FIFO_COUNTH 0x72 +#define FIFO_COUNTL 0x73 +#define FIFO_R_W 0x74 +#define WHO_AM_I_MPU6050 0x75 // Should return 0x68 + +// Using the GY-521 breakout board, I set ADO to 0 by grounding through a 4k7 resistor +// Seven-bit device address is 110100 for ADO = 0 and 110101 for ADO = 1 + +//create constructor +#define MPU6050_ADDRESS 0x69<<1 // Device address when ADO = 1 + +//Set up I2C, (SDA,SCL) +I2C i2c(D14, D15); + +// Set initial input parameters +enum Ascale { + AFS_2G = 0, + AFS_4G, + AFS_8G, + AFS_16G +}; + +enum Gscale { + GFS_250DPS = 0, + GFS_500DPS, + GFS_1000DPS, + GFS_2000DPS +}; + +// Specify sensor full scale +int Gscale = GFS_250DPS; +int Ascale = AFS_2G; + + +float aRes, gRes; // scale resolutions per LSB for the sensors + +// Pin definitions +int intPin = 12; // These can be changed, 2 and 3 are the Arduinos ext int pins + +int16_t accelCount[3]; // Stores the 16-bit signed accelerometer sensor output +float ax, ay, az; // Stores the real accel value in g's +int16_t gyroCount[3]; // Stores the 16-bit signed gyro sensor output +float gx, gy, gz; // Stores the real gyro value in degrees per seconds +float gyroBias[3] = {0, 0, 0}, accelBias[3] = {0, 0, 0}; // Bias corrections for gyro and accelerometer +int16_t tempCount; // Stores the real internal chip temperature in degrees Celsius +float temperature; +float SelfTest[6]; + +signed int accelerationx[2], accelerationy[2]; +signed long velocityx[2], velocityy[2]; +signed long positionX[2]; +signed long positionY[2]; +signed long positionZ[2]; +unsigned char countx, county; + +float heading = 0; +float magdata[3]; + +int delt_t = 0; // used to control display output rate +int count = 0; // used to control display output rate + +// parameters for 9 DoF sensor fusion calculations +float PI = 3.14159265358979323846f; +float GyroMeasError = PI * (90.0f / 180.0f); // gyroscope measurement error in rads/s (start at 60 deg/s), then reduce after ~10 s to 3 +float beta = sqrt(3.0f / 4.0f) * GyroMeasError; // compute beta +float GyroMeasDrift = PI * (3.0f / 180.0f); // gyroscope measurement drift in rad/s/s (start at 0.0 deg/s/s) +float zeta = sqrt(3.0f / 4.0f) * GyroMeasDrift; // compute zeta, the other free parameter in the Madgwick scheme usually set to a small or zero value +float yaw, pitch, roll; +float deltat = 0.0f; // integration interval for both filter schemes +int lastUpdate = 0, firstUpdate = 0, Now = 0; // used to calculate integration interval // used to calculate integration interval +float q[4] = {1.0f, 0.0f, 0.0f, 0.0f}; // vector to hold quaternion + +//free IMU variables +#define twoKpDef (2.0f * 0.5f) // 2 * proportional gain +#define twoKiDef (2.0f * 0.1f) // 2 * integral gain +float sampleFreq; // half the sample period expressed in seconds +volatile float twoKp = twoKpDef; // 2 * proportional gain (Kp) +volatile float twoKi = twoKiDef; // 2 * integral gain (Ki) +float exInt, eyInt, ezInt; // scaled integral error +volatile float integralFBx, integralFBy, integralFBz; + +//math helper +float invSqrt(float number) { + volatile long i; + volatile float x, y; + volatile const float f = 1.5F; + + x = number * 0.5F; + y = number; + i = * ( long * ) &y; + i = 0x5f375a86 - ( i >> 1 ); + y = * ( float * ) &i; + y = y * ( f - ( x * y * y ) ); + return y; +} + + +class MPU6050 +{ + protected: + + public: + //=================================================================================================================== + //====== Set of useful function to access acceleratio, gyroscope, and temperature data + //=================================================================================================================== + + //create constructor to pass in address + + void writeByte(uint8_t address, uint8_t subAddress, uint8_t data) { + char data_write[2]; + data_write[0] = subAddress; + data_write[1] = data; + i2c.write(address, data_write, 2, 0); + } + + char readByte(uint8_t address, uint8_t subAddress) { + char data[1]; // `data` will store the register data + char data_write[1]; + data_write[0] = subAddress; + i2c.write(address, data_write, 1, 1); // no stop + i2c.read(address, data, 1, 0); + return data[0]; + } + + void readBytes(uint8_t address, uint8_t subAddress, uint8_t count, uint8_t * dest) { + char data[14]; + char data_write[1]; + data_write[0] = subAddress; + i2c.write(address, data_write, 1, 1); // no stop + i2c.read(address, data, count, 0); + for(int ii = 0; ii < count; ii++) { + dest[ii] = data[ii]; + } + } + + + void getGres() { + switch (Gscale) { + // Possible gyro scales (and their register bit settings) are: + // 250 DPS (00), 500 DPS (01), 1000 DPS (10), and 2000 DPS (11). + // Here's a bit of an algorith to calculate DPS/(ADC tick) based on that 2-bit value: + case GFS_250DPS: + gRes = 250.0/32768.0; + break; + case GFS_500DPS: + gRes = 500.0/32768.0; + break; + case GFS_1000DPS: + gRes = 1000.0/32768.0; + break; + case GFS_2000DPS: + gRes = 2000.0/32768.0; + break; + } + } + + void getAres() { + switch (Ascale) { + // Possible accelerometer scales (and their register bit settings) are: + // 2 Gs (00), 4 Gs (01), 8 Gs (10), and 16 Gs (11). + // Here's a bit of an algorith to calculate DPS/(ADC tick) based on that 2-bit value: + case AFS_2G: + aRes = 2.0/32768.0; + break; + case AFS_4G: + aRes = 4.0/32768.0; + break; + case AFS_8G: + aRes = 8.0/32768.0; + break; + case AFS_16G: + aRes = 16.0/32768.0; + break; + } + } + + + void readAccelData(int16_t * destination) { + uint8_t rawData[6]; // x/y/z accel register data stored here + readBytes(MPU6050_ADDRESS, ACCEL_XOUT_H, 6, &rawData[0]); // Read the six raw data registers into data array + destination[0] = (int16_t)(((int16_t)rawData[0] << 8) | rawData[1]) ; // Turn the MSB and LSB into a signed 16-bit value + destination[1] = (int16_t)(((int16_t)rawData[2] << 8) | rawData[3]) ; + destination[2] = (int16_t)(((int16_t)rawData[4] << 8) | rawData[5]) ; + } + + void readGyroData(int16_t * destination) { + uint8_t rawData[6]; // x/y/z gyro register data stored here + readBytes(MPU6050_ADDRESS, GYRO_XOUT_H, 6, &rawData[0]); // Read the six raw data registers sequentially into data array + destination[0] = (int16_t)(((int16_t)rawData[0] << 8) | rawData[1]) ; // Turn the MSB and LSB into a signed 16-bit value + destination[1] = (int16_t)(((int16_t)rawData[2] << 8) | rawData[3]) ; + destination[2] = (int16_t)(((int16_t)rawData[4] << 8) | rawData[5]) ; + } + + int16_t readTempData() { + uint8_t rawData[2]; // x/y/z gyro register data stored here + readBytes(MPU6050_ADDRESS, TEMP_OUT_H, 2, &rawData[0]); // Read the two raw data registers sequentially into data array + return (int16_t)(((int16_t)rawData[0]) << 8 | rawData[1]) ; // Turn the MSB and LSB into a 16-bit value + } + + + + // Configure the motion detection control for low power accelerometer mode + void LowPowerAccelOnly() { + + // The sensor has a high-pass filter necessary to invoke to allow the sensor motion detection algorithms work properly + // Motion detection occurs on free-fall (acceleration below a threshold for some time for all axes), motion (acceleration + // above a threshold for some time on at least one axis), and zero-motion toggle (acceleration on each axis less than a + // threshold for some time sets this flag, motion above the threshold turns it off). The high-pass filter takes gravity out + // consideration for these threshold evaluations; otherwise, the flags would be set all the time! + + uint8_t c = readByte(MPU6050_ADDRESS, PWR_MGMT_1); + writeByte(MPU6050_ADDRESS, PWR_MGMT_1, c & ~0x30); // Clear sleep and cycle bits [5:6] + writeByte(MPU6050_ADDRESS, PWR_MGMT_1, c | 0x30); // Set sleep and cycle bits [5:6] to zero to make sure accelerometer is running + + c = readByte(MPU6050_ADDRESS, PWR_MGMT_2); + writeByte(MPU6050_ADDRESS, PWR_MGMT_2, c & ~0x38); // Clear standby XA, YA, and ZA bits [3:5] + writeByte(MPU6050_ADDRESS, PWR_MGMT_2, c | 0x00); // Set XA, YA, and ZA bits [3:5] to zero to make sure accelerometer is running + + c = readByte(MPU6050_ADDRESS, ACCEL_CONFIG); + writeByte(MPU6050_ADDRESS, ACCEL_CONFIG, c & ~0x07); // Clear high-pass filter bits [2:0] + // Set high-pass filter to 0) reset (disable), 1) 5 Hz, 2) 2.5 Hz, 3) 1.25 Hz, 4) 0.63 Hz, or 7) Hold + writeByte(MPU6050_ADDRESS, ACCEL_CONFIG, c | 0x00); // Set ACCEL_HPF to 0; reset mode disbaling high-pass filter + + c = readByte(MPU6050_ADDRESS, CONFIG); + writeByte(MPU6050_ADDRESS, CONFIG, c & ~0x07); // Clear low-pass filter bits [2:0] + writeByte(MPU6050_ADDRESS, CONFIG, c | 0x00); // Set DLPD_CFG to 0; 260 Hz bandwidth, 1 kHz rate + + c = readByte(MPU6050_ADDRESS, INT_ENABLE); + writeByte(MPU6050_ADDRESS, INT_ENABLE, c & ~0xFF); // Clear all interrupts + writeByte(MPU6050_ADDRESS, INT_ENABLE, 0x40); // Enable motion threshold (bits 5) interrupt only + + // Motion detection interrupt requires the absolute value of any axis to lie above the detection threshold + // for at least the counter duration + writeByte(MPU6050_ADDRESS, MOT_THR, 0x80); // Set motion detection to 0.256 g; LSB = 2 mg + writeByte(MPU6050_ADDRESS, MOT_DUR, 0x01); // Set motion detect duration to 1 ms; LSB is 1 ms @ 1 kHz rate + + wait(0.1); // Add delay for accumulation of samples + + c = readByte(MPU6050_ADDRESS, ACCEL_CONFIG); + writeByte(MPU6050_ADDRESS, ACCEL_CONFIG, c & ~0x07); // Clear high-pass filter bits [2:0] + writeByte(MPU6050_ADDRESS, ACCEL_CONFIG, c | 0x07); // Set ACCEL_HPF to 7; hold the initial accleration value as a referance + + c = readByte(MPU6050_ADDRESS, PWR_MGMT_2); + writeByte(MPU6050_ADDRESS, PWR_MGMT_2, c & ~0xC7); // Clear standby XA, YA, and ZA bits [3:5] and LP_WAKE_CTRL bits [6:7] + writeByte(MPU6050_ADDRESS, PWR_MGMT_2, c | 0x47); // Set wakeup frequency to 5 Hz, and disable XG, YG, and ZG gyros (bits [0:2]) + + c = readByte(MPU6050_ADDRESS, PWR_MGMT_1); + writeByte(MPU6050_ADDRESS, PWR_MGMT_1, c & ~0x20); // Clear sleep and cycle bit 5 + writeByte(MPU6050_ADDRESS, PWR_MGMT_1, c | 0x20); // Set cycle bit 5 to begin low power accelerometer motion interrupts + + } + + + void resetMPU6050() { + // reset device + writeByte(MPU6050_ADDRESS, PWR_MGMT_1, 0x80); // Write a one to bit 7 reset bit; toggle reset device + wait(0.1); + } + + + void initMPU6050() { + // Initialize MPU6050 device + // wake up device + writeByte(MPU6050_ADDRESS, PWR_MGMT_1, 0x00); // Clear sleep mode bit (6), enable all sensors + wait(0.1); // Delay 100 ms for PLL to get established on x-axis gyro; should check for PLL ready interrupt + + // get stable time source + writeByte(MPU6050_ADDRESS, PWR_MGMT_1, 0x01); // Set clock source to be PLL with x-axis gyroscope reference, bits 2:0 = 001 + + // Configure Gyro and Accelerometer + // Disable FSYNC and set accelerometer and gyro bandwidth to 44 and 42 Hz, respectively; + // DLPF_CFG = bits 2:0 = 010; this sets the sample rate at 1 kHz for both + // Maximum delay is 4.9 ms which is just over a 200 Hz maximum rate + writeByte(MPU6050_ADDRESS, CONFIG, 0x03); + + // Set sample rate = gyroscope output rate/(1 + SMPLRT_DIV) + writeByte(MPU6050_ADDRESS, SMPLRT_DIV, 0x04); // Use a 200 Hz rate; the same rate set in CONFIG above + + // Set gyroscope full scale range + // Range selects FS_SEL and AFS_SEL are 0 - 3, so 2-bit values are left-shifted into positions 4:3 + uint8_t c = readByte(MPU6050_ADDRESS, GYRO_CONFIG); + writeByte(MPU6050_ADDRESS, GYRO_CONFIG, c & ~0xE0); // Clear self-test bits [7:5] + writeByte(MPU6050_ADDRESS, GYRO_CONFIG, c & ~0x18); // Clear AFS bits [4:3] + writeByte(MPU6050_ADDRESS, GYRO_CONFIG, c | Gscale << 3); // Set full scale range for the gyro + + // Set accelerometer configuration + c = readByte(MPU6050_ADDRESS, ACCEL_CONFIG); + writeByte(MPU6050_ADDRESS, ACCEL_CONFIG, c & ~0xE0); // Clear self-test bits [7:5] + writeByte(MPU6050_ADDRESS, ACCEL_CONFIG, c & ~0x18); // Clear AFS bits [4:3] + writeByte(MPU6050_ADDRESS, ACCEL_CONFIG, c | Ascale << 3); // Set full scale range for the accelerometer + + // Configure Interrupts and Bypass Enable + // Set interrupt pin active high, push-pull, and clear on read of INT_STATUS, enable I2C_BYPASS_EN so additional chips + // can join the I2C bus and all can be controlled by the Arduino as master + writeByte(MPU6050_ADDRESS, INT_PIN_CFG, 0x22); + writeByte(MPU6050_ADDRESS, INT_ENABLE, 0x01); // Enable data ready (bit 0) interrupt + } + + // Function which accumulates gyro and accelerometer data after device initialization. It calculates the average + // of the at-rest readings and then loads the resulting offsets into accelerometer and gyro bias registers. + void calibrateMPU6050(float * dest1, float * dest2) { + uint8_t data[12]; // data array to hold accelerometer and gyro x, y, z, data + uint16_t ii, packet_count, fifo_count; + int32_t gyro_bias[3] = {0, 0, 0}, accel_bias[3] = {0, 0, 0}; + + // reset device, reset all registers, clear gyro and accelerometer bias registers + writeByte(MPU6050_ADDRESS, PWR_MGMT_1, 0x80); // Write a one to bit 7 reset bit; toggle reset device + wait(0.1); + + // get stable time source + // Set clock source to be PLL with x-axis gyroscope reference, bits 2:0 = 001 + writeByte(MPU6050_ADDRESS, PWR_MGMT_1, 0x01); + writeByte(MPU6050_ADDRESS, PWR_MGMT_2, 0x00); + wait(0.2); + + // Configure device for bias calculation + writeByte(MPU6050_ADDRESS, INT_ENABLE, 0x00); // Disable all interrupts + writeByte(MPU6050_ADDRESS, FIFO_EN, 0x00); // Disable FIFO + writeByte(MPU6050_ADDRESS, PWR_MGMT_1, 0x00); // Turn on internal clock source + writeByte(MPU6050_ADDRESS, I2C_MST_CTRL, 0x00); // Disable I2C master + writeByte(MPU6050_ADDRESS, USER_CTRL, 0x00); // Disable FIFO and I2C master modes + writeByte(MPU6050_ADDRESS, USER_CTRL, 0x0C); // Reset FIFO and DMP + wait(0.015); + + // Configure MPU6050 gyro and accelerometer for bias calculation + writeByte(MPU6050_ADDRESS, CONFIG, 0x01); // Set low-pass filter to 188 Hz + writeByte(MPU6050_ADDRESS, SMPLRT_DIV, 0x00); // Set sample rate to 1 kHz + writeByte(MPU6050_ADDRESS, GYRO_CONFIG, 0x00); // Set gyro full-scale to 250 degrees per second, maximum sensitivity + writeByte(MPU6050_ADDRESS, ACCEL_CONFIG, 0x00); // Set accelerometer full-scale to 2 g, maximum sensitivity + + uint16_t gyrosensitivity = 131; // = 131 LSB/degrees/sec + uint16_t accelsensitivity = 16384; // = 16384 LSB/g + + // Configure FIFO to capture accelerometer and gyro data for bias calculation + writeByte(MPU6050_ADDRESS, USER_CTRL, 0x40); // Enable FIFO + writeByte(MPU6050_ADDRESS, FIFO_EN, 0x78); // Enable gyro and accelerometer sensors for FIFO (max size 1024 bytes in MPU-6050) + wait(0.08); // accumulate 80 samples in 80 milliseconds = 960 bytes + + // At end of sample accumulation, turn off FIFO sensor read + writeByte(MPU6050_ADDRESS, FIFO_EN, 0x00); // Disable gyro and accelerometer sensors for FIFO + readBytes(MPU6050_ADDRESS, FIFO_COUNTH, 2, &data[0]); // read FIFO sample count + fifo_count = ((uint16_t)data[0] << 8) | data[1]; + packet_count = fifo_count/12;// How many sets of full gyro and accelerometer data for averaging + + for (ii = 0; ii < packet_count; ii++) { + int16_t accel_temp[3] = {0, 0, 0}, gyro_temp[3] = {0, 0, 0}; + readBytes(MPU6050_ADDRESS, FIFO_R_W, 12, &data[0]); // read data for averaging + accel_temp[0] = (int16_t) (((int16_t)data[0] << 8) | data[1] ) ; // Form signed 16-bit integer for each sample in FIFO + accel_temp[1] = (int16_t) (((int16_t)data[2] << 8) | data[3] ) ; + accel_temp[2] = (int16_t) (((int16_t)data[4] << 8) | data[5] ) ; + gyro_temp[0] = (int16_t) (((int16_t)data[6] << 8) | data[7] ) ; + gyro_temp[1] = (int16_t) (((int16_t)data[8] << 8) | data[9] ) ; + gyro_temp[2] = (int16_t) (((int16_t)data[10] << 8) | data[11]) ; + + accel_bias[0] += (int32_t) accel_temp[0]; // Sum individual signed 16-bit biases to get accumulated signed 32-bit biases + accel_bias[1] += (int32_t) accel_temp[1]; + accel_bias[2] += (int32_t) accel_temp[2]; + gyro_bias[0] += (int32_t) gyro_temp[0];// * scale_factor_gyro; + gyro_bias[1] += (int32_t) gyro_temp[1];// * scale_factor_gyro; + gyro_bias[2] += (int32_t) gyro_temp[2];// * scale_factor_gyro; + + } + accel_bias[0] /= (int32_t) packet_count; // Normalize sums to get average count biases + accel_bias[1] /= (int32_t) packet_count; + accel_bias[2] /= (int32_t) packet_count; + + gyro_bias[0] /= (int32_t) packet_count; + gyro_bias[1] /= (int32_t) packet_count; + gyro_bias[2] /= (int32_t) packet_count; + + + if(accel_bias[2] > 0L) { + accel_bias[2] -= (int32_t) accelsensitivity; // Remove gravity from the z-axis accelerometer bias calculation + } else { + accel_bias[2] += (int32_t) accelsensitivity; + } + + + // Construct the gyro biases for push to the hardware gyro bias registers, which are reset to zero upon device startup + data[0] = (-gyro_bias[0]/4 >> 8) & 0xFF; // Divide by 4 to get 32.9 LSB per deg/s to conform to expected bias input format + data[1] = (-gyro_bias[0]/4) & 0xFF; // Biases are additive, so change sign on calculated average gyro biases + data[2] = (-gyro_bias[1]/4 >> 8) & 0xFF; + data[3] = (-gyro_bias[1]/4) & 0xFF; + data[4] = (-gyro_bias[2]/4 >> 8) & 0xFF; + data[5] = (-gyro_bias[2]/4) & 0xFF; + + // Push gyro biases to hardware registers + writeByte(MPU6050_ADDRESS, XG_OFFS_USRH, data[0]); + writeByte(MPU6050_ADDRESS, XG_OFFS_USRL, data[1]); + writeByte(MPU6050_ADDRESS, YG_OFFS_USRH, data[2]); + writeByte(MPU6050_ADDRESS, YG_OFFS_USRL, data[3]); + writeByte(MPU6050_ADDRESS, ZG_OFFS_USRH, data[4]); + writeByte(MPU6050_ADDRESS, ZG_OFFS_USRL, data[5]); + + dest1[0] = (float) gyro_bias[0]/(float) gyrosensitivity; // construct gyro bias in deg/s for later manual subtraction + dest1[1] = (float) gyro_bias[1]/(float) gyrosensitivity; + dest1[2] = (float) gyro_bias[2]/(float) gyrosensitivity; + + // Construct the accelerometer biases for push to the hardware accelerometer bias registers. These registers contain + // factory trim values which must be added to the calculated accelerometer biases; on boot up these registers will hold + // non-zero values. In addition, bit 0 of the lower byte must be preserved since it is used for temperature + // compensation calculations. Accelerometer bias registers expect bias input as 2048 LSB per g, so that + // the accelerometer biases calculated above must be divided by 8. + + int32_t accel_bias_reg[3] = {0, 0, 0}; // A place to hold the factory accelerometer trim biases + readBytes(MPU6050_ADDRESS, XA_OFFSET_H, 2, &data[0]); // Read factory accelerometer trim values + accel_bias_reg[0] = (int16_t) ((int16_t)data[0] << 8) | data[1]; + readBytes(MPU6050_ADDRESS, YA_OFFSET_H, 2, &data[0]); + accel_bias_reg[1] = (int16_t) ((int16_t)data[0] << 8) | data[1]; + readBytes(MPU6050_ADDRESS, ZA_OFFSET_H, 2, &data[0]); + accel_bias_reg[2] = (int16_t) ((int16_t)data[0] << 8) | data[1]; + + uint32_t mask = 1uL; // Define mask for temperature compensation bit 0 of lower byte of accelerometer bias registers + uint8_t mask_bit[3] = {0, 0, 0}; // Define array to hold mask bit for each accelerometer bias axis + + for(ii = 0; ii < 3; ii++) { + if(accel_bias_reg[ii] & mask) mask_bit[ii] = 0x01; // If temperature compensation bit is set, record that fact in mask_bit + } + + // Construct total accelerometer bias, including calculated average accelerometer bias from above + accel_bias_reg[0] -= (accel_bias[0]/8); // Subtract calculated averaged accelerometer bias scaled to 2048 LSB/g (16 g full scale) + accel_bias_reg[1] -= (accel_bias[1]/8); + accel_bias_reg[2] -= (accel_bias[2]/8); + + data[0] = (accel_bias_reg[0] >> 8) & 0xFF; + data[1] = (accel_bias_reg[0]) & 0xFF; + data[1] = data[1] | mask_bit[0]; // preserve temperature compensation bit when writing back to accelerometer bias registers + data[2] = (accel_bias_reg[1] >> 8) & 0xFF; + data[3] = (accel_bias_reg[1]) & 0xFF; + data[3] = data[3] | mask_bit[1]; // preserve temperature compensation bit when writing back to accelerometer bias registers + data[4] = (accel_bias_reg[2] >> 8) & 0xFF; + data[5] = (accel_bias_reg[2]) & 0xFF; + data[5] = data[5] | mask_bit[2]; // preserve temperature compensation bit when writing back to accelerometer bias registers + + // Push accelerometer biases to hardware registers + writeByte(MPU6050_ADDRESS, XA_OFFSET_H, data[0]); + writeByte(MPU6050_ADDRESS, XA_OFFSET_L_TC, data[1]); + writeByte(MPU6050_ADDRESS, YA_OFFSET_H, data[2]); + writeByte(MPU6050_ADDRESS, YA_OFFSET_L_TC, data[3]); + writeByte(MPU6050_ADDRESS, ZA_OFFSET_H, data[4]); + writeByte(MPU6050_ADDRESS, ZA_OFFSET_L_TC, data[5]); + + // Output scaled accelerometer biases for manual subtraction in the main program + dest2[0] = (float)accel_bias[0]/(float)accelsensitivity; + dest2[1] = (float)accel_bias[1]/(float)accelsensitivity; + dest2[2] = (float)accel_bias[2]/(float)accelsensitivity; + } + + + // Accelerometer and gyroscope self test; check calibration wrt factory settings + void MPU6050SelfTest(float * destination) { // Should return percent deviation from factory trim values, +/- 14 or less deviation is a pass + uint8_t rawData[4] = {0, 0, 0, 0}; + uint8_t selfTest[6]; + float factoryTrim[6]; + + // Configure the accelerometer for self-test + writeByte(MPU6050_ADDRESS, ACCEL_CONFIG, 0xF0); // Enable self test on all three axes and set accelerometer range to +/- 8 g + writeByte(MPU6050_ADDRESS, GYRO_CONFIG, 0xE0); // Enable self test on all three axes and set gyro range to +/- 250 degrees/s + wait(0.25); // Delay a while to let the device execute the self-test + rawData[0] = readByte(MPU6050_ADDRESS, SELF_TEST_X); // X-axis self-test results + rawData[1] = readByte(MPU6050_ADDRESS, SELF_TEST_Y); // Y-axis self-test results + rawData[2] = readByte(MPU6050_ADDRESS, SELF_TEST_Z); // Z-axis self-test results + rawData[3] = readByte(MPU6050_ADDRESS, SELF_TEST_A); // Mixed-axis self-test results + // Extract the acceleration test results first + selfTest[0] = (rawData[0] >> 3) | (rawData[3] & 0x30) >> 4 ; // XA_TEST result is a five-bit unsigned integer + selfTest[1] = (rawData[1] >> 3) | (rawData[3] & 0x0C) >> 4 ; // YA_TEST result is a five-bit unsigned integer + selfTest[2] = (rawData[2] >> 3) | (rawData[3] & 0x03) >> 4 ; // ZA_TEST result is a five-bit unsigned integer + // Extract the gyration test results first + selfTest[3] = rawData[0] & 0x1F ; // XG_TEST result is a five-bit unsigned integer + selfTest[4] = rawData[1] & 0x1F ; // YG_TEST result is a five-bit unsigned integer + selfTest[5] = rawData[2] & 0x1F ; // ZG_TEST result is a five-bit unsigned integer + // Process results to allow final comparison with factory set values + factoryTrim[0] = (4096.0f*0.34f)*(pow( (0.92f/0.34f) , ((selfTest[0] - 1.0f)/30.0f))); // FT[Xa] factory trim calculation + factoryTrim[1] = (4096.0f*0.34f)*(pow( (0.92f/0.34f) , ((selfTest[1] - 1.0f)/30.0f))); // FT[Ya] factory trim calculation + factoryTrim[2] = (4096.0f*0.34f)*(pow( (0.92f/0.34f) , ((selfTest[2] - 1.0f)/30.0f))); // FT[Za] factory trim calculation + factoryTrim[3] = ( 25.0f*131.0f)*(pow( 1.046f , (selfTest[3] - 1.0f) )); // FT[Xg] factory trim calculation + factoryTrim[4] = (-25.0f*131.0f)*(pow( 1.046f , (selfTest[4] - 1.0f) )); // FT[Yg] factory trim calculation + factoryTrim[5] = ( 25.0f*131.0f)*(pow( 1.046f , (selfTest[5] - 1.0f) )); // FT[Zg] factory trim calculation + +// Output self-test results and factory trim calculation if desired +// Serial.println(selfTest[0]); Serial.println(selfTest[1]); Serial.println(selfTest[2]); +// Serial.println(selfTest[3]); Serial.println(selfTest[4]); Serial.println(selfTest[5]); +// Serial.println(factoryTrim[0]); Serial.println(factoryTrim[1]); Serial.println(factoryTrim[2]); +// Serial.println(factoryTrim[3]); Serial.println(factoryTrim[4]); Serial.println(factoryTrim[5]); + +// Report results as a ratio of (STR - FT)/FT; the change from Factory Trim of the Self-Test Response +// To get to percent, must multiply by 100 and subtract result from 100 + for (int i = 0; i < 6; i++) { + destination[i] = 100.0f + 100.0f*(selfTest[i] - factoryTrim[i])/factoryTrim[i]; // Report percent differences + } + + } + + +// Implementation of Sebastian Madgwick's "...efficient orientation filter for... inertial/magnetic sensor arrays" +// (see http://www.x-io.co.uk/category/open-source/ for examples and more details) +// which fuses acceleration and rotation rate to produce a quaternion-based estimate of relative +// device orientation -- which can be converted to yaw, pitch, and roll. Useful for stabilizing quadcopters, etc. +// The performance of the orientation filter is at least as good as conventional Kalman-based filtering algorithms +// but is much less computationally intensive---it can be performed on a 3.3 V Pro Mini operating at 8 MHz! + void MadgwickQuaternionUpdate(float ax, float ay, float az, float gx, float gy, float gz) { + float q1 = q[0], q2 = q[1], q3 = q[2], q4 = q[3]; // short name local variable for readability + float norm; // vector norm + float f1, f2, f3; // objective funcyion elements + float J_11or24, J_12or23, J_13or22, J_14or21, J_32, J_33; // objective function Jacobian elements + float qDot1, qDot2, qDot3, qDot4; + float hatDot1, hatDot2, hatDot3, hatDot4; + float gerrx, gerry, gerrz, gbiasx, gbiasy, gbiasz; // gyro bias error + + // Auxiliary variables to avoid repeated arithmetic + float _halfq1 = 0.5f * q1; + float _halfq2 = 0.5f * q2; + float _halfq3 = 0.5f * q3; + float _halfq4 = 0.5f * q4; + float _2q1 = 2.0f * q1; + float _2q2 = 2.0f * q2; + float _2q3 = 2.0f * q3; + float _2q4 = 2.0f * q4; +// float _2q1q3 = 2.0f * q1 * q3; +// float _2q3q4 = 2.0f * q3 * q4; + + // Normalise accelerometer measurement + norm = sqrt(ax * ax + ay * ay + az * az); + if (norm == 0.0f) return; // handle NaN + norm = 1.0f/norm; + ax *= norm; + ay *= norm; + az *= norm; + + // Compute the objective function and Jacobian + f1 = _2q2 * q4 - _2q1 * q3 - ax; + f2 = _2q1 * q2 + _2q3 * q4 - ay; + f3 = 1.0f - _2q2 * q2 - _2q3 * q3 - az; + J_11or24 = _2q3; + J_12or23 = _2q4; + J_13or22 = _2q1; + J_14or21 = _2q2; + J_32 = 2.0f * J_14or21; + J_33 = 2.0f * J_11or24; + + // Compute the gradient (matrix multiplication) + hatDot1 = J_14or21 * f2 - J_11or24 * f1; + hatDot2 = J_12or23 * f1 + J_13or22 * f2 - J_32 * f3; + hatDot3 = J_12or23 * f2 - J_33 *f3 - J_13or22 * f1; + hatDot4 = J_14or21 * f1 + J_11or24 * f2; + + // Normalize the gradient + norm = sqrt(hatDot1 * hatDot1 + hatDot2 * hatDot2 + hatDot3 * hatDot3 + hatDot4 * hatDot4); + hatDot1 /= norm; + hatDot2 /= norm; + hatDot3 /= norm; + hatDot4 /= norm; + + // Compute estimated gyroscope biases + gerrx = _2q1 * hatDot2 - _2q2 * hatDot1 - _2q3 * hatDot4 + _2q4 * hatDot3; + gerry = _2q1 * hatDot3 + _2q2 * hatDot4 - _2q3 * hatDot1 - _2q4 * hatDot2; + gerrz = _2q1 * hatDot4 - _2q2 * hatDot3 + _2q3 * hatDot2 - _2q4 * hatDot1; + + // Compute and remove gyroscope biases + gbiasx += gerrx * deltat * zeta; + gbiasy += gerry * deltat * zeta; + gbiasz += gerrz * deltat * zeta; + // gx -= gbiasx; + // gy -= gbiasy; + // gz -= gbiasz; + + // Compute the quaternion derivative + qDot1 = -_halfq2 * gx - _halfq3 * gy - _halfq4 * gz; + qDot2 = _halfq1 * gx + _halfq3 * gz - _halfq4 * gy; + qDot3 = _halfq1 * gy - _halfq2 * gz + _halfq4 * gx; + qDot4 = _halfq1 * gz + _halfq2 * gy - _halfq3 * gx; + + // Compute then integrate estimated quaternion derivative + q1 += (qDot1 -(beta * hatDot1)) * deltat; + q2 += (qDot2 -(beta * hatDot2)) * deltat; + q3 += (qDot3 -(beta * hatDot3)) * deltat; + q4 += (qDot4 -(beta * hatDot4)) * deltat; + + // Normalize the quaternion + norm = sqrt(q1 * q1 + q2 * q2 + q3 * q3 + q4 * q4); // normalise quaternion + norm = 1.0f/norm; + q[0] = q1 * norm; + q[1] = q2 * norm; + q[2] = q3 * norm; + q[3] = q4 * norm; + } + +// Implementation of Sebastian Madgwick's "...efficient orientation filter for... inertial/magnetic sensor arrays" +// (see http://www.x-io.co.uk/category/open-source/ for examples and more details) +// which fuses acceleration, rotation rate, and magnetic moments to produce a quaternion-based estimate of absolute +// device orientation -- which can be converted to yaw, pitch, and roll. Useful for stabilizing quadcopters, etc. +// The performance of the orientation filter is at least as good as conventional Kalman-based filtering algorithms +// but is much less computationally intensive---it can be performed on a 3.3 V Pro Mini operating at 8 MHz! + void MadgwickQuaternionUpdate(float ax, float ay, float az, float gx, float gy, float gz, float mx, float my, float mz) + { + float q1 = q[0], q2 = q[1], q3 = q[2], q4 = q[3]; // short name local variable for readability + float norm; + float hx, hy, _2bx, _2bz; + float s1, s2, s3, s4; + float qDot1, qDot2, qDot3, qDot4; + + // Auxiliary variables to avoid repeated arithmetic + float _2q1mx; + float _2q1my; + float _2q1mz; + float _2q2mx; + float _4bx; + float _4bz; + float _2q1 = 2.0f * q1; + float _2q2 = 2.0f * q2; + float _2q3 = 2.0f * q3; + float _2q4 = 2.0f * q4; + float _2q1q3 = 2.0f * q1 * q3; + float _2q3q4 = 2.0f * q3 * q4; + float q1q1 = q1 * q1; + float q1q2 = q1 * q2; + float q1q3 = q1 * q3; + float q1q4 = q1 * q4; + float q2q2 = q2 * q2; + float q2q3 = q2 * q3; + float q2q4 = q2 * q4; + float q3q3 = q3 * q3; + float q3q4 = q3 * q4; + float q4q4 = q4 * q4; + + // Normalise accelerometer measurement + norm = sqrt(ax * ax + ay * ay + az * az); + if (norm == 0.0f) return; // handle NaN + norm = 1.0f/norm; + ax *= norm; + ay *= norm; + az *= norm; + + // Normalise magnetometer measurement + norm = sqrt(mx * mx + my * my + mz * mz); + if (norm == 0.0f) return; // handle NaN + norm = 1.0f/norm; + mx *= norm; + my *= norm; + mz *= norm; + + // Reference direction of Earth's magnetic field + _2q1mx = 2.0f * q1 * mx; + _2q1my = 2.0f * q1 * my; + _2q1mz = 2.0f * q1 * mz; + _2q2mx = 2.0f * q2 * mx; + hx = mx * q1q1 - _2q1my * q4 + _2q1mz * q3 + mx * q2q2 + _2q2 * my * q3 + _2q2 * mz * q4 - mx * q3q3 - mx * q4q4; + hy = _2q1mx * q4 + my * q1q1 - _2q1mz * q2 + _2q2mx * q3 - my * q2q2 + my * q3q3 + _2q3 * mz * q4 - my * q4q4; + _2bx = sqrt(hx * hx + hy * hy); + _2bz = -_2q1mx * q3 + _2q1my * q2 + mz * q1q1 + _2q2mx * q4 - mz * q2q2 + _2q3 * my * q4 - mz * q3q3 + mz * q4q4; + _4bx = 2.0f * _2bx; + _4bz = 2.0f * _2bz; + + // Gradient decent algorithm corrective step + s1 = -_2q3 * (2.0f * q2q4 - _2q1q3 - ax) + _2q2 * (2.0f * q1q2 + _2q3q4 - ay) - _2bz * q3 * (_2bx * (0.5f - q3q3 - q4q4) + _2bz * (q2q4 - q1q3) - mx) + (-_2bx * q4 + _2bz * q2) * (_2bx * (q2q3 - q1q4) + _2bz * (q1q2 + q3q4) - my) + _2bx * q3 * (_2bx * (q1q3 + q2q4) + _2bz * (0.5f - q2q2 - q3q3) - mz); + s2 = _2q4 * (2.0f * q2q4 - _2q1q3 - ax) + _2q1 * (2.0f * q1q2 + _2q3q4 - ay) - 4.0f * q2 * (1.0f - 2.0f * q2q2 - 2.0f * q3q3 - az) + _2bz * q4 * (_2bx * (0.5f - q3q3 - q4q4) + _2bz * (q2q4 - q1q3) - mx) + (_2bx * q3 + _2bz * q1) * (_2bx * (q2q3 - q1q4) + _2bz * (q1q2 + q3q4) - my) + (_2bx * q4 - _4bz * q2) * (_2bx * (q1q3 + q2q4) + _2bz * (0.5f - q2q2 - q3q3) - mz); + s3 = -_2q1 * (2.0f * q2q4 - _2q1q3 - ax) + _2q4 * (2.0f * q1q2 + _2q3q4 - ay) - 4.0f * q3 * (1.0f - 2.0f * q2q2 - 2.0f * q3q3 - az) + (-_4bx * q3 - _2bz * q1) * (_2bx * (0.5f - q3q3 - q4q4) + _2bz * (q2q4 - q1q3) - mx) + (_2bx * q2 + _2bz * q4) * (_2bx * (q2q3 - q1q4) + _2bz * (q1q2 + q3q4) - my) + (_2bx * q1 - _4bz * q3) * (_2bx * (q1q3 + q2q4) + _2bz * (0.5f - q2q2 - q3q3) - mz); + s4 = _2q2 * (2.0f * q2q4 - _2q1q3 - ax) + _2q3 * (2.0f * q1q2 + _2q3q4 - ay) + (-_4bx * q4 + _2bz * q2) * (_2bx * (0.5f - q3q3 - q4q4) + _2bz * (q2q4 - q1q3) - mx) + (-_2bx * q1 + _2bz * q3) * (_2bx * (q2q3 - q1q4) + _2bz * (q1q2 + q3q4) - my) + _2bx * q2 * (_2bx * (q1q3 + q2q4) + _2bz * (0.5f - q2q2 - q3q3) - mz); + norm = sqrt(s1 * s1 + s2 * s2 + s3 * s3 + s4 * s4); // normalise step magnitude + norm = 1.0f/norm; + s1 *= norm; + s2 *= norm; + s3 *= norm; + s4 *= norm; + + // Compute rate of change of quaternion + qDot1 = 0.5f * (-q2 * gx - q3 * gy - q4 * gz) - beta * s1; + qDot2 = 0.5f * (q1 * gx + q3 * gz - q4 * gy) - beta * s2; + qDot3 = 0.5f * (q1 * gy - q2 * gz + q4 * gx) - beta * s3; + qDot4 = 0.5f * (q1 * gz + q2 * gy - q3 * gx) - beta * s4; + + // Integrate to yield quaternion + q1 += qDot1 * deltat; + q2 += qDot2 * deltat; + q3 += qDot3 * deltat; + q4 += qDot4 * deltat; + norm = sqrt(q1 * q1 + q2 * q2 + q3 * q3 + q4 * q4); // normalise quaternion + norm = 1.0f/norm; + q[0] = q1 * norm; + q[1] = q2 * norm; + q[2] = q3 * norm; + q[3] = q4 * norm; + + } + + void getDisplacement(float ax, float ay) + { + unsigned char count2 ; + count2=0; + + do{ + accelerationx[1] = accelerationx[1] + ax; //filtering routine for noise attenuation + accelerationy[1] = accelerationy[1] + ay; //64 samples are averaged. The resulting + + //average represents the acceleration of + //an instant + count2++; + }while (count2!=0x40); // 64 sums of the acceleration sample + + accelerationx[1]= accelerationx[1]>>6; // division by 64 + accelerationy[1]= accelerationy[1]>>6; + + //accelerationx[1] = accelerationx[1] - (int)sstatex; //eliminating zero reference + //offset of the acceleration data + //accelerationy[1] = accelerationy[1] - (int)sstatey; // to obtain positive and negative + //acceleration + + + if ((accelerationx[1] <=3)&&(accelerationx[1] >= -3)) //Discrimination window applied + {accelerationx[1] = 0;} // to the X axis acceleration variable + + if ((accelerationy[1] <=3)&&(accelerationy[1] >= -3)) + {accelerationy[1] = 0;} + + //first X integration: + velocityx[1]= velocityx[0]+ accelerationx[0]+ ((accelerationx[1] - accelerationx[0])>>1); + //second X integration: + positionX[1]= positionX[0] + velocityx[0] + ((velocityx[1] - velocityx[0])>>1); + //first Y integration: + velocityy[1] = velocityy[0] + accelerationy[0] + ((accelerationy[1] -accelerationy[0])>>1); + //second Y integration: + positionY[1] = positionY[0] + velocityy[0] + ((velocityy[1] - velocityy[0])>>1); + + accelerationx[0] = accelerationx[1]; //The current acceleration value must be sent + //to the previous acceleration + accelerationy[0] = accelerationy[1]; //variable in order to introduce the new + //acceleration value. + + velocityx[0] = velocityx[1]; //Same done for the velocity variable + velocityy[0] = velocityy[1]; + + positionX[1] = positionX[1]<<18; //The idea behind this shifting (multiplication) + //is a sensibility adjustment. + positionY[1] = positionY[1]<<18; //Some applications require adjustments to a + //particular situation i.e. mouse application + + positionX[1] = positionX[1]>>18; //once the variables are sent them must return to + positionY[1] = positionY[1]>>18; //their original state + + movement_end_check(); + + positionX[0] = positionX[1]; //actual position data must be sent to the + positionY[0] = positionY[1]; //previous position + } + + void movement_end_check(void) + { + if (accelerationx[1]==0) //we count the number of acceleration samples that equals cero + { countx++;} + else { countx =0;} + + if (countx>=25) //if this number exceeds 25, we can assume that velocity is cero + { + velocityx[1]=0; + velocityx[0]=0; + } + + if (accelerationy[1]==0) //we do the same for the Y axis + { county++;} + else { county =0;} + + if (county>=25) + { + velocityy[1]=0; + velocityy[0]=0; + } + } + +}; +#endif \ No newline at end of file
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/main.cpp Sat Jul 22 05:58:03 2017 +0000 @@ -0,0 +1,319 @@ +//Robosub Control Interface + +#include "mbed.h" +#include "IMU.h" +#include "PID.h" +#include "HMC5883L.h" + +//------------Declare Objects------------------// +PwmOut m1(D3); +PwmOut m2(D4); +PwmOut m3(D5); +PwmOut m4(D6); + +// Declare mpu6050 and compass object +MPU6050 mpu1; +HMC5883L compass; + +// Serial communication between Arduino NANO +RawSerial device(PA_11, PA_12); //TX RX + +//-----------Global Variables------------------// +char command = 0; +Timer calibrate; + +int pwmMax = 1100; // Reversed due to motor orientation +int pwmMin = 1500; + +// PWM output variable for each motor +int m1pwm = pwmMin; +int m2pwm = pwmMin; +int m3pwm = pwmMin; +int m4pwm = pwmMin; + +// Individual pid parameters +double myYaw, yawPoint, yawOut; +double myPitch, pitchPoint, pitchOut; +double myRoll, rollPoint, rollOut; +double myDepth, depthPoint, depthOut; + +int depth = 1; + +double kpVal = 0; + +//-----------End Global Variables--------------// + + + //----PID objects------// + +// Input, Output, SetPoint, kp, ki, kd, Controller Direction +PID pidy(&myYaw, &yawOut, &yawPoint, 1, 1, 1, DIRECT); +PID pidp(&myPitch, &pitchOut, &pitchPoint, 1, 1, 1, DIRECT); +PID pidr(&myRoll, &rollOut, &rollPoint, 1, 1, 1, DIRECT); +PID pidd(&myDepth, &depthOut, &depthPoint, 1, 1, 1, DIRECT); + + //----End PID objects--// + + +//-----------Helper functions------------------// +void calibrateFilter() +{ + calibrate.start(); + while(calibrate.read() < 10) + { + IMUPrintData(mpu1, compass); + + char text[90]; + sprintf(text, "%f,%f,%f \n", yaw, pitch, roll); + pc.printf("%s", text); + } + calibrate.stop(); +} + +void updateMotors() +{ + m1.pulsewidth_us(m1pwm); + m2.pulsewidth_us(m2pwm); + m3.pulsewidth_us(m3pwm); + m4.pulsewidth_us(m4pwm); +} + +void neutralizeMotors() +{ + m1pwm = pwmMin; + m2pwm = pwmMin; + m3pwm = pwmMin; + m4pwm = pwmMin; + updateMotors(); +} + +void readUserInput() +{ + if(pc.readable()) + { + command = pc.getc(); + } +} + +void initializePIDs() +{ + pidy.SetMode(AUTOMATIC); // Yaw PID + pidy.SetOutputLimits(pwmMin, pwmMax); + + pidp.SetMode(AUTOMATIC); // Pitch PID + pidp.SetOutputLimits(pwmMin, pwmMax); + + pidr.SetMode(AUTOMATIC); // Roll PID + pidr.SetOutputLimits(pwmMin, pwmMax); + + pidd.SetMode(AUTOMATIC); // Depth PID + pidd.SetOutputLimits(pwmMin, pwmMax); + + depthPoint = 0; +} + +void readDepth() +{ + // Read pressure sensor data if available + if (device.readable()) + { + // Receive depth in inches as an integer + depth = device.getc(); + + // Convert to feet + } +} + +void displayTelemetry() +{ + char text[90]; + sprintf(text, "%f,%f,%f,%d \n", yaw, pitch, roll, depth); + pc.printf("%s", text); +} + +//-----------End Helper functions--------------// + + + +//-----------Interface States------------------// +enum controlStates { init, idle, manual, preparePid, beginTune } controlState; + +void controlInterface(){ + + switch(controlState) //Actions + { + case init: + pc.printf("Initialize sensors \n"); + IMUinit(mpu1); + compass.init(); + + pc.printf("Initialize motors \n"); + neutralizeMotors(); + + pc.printf("Initialize PID objects \n"); + initializePIDs(); + + pc.printf("Calibrate MARG Filter \n"); + calibrateFilter(); + break; + + case idle: + IMUPrintData(mpu1, compass); + readDepth(); + displayTelemetry(); + break; + + case manual: + //pc.printf("Manual Control \n"); + switch(command) + { + case 'N': + //pc.printf("Neutralize motors\n"); + neutralizeMotors(); + break; + + case 'R': + //pc.printf("Reduce Thrust\n"); + if (m1pwm < pwmMin) + { + m1pwm++; + m2pwm++; + m3pwm++; + m4pwm++; + } + break; + + case 'I': + //pc.printf("Increase Thrust\n"); + if (m1pwm > pwmMax) + { + m1pwm--; + m2pwm--; + m3pwm--; + m4pwm--; + } + break; + + default: + break; + } + updateMotors(); + break; + + case preparePid: + // pc.printf("Prepare PID \n"); + switch(command) + { + case 'I': // Increase Kp gain + kpVal += .1; + break; + + case 'R': + if (kpVal > 0 ) // Decreae Kp gain + { + kpVal -= .1; + } + break; + + case 'S': // Increase depth + depthPoint++; + + case 's': // Decrease setpoint + if(depthPoint > 0) + { + depthPoint--; + } + break; + + default: + break; + } + + // Set tunings + pidd.SetTunings(kpVal,0,0); //Set Ki Kd = 0 + + // Print Set parameters + pc.printf("DepthPoint: %d \n", depthPoint); + pc.printf("Kp gain: %d \n", pidd.GetKp()); + + break; + + case beginTune: + //pc.printf("Tuning process begins.. \n"); + + // Sense inertial / depth data + IMUPrintData(mpu1, compass); + readDepth(); + + // Assign feedback variables + myDepth = depth; + + // Compute PID + pidd.Compute(); + + // Output pwm to motors // FIXME : account for pitch, roll and maybe yaw depending on motor configuration + m1pwm = m2pwm = m3pwm = m4pwm = depthOut; + updateMotors(); + + // Display telemetry + displayTelemetry(); + + break; + + default: + pc.printf("Error! \n"); + break; + } + + switch(controlState) //Transitions + { + case init: + controlState = idle; + break; + + case idle: + controlState = (command == 'm') ? manual : ((command == 'p') ? preparePid : idle); + break; + + case manual: + controlState = (command == 'p') ? preparePid : manual; + if (controlState == preparePid) + { + //pc.printf("Neutralize Motors \n"); + neutralizeMotors(); + } + break; + + case preparePid: + controlState = (command == 'g') ? beginTune : preparePid; + break; + + case beginTune: + controlState = (command == 't') ? preparePid : beginTune; + if (controlState == preparePid) + { + //pc.printf("Neutralize Motors \n"); + neutralizeMotors(); + } + break; + + default: + break; + } +} + +//-----------End Interface---------------------// + +int main() { + // Initialize control state + controlState = init; + + while(1) + { + // Read user input + readUserInput(); + + // Begin Interface + controlInterface(); + } +} \ No newline at end of file
--- /dev/null Thu Jan 01 00:00:00 1970 +0000 +++ b/mbed.bld Sat Jul 22 05:58:03 2017 +0000 @@ -0,0 +1,1 @@ +http://mbed.org/users/mbed_official/code/mbed/builds/9baf128c2fab \ No newline at end of file