misan / dcservo

Position control of DC motors
312 stars 113 forks source link

Any plans to port to ESP32 ? #77

Open kotopuz opened 3 years ago

kotopuz commented 3 years ago

Dear all, Not sure if there are any plans to port it to ESP32 ? Somehow PWM is not working.

Few changes might be needed(I've used dcservoESP_wifi.ino).

  1. Add this and change all BUILTIN_LED to LED_BUILTIN int LED_BUILTIN = 2; for dev board.

  2. Change analog write analogWrite(M2,out) to something like ledcWrite(1, out); . PWM setup if different: ledcSetup(0, 20000, 255); // set PWM to 20Khz ,set PWM to 255 levels ledcAttachPin(M1, 0); ledcSetup(1, 20000, 255); // set PWM to 20Khz ,set PWM to 255 levels ledcAttachPin(M2, 1);

  3. Library change from 8266 to WIFI.h //#include

    include

  4. CHange of ESP32 hostname WiFi.begin(ssid, password); WiFi.config(INADDR_NONE, INADDR_NONE, INADDR_NONE, INADDR_NONE); // required to set hostname properly WiFi.setHostname("your host name");

If someone will make working example please upload. Mine still not OK, but at least those are needed for sure.

May be I've accidently burned mine ESP32, but hope I will have time to order new one and try again.

Regards

ghaz007 commented 3 years ago

Hi, It's just work fine on ESP32 with some modifications. I remove all wifi code , and keep serial communication.

const int encoder0PinA = 32;
const int encoder0PinB = 33;
const int Step = 21;
const int M1=26;
const int M2=27;
const int DIR=22;
const int PWM_MOT=25 ;

// Setting PWM properties
const int freq = 1000;
const int pwmChannel = 0;
const int resolution = 8;
int dutyCycle = 200;

byte pos[4800]; int p=0;

Also the setup :

pinMode(PWM_MOT, OUTPUT);
  pinMode(M1,OUTPUT);
  pinMode(M2,OUTPUT);
// configure LED PWM functionalitites
  ledcSetup(pwmChannel, freq, resolution);

  // attach the channel to the GPIO to be controlled
  ledcAttachPin(PWM_MOT, pwmChannel);

With L298 driver, the pwmount is changed :

  void` pwmOut(int out) {

   if(out<0) { analogWrite(M1,0); analogWrite(M2,abs(out)); }
   else { analogWrite(M2,0); analogWrite(M1,abs(out)); }
  ledcWrite(pwmChannel, abs(out));
  } 

And the loop :

void loop() {
    //if(!client) client = server.available();
    input = encoder0Pos; 
    setpoint=target1;

    while(!myPID.Compute()); // wait till PID is actually computed

   if(Serial.available()) process_line();
   //  if(input==setpoint)pwmOut(0); 
    if(abs(input- setpoint) < 10)    pwmOut(0); // because I have 48000 steps in my configuration, just a lot ! .   
     else pwmOut(output); 

    if(auto1) if(millis() % 3000 == 0) target1=random(2000); // that was for self test with no input from main controller
    if(auto2) if(millis() % 1000 == 0) printPos();
    if(counting && abs(input-target1)<15) counting=false; 
    if(counting &&  (skip++ % 5)==0 ) {pos[p]=encoder0Pos; if(p<4799) p++; else counting=false;}

   }

All the code wifi and eeprom will be changed too , but it's no important to have a good control on the motors with the pid algorithm. My configuation for a DC motor with a ratio of 30 is : P : 500 , I:4, D:6. I have a good result and the motor freeze very slitely in the end.

misan commented 3 years ago

Thanks a lot @ghaz007 for your comments.

I reckon you can remove the analogWrite from your L298 code entirely. And those that write a 0 can be replaced by digitalWrite(M<1|2>,LOW);

ghaz007 commented 3 years ago

Great job misan, it's just perfect, thank's !! Now, I slitly changed the pwmOut routine to reduce speed in the end, at the last RPM, and the difference between input and setpoint is always 0!!! perfect.

void pwmOut(int out) {

   if(out>0) { digitalWrite(M1,LOW); digitalWrite(M2,HIGH); }
   else      { digitalWrite(M2,LOW); digitalWrite(M1,HIGH); }

   if(abs(input- setpoint) < fentesperRPM) out = out/2; // 48000 in my case
   else if(abs(input- setpoint) < fentesperRPM/2) out = out/4;
    ledcWrite(pwmChannel, abs(out));
    }

We can keep you initial code without modifications in the loop routine.

if (input== setpoint)  pwmOut(0); 
     else pwmOut(output);
happytm commented 3 years ago

@ghaz007 Good job. Can you please post you whole code for everybody else?

Thanks.

ghaz007 commented 3 years ago

Hi, Somemodifications in the eeprom procedure. Now it's work.

/*
 * Miguel Sanchez 2106
   Mauro Manco 2016 Porting on ESP8266

   Please note PID gains kp, ki, kd need to be tuned to each different setup. 
*/

#include <EEPROM.h>
#include <PID_v1.h>

#define EEPROM_SIZE 256

 int fentespercycle ; // number of lines in the wheel encoder per cycle ( 400 x 4 x 30 = 48000)
const int encoder0PinA = 32;
const int encoder0PinB = 33;
const int Step = 21;
const int M1=26;
const int M2=27;
const int DIR=22;
const int PWM_MOT=25 ;

byte pos[48000]; int p=0; // I don't know if 48000 will be correct ????
double kp=3,ki=0,kd=0.0;
double input=0, output=0, setpoint=0;
PID myPID(&input, &output, &setpoint,kp,ki,kd, DIRECT);
volatile long encoder0Pos = 0;
boolean auto1=false, auto2=false,counting=false;
long previousMillis = 0;        // will store last time LED was updated

long target1=0;  // destination location at any moment

//for motor control ramps 1.4
bool newStep = false;
bool oldStep = false;
bool dir = false;
byte skip=0;

// Setting PWM properties
const int freq = 1000;
const int pwmChannel = 0;
const int resolution = 8;
int dutyCycle = 200;

  void pwmOut(int out) {    
   if(out>0) { digitalWrite(M1,LOW); digitalWrite(M2,HIGH); }
   else      { digitalWrite(M2,LOW); digitalWrite(M1,HIGH); }

   if(abs(input- setpoint) < fentespercycle*2)    out = out/2;
   else if(abs(input- setpoint) < fentespercycle) out = out/4;

   ledcWrite(pwmChannel, abs(out));
    }

const int QEM [16] = {0,-1,1,2,1,0,2,-1,-1,2,0,1,2,1,-1,0};               // Quadrature Encoder Matrix
static unsigned char New, Old;

void encoderInt() { // handle pin change interrupt for D2
  Old = New;
  //New = PIND & 3; //(PINB & 1 )+ ((PIND & 4) >> 1); //   Mauro Manco
  New = digitalRead(encoder0PinA)*2 + digitalRead(encoder0PinB);
  encoder0Pos+= QEM [Old * 4 + New];
}

void countStep(){ if (digitalRead(DIR)== HIGH) target1--;else target1++;
} 

void printPos() {
  Serial.print(F("Position=")); Serial.print(encoder0Pos); Serial.print(F(" PID_output=")); Serial.print(output); Serial.print(F(" Target=")); Serial.print(setpoint);
  Serial.print(F(" Difference =")); Serial.println(setpoint- encoder0Pos);
}

void help() {
 Serial.println(F("\nPID DC motor controller and stepper interface emulator"));
 Serial.println(F("by misan"));
 Serial.println(F("Available serial commands: (lines end with CRLF or LF)"));
 Serial.println(F("P123.34 sets proportional term to 123.34"));
 Serial.println(F("I123.34 sets integral term to 123.34"));
 Serial.println(F("D123.34 sets derivative term to 123.34"));
 Serial.println(F("? prints out current encoder, output and setpoint values"));
 Serial.println(F("X123 sets the target destination for the motor to 123 encoder pulses"));
 Serial.println(F("T will start a sequence of random destinations (between 0 and 2000) every 3 seconds. T again will disable that"));
 Serial.println(F("Q will print out the current values of P, I and D parameters")); 
 Serial.println(F("W will store current values of P, I and D parameters into EEPROM")); 
 Serial.println(F("H will print this help message again")); 
 Serial.println(F("A will toggle on/off showing regulator status every second")); 

}

void eeput(double value, int dir) { // Snow Leopard keeps me grounded to 1.0.6 Arduino, so I have to do this :-(
  //double * addr = (double * ) &value;
 // for(int i=dir; i<dir+4; i++) { EEPROM.writeDouble(i,addr[i-dir]);
  EEPROM.writeDouble(dir, value) ;
  EEPROM.commit();  
}

void writetoEEPROM() { // keep PID set values in EEPROM so they are kept when arduino goes off   

  eeput(kp,0);
  eeput(ki,8);
  eeput(kd,16);
  double cks=0;
  for(int i=0; i<24; i++) cks+= EEPROM.read(i);                          
  eeput(cks,24);
  Serial.println("\nPID values stored to EEPROM");
  Serial.println(cks);
}

double eeget(int dir) { // Snow Leopard keeps me grounded to 1.0.6 Arduino, so I have to do this :-(
  double value; 
 value = EEPROM.readDouble(dir) ;
 return value ;
}

void recoverPIDfromEEPROM() {
  double cks=0;
  double cksEE;
  for(int i=0; i<24; i++) cks+=EEPROM.read(i);

  cksEE=eeget(24);
  //Serial.println(cks);
  if(cks==cksEE) {
    Serial.println(F("*** Found PID values on EEPROM"));
    kp=eeget(0);
    ki=eeget(8);
    kd=eeget(16);
    myPID.SetTunings(kp,ki,kd); 
  }
  else Serial.println(F("*** Bad checksum"));
}

void eedump() {
 for(int i=0; i<32; i++) { Serial.print(EEPROM.read(i),HEX); Serial.print(" "); }Serial.println(); 
}
void eedump2() {
 for(int i=0; i<32; i+=8) { Serial.print(EEPROM.readDouble(i)); Serial.print(" "); }Serial.println(); 
}

void setup() {
  Serial.begin (115200);
  fentespercycle = 48000 ;
  pinMode(encoder0PinA, INPUT);
  pinMode(encoder0PinB, INPUT);
  pinMode(Step, INPUT);
  pinMode(PWM_MOT, OUTPUT);
  pinMode(M1,OUTPUT);
  pinMode(M2,OUTPUT);
   // configure LED PWM functionalitites
  ledcSetup(pwmChannel, freq, resolution);

  // attach the channel to the GPIO to be controlled
  ledcAttachPin(PWM_MOT, pwmChannel);

  attachInterrupt(encoder0PinA, encoderInt, CHANGE);
  attachInterrupt(encoder0PinB, encoderInt, CHANGE);
  attachInterrupt(Step, countStep, RISING);

   // initialize EEPROM with predefined size
  EEPROM.begin(EEPROM_SIZE);

  help();
  recoverPIDfromEEPROM();
  //Setup the pid 
  myPID.SetMode(AUTOMATIC);
  myPID.SetSampleTime(1);
  myPID.SetOutputLimits(-255,255);

  Serial.println("");
  Serial.println("Let's Go.....");  

}

void process_line() {
 char cmd = Serial.read();
 if(cmd>'Z') cmd-=32;
 switch(cmd) {
  case 'P': kp= Serial.parseFloat(); myPID.SetTunings(kp,ki,kd); break;
  case 'D': kd= Serial.parseFloat(); myPID.SetTunings(kp,ki,kd); break;
  case 'I': ki= Serial.parseFloat(); myPID.SetTunings(kp,ki,kd); break;
  case '?': printPos(); break;
  case 'X': target1=Serial.parseInt(); counting=true; for(int i=0; i<p; i++) pos[i]=0; p=0; break;
  case 'T': auto1 = !auto1; break;
  case 'A': auto2 = !auto2; break;
  case 'Q': Serial.print("P="); Serial.print(kp); Serial.print(" I="); Serial.print(ki); Serial.print(" D="); Serial.println(kd); break;
  case 'H': help(); break;
  case 'W': writetoEEPROM(); break;
  case 'K': eedump(); break;
  case 'R': recoverPIDfromEEPROM() ; break;
  case 'S': for(int i=0; i<p; i++) Serial.println(pos[i]); break;
  case 'B': eedump2(); break;
 }
// while(Serial.read()!=10); // dump extra characters till LF is seen (you can use CRLF or just LF)
}

void loop() {

    input = encoder0Pos; 
    setpoint=target1;

    while(!myPID.Compute()); // wait till PID is actually computed

   if(Serial.available()) process_line(); 
    if (input== setpoint)  pwmOut(0); 
     else pwmOut(output);

    if(auto1) if(millis() % 3000 == 0) target1=random(2000); // that was for self test with no input from main controller
    if(auto2) if(millis() % 1000 == 0) printPos();
    if(counting && abs(input-target1)<15) counting=false; 
    if(counting &&  (skip++ % 5)==0 ) {pos[p]=encoder0Pos; if(p<4799) p++; else counting=false;}

   }
bogus105 commented 3 years ago

one more thing: just get rid of digitalWrite method in pwmOut routine. Use the method described here instead: http://www.billporter.info/2010/08/18/ready-set-oscillate-the-fastest-way-to-change-arduino-pins/

Have you got some videos showing your servo in action? Can you explain the issue with input vs setpoint? I'm wondering if it is the same issue i've faced ca 5 years ago when i first time was playing with Mr. Sanchez code. I used Arduino Nano and L298. I remember that my DC servo was not able to get to exact position. There was some offset which was getting smaller over time (i was trying many different integral values to amplify response) but it was taking to long to get zero position error. It looked like PID calculation in the last phase, when position error was close to zero, was not giving "strong" enough PWM to set motor to zero-error position. I'm really interested in performance using esp32 (or 8266).

happytm commented 3 years ago

@ghaz007 Thank you.

misan commented 3 years ago

Hi @bogus105,

Please take into account that ESP32 is a much faster processor than Arduino (and totally different architecture) so the Arduino macros will not work with it.

What you are describing seems to be a dead-band problem: Real-world does not always conform according to our models, and that kind of breaks some of the assumptions of PID regulators. If your motor does not move with a non-zero output (dead-band), then it cannot correct the error at this stage. You can deal with that by adding some non-linear behavior on pwmOut (so you do not use output values that do not move the motor, though you still keep the 0 value).

A large integrative action can help to correct the error but it will take a long time to do so, which is not what you want, and it might also end up oscillating around the target.