mirror of
https://github.com/PotentiaRobotics/engine-software.git
synced 2025-04-03 20:10:19 -04:00
Added PID code for Ultrasonic demo (may not work)
This commit is contained in:
parent
20fb91d9e7
commit
e521c124f4
44
FakePID/PID_Practice/PID_Practice.ino
Normal file
44
FakePID/PID_Practice/PID_Practice.ino
Normal file
|
@ -0,0 +1,44 @@
|
|||
#include <SR04.h>
|
||||
//PID constants
|
||||
double kp = 2;
|
||||
double ki = 5;
|
||||
double kd = 1;
|
||||
|
||||
unsigned long currentTime, previousTime;
|
||||
double elapsedTime;
|
||||
double error;
|
||||
double lastError;
|
||||
double input, output, setPoint;
|
||||
double cumError, rateError;
|
||||
double Setpoint = 100;
|
||||
long dist;
|
||||
SR04 sr04 = SR04(2,3);
|
||||
|
||||
void setup(){
|
||||
setPoint = 0;
|
||||
Serial.begin(115200);//set point at zero degrees
|
||||
}
|
||||
|
||||
void loop(){
|
||||
dist = sr04.Distance(); //read from rotary encoder connected to A0
|
||||
output = computePID(input);
|
||||
delay(100);
|
||||
Serial.println("Read: "+String(dist)+", Move: "+String(output));
|
||||
|
||||
}
|
||||
|
||||
double computePID(double inp){
|
||||
currentTime = millis(); //get current time
|
||||
elapsedTime = (double)(currentTime - previousTime); //compute time elapsed from previous computation
|
||||
|
||||
error = Setpoint - inp; // determine error
|
||||
cumError += error * elapsedTime; // compute integral
|
||||
rateError = (error - lastError)/elapsedTime; // compute derivative
|
||||
|
||||
double out = kp*error + ki*cumError + kd*rateError; //PID output
|
||||
|
||||
lastError = error; //remember current error
|
||||
previousTime = currentTime; //remember current time
|
||||
|
||||
return out; //have function return the PID output
|
||||
}
|
47
FakePID/Pid2/Pid2.ino
Normal file
47
FakePID/Pid2/Pid2.ino
Normal file
|
@ -0,0 +1,47 @@
|
|||
/*
|
||||
sketch belongs to this video: https://youtu.be/crw0Hcc67RY
|
||||
write by Moz for YouTube changel logMaker360
|
||||
4-12-2017
|
||||
*/
|
||||
|
||||
#include <PID_v1.h>
|
||||
#include <SR04.h>
|
||||
double Setpoint ; // will be the desired value
|
||||
double Input; // photo sensor
|
||||
double Output ; //LED
|
||||
//PID parameters
|
||||
double Kp=0, Ki=10, Kd=0;
|
||||
long dist;
|
||||
SR04 sr04 = SR04(2,3);
|
||||
|
||||
//create PID instance
|
||||
PID myPID(&Input, &Output, &Setpoint, Kp, Ki, Kd, DIRECT);
|
||||
|
||||
void setup()
|
||||
{
|
||||
|
||||
Serial.begin(9600);
|
||||
//Hardcode the brigdness value
|
||||
Setpoint = 100;
|
||||
//Turn the PID on
|
||||
myPID.SetMode(AUTOMATIC);
|
||||
//Adjust PID values
|
||||
myPID.SetTunings(Kp, Ki, Kd);
|
||||
}
|
||||
|
||||
void loop()
|
||||
{
|
||||
//Read the value from the light sensor. Analog input : 0 to 1024. We map is to a value from 0 to 255 as it's used for our PWM function.
|
||||
Input = sr04.Distance(); // photo senor is set on analog pin 5
|
||||
//PID calculation
|
||||
myPID.Compute();
|
||||
//Write the output as calculated by the PID function
|
||||
analogWrite(3,Output); //LED is set to digital 3 this is a pwm pin.
|
||||
//Send data by serial for plotting
|
||||
//Serial.print(Input);
|
||||
//Serial.print(" ");
|
||||
Serial.println(Output);
|
||||
//Serial.print(" ");
|
||||
//Serial.println(Setpoint);
|
||||
// delay(100);
|
||||
}
|
Loading…
Reference in New Issue
Block a user