From af115a1b706f88a381875be3e617c01b7ffa8636 Mon Sep 17 00:00:00 2001 From: bigalex Date: Sat, 6 Jun 2020 00:59:34 +0200 Subject: [PATCH] provide PWM control for motors --- src/app_httpd.cpp | 12 +++++------- src/esp32-cam-webserver.cpp | 23 ++++++++++++++--------- src/robot_pins.h | 16 +++++++++++----- 3 files changed, 30 insertions(+), 21 deletions(-) diff --git a/src/app_httpd.cpp b/src/app_httpd.cpp index 308b169..741e394 100644 --- a/src/app_httpd.cpp +++ b/src/app_httpd.cpp @@ -446,14 +446,12 @@ void startCameraServer(){ } -// set motor directions and toggle motors on/off -// TODO: control motor speed with PWM +// set motor directions and speed // TODO: fix bad SoC, this routine has nothing to do with the web server void updateMotors(){ - // motor is switched on if the speed is >0.5 or <-0.5, else motor off - abs(current_speed_left)>0.5 ? digitalWrite(MOTOR_L_PWM, HIGH) : digitalWrite(MOTOR_L_PWM, LOW); - abs(current_speed_right)>0.5 ? digitalWrite(MOTOR_R_PWM, HIGH) : digitalWrite(MOTOR_R_PWM, LOW); + ledcWrite(MOTOR_L_PWM_CHAN, abs(current_speed_left)*1023); + ledcWrite(MOTOR_R_PWM_CHAN, abs(current_speed_right)*1023); // directions depends on whether speed is negative or positive - current_speed_left > 0 ? digitalWrite(MOTOR_L_DIR, HIGH) : digitalWrite(MOTOR_L_DIR, LOW); - current_speed_right > 0 ? digitalWrite(MOTOR_R_DIR, HIGH) : digitalWrite(MOTOR_R_DIR, LOW); + current_speed_left > 0 ? digitalWrite(MOTOR_L_DIR_PIN, HIGH) : digitalWrite(MOTOR_L_DIR_PIN, LOW); + current_speed_right > 0 ? digitalWrite(MOTOR_R_DIR_PIN, HIGH) : digitalWrite(MOTOR_R_DIR_PIN, LOW); } diff --git a/src/esp32-cam-webserver.cpp b/src/esp32-cam-webserver.cpp index 631d3f3..3c9d770 100644 --- a/src/esp32-cam-webserver.cpp +++ b/src/esp32-cam-webserver.cpp @@ -60,12 +60,14 @@ char myVer[] PROGMEM = __DATE__ " @ " __TIME__; int lampVal = -1; // disable Lamp #endif int lampChannel = 7; // a free PWM channel (some channels used by camera) + // according to https://esp32.com/viewtopic.php?t=11379 those are channel 1 and 2 const int pwmfreq = 50000; // 50K pwm frequency const int pwmresolution = 9; // duty cycle bit range // https://diarmuid.ie/blog/pwm-exponential-led-fading-on-arduino-or-other-platforms const int pwmIntervals = 100; // The number of Steps between the output being on and off float lampR; // The R value in the PWM graph equation (calculated in setup) + void startCameraServer(); void flashLED(int flashtime); @@ -154,15 +156,18 @@ void setup() { #endif // Mötör init - pinMode(MOTOR_L_PWM, OUTPUT); - digitalWrite(MOTOR_L_PWM, LOW); //off - pinMode(MOTOR_R_PWM, OUTPUT); - digitalWrite(MOTOR_R_PWM, LOW); //off - pinMode(MOTOR_L_DIR, OUTPUT); - digitalWrite(MOTOR_L_DIR, LOW); - pinMode(MOTOR_R_DIR, OUTPUT); - digitalWrite(MOTOR_R_DIR, LOW); - + pinMode(MOTOR_L_PWM_PIN, OUTPUT); + ledcSetup(MOTOR_L_PWM_CHAN, MOTOR_PWM_FREQ_HZ, MOTOR_PWM_RES_BIT); + ledcAttachPin(MOTOR_L_PWM_PIN, MOTOR_L_PWM_CHAN); + ledcWrite(MOTOR_L_PWM_CHAN, 0); //off + pinMode(MOTOR_R_PWM_PIN, OUTPUT); + ledcSetup(MOTOR_R_PWM_CHAN, MOTOR_PWM_FREQ_HZ, MOTOR_PWM_RES_BIT); + ledcAttachPin(MOTOR_R_PWM_PIN, MOTOR_R_PWM_CHAN); + ledcWrite(MOTOR_R_PWM_CHAN, 0); //off + pinMode(MOTOR_L_DIR_PIN, OUTPUT); + digitalWrite(MOTOR_L_DIR_PIN, LOW); + pinMode(MOTOR_R_DIR_PIN, OUTPUT); + digitalWrite(MOTOR_R_DIR_PIN, LOW); // Feedback that hardware init is complete and we are now attempting to connect Serial.println(""); diff --git a/src/robot_pins.h b/src/robot_pins.h index c9451be..1448161 100644 --- a/src/robot_pins.h +++ b/src/robot_pins.h @@ -1,4 +1,4 @@ -// Pin definitions for robot peripherals (actuators, LEDs, ...) +// Pin and PWM definitions for robot peripherals (actuators, LEDs, ...) // TB6612FNG with // GPIO 12 - PWM A left motor @@ -6,8 +6,14 @@ // GPIO 14 - DIR A // GPIO 15 - DIR B -#define MOTOR_L_PWM 12 -#define MOTOR_R_PWM 13 -#define MOTOR_L_DIR 14 -#define MOTOR_R_DIR 15 +#define MOTOR_L_PWM_PIN 12 +#define MOTOR_R_PWM_PIN 13 +#define MOTOR_L_DIR_PIN 14 +#define MOTOR_R_DIR_PIN 15 +#define MOTOR_L_PWM_CHAN 3 +#define MOTOR_R_PWM_CHAN 4 +// PWM resolution +#define MOTOR_PWM_RES_BIT 10 +// PWM frequency +#define MOTOR_PWM_FREQ_HZ 10000