-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathexample16.js
305 lines (262 loc) · 10.4 KB
/
example16.js
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
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
var http = require("http").createServer(handler); // on req - hand
var io = require("socket.io").listen(http); // socket library
var fs = require("fs"); // variable for file system for providing html
var firmata = require("firmata");
console.log("Starting the code");
var board = new firmata.Board("COM3", function () {
console.log("Connecting to Arduino");
board.pinMode(0, board.MODES.ANALOG); // enable analog pin 0
board.pinMode(1, board.MODES.ANALOG); // enable analog pin 1
board.pinMode(2, board.MODES.OUTPUT); // direction of DC motor
board.pinMode(3, board.MODES.PWM); // PWM of motor
});
function handler(req, res) {
fs.readFile(__dirname + "/example16.html",
function (err, data) {
if (err) {
res.writeHead(500, {
"Content-Type": "text/plain"
});
return res.end("Error loading html page.");
}
res.writeHead(200);
res.end(data);
})
}
var desiredValue = 0; // desired value var
var actualValue = 0; // actual value var
var pwm = 0; // set pwm as global variable
var pwmLimit = 254; // to limit value of the pwm that is sent to the motor
var err = 0; // error
var errSum = 0; // sum of errors as integral
var dErr = 0; // difference of error
var lastErr = 0; // to keep the value of previous error to estimate derivative
var controlAlgorithmStartedFlag = 0; // variable for indicating weather the Alg has benn sta.
var intervalCtrl; // var for setInterval in global scope
http.listen(8080); // server will listen on port 8080
board.on("ready", function () {
board.analogRead(0, function (value) {
desiredValue = value; // continuous read of analog pin 0
});
board.analogRead(1, function (value) {
actualValue = value; // continuous read of analog pin 1
});
io.sockets.on("connection", function (socket) {
socket.emit("messageToClient", "Srv connected, board OK");
socket.emit("staticMsgToClient", "Srv connected, board OK"); // ??????
setInterval(sendValues, 40, socket); // on 40ms trigerr func. sendValues
socket.on("startControlAlgorithm", function(numberOfControlAlgorithm){
startControlAlgorithm(numberOfControlAlgorithm);
});
socket.on("stopControlAlgorithm", function(){
stopControlAlgorithm();
});
sendStaticMsgViaSocket = function(value) {
io.sockets.emit("staticMsgToClient", value);
};
}); // end of sockets.on connection
}); // end of board.on ready
////////////////////////////////////////////////fuzzy
var NFuzzyVars = 2;
var NFuzzyOutputs = 1;
var NFuzzySets = new Array(NFuzzyVars);
NFuzzySets[0] = 3;
NFuzzySets[1] = 3;
var FSvalues = new Array(NFuzzyVars);
for (var i = 0; i != NFuzzyVars; i++) {
FSvalues[i] = new Array(NFuzzySets[i]);
for (var j = 0; j != NFuzzySets[i]; j++) {
FSvalues[i][j] = new Array(3);
}
}
var NRules = 3;
var RBase = new Array(NRules);
for (var i = 0; i != NRules; i++) {
RBase[i] = new Array(NFuzzyVars);
}
var ValuesForFuzzy = new Array(NFuzzyVars);
ValuesForFuzzy[0] = 0;
ValuesForFuzzy[1] = 0;
var AlphaCut = new Array(NFuzzySets[0]);
var RN = 0;
RBase[RN][0] = 0;
RBase[RN][1] = 0;
RN++;
RBase[RN][0] = 1;
RBase[RN][1] = 1;
RN++;
RBase[RN][0] = 2;
RBase[RN][1] = 2;
RN++;
var FSpos1 = 125;
var FSpos2 = 25;
function resetFSvalues() {
FSvalues[0][0][0] = -FSpos1;
FSvalues[0][0][1] = -FSpos1;
FSvalues[0][0][2] = 0;
FSvalues[0][1][0] = -FSpos1;
FSvalues[0][1][1] = 0;
FSvalues[0][1][2] = FSpos1;
FSvalues[0][2][0] = 0;
FSvalues[0][2][1] = FSpos1;
FSvalues[0][2][2] = FSpos1;
FSvalues[1][0][0] = -FSpos2;
FSvalues[1][0][1] = -FSpos2;
FSvalues[1][0][2] = 0;
FSvalues[1][1][0] = -FSpos2;
FSvalues[1][1][1] = 0;
FSvalues[1][1][2] = FSpos2;
FSvalues[1][2][0] = 0;
FSvalues[1][2][1] = FSpos2;
FSvalues[1][2][2] = FSpos2;
}
function getMRFromFSvalues(value, NumOfVar, NumOfSet) {
if (NumOfSet === 0) {
if (value < FSvalues[NumOfVar][NumOfSet][0]) {
return 1;
} else if (value > FSvalues[NumOfVar][NumOfSet][2]) {
return 0;
} else {
return (FSvalues[NumOfVar][NumOfSet][2] - value) / (FSvalues[NumOfVar][NumOfSet][2] - FSvalues[NumOfVar][NumOfSet][1]);
}
} else if (NumOfSet === NFuzzySets[NumOfVar] - 1) {
if (value < FSvalues[NumOfVar][NumOfSet][0]) {
return 0;
} else if (value > FSvalues[NumOfVar][NumOfSet][2]) {
return 1;
} else if (value < FSvalues[NumOfVar][NumOfSet][1]) {
return (value - FSvalues[NumOfVar][NumOfSet][0]) / (FSvalues[NumOfVar][NumOfSet][1] - FSvalues[NumOfVar][NumOfSet][0]);
}
} else {
if (value < FSvalues[NumOfVar][NumOfSet][0]) {
return 0;
} else if (value > FSvalues[NumOfVar][NumOfSet][2]) {
return 0;
} else if (value < FSvalues[NumOfVar][NumOfSet][1]) {
return (value - FSvalues[NumOfVar][NumOfSet][0]) / (FSvalues[NumOfVar][NumOfSet][1] - FSvalues[NumOfVar][NumOfSet][0]);
} else {
return (FSvalues[NumOfVar][NumOfSet][2] - value) / (FSvalues[NumOfVar][NumOfSet][2] - FSvalues[NumOfVar][NumOfSet][1]);
}
}
}
function getDesiredValuesFuzzy() {
resetFSvalues();
for (var j = 0; j != NFuzzySets[0]; j++) {
AlphaCut[j] = 0;
}
for (var i = 0; i != NRules; i++) {
var tempMR = 0;
var tempMinMR = 1;
for (var CurrentVar = NFuzzyOutputs; CurrentVar != NFuzzyVars; CurrentVar++) {
tempMR = getMRFromFSvalues(ValuesForFuzzy[CurrentVar], CurrentVar, RBase[i][CurrentVar]);
if (tempMR < tempMinMR)
tempMinMR = tempMR;
}
for (var CurrentVar = 0; CurrentVar != NFuzzyOutputs; CurrentVar++) {
if (tempMinMR > AlphaCut[RBase[i][CurrentVar]])
AlphaCut[RBase[i][CurrentVar]] = tempMinMR;
}
}
for (var CurrentVar = 0; CurrentVar != NFuzzyOutputs; CurrentVar++) {
var FuzzyRange = FSvalues[CurrentVar][NFuzzySets[CurrentVar] - 1][2] - FSvalues[CurrentVar][0][0];
console.log(FuzzyRange);
var NIntervals = 100;
var CoordinateMassSumm = 0;
var MassSumm = 0;
for (var i = 0; i != NIntervals; i++) {
var TempCoordinate = FSvalues[CurrentVar][0][0] + FuzzyRange / NIntervals * i;
var TempMass1 = 0;
var TempMass2 = 0;
for (var j = 0; j != NFuzzySets[CurrentVar]; j++) {
TempMass2 = getMRFromFSvalues(TempCoordinate, CurrentVar, j);
if (TempMass2 > AlphaCut[j])
TempMass2 = AlphaCut[j];
if (TempMass2 > TempMass1)
TempMass1 = TempMass2;
}
MassSumm += TempMass1;
CoordinateMassSumm += TempCoordinate * TempMass1;
}
if (MassSumm != 0)
ValuesForFuzzy[CurrentVar] = CoordinateMassSumm / MassSumm;
if (ValuesForFuzzy[CurrentVar].isNaN)
ValuesForFuzzy[CurrentVar] = 0;
}
}
////////////////////////////////////////////////unfuzzy
function sendPwmToArduino() {
if (pwm > pwmLimit) {pwm = pwmLimit} // to limit pwm values
if (pwm < -pwmLimit) {pwm = -pwmLimit} // to limit pwm values
if (pwm > 0) {board.digitalWrite(2, 0)} // direction if > 0
if (pwm < 0) {board.digitalWrite(2, 1)} // direction if < 0
board.analogWrite(3, Math.abs(pwm));
}
function controlAlgorithm (parameters) {
switch (parameters.ctrlAlgNo) {
case 1:
pwm = parameters.pCoeff * (desiredValue - actualValue);
sendPwmToArduino();
break;
case 2:
err = desiredValue - actualValue; // error as difference between desired and actual val.
errSum += err; // sum of errors | like integral
dErr = err - lastErr; // difference of error
pwm = parameters.Kp1 * err + parameters.Ki1 * errSum + parameters.Kd1 * dErr; // PID expression
lastErr = err; // save the value of error for next cycle to estimate the derivative
sendPwmToArduino();
break;
case 3:
err = desiredValue - actualValue; // error as difference between desired and actual val.
errSum += err; // sum of errors | like integral
dErr = err - lastErr; // difference of error
pwm = parameters.Kp2 * err + parameters.Ki2 * errSum + parameters.Kd2 * dErr; // PID expression
console.log(parameters.Kp2 + "|" + parameters.Ki2 + "|" + parameters.Kd2);
lastErr = err; // save the value of error for next cycle to estimate the derivative
sendPwmToArduino();
break;
case 4:
ValuesForFuzzy[1] = desiredValue - actualValue;
FSpos1 = parameters.FSpos1;
FSpos2 = parameters.FSpos2;
//console.log(parameters);
getDesiredValuesFuzzy();
pwm = ValuesForFuzzy[0];
err = desiredValue - actualValue; // error as difference between desired and actual val.
lastErr = err; // save the value of error for next cycle to estimate the derivative
sendPwmToArduino();
break;
}
};
function startControlAlgorithm (parameters) {
if (controlAlgorithmStartedFlag === 0) {
controlAlgorithmStartedFlag = 1;
intervalCtrl = setInterval(function(){controlAlgorithm(parameters);}, 30); // call the alg. on 30ms
console.log("Control algorithm has been started.");
sendStaticMsgViaSocket("Control alg " + parameters.ctrlAlgNo + " started | " + JSON.stringify(parameters));
}
};
function stopControlAlgorithm () {
clearInterval(intervalCtrl); // clear the interval of control algorihtm
board.analogWrite(3, 0);
err = 0; // error as difference between desired and actual val.
errSum = 0; // sum of errors | like integral
dErr = 0;
lastErr = 0; // difference
pwm = 0;
controlAlgorithmStartedFlag = 0;
console.log("Control algorithm has been stopped.");
sendStaticMsgViaSocket("Stopped.")
};
function sendValues (socket) {
socket.emit("clientReadValues",
{
"desiredValue": desiredValue,
"actualValue": actualValue,
"pwm": pwm,
"err": err,
"errSum": errSum,
"dErr": dErr,
"AlphaCut":AlphaCut,
"ValuesForFuzzy":ValuesForFuzzy
});
};