-
Notifications
You must be signed in to change notification settings - Fork 0
Expand file tree
/
Copy pathautoPilot.cpp
More file actions
125 lines (123 loc) · 3.77 KB
/
autoPilot.cpp
File metadata and controls
125 lines (123 loc) · 3.77 KB
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
#include "autoPilot.h"
#include "miniCopterPro.h"
#define copter ((miniCopterPro*)copterPointer)
//------------------------------------------------------------------------------
void autoPilot::init(){
copter->io.sendMesgNoNl(ioText_pilotInit);
pidDataPointers[0][0]=copter->sensors.getPitchPointer();
pidDataPointers[0][1]=copter->getPitchTargetPointer();
pidDataPointers[1][0]=copter->sensors.getRollPointer();
pidDataPointers[1][1]=copter->getRollTargetPointer();
pidDataPointers[2][0]=copter->sensors.getYawPointer();
pidDataPointers[2][1]=copter->getYawTargetPointer();
pidDataPointers[3][0]=copter->sensors.getPitchPointer();
pidDataPointers[3][1]=copter->getPitchTargetPointer();
workMode = PILOT_MODE_GIMBAL_RUN;
initPID();
copter->io.sendMesgNoStart(ioText_OK);
}
//------------------------------------------------------------------------------
void autoPilot::fixGimbal(){
copter->effectors.setGimbalArc(0,copter->sensors.getRoll()+copter->getGimbalTarget(0));
copter->effectors.setGimbalArc(1,copter->sensors.getPitch()+copter->getGimbalTarget(1));
}
//------------------------------------------------------------------------------
void autoPilot::tunePID(int pidNo,double* pidK){
uint8_t i;
for(i=0;i<12;i++)
saveInEEPROM(i+(pidNo*12), *((byte*)(&pidK)+i) );
initPID();
}
void autoPilot::initPID(){
double pidK[3] = {1.0,0.5,0.1};
uint8_t pidNo,i;
for(pidNo=0;pidNo<4;pidNo++){
// Free on reload
if(pids[pidNo])
free(pids[pidNo]);
// Load from EEPROM
if(
170 == getEEPROM(3) &&
170 == getEEPROM(2) &&
170 == getEEPROM(1) &&
170 == getEEPROM(0)
)
for(i=0;i<12;i++)
*(((byte*)pidK)+i) = getEEPROM(4 + i + (pidNo*12));
// Create PID
pids[pidNo] =
new PID(
// Input
pidDataPointers[pidNo][0],
// Output
pidsOut+pidNo,
// Target
pidDataPointers[pidNo][2],
pidK[0], // P
pidK[1], // I
pidK[2], // D
DIRECT
);
}
}
//------------------------------------------------------------------------------
void autoPilot::fixPlatform(){
static double throtle = 0 ;
pids[CPID_ROLL]->Compute();
pids[CPID_ROT]->Compute();
pids[CPID_PITCH]->Compute();
// pids[CPID_THROTLE]->Compute();
throtle = copter->getAltChangeTarget();
copter->effectors.setMotorSpeed(0,
pidsOut[CPID_ROT] + pidsOut[CPID_ROLL] + pidsOut[CPID_PITCH] + throtle
);
copter->effectors.setMotorSpeed(1,
-pidsOut[CPID_ROT] + pidsOut[CPID_ROLL] - pidsOut[CPID_PITCH] + throtle
);
copter->effectors.setMotorSpeed(2,
pidsOut[CPID_ROT] - pidsOut[CPID_ROLL] - pidsOut[CPID_PITCH] + throtle
);
copter->effectors.setMotorSpeed(3,
-pidsOut[CPID_ROT] - pidsOut[CPID_ROLL] + pidsOut[CPID_PITCH] + throtle
);
}
//------------------------------------------------------------------------------
void autoPilot::doJob(){
switch(workMode){
case PILOT_MODE_FLY:
/*********************************************/
fixPlatform();
fixGimbal();
/*###########################################*/
break;
case PILOT_MODE_IDLE:
/*********************************************/
copter->effectors.stopMotors();
copter->effectors.setGimbalArc(0,0);
copter->effectors.setGimbalArc(0,1);
/*###########################################*/
break;
case PILOT_MODE_GIMBAL_RUN:
/*********************************************/
fixGimbal();
copter->effectors.stopMotors();
/*###########################################*/
break;
case PILOT_MODE_MOTOR_TEST:
/*********************************************/
copter->effectors.setMotorSpeed(0,
copter->getPitchTarget()
);
copter->effectors.setMotorSpeed(1,
copter->getPitchTarget()
);
copter->effectors.setMotorSpeed(2,
copter->getPitchTarget()
);
copter->effectors.setMotorSpeed(3,
copter->getPitchTarget()
);
/*###########################################*/
break;
}
}