#include "CurieIMU.h"
#include <MadgwickAHRS.h>
Madgwick filter;
#define motor1 6
#define motor2 9
#define motor3 3
#define motor4 5
int duty_percent = 0;
int duty_255 = 97;
int freq = 475;
int xOffset = 2;
char buff[2];
float elapsedTime, time, timePrev;
unsigned long microsPerReading, microsPrevious;
int aix, aiy, aiz, gix, giy, giz;
float ax, ay, az; //scaled accelerometer values
float gx, gy, gz; //scaled Gyro values
float Total_angle[2];
float xPID, yPID, xerror, previous_xerror, yerror, previous_yerror;
int pwm1, pwm2, pwm3, pwm4;
float xpid_p = 0;
float xpid_i = 0;
float xpid_d = 0;
float ypid_p = 0;
float ypid_i = 0;
float ypid_d = 0;
/////////////////PID CONSTANTS/////////////////
double kp = 1.0; //3.55
double ki = 0.0; //0.003
double kd = 1.0; //2.05
///////////////////////////////////////////////
int throttle = 97;
int max_throttle = 250;
float desired_xangle = 0;
float desired_yangle = 0;
void setup() {
pinMode(motor1, OUTPUT); //pwm
pinMode(motor2, OUTPUT); //pwm
pinMode(motor3, OUTPUT); //pwm
pinMode(motor4, OUTPUT); //pwm
analogWriteFrequency(motor1, freq);
analogWriteFrequency(motor2, freq);
analogWriteFrequency(motor3, freq);
analogWriteFrequency(motor4, freq);
Serial.begin(9600);
while (!Serial) {};
Serial.println("Initializing IMU device...");
CurieIMU.begin();
CurieIMU.setGyroRate(25);
CurieIMU.setAccelerometerRate(25);
filter.begin(25);
CurieIMU.setAccelerometerRange(2);
CurieIMU.setGyroRange(250);
CurieIMU.autoCalibrateAccelerometerOffset(X_AXIS, 0);
CurieIMU.autoCalibrateAccelerometerOffset(Y_AXIS, 0);
CurieIMU.autoCalibrateAccelerometerOffset(Z_AXIS, 1);
CurieIMU.autoCalibrateGyroOffset();
microsPerReading = 1000000 / 25;
microsPrevious = micros();
time = millis();
Serial.println("Ready");
}
void loop() {
if (Serial.available() > 0) {
if (Serial.peek() == 'p') {
Serial.readBytes(buff, 2);
kp = Serial.readStringUntil('\n').toFloat();
Serial.print("--------------------------");
Serial.print("kp=");
Serial.print(kp, 4);
Serial.println("--------------------------");
} else if (Serial.peek() == 'i') {
Serial.readBytes(buff, 2);
ki = Serial.readStringUntil('\n').toFloat();
Serial.print("--------------------------");
Serial.print("ki=");
Serial.print(ki, 4);
Serial.println("--------------------------");
} else if (Serial.peek() == 'd') {
Serial.readBytes(buff, 2);
kd = Serial.readStringUntil('\n').toFloat();
Serial.print("--------------------------");
Serial.print("kd=");
Serial.print(kd, 4);
Serial.println("--------------------------");
} else {
duty_percent = Serial.readStringUntil('\n').toInt();
duty_255 = map(duty_percent, 0, 100, 97, 250);
throttle = duty_255;
Serial.print("==========================");
Serial.print(duty_percent);
Serial.print("% (throttle = ");
Serial.print(throttle);
Serial.println(")==========================");
}
}
// Serial.println(elapsedTime, 3);
unsigned long microsNow;
// check if it's time to read data and update the filter
microsNow = micros();
Serial.println(microsNow);
if (microsNow - microsPrevious >= microsPerReading) {
timePrev = time; // the previous time is stored before the actual time read
time = millis(); // actual time read
elapsedTime = (time - timePrev);
noInterrupts();
CurieIMU.readMotionSensor(aix, aiy, aiz, gix, giy, giz);
interrupts();
ax = convertRawAcceleration(aix);
ay = convertRawAcceleration(aiy);
az = convertRawAcceleration(aiz);
gx = convertRawGyro(gix);
gy = convertRawGyro(giy);
gz = convertRawGyro(giz);
filter.updateIMU(gx, gy, gz, ax, ay, az);
Total_angle[0] = filter.getPitch(); // X
Total_angle[1] = filter.getRoll(); // Y
Serial.print("X_angle:"); Serial.print(Total_angle[0]);
Serial.print("\t");
Serial.print("Y_angle:"); Serial.print(Total_angle[1]);
Serial.print("\t");
/* / / / / / / / / / / / PID \ \ \ \ \ \ \ \ \ \ \ \*/
xerror = Total_angle[0] - desired_xangle;
Serial.print("err:");
Serial.print(xerror);
Serial.print("\t");
/*P*/
xpid_p = kp * xerror;
/*I*/
if ((-2 < xerror) && (xerror < 2))
{
xpid_i = xpid_i + (ki * xerror);
}
// /*D*/
xpid_d = kd * ((xerror - previous_xerror) / elapsedTime);
xPID = xpid_p + xpid_i + xpid_d;
xPID = xPID ;/// 15;
Serial.print("xPID:"); Serial.print(xPID); Serial.print('\t');
Serial.print(xpid_p); Serial.print('\t');
Serial.print(xpid_i); Serial.print('\t');
Serial.print(xpid_d);
if (throttle > 105) {
// pwm1=throttle;pwm2=throttle;pwm3=throttle;pwm4=throttle;
pwm1 = round(throttle - xPID) + xOffset;
pwm2 = round(throttle - xPID) + xOffset;
pwm3 = round(throttle + xPID) - xOffset;
pwm4 = round(throttle + xPID) - xOffset;
} else if (throttle == 97) {
pwm1 = throttle;
pwm2 = throttle;
pwm3 = throttle;
pwm4 = throttle;
}
if (pwm1 < 97) {
pwm1 = 97;
} else if (pwm1 > max_throttle) {
pwm1 = max_throttle;
}
if (pwm2 < 97) {
pwm2 = 97;
} else if (pwm2 > max_throttle) {
pwm2 = max_throttle;
}
if (pwm3 < 97) {
pwm3 = 97;
} else if (pwm3 > max_throttle) {
pwm3 = max_throttle;
}
if (pwm4 < 97) {
pwm4 = 97;
} else if (pwm4 > max_throttle) {
pwm4 = max_throttle;
}
analogWrite(motor1 , pwm1);
analogWrite(motor2 , pwm2);
analogWrite(motor3 , pwm3);
analogWrite(motor4 , pwm4);
Serial.print("\tthrottle:"); Serial.print(throttle);
Serial.print("\tpwm_front:"); Serial.print(pwm1);
Serial.print("\tpwm_back:") ; Serial.print(pwm3);
previous_xerror = xerror;
microsPrevious = microsPrevious + microsPerReading;
Serial.println();
}
}
float convertRawAcceleration(int aRaw) {
// since we are using 2G range
// -2g maps to a raw value of -32768
// +2g maps to a raw value of 32767
float a = (aRaw * 2.0) / 32768.0;
return a;
}
float convertRawGyro(int gRaw) {
// since we are using 250 degrees/seconds range
// -250 maps to a raw value of -32768
// +250 maps to a raw value of 32767
float g = (gRaw * 250.0) / 32768.0;
return g;
}