In this example, we will provide testing function, which will not include feedback. Later on, we could compare the response of the HW implementation and model. Outlook of the GUI (observe first two graphs in the first column - response to the pulse function) is in the following figure.
The red button is added to test the response of the motor to pulse function.
var http = require("http").createServer(handler); // on req - hand
var fs = require("fs"); // variable for file system for providing html
var firmata = require("firmata");
const WebSocket = require('ws'); // for permanent connection between server and client
const wss = new WebSocket.Server({port: 8888}); // websocket port is 8888
wss.broadcast = function broadcast(data) {
wss.clients.forEach(function each(client) {
if (client.readyState === WebSocket.OPEN) {
client.send(data);
}
});
};
var messageJSON;
var controlAlgorithmStartedFlag = 0; // variable for indicating weather the Alg has benn sta.
var intervalCtrl; // var for setInterval in global scope
var intervalPulseFunction; // for setTimeout / setInterval
var performanceMeasure = 0;
var readAnalogPin0Flag = 1; // flag for reading the pin if the pot is driver
console.log("Starting the code");
var board = new firmata.Board("/dev/ttyACM0", function(){
console.log("Connecting to Arduino");
console.log("Enabling analog Pin 0");
board.pinMode(0, board.MODES.ANALOG); // analog pin 0
board.pinMode(1, board.MODES.ANALOG); // analog pin 1
board.pinMode(2, board.MODES.OUTPUT); // direction of DC motor
board.pinMode(3, board.MODES.PWM); // PWM of motor i.e. speed of rotation
board.pinMode(4, board.MODES.OUTPUT); // direction DC motor
});
function handler(req, res) {
fs.readFile(__dirname + "/example24.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; // variable for actual value (output value)
var Kp1 = 0.55; // proportional factor of PID controller
var Ki1 = 0.008; // integral factor of PID controller
var Kd1 = 0.15; // differential factor of PID controller
var factor = 0.3; // proportional factor that determines speed of resonse
var pwm = 0; // set pwm as global variable
var pwmLimit = 150; // 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 KpE = 0; // multiplication of Kp x error
var KiIedt = 0; // multiplication of Ki x integ. of error
var KdDe_dt = 0; // multiplication of Kd x differential of err.
var errSumAbs = 0; // sum of absolute errors as performance measure
var errAbs = 0; // absolute error
var parametersStore ={}; // variable for json structure of parameters
http.listen(8080); // server will listen on port 8080
board.on("ready", function() {
board.analogRead(0, function(value){
if (readAnalogPin0Flag == 1) desiredValue = value; // continuous read of analog pin 0 - if we want desired value from the potentiometer
});
board.analogRead(1, function(value) {
actualValue = value; // continuous read of pin A1
if(actualValue < 150 || actualValue > 870) {
stopControlAlgorithm();
}
});
wss.on('connection', function (ws, req) { // start of wss code
messageJSON = {"type": "message", "content": "Srv connected, board OK"};
ws.send(JSON.stringify(messageJSON));
messageJSON = {"type": "staticMsgToClient", "content": "Srv connected, board OK"};
ws.send(JSON.stringify(messageJSON));
setInterval(sendValues, 40); // on 40ms we send message to client
ws.on("message", function (msgString) { // message comes as string -> msgString
var msg = JSON.parse(msgString); // string from ws which comes as a string is put to JSON
switch(msg.type) {
case "startControlAlgorithm":
startControlAlgorithm(msg); // msg has all values, alg. type and parameters
break;
case "stopControlAlgorithm":
stopControlAlgorithm();
break;
case "sendPosition":
readAnalogPin0Flag = 0; // we don't read from the analog pin anymore, value comes from GUI
desiredValue = msg.positionValue; // GUI takes control
messageJSON = {"type": "message", "content": "Position set to: " + msg.positionValue};
ws.send(JSON.stringify(messageJSON));
break;
case "sendInput":
readAnalogPin0Flag = 0; // we don't read from the analog pin anymore, value comes from GUI
desiredValue = msg.input; // GUI takes control
messageJSON = {"type": "message", "content": "Position set to: " + msg.input};
ws.send(JSON.stringify(messageJSON));
break;
}
}); // end of wss.on code
}); // end of sockets.on connection
}); // end of board.on(ready)
function controlAlgorithm (msg) { // the parameter in the argument holds ctrlAlgNo and param. values
if(msg.ctrlAlgNo == 1) {
err = desiredValue-actualValue;
pwm = msg.pCoeff*err;
errAbs = Math.abs(err);
errSumAbs += errAbs;
if(pwm > pwmLimit) {pwm = pwmLimit}; // to limit the value for pwm / positive
if(pwm < -pwmLimit) {pwm = -pwmLimit}; // to limit the value for pwm / negative
if (pwm > 0) {board.digitalWrite(2,1); board.digitalWrite(4,0);}; // določimo smer če je > 0
if (pwm < 0) {board.digitalWrite(2,0); board.digitalWrite(4,1);}; // določimo smer če je < 0
board.analogWrite(3, Math.abs(pwm));
console.log(Math.round(pwm));
}
if(msg.ctrlAlgNo == 2) {
err = desiredValue - actualValue; // error as difference between desired and actual val.
errSum += err; // sum of errors | like integral
errAbs = Math.abs(err);
errSumAbs += errAbs;
dErr = err - lastErr; // difference of error
// we will put parts of expression for pwm to
// global workspace
KpE = msg.Kp1*err;
KiIedt = msg.Ki1*errSum;
KdDe_dt = msg.Kd1*dErr;
pwm = KpE + KiIedt + KdDe_dt; // we use above parts for PID expression
lastErr = err; // save the value of error for next cycle to estimate the derivative
if(pwm > pwmLimit) {pwm = pwmLimit}; // to limit the value for pwm / positive
if(pwm < -pwmLimit) {pwm = -pwmLimit}; // to limit the value for pwm / negative
if (pwm > 0) {board.digitalWrite(2,1); board.digitalWrite(4,0);}; // determine direction if > 0
if (pwm < 0) {board.digitalWrite(2,0); board.digitalWrite(4,1);}; // determine direction if < 0
board.analogWrite(3, Math.abs(pwm));
};
if(msg.ctrlAlgNo == 3) {
err = desiredValue - actualValue; // error as difference between desired and actual val.
errSum += err; // sum of errors | like integral
errSumAbs += Math.abs(err);
dErr = err - lastErr; // difference of error
// we will put parts of expression for pwm to
// global workspace
KpE = msg.Kp2*err;
KiIedt = msg.Ki2*errSum;
KdDe_dt = msg.Kd2*dErr;
pwm = KpE + KiIedt + KdDe_dt; // we use above parts for PID expression
lastErr = err; // save the value of error for next cycle to estimate the derivative
if(pwm > pwmLimit) {pwm = pwmLimit}; // to limit the value for pwm / positive
if(pwm < -pwmLimit) {pwm = -pwmLimit}; // to limit the value for pwm / negative
if (pwm > 0) {board.digitalWrite(2,1); board.digitalWrite(4,0);}; // determine direction if > 0
if (pwm < 0) {board.digitalWrite(2,0); board.digitalWrite(4,1);}; // determine direction if < 0
board.analogWrite(3, Math.abs(pwm));
};
if (msg.ctrlAlgNo == 5) { // only input
pwm = desiredValue;
if(pwm > pwmLimit) {pwm = pwmLimit}; // to limit the value for pwm / positive
if(pwm < -pwmLimit) {pwm = -pwmLimit}; // to limit the value for pwm / negative
if (pwm > 0) {board.digitalWrite(2,1); board.digitalWrite(4,0);}; // določimo smer če je > 0
if (pwm < 0) {board.digitalWrite(2,0); board.digitalWrite(4,1);}; // določimo smer če je < 0
board.analogWrite(3, Math.round(Math.abs(pwm)));
console.log(Math.round(pwm));
}
}
function startControlAlgorithm (msg) {
if (controlAlgorithmStartedFlag == 0) {
// reset parameters
pwm = 0; // Reset Pulse Width Modulation value
err = 0; // Reset error
errSum = 0; // Reset sum of errors as integral
dErr = 0; // Reset difference of error
lastErr = 0; // Reset value which keeps the value of previous error to estimate derivative
controlAlgorithmStartedFlag = 1;
intervalCtrl = setInterval(function(){controlAlgorithm(msg);}, 30); // call the alg. on 30ms
console.log("Control algorithm has been started.");
messageJSON = {"type": "staticMsgToClient", "content": " No. " + msg.ctrlAlgNo + " started | " + json2txt(msg)};
wss.broadcast(JSON.stringify(messageJSON));
parametersStore = msg; // store to report back to the client on algorithm stop
}
};
function stopControlAlgorithm () {
clearInterval(intervalCtrl); // clear the interval of control algorihtm
board.analogWrite(3, 0);
controlAlgorithmStartedFlag = 0;
pwm = 0;
console.log("Control algorithm has been stopped.");
messageJSON = {"type": "staticMsgToClient", "content": "Control algorithm " + parametersStore.ctrlAlgNo + " stopped | " + json2txt(parametersStore) + " | errSumAbs = " + errSumAbs};
wss.broadcast(JSON.stringify(messageJSON));
parametersStore = {}; // empty temporary json object to report at controAlg stop
errSumAbs = 0; // put the value of the criteria function to 0
};
function sendValues () {
wss.broadcast(JSON.stringify({"type": "clientReadValues", "desiredValue": desiredValue, "actualValue": actualValue, "error": (desiredValue - actualValue), "pwm": (pwm).toFixed(0), "err": err,"errSum": errSum, "dErr": dErr, "KpE": KpE, "KiIedt": KiIedt, "KdDe_dt": KdDe_dt, "errSumAbs": errSumAbs, "errAbs": errAbs}));
};
function json2txt(obj) // function to print out the json names and values
{
var txt = '';
var recurse = function(_obj) {
if ('object' != typeof(_obj)) {
txt += ' = ' + _obj + '\n';
}
else {
for (var key in _obj) {
if (_obj.hasOwnProperty(key)) {
txt += '.' + key;
recurse(_obj[key]);
}
}
}
};
recurse(obj);
return txt;
}
<!DOCTYPE html>
<meta charset = utf8>
<html>
<head>
<title>Example with potentiometers</title>
</head>
<body onload="load()";>
<div>
<canvas id="canvas1" width ="200" height = "100" style="border: 1px dashed #00c3c3;"></canvas>
<canvas id="canvas4" width = "200" height = "100" style="border: 1px dashed #00c3c3;"></canvas>
<canvas id="canvas7" width = "200" height = "100" style="border: 1px dashed #00c3c3;"></canvas>
<br>
<canvas id="canvas2" width = "200" height = "100" style="border: 1px dashed #00c3c3;"></canvas>
<canvas id="canvas5" width = "200" height = "100" style="border: 1px dashed #00c3c3;"></canvas>
<canvas id="canvas8" width = "200" height = "100" style="border: 1px dashed #00c3c3;"></canvas>
<br>
<canvas id="canvas3" width = "200" height = "100" style="border: 1px dashed #00c3c3;"></canvas>
<canvas id="canvas6" width = "200" height = "100" style="border: 1px dashed #00c3c3;"></canvas>
<canvas id="canvas9" width = "200" height = "100" style="border: 1px dashed #00c3c3;"></canvas>
<p></p>
</div>
Position: <input id="position" value=512 />
Set Algorithm: <input id="whichAlgorithm" value=1 />
<button id="sendPosition" onClick="sendPosition()">Send position</button>
<p></p>
Pulse duration in s: <input id="pulseDuration" value="7" size="5" />
<button id="pulse" onClick="pulseTimed()">Send pulse</button>
<button id="pulse" onClick="pulseTimed2();" style="width:160;height:24; background-color:#ff4c4c">Send Test Input</button>
<button id="buttonStop" onClick="stop()">Stop pulse</button>
<button id="testFunction" onClick="startTestFunction()">Send test Fun</button>
<br>
pCoeff: <input id="pCoeff" value="0.1" size="5" />
<button id="buttonStartControlAlgorithm1" onClick="startControlAlgorithm1();">Start Ctrl Alg1</button>
<button id="buttonStopControlAlgorithm" onClick="stopControlAlgorithm();">Stop Ctrl Alg</button>
<p></p>
Kp: <input id="Kp1" value="0.15" size = "5" />
Ki: <input id="Ki1" value="0.0055" size = "5" />
Kd: <input id="Kd1" value="0.25" size = "5" />
<button id="buttonStartControlAlgorithm2" onClick="startControlAlgorithm2();">Start Ctrl Alg2</button>
<button id="buttonStopControlAlgorithm" onClick="stopControlAlgorithm();">Stop Ctrl Alg</button>
<p></p>
Kp: <input id="Kp2" value="0.5" size = "5" />
Ki: <input id="Ki2" value="0.008" size = "5" />
Kd: <input id="Kd2" value="0.35" size = "5" />
<button id="buttonStartControlAlgorithm3" onClick="startControlAlgorithm3();">Start Ctrl Alg3</button>
<button id="buttonStopControlAlgorithm" onClick="stopControlAlgorithm();">Stop Ctrl Alg</button>
<div id="divForStaticPrint"> </div>
<p></p>
<div id="print1"></div>
<br>
<script type="text/javascript">
"use strict"; // in order to use clasess
var potValue1 = 0; // value of the first potentiometer
var potValue2 = 0; // value of second potentiometer
var pwm = 0;
var pCoeff = 0;
var Kp1 = 0;
var Ki1 = 0;
var Kd1 = 0;
var graph1; // variable for graph object
var graph2; // variable for graph object
var graph3; // variable for graph object
var graph4; // variable for graph object
var graph5; // variable for graph object
var graph6; // variable for graph object
var graph7; // variable for graph object
var graph8; // variable for graph object
var graph9; // variable for graph object
var divPrint1; // var for object div print
let ws = new WebSocket("ws://192.168.254.149:8888"); // create socket - connect to it
var messageJSON;
var intervalPulseFunction;
var performanceMeasure;
var intervalTestFunction; // for setTimeout / setInterval
var timeCounter = 0;
function load() { // function that is started, when we open the page
// create graph1 ~ graph7 objects for displaying the graphs
graph1 = new Graph("canvas1", 0, 200, 0, 1023, ["green"], ["Actual"], ["0", "200", "0", "1023"]); // arguments: Arg1: canvasId, Arg2: maxX, Arg3: maxY, Arg4: [vector of colors]; this determines the size of yValue matrix (if we state one color as eg. ["red"], we assume only one time series, ["red", "green", "blue"] -> three time series)
graph2 = new Graph("canvas2", 0, 200, -254, 254, ["orange"], ["PWM"], ["0", "200", "-254", "254"]);
graph3 = new Graph("canvas3", 0, 200, -100, 100, ["red", "green", "blue"], ["KpE", "KiIedt", "KdDe_dt"], ["0", "200", "-100", "100"]); // arguments: Arg1: canvasId, Arg2: maxX, Arg3: maxY, Arg4: [vector of colors]; this determines the size of yValue matrix (if we state one color as eg. ["red"], we assume only one time series, ["red", "green", "blue"] -> three time series)
graph4 = new Graph("canvas4", 0, 200, -1023, 1023, ["red"], ["Error"], ["0", "200", "-1023", "1023"]); // arguments: Arg1: canvasId, Arg2: maxX, Arg3: maxY, Arg4: [vector of colors]; this determines the size of yValue matrix (if we state one color as eg. ["red"], we assume only one time series, ["red", "green", "blue"] -> three time series)
graph5 = new Graph("canvas5", 0, 200, -10000, 10000, ["red"], ["Integ(Err*dt)"], ["0", "200", "-10000", "10000"]); // arguments: Arg1: canvasId, Arg2: maxX, Arg3: maxY, Arg4: [vector of colors]; this determines the size of yValue matrix (if we state one color as eg. ["red"], we assume only one time series, ["red", "green", "blue"] -> three time series)
graph6 = new Graph("canvas6", 0, 200, -150, 150, ["red"], ["dError/dt"], ["0", "200", "-150", "150"]); // arguments: Arg1: canvasId, Arg2: maxX, Arg3: maxY, Arg4: [vector of colors]; this determines the size of yValue matrix (if we state one color as eg. ["red"], we assume only one time series, ["red", "green", "blue"] -> three time series)
graph7 = new Graph("canvas7", 0, 2000, 0, 500000, ["red"], ["Int(Abs(Error)dt)"], ["0", "2000", "0", "0.5M"]); // arguments: Arg1: canvasId, Arg2: maxX, Arg3: maxY, Arg4: [vector of colors]; this determines the size o
graph8 = new Graph("canvas8", 0, 200, 0, 1000, ["red"], ["errAbs"], ["0", "200", "0", "1000"]); // arguments: Arg1: canvasId, Arg2: maxX, Arg3: maxY, Arg4: [vector of colors]; this determines the size of yValue matrix (if we state one color as eg. ["red"], we assume only one time series, ["red", "green", "blue"] -> three time series)
graph9 = new Graph("canvas9", 0, 200, 0, 1000, ["red"], ["errAbs"], ["0", "200", "0", "1000"]); // arguments: Arg1: canvasId, Arg2: maxX, Arg3: maxY, Arg4: [vector of colors]; this determines the size of yValue matrix (if we state one color as eg. ["red"], we assume only one time series, ["red", "green", "blue"] -> three time series)
// create divPrint1 object to output the numbers
divPrint1 = new LogDiv("print1", 10); // as the argument at the creation of the new object we declare the div name into which the printout of the log will be performed and the number of lines before the scroll
};
class Graph {
constructor(canvasId, minGraphX, maxGraphX, minGraphY, maxGraphY, color, legend, axisDescription) { // pri konstruktorju moramo podati ID platna, ki ga sicer ustvarimo v html-ju
this.canvas = document.getElementById(canvasId);
this.ctx = this.canvas.getContext("2d");
this.canvasWidth = this.canvas.width; // mind capital W at Width
this.canvasHeight = this.canvas.height; // mind capital H at Height
this.x = new Array(); // create new Array x
this.y = new Array();
this.rangeX = maxGraphX - minGraphX;
this.rangeY = maxGraphY - minGraphY;
// create y array (size) according to the color vector (could have multiple rows i.e. 2d)
for( var i=0; i<color.length; i++ ) {
this.y.push([]); // example of three row array init. would be: this.y = [[],[],[]];
}
this.minGraphX = minGraphX;
this.maxGraphX = maxGraphX;
this.minGraphY = minGraphY;
this.maxGraphY = maxGraphY;
this.color = color; // color of the graph
this.legend = legend;
this.axisDescription = axisDescription;
// fill x vector; vector y is filled in real-time
for (var i=0; i<this.maxGraphX+1; i++) {
this.x[i] = i; // values for the x coordinate; 0, 1, 2, ...
}
}
addValueOrCutAndAdd(yValue) {
if (this.y[0].length == this.maxGraphX+1) { // if canvas size is 10x10 we have 11x11 points (starting with 0 and ending with 10)
for (var i = 0; i < yValue.length; i++) { // v zanki gremo po polju yInput in na mestu 0 eno vrednost odrežemo, na koncu pa eno mesto dodamo - zapišemo novo vrednost yInput
this.y[i].splice(0, 1); // on the position 0 in the vector y we cut one value
this.y[i][this.maxGraphX] = yValue[i]; // at the end of the array the new value is added
}
}
else {
for (var i = 0; i < yValue.length; i++) { // z zanko gremo po vseh vrsticah za matrike y
this.y[i].push(yValue[i]); // if the array is not yet full, we push the new value in the array / vrednost v oklepaju [] t.j. index je za ena večji; npr., če imamo eno vrednost je indeks [0], length pa 1
}
}
}
plot(yValue) {
this.addValueOrCutAndAdd(yValue);
this.ctx.clearRect(0, 0, this.canvasWidth, this.canvasHeight); // clear the canvas
for (var i=0; i < yValue.length; i++) { // zanka, ki gre po vrsticah y matrike
this.ctx.strokeStyle = this.color[i]; // determine color
this.ctx.beginPath(); // for the start of the line
for (var j=0; j<this.y[0].length; j++) {
this.ctx.lineTo(this.x[j]/this.rangeX*this.canvasWidth, (this.canvasHeight - ((this.y[i][j]-this.minGraphY)/this.rangeY) * this.canvasHeight)); // for y values we multiply with canas height, eg. 0.25 * 100 = 25
}
this.ctx.stroke();
}
// add legend
for( var i=0; i<this.legend.length; i++ ) { // legend and color should be of the same size
this.ctx.font = "11px Arial";
this.ctx.fillText(this.legend[i], 49+i*54, 10);
this.ctx.strokeStyle = this.color[i];
this.ctx.beginPath(); // beginning of the short line for the legend
this.ctx.lineTo(37+i*54, 6);
this.ctx.lineTo(46+i*54, 6);
this.ctx.stroke();
}
// add axis descritions
this.ctx.fillText("<-" + this.axisDescription[0] + "|" + this.axisDescription[1] + "->", 150, 95)
this.ctx.fillText(this.axisDescription[2], 5, 95);
this.ctx.fillText(this.axisDescription[3], 5, 11);
}
}
class LogDiv {
constructor(divId, numberOfLinesBeforeScroll) {
this.divElement = document.getElementById(divId); // name of div where values will be printed
this.numberOfLinesBeforeScroll = numberOfLinesBeforeScroll; // number of lines which print before scroll
this.linesPrintCounter = 0;
}
log(msg) { // function for printout of the messages with scroll functionality
var node=document.createElement("tr"); // we create the variable node as the a table row (table row)
var textnode=document.createTextNode(this.linesPrintCounter + " | " + msg); // we create element with the text
node.appendChild(textnode); // adding text to "node", t.j. vrstici tabele
this.divElement.insertBefore(node, this.divElement.childNodes[0]); // inserting into variable node
if (this.linesPrintCounter > this.numberOfLinesBeforeScroll-1) { // if the lines are more than limit -> start with scroll
this.divElement.removeChild(this.divElement.childNodes[this.numberOfLinesBeforeScroll], this.divElement.childNodes[this.numberOfLinesBeforeScroll]); // we remove the oldest printout
}
this.linesPrintCounter++; // increasing the number of printouts
}
}
ws.onmessage = function(event) {
var msg = JSON.parse(event.data); // string from ws is put to JSON
switch(msg.type) {
case "message":
divPrint1.log(msg.content); // add msg to div
break;
case "staticMsgToClient":
document.getElementById("divForStaticPrint").innerHTML = "Status: Ctrl. Alg. " + msg.content; // we print to div
break;
case "clientReadValues":
potValue1 = msg.desiredValue;
potValue2 = msg.actualValue;
pwm = parseInt((Number(msg.pwm)).toFixed(0), 10);
graph1.plot([potValue2]); // desired Vs actual graph
graph2.plot([pwm]); // plot pwm
// draw centerline in graph2
graph2.ctx.strokeStyle = "#add8e6";
graph2.ctx.beginPath(); // draw centerline at 0
graph2.ctx.lineTo(0, 50); // starting point
graph2.ctx.lineTo(200, 50); // ending point
graph2.ctx.stroke();
graph3.plot([msg.KpE, msg.KiIedt, msg.KdDe_dt]);
graph4.plot([msg.err]); // graph for P part
graph5.plot([msg.errSum]); // graph for I part
graph6.plot([msg.dErr]); // graph for D part
graph7.plot([msg.errSumAbs]); // graph for performance measure
graph8.plot([msg.errAbs]); // graph for performance measure
graph9.plot([msg.errAbs]); // graph for performance measure
performanceMeasure = msg.errSumAbs; // write into global var to get results at the end
graph7.ctx.fillText(parseInt(msg.errSumAbs),70,27);
divPrint1.log(potValue1 + "|" + potValue2 + "|" + msg.error + "|" + msg.pwm);
break;
}
};
function startControlAlgorithm1() {
stopControlAlgorithm(); // just in case, if it is not started
pCoeff = document.getElementById("pCoeff").value; // read the value of coeff from input field
messageJSON = {"type": "startControlAlgorithm", "ctrlAlgNo": 1, "pCoeff": pCoeff};
ws.send(JSON.stringify(messageJSON)); // we have to stringify JSON to send it over websocket
}
function startControlAlgorithm2() {
stopControlAlgorithm(); // just in case, if it is not started
Kp1 = document.getElementById("Kp1").value; // read the value of coeff from input field
Ki1 = document.getElementById("Ki1").value; // read the value of coeff from input field
Kd1 = document.getElementById("Kd1").value; // read the value of coeff from input field
messageJSON = {"type": "startControlAlgorithm", "ctrlAlgNo": 2, "Kp1": Kp1, "Ki1": Ki1, "Kd1": Kd1};
ws.send(JSON.stringify(messageJSON)); // we have to stringify JSON to send it over websocket
}
function sendPosition () {
var positionValue = document.getElementById("position").value;
stopControlAlgorithm(); // stop just in case
if(document.getElementById("whichAlgorithm").value == "5") {
document.getElementById("whichAlgorithm").value = 2; // alg. 5. uses just input - swithc to two
}
switchAlgorihtm();
messageJSON = {"type": "sendPosition", "positionValue": positionValue};
ws.send(JSON.stringify(messageJSON)); // we have to stringify JSON to send it over websocket
};
function pulse() {
var desiredPositionByInterval = 320;
messageJSON = {"type": "sendPosition", "positionValue": desiredPositionByInterval}; // at start we send position
ws.send(JSON.stringify(messageJSON)); // we have to stringify JSON to send it over websocket
intervalPulseFunction = setInterval(function() {
if (desiredPositionByInterval == 320) {
desiredPositionByInterval = 704;
}
else {
desiredPositionByInterval = 320;
}
messageJSON = {"type": "sendPosition", "positionValue": desiredPositionByInterval};
ws.send(JSON.stringify(messageJSON)); // we have to stringify JSON to send it over websocket
}, 2000);
}
function stop () {
document.getElementById("divForStaticPrint").innerHTML = document.getElementById("divForStaticPrint").innerHTML + " | C = " + performanceMeasure;
clearInterval(intervalPulseFunction);
clearInterval(intervalTestFunction);
stopControlAlgorithm();
}
function inputPulse() {
var input = 0; // tole je tokrat kar pwm
messageJSON = {"type": "sendInput", "input": input};
ws.send(JSON.stringify(messageJSON)); // we have to stringify JSON to send it over websocket
intervalPulseFunction = setInterval(function() {
if (input == 50) {
input = -50;
}
else {
input = 50
}
messageJSON = {"type": "sendInput", "input": input};
ws.send(JSON.stringify(messageJSON)); // we have to stringify JSON to send it over websocket
}, 400);
}
var functionValue = 0;
function testFunction() {
var initialValue = 256;
switch (timeCounter >= 0) {
case (timeCounter <= 1000):
functionValue = initialValue + 0.5 * timeCounter;
break;
case (timeCounter > 1000 && timeCounter <= 1500):
functionValue = 256 + 500 + (-0.5 * (timeCounter - 1000)); // 500 = previous max value
break;
case (timeCounter > 1500 && timeCounter <= 2000):
functionValue = 506 + (0.5 * (timeCounter - 1500));
break;
case (timeCounter > 2000 && timeCounter <= 3000):
functionValue = 756 - 500 + 500 * Math.exp(-0.005 * (timeCounter - 2000)); // 756 - previous val; (756-220) - limit val
}
messageJSON = {"type": "sendPosition", "positionValue": functionValue};
ws.send(JSON.stringify(messageJSON)); // we have to stringify JSON to send it over websocket
timeCounter++;
}
function startTestFunction () {
stopControlAlgorithm ();
switchAlgorihtm();
timeCounter = 0;
intervalTestFunction = setInterval(function() {testFunction(), 10});
var pulseDuration = document.getElementById("pulseDuration").value;
setTimeout(function() {stop();}, pulseDuration * 1000); // 30000
}
function stopTestFunction () {
clearInterval(intervalTestFunction);
}
function pulseTimed () {
// first stop ctrlAlg, just in case
stopControlAlgorithm ();
switchAlgorihtm();
pulse(); // starting pulse function
var pulseDuration = document.getElementById("pulseDuration").value;
setTimeout(function() {stop();}, pulseDuration * 1000); // wait for 3s to get performance measure value out
}
function pulseTimed2 () {
// first stop ctrlAlg, just in case
document.getElementById("whichAlgorithm").value = 5;
stopControlAlgorithm ();
switchAlgorihtm();
inputPulse(); // starting pulse function for INPUT
var pulseDuration = document.getElementById("pulseDuration").value;
setTimeout(function() {stop();}, pulseDuration * 1000); // 30000
}
function startControlAlgorithm3() {
stopControlAlgorithm(); // just in case, if it is not started
var Kp2 = document.getElementById("Kp2").value; // read the value of coeff from input field
var Ki2 = document.getElementById("Ki2").value; // read the value of coeff from input field
var Kd2 = document.getElementById("Kd2").value; // read the value of coeff from input field
messageJSON = {"type": "startControlAlgorithm", "ctrlAlgNo": 3, "Kp2": Kp2, "Ki2": Ki2, "Kd2": Kd2};
ws.send(JSON.stringify(messageJSON)); // we have to stringify JSON to send it over websocket
}
function startControlAlgorithm5() {
stopControlAlgorithm(); // just in case, if it is not started
messageJSON = {"type": "startControlAlgorithm", "ctrlAlgNo": 5};
ws.send(JSON.stringify(messageJSON)); // we have to stringify JSON to send it over websocket
}
function switchAlgorihtm () {
var whichAlgorithm = document.getElementById("whichAlgorithm").value;
switch (whichAlgorithm) {
case "1":
startControlAlgorithm1();
break;
case "2":
startControlAlgorithm2();
break;
case "3":
startControlAlgorithm3();
break;
case "5":
startControlAlgorithm5();
break;
}
}
function stopControlAlgorithm () {
messageJSON = {"type": "stopControlAlgorithm"};
ws.send(JSON.stringify(messageJSON)); // we have to stringify JSON to send it over websocket
}
</script>
</body>
</html>