forked from MaEtUgR/FlyBed
-
Notifications
You must be signed in to change notification settings - Fork 0
/
main.cpp
225 lines (198 loc) · 10.3 KB
/
main.cpp
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
/* X- Configuration
m2 m3 -- >
\ / / \ /
/ \ V |
m1 m0 \
ROLL PITCH */
#include "mbed.h"
#include "LED.h" // LEDs framework for blinking ;)
#include "PC.h" // Serial Port via USB by Roland Elmiger for debugging with Terminal (driver needed: https://mbed.org/media/downloads/drivers/mbedWinSerial_16466.exe)
#include "IMU_10DOF.h" // Complete IMU class for 10DOF-Board (L3G4200D, ADXL345, HMC5883, BMP085)
#include "RemoteControl.h" // RemoteControl Channels with PPM
#include "PID.h" // PID Library (slim, self written)
#include "Servo.h" // Motor PPM using any DigitalOut Pin
#include "LowPassFilter.h"
#define PPM_FREQU 495 // Hz Frequency of PPM Signal for ESCs (maximum <500Hz)
#define INTEGRAL_MAX 300 // maximal output offset that can result from integrating errors
#define ROLL 0 // Axes
#define PITCH 1
#define YAW 2
#define SQRT2 0.7071067811865
bool debug = true; // shows if we want output for the computer
bool level = false; // switches between self leveling and acro mode
float P_R = 6.0, I_R = 0.3, D_R = 0.1; // PID values for the rate controller
float P_A = 1.7, I_A = 0.2, D_A = 0.07; // PID values for the angle controller P_A = 1.9, I_A = 0.2, D_A = 0
float PY = 2.3, IY = 0, DY = 0; // PID values for Yaw
float Motor_speed[4] = {0,0,0,0}; // Mixed Motorspeeds, ready to send
bool toRCCalibrate = false;
Timer LoopTimer;
float Times[10] = {0,0,0,0,0,0,0,0,0,0};
float control_frequency = 800;//PPM_FREQU; // frequency for the main loop in Hz
int counter = 0;
int divider = 20;
LED LEDs;
//PC pc(USBTX, USBRX, 115200); // USB
PC pc(p9, p10, 115200); // Bluetooth PIN: 1234
IMU_10DOF IMU(p5, p6, p7, p19, p28, p27);
RemoteControl RC; // no p19/p20 !
PID Controller_Rate[] = {PID(P_R, I_R, D_R, INTEGRAL_MAX), PID(P_R, I_R, D_R, INTEGRAL_MAX), PID(PY, IY, DY, INTEGRAL_MAX)}; // 0:X:Roll 1:Y:Pitch 2:Z:Yaw
PID Controller_Angle[] = {PID(P_A, I_A, D_A, INTEGRAL_MAX), PID(P_A, I_A, D_A, INTEGRAL_MAX), PID(0, 0, 0, INTEGRAL_MAX)};
Servo ESC[] = {Servo(p21,PPM_FREQU), Servo(p22,PPM_FREQU), Servo(p23,PPM_FREQU), Servo(p24,PPM_FREQU)}; // use any DigitalOit Pin
float gyro_filter_frequ = 30;
LowPassFilter gyro_filter[] = {LowPassFilter(control_frequency, gyro_filter_frequ), LowPassFilter(control_frequency, gyro_filter_frequ), LowPassFilter(control_frequency, gyro_filter_frequ)};
float RC_filter_frequ = 5;
LowPassFilter RC_filter[] = {LowPassFilter(control_frequency, RC_filter_frequ), LowPassFilter(control_frequency, RC_filter_frequ), LowPassFilter(control_frequency, RC_filter_frequ)};
extern "C" void mbed_reset();
void loop() { // TODO: Times!!
LoopTimer.start(); // a timer to monitor how long the steps take
RC.run(IMU.angle[YAW]); // remote control tasks (like arming!)
IMU.readAngles(); // reading sensor data
Times[1] = LoopTimer.read(); // 197us
// Setting PID Values from auxiliary RC channels
for(int i=0;i<3;i++)
Controller_Angle[i].setPID(P_A,I_A,D_A);
for(int i=0;i<2;i++)
Controller_Rate[i].setPID(P_R,I_R,D_R); // give the new PID values to roll and pitch controller
Controller_Rate[YAW].setPID(PY,IY,DY);
Times[2] = LoopTimer.read(); // 7us
Times[3] = LoopTimer.read(); // 6us
// Controlling
if (level) {
for(int i=0;i<2;i++) { // LEVEL
Controller_Angle[i].setIntegrate(RC.armed()); // only integrate in controller when armed, so the value is not totally odd from not flying
if (counter % 16 == 0)
Controller_Angle[i].compute(RC._angle[i], IMU.angle[i]); // give the controller the actual angles and get his advice to correct
Controller_Rate[i].setIntegrate(RC.armed()); // only integrate in controller when armed, so the value is not totally odd from not flying
Controller_Rate[i].compute(-Controller_Angle[i].Value, /*IMU.mpu2.data_gyro[i]*/gyro_filter[i].apply(IMU.mpu.Gyro[i])); // give the controller the actual gyro values and get his advice to correct
//Controller_Rate[i].compute(-Controller_Angle[i].Value, (IMU.mpu2.data_gyro[i] + IMU.mpu.Gyro[i])/2 );
}
} else {
for(int i=0;i<2;i++) { // ACRO
Controller_Rate[i].setIntegrate(RC.armed()); // only integrate in controller when armed, so the value is not totally odd from not flying
Controller_Rate[i].compute(RC_filter[i].apply((RC[i]-500.0)*100.0/500.0), /*IMU.mpu2.data_gyro[i]*/gyro_filter[i].apply(IMU.mpu.Gyro[i])); // give the controller the actual gyro values and get his advice to correct
//Controller_Rate[i].compute((RC[i].read()-500.0)*100.0/500.0, (IMU.mpu2.data_gyro[i] + IMU.mpu.Gyro[i])/2 );
}
}
Controller_Rate[2].setIntegrate(RC.armed()); // only integrate in controller when armed, so the value is not totally odd from not flying
if (RC[THROTTLE] > 20)
Controller_Rate[2].compute(-(RC[RUDDER]-500.0)*100.0/500.0, IMU.mpu.Gyro[2]); // give the controller the actual gyro values and get his advice to correct
else
Controller_Rate[2].compute(0, IMU.mpu.Gyro[2]); // give the controller the actual gyro values and get his advice to correct
float throttle = 100 + (RC[THROTTLE] * 700 / 1000); // power limitation to 60% TODO: better throttle control, so we don't need this
Times[4] = LoopTimer.read(); // 53us
// Mixing
Motor_speed[0] = throttle +SQRT2*Controller_Rate[ROLL].Value -SQRT2*Controller_Rate[PITCH].Value -Controller_Rate[YAW].Value; // X Configuration
Motor_speed[1] = throttle -SQRT2*Controller_Rate[ROLL].Value -SQRT2*Controller_Rate[PITCH].Value +Controller_Rate[YAW].Value;
Motor_speed[2] = throttle -SQRT2*Controller_Rate[ROLL].Value +SQRT2*Controller_Rate[PITCH].Value -Controller_Rate[YAW].Value;
Motor_speed[3] = throttle +SQRT2*Controller_Rate[ROLL].Value +SQRT2*Controller_Rate[PITCH].Value +Controller_Rate[YAW].Value;
Times[5] = LoopTimer.read(); // 17us
if(RC.armed()) { // for SECURITY!
debug = false;
#if 1
for(int i=0;i<4;i++) // Set new motorspeeds
ESC[i] = (int)Motor_speed[i]>100 ? (int)Motor_speed[i] : 100;
#else
//ESC[0] = (int)Motor_speed[0]>50 ? (int)Motor_speed[0] : 50; // right diagonal
//ESC[2] = (int)Motor_speed[2]>50 ? (int)Motor_speed[2] : 50;
ESC[1] = (int)Motor_speed[1]>50 ? (int)Motor_speed[1] : 50; // left diagonal
ESC[3] = (int)Motor_speed[3]>50 ? (int)Motor_speed[3] : 50;
#endif
} else {
for(int i=0;i<4;i++) // for security reason, set every motor to zero speed
ESC[i] = 0;
//debug = true;
}
Times[6] = LoopTimer.read(); // 6us
LEDs.rollnext();
counter++;
Times[7] = LoopTimer.read(); // 7us TOTAL 297us
//while(LoopTimer.read() < 1/control_frequency); // Kill the rest of the time TODO: make a better solution so we can do misc things with these cycles
Times[8] = LoopTimer.read();
LoopTimer.stop();
LoopTimer.reset();
if(toRCCalibrate) {
toRCCalibrate = false;
LEDs.shownumber(0xF);
RC.calibrate(10);
LEDs.rollreset();
}
if (debug) {
pc.printf("$STATE,%d,%d,%.f,%.3f,%.3f\r\n", RC.armed(), level, control_frequency, IMU.dt*1e3, IMU.dt_sensors*1e6);
pc.printf("$RC, %d,%.0f,%.0f,%.0f,%.0f,%.0f,%.0f,%.0f\r\n", RC.present(), RC[AILERON], RC[ELEVATOR], RC[RUDDER], RC[THROTTLE], RC[CHANNEL6], RC[CHANNEL7], RC[CHANNEL8]);
//pc.printf("$GYRO,%.3f,%.3f,%.3f\r\n", IMU.mpu.Gyro[ROLL], IMU.mpu.Gyro[PITCH], IMU.mpu.Gyro[YAW]);
//pc.printf("$GYRO2,%.3f,%.3f,%.3f\r\n", IMU.mpu2.data_gyro[ROLL], IMU.mpu2.data_gyro[PITCH], IMU.mpu2.data_gyro[YAW]);
//pc.printf("$ACC,%.3f,%.3f,%.3f\r\n", IMU.mpu.Acc[ROLL], IMU.mpu.Acc[PITCH], IMU.mpu.Acc[YAW]);
//pc.printf("$ANG,%.3f,%.3f,%.3f\r\n", IMU.angle[ROLL], IMU.angle[PITCH], IMU.angle[YAW]);
pc.printf("$RCANG,%.3f,%.3f,%.3f\r\n", RC._angle[ROLL], RC._angle[PITCH], RC._angle[YAW]);
pc.printf("$CONTR,%.3f,%.3f,%.3f,%.3f,%.3f,%.3f,%.3f\r\n", Controller_Rate[ROLL].Value, Controller_Rate[PITCH].Value, Controller_Rate[YAW].Value, P_R, I_R, D_R, PY);
//pc.printf("$FILTER,%.3f,%.3f,%.3f\r\n", gyro_filter[ROLL].get_cutoff_freq(), gyro_filter[PITCH].get_cutoff_freq(), gyro_filter[YAW].get_cutoff_freq());
pc.printf("$CONTA,%.3f,%.3f,%.3f,%.3f,%.3f,%.3f\r\n", Controller_Angle[ROLL].Value, Controller_Angle[PITCH].Value, Controller_Angle[YAW].Value, P_A, I_A, D_A);
//pc.printf("$MOT,%d,%d,%d,%d\r\n", (int)Motor_speed[0], (int)Motor_speed[1], (int)Motor_speed[2], (int)Motor_speed[3]);
/*pc.printf("$TIMES");
for(int i = 1; i < 10; i++)
pc.printf(",%.3f", (Times[i]-Times[i-1])*1e6);
pc.printf("\r\n");*/
wait(0.1);
} else {
/*int toplot = (int)(IMU.mpu.Gyro[1])*10;
for(int i = 0; i < toplot+200; i++)
pc.putc('=');
pc.putc('\r');
pc.putc('\n');*/
/*pc.putc('#');
pc.putc('!');
pc.putc('#');
float tosend = IMU.mpu.Gyro[1];
//float tosend = gyro_filter.apply(IMU.mpu.Gyro[1]);
//float tosend = gyro_filter.apply((RC[ELEVATOR]-500.0)*100.0/500.0);
for(unsigned int i = 0; i < sizeof(tosend); i++)
pc.putc(((char*)&tosend)[i]);*/
}
}
void executer() {
char command = pc.getc();
switch(command) {
case 'X': mbed_reset(); break;
case '-': debug = !debug; break;
case ':': RC._armed = true; break;
case ' ': RC._armed = false; break;
case 'q': level = true; break;
case 'a': level = false; break;
case 'w': P_R += 0.1; break;
case 's': P_R -= 0.1; break;
case 'e': I_R += 0.1; break;
case 'd': I_R -= 0.1; break;
case 'x': D_R += 0.01; break;
case 'c': D_R -= 0.01; break;
case 'r': P_A += 0.1; break;
case 'f': P_A -= 0.1; break;
case 't': I_A += 0.1; break;
case 'g': I_A -= 0.1; break;
case 'z': D_A += 0.01; break;
case 'h': D_A -= 0.01; break;
case 'u': PY += 0.1; break;
case 'j': PY -= 0.1; break;
case 'o': control_frequency += 100; break;
case 'l': control_frequency -= 100; break;
case '?': toRCCalibrate = true; break;
case '\'': RC.enableStickCentering(); break;
/*case 'b': {
gyro_filter_frequ += 5;
for(int i=0;i<3;i++)
gyro_filter[i].set_cutoff_frequency(control_frequency, gyro_filter_frequ);
} break;
case 'v': {
gyro_filter_frequ -= 5;
for(int i=0;i<3;i++)
gyro_filter[i].set_cutoff_frequency(control_frequency, gyro_filter_frequ);
} break;*/
}
pc.putc(command);
LEDs.tilt(2);
}
int main() {
pc.attach(&executer);
while(1) {
loop();
}
}