

과적분 보정 함수 추가
@9246661c8da274f562f73f6f6c14ace56623a225
+++ Back_calculate_0_280.ino
... | ... | @@ -0,0 +1,223 @@ |
1 | +// === 1번 모터 핀 정의 === | |
2 | +#define DIR_1 8 | |
3 | +#define ST_1 9 | |
4 | +#define PWM_1 45 | |
5 | +#define ENCA_1 2 | |
6 | +#define ENCB_1 3 | |
7 | + | |
8 | +// === 2번 모터 핀 정의 === | |
9 | +#define DIR_2 22 | |
10 | +#define ST_2 24 | |
11 | +#define PWM_2 44 | |
12 | +#define ENCA_2 18 | |
13 | +#define ENCB_2 19 | |
14 | + | |
15 | +// === 목표 RPM (부호 포함) === | |
16 | +int setRPM1 = 0; | |
17 | +int setRPM2 = 0; | |
18 | + | |
19 | +// === PID 계수 === | |
20 | +double kp1 = 0.5, ki1 = 3, kd1 = 0.01; | |
21 | +double kp2 = 0.0, ki2 = 0.0, kd2 = 0.0; | |
22 | +double kb1 = 2; // ← Back Calculation 계수 | |
23 | + | |
24 | +// === 상태 변수 === | |
25 | +// 1번 모터 | |
26 | +volatile long encoderPos1 = 0; | |
27 | +double rpm1 = 0; | |
28 | +int calPWM1 = 0; | |
29 | +double error1 = 0, prevError1 = 0, integral1 = 0, derivative1 = 0; | |
30 | +double prevRPM1 = 0; | |
31 | +double alpha = 0.2; | |
32 | +double backError1 = 0; | |
33 | + | |
34 | +// 2번 모터 | |
35 | +volatile long encoderPos2 = 0; | |
36 | +double rpm2 = 0; | |
37 | +int calPWM2 = 0; | |
38 | +double error2 = 0, prevError2 = 0, integral2 = 0, derivative2 = 0; | |
39 | + | |
40 | +// 제어 주기 | |
41 | +const unsigned long interval = 30; | |
42 | +unsigned long prevTime = 0; | |
43 | +double dt = interval / 1000.0; | |
44 | + | |
45 | +// === 인터럽트 핸들러 === | |
46 | +void doEncoderA1() { | |
47 | + if (digitalRead(ENCB_1) == LOW) encoderPos1++; | |
48 | + else encoderPos1--; | |
49 | +} | |
50 | +void doEncoderB1() { | |
51 | + if (digitalRead(ENCA_1) == HIGH) encoderPos1++; | |
52 | + else encoderPos1--; | |
53 | +} | |
54 | +void doEncoderA2() { | |
55 | + if (digitalRead(ENCB_2) == LOW) encoderPos2--; | |
56 | + else encoderPos2++; | |
57 | +} | |
58 | +void doEncoderB2() { | |
59 | + if (digitalRead(ENCA_2) == HIGH) encoderPos2--; | |
60 | + else encoderPos2++; | |
61 | +} | |
62 | + | |
63 | +// === RPM 계산 함수 === | |
64 | +double calculateRPM(long counts) { | |
65 | + return ((double)counts / (4096.0 * 2)) * (60.0 / dt); | |
66 | +} | |
67 | + | |
68 | +// === PID 계산 함수 === | |
69 | +int computePID(double currentRPM, double &error, double &prevError, | |
70 | + double &integral, double &derivative, int targetRPM, | |
71 | + double kp, double ki, double kd, bool isMotor1) { | |
72 | + error = targetRPM - currentRPM; | |
73 | + integral += error * dt; | |
74 | + | |
75 | + if (isMotor1) { | |
76 | + double rawDerivative = -(currentRPM - prevRPM1) / dt; | |
77 | + derivative = alpha * rawDerivative + (1 - alpha) * derivative1; | |
78 | + prevRPM1 = currentRPM; | |
79 | + | |
80 | + double P = kp * error; | |
81 | + double I = ki * integral; | |
82 | + double D = kd * derivative; | |
83 | + double output = P + I + D; | |
84 | + | |
85 | + // Back Calculation | |
86 | + double outputSat = constrain(output, 0, 255); | |
87 | + backError1 = outputSat - output; | |
88 | + integral += kb1 * backError1 * dt; | |
89 | + | |
90 | + Serial.print(setRPM1); Serial.print('\t'); | |
91 | + Serial.print(currentRPM, 2); Serial.print('\t'); | |
92 | + Serial.print("P : "); Serial.print(P, 2); Serial.print('\t'); | |
93 | + Serial.print("I : "); Serial.print(I, 2); Serial.print('\t'); | |
94 | + Serial.print("D : "); Serial.print(D, 2); Serial.println('\t'); | |
95 | + | |
96 | + return (int)output; | |
97 | + } else { | |
98 | + derivative = (error - prevError) / dt; | |
99 | + prevError = error; | |
100 | + return (int)((kp * error) + (ki * integral) + (kd * derivative)); | |
101 | + } | |
102 | +} | |
103 | + | |
104 | +// === 실시간 입력 === | |
105 | +void serialSetRPM() { | |
106 | + if (Serial.available()) { | |
107 | + String input = Serial.readStringUntil('\n'); | |
108 | + input.trim(); | |
109 | + | |
110 | + int rIndex = input.indexOf('R'); | |
111 | + int lIndex = input.indexOf('L'); | |
112 | + | |
113 | + if (rIndex == -1 && lIndex == -1) { | |
114 | + Serial.println("입력 오류: 'R' 또는 'L'이 포함되어야 합니다. 예: R100 L-80"); | |
115 | + return; | |
116 | + } | |
117 | + | |
118 | + bool validInput = false; | |
119 | + | |
120 | + if (rIndex != -1) { | |
121 | + int end = (lIndex != -1 && lIndex > rIndex) ? lIndex : input.length(); | |
122 | + String rValStr = input.substring(rIndex + 1, end); | |
123 | + rValStr.trim(); | |
124 | + | |
125 | + if (rValStr.length() == 0) { | |
126 | + Serial.println("오류: R 뒤에 숫자가 없습니다. 예: R100"); | |
127 | + } else { | |
128 | + int rpmVal = rValStr.toInt(); | |
129 | + if (String(rpmVal) != rValStr || abs(rpmVal) > 400) { | |
130 | + Serial.println("오류: R 값 형식 또는 범위 초과"); | |
131 | + } else { | |
132 | + setRPM1 = rpmVal; | |
133 | + Serial.print("모터1 (R) 목표 RPM → "); Serial.println(setRPM1); | |
134 | + validInput = true; | |
135 | + } | |
136 | + } | |
137 | + } | |
138 | + | |
139 | + if (lIndex != -1) { | |
140 | + int end = (rIndex != -1 && rIndex > lIndex) ? rIndex : input.length(); | |
141 | + String lValStr = input.substring(lIndex + 1, end); | |
142 | + lValStr.trim(); | |
143 | + | |
144 | + if (lValStr.length() == 0) { | |
145 | + Serial.println("오류: L 뒤에 숫자가 없습니다. 예: L-80"); | |
146 | + } else { | |
147 | + int rpmVal = lValStr.toInt(); | |
148 | + if (String(rpmVal) != lValStr || abs(rpmVal) > 400) { | |
149 | + Serial.println("오류: L 값 형식 또는 범위 초과"); | |
150 | + } else { | |
151 | + setRPM2 = rpmVal; | |
152 | + Serial.print("모터2 (L) 목표 RPM → "); Serial.println(setRPM2); | |
153 | + validInput = true; | |
154 | + } | |
155 | + } | |
156 | + } | |
157 | + | |
158 | + if (!validInput) { | |
159 | + Serial.println("R숫자 L숫자 형식으로 입력해주세요. 예: R100 L-80"); | |
160 | + } | |
161 | + } | |
162 | +} | |
163 | + | |
164 | +void setup() { | |
165 | + Serial.begin(19200); | |
166 | + | |
167 | + pinMode(DIR_1, OUTPUT); pinMode(PWM_1, OUTPUT); pinMode(ST_1, OUTPUT); | |
168 | + pinMode(ENCA_1, INPUT_PULLUP); pinMode(ENCB_1, INPUT_PULLUP); | |
169 | + attachInterrupt(digitalPinToInterrupt(ENCA_1), doEncoderA1, RISING); | |
170 | + attachInterrupt(digitalPinToInterrupt(ENCB_1), doEncoderB1, RISING); | |
171 | + | |
172 | + pinMode(DIR_2, OUTPUT); pinMode(PWM_2, OUTPUT); pinMode(ST_2, OUTPUT); | |
173 | + pinMode(ENCA_2, INPUT_PULLUP); pinMode(ENCB_2, INPUT_PULLUP); | |
174 | + attachInterrupt(digitalPinToInterrupt(ENCA_2), doEncoderA2, RISING); | |
175 | + attachInterrupt(digitalPinToInterrupt(ENCB_2), doEncoderB2, RISING); | |
176 | + | |
177 | + digitalWrite(ST_1, LOW); | |
178 | + digitalWrite(ST_2, LOW); | |
179 | + prevTime = millis(); | |
180 | +} | |
181 | + | |
182 | +void loop() { | |
183 | + unsigned long now = millis(); | |
184 | + | |
185 | + if (now - prevTime >= interval) { | |
186 | + prevTime += interval; | |
187 | + | |
188 | + // 모터 1 | |
189 | + noInterrupts(); long currentPos1 = encoderPos1; encoderPos1 = 0; interrupts(); | |
190 | + rpm1 = calculateRPM(currentPos1); | |
191 | + calPWM1 = computePID(rpm1, error1, prevError1, integral1, derivative1, abs(setRPM1), kp1, ki1, kd1, true); | |
192 | + digitalWrite(DIR_1, setRPM1 >= 0 ? HIGH : LOW); | |
193 | + calPWM1 = constrain(abs(calPWM1), 0, 255); | |
194 | + analogWrite(PWM_1, calPWM1); | |
195 | + | |
196 | + // 모터 2 | |
197 | + noInterrupts(); long currentPos2 = encoderPos2; encoderPos2 = 0; interrupts(); | |
198 | + rpm2 = calculateRPM(currentPos2); | |
199 | + calPWM2 = computePID(rpm2, error2, prevError2, integral2, derivative2, abs(setRPM2), kp2, ki2, kd2, false); | |
200 | + digitalWrite(DIR_2, setRPM2 >= 0 ? HIGH : LOW); | |
201 | + calPWM2 = constrain(abs(calPWM2), 0, 255); | |
202 | + analogWrite(PWM_2, calPWM2); | |
203 | + | |
204 | + // 시리얼 출력 | |
205 | + // Serial.print("R:"); Serial.println(setRPM1); | |
206 | + // Serial.print("RPM:"); Serial.println(rpm1, 2); | |
207 | + // Serial.print("PWM:"); Serial.println(calPWM1); | |
208 | + // Serial.println(" "); | |
209 | + // Serial.print("L:"); Serial.println(setRPM2); | |
210 | + // Serial.print("RPM:"); Serial.println(rpm2, 2); | |
211 | + // Serial.print("PWM:"); Serial.println(calPWM2); | |
212 | + // Serial.println("--------------------"); | |
213 | + | |
214 | + // Serial Plotter용 출력 | |
215 | + Serial.print(setRPM1); Serial.print('\t'); | |
216 | + Serial.println(rpm1, 2); | |
217 | + // Serial.print(setRPM2); Serial.print('\t'); | |
218 | + // Serial.println(rpm2, 2); | |
219 | + } | |
220 | + | |
221 | + | |
222 | + serialSetRPM(); | |
223 | +} |
Add a comment
Delete comment
Once you delete this comment, you won't be able to recover it. Are you sure you want to delete this comment?