From 13fc30d722073c901be50127b8c1efb006bde3cd Mon Sep 17 00:00:00 2001 From: pieniacy Date: Sun, 21 Nov 2021 15:36:08 +0100 Subject: [PATCH] Refactor, rework, reformat, add motorsSet(), bump version to 0.2.0. This commit preserves full backwards compatibility with the previous version. --- ESP32MotorControl.cpp | 350 ++++++++++++------------------------------ ESP32MotorControl.h | 49 +++--- README.md | 11 +- library.json | 2 +- library.properties | 4 +- 5 files changed, 132 insertions(+), 284 deletions(-) mode change 100755 => 100644 ESP32MotorControl.cpp mode change 100755 => 100644 ESP32MotorControl.h diff --git a/ESP32MotorControl.cpp b/ESP32MotorControl.cpp old mode 100755 new mode 100644 index edc959d..4001236 --- a/ESP32MotorControl.cpp +++ b/ESP32MotorControl.cpp @@ -7,11 +7,14 @@ * Versions : * ------ ---------- ------------------------- * 0.1.0 2018-12-26 First beta + * 0.2.0 2021-11-21 Revision by Karol Pieniacy *****************************************/ /* * Source for ESP32MotorControl * + * Copyright (C) 2021 Karol Pieniacy https://github.com/pieniacy/ESP32MotorControl + * * Copyright (C) 2018 Joao Lopes https://github.com/JoaoLopesF/ESP32MotorControl * * This program is free software: you can redistribute it and/or modify @@ -30,317 +33,166 @@ * */ -/* - * TODO list: - * - Port to L298 - */ - -/* - * TODO known issues: - */ - -////// Includes - -#include "Arduino.h" - #include "ESP32MotorControl.h" -#include - -#include "esp_system.h" -#include "esp_attr.h" +#include +#include "Arduino.h" #include "driver/mcpwm.h" +#include "esp_attr.h" +#include "esp_system.h" #include "soc/mcpwm_reg.h" #include "soc/mcpwm_struct.h" -///// Defines - -// debug - -//#define debug(fmt, ...) -#define debug(fmt, ...) Serial.printf("%s: " fmt "\r\n", __func__, ##__VA_ARGS__) - -///// Methods - -///// Driver with 4 pins: DRV88nn, DRV8833, DRV8825, etc. - -// Attach one motor - -void ESP32MotorControl::attachMotor(uint8_t gpioIn1, uint8_t gpioIn2) +namespace { +inline constexpr mcpwm_unit_t MCPWM_UNIT(uint8_t motor) { - attachMotors(gpioIn1, gpioIn2, 0, 0); + return motor == 0 ? MCPWM_UNIT_0 : MCPWM_UNIT_1; } - -// Attach two motors - -void ESP32MotorControl::attachMotors(uint8_t gpioIn1, uint8_t gpioIn2, uint8_t gpioIn3, uint8_t gpioIn4) +inline constexpr mcpwm_timer_t MCPWM_TIMER(uint8_t motor) { - // debug - - debug("init MCPWM Motor 0"); - - // Attach motor 0 input pins. - - // Set MCPWM unit 0 - - mcpwm_gpio_init(MCPWM_UNIT_0, MCPWM0A, gpioIn1); - mcpwm_gpio_init(MCPWM_UNIT_0, MCPWM0B, gpioIn2); - - // Indicate the motor 0 is attached. - - this->mMotorAttached[0] = true; - - // Attach motor 1 input pins. - - if (!(gpioIn3 == 0 && gpioIn4 ==0)) { - - debug("init MCPWM Motor 1"); - - // Set MCPWM unit 1 - - mcpwm_gpio_init(MCPWM_UNIT_1, MCPWM1A, gpioIn3); - mcpwm_gpio_init(MCPWM_UNIT_1, MCPWM1B, gpioIn4); - - // Indicate the motor 1 is attached. - - this->mMotorAttached[1] = true; - } - - // Initial MCPWM configuration - - debug ("Configuring Initial Parameters of MCPWM..."); - - mcpwm_config_t pwm_config; - pwm_config.frequency = 1000; //frequency, - pwm_config.cmpr_a = 0; //duty cycle of PWMxA = 0 - pwm_config.cmpr_b = 0; //duty cycle of PWMxb = 0 - pwm_config.counter_mode = MCPWM_UP_COUNTER; - pwm_config.duty_mode = MCPWM_DUTY_MODE_0; - - mcpwm_init(MCPWM_UNIT_0, MCPWM_TIMER_0, &pwm_config); //Configure PWM0A & PWM0B with above settings - - mcpwm_init(MCPWM_UNIT_1, MCPWM_TIMER_1, &pwm_config); //Configure PWM1A & PWM1B with above settings - - debug ("MCPWM initialized"); + return motor == 0 ? MCPWM_TIMER_0 : MCPWM_TIMER_1; } -// Motor full forward - -void ESP32MotorControl::motorFullForward(uint8_t motor) +void setMotorNoPWM(uint8_t motor, int8_t dir) { - if (!isMotorValid(motor)) { - return; - } - - // Full forward - - if (motor == 0) { - - mcpwm_set_signal_low(MCPWM_UNIT_0, MCPWM_TIMER_0, MCPWM_OPR_B); - mcpwm_set_signal_high(MCPWM_UNIT_0, MCPWM_TIMER_0, MCPWM_OPR_A); - + if (dir > 0) { + // Full forward + mcpwm_set_signal_low(MCPWM_UNIT(motor), MCPWM_TIMER(motor), MCPWM_OPR_B); + mcpwm_set_signal_high(MCPWM_UNIT(motor), MCPWM_TIMER(motor), MCPWM_OPR_A); + } else if (dir < 0) { + // Full reverse + mcpwm_set_signal_low(MCPWM_UNIT(motor), MCPWM_TIMER(motor), MCPWM_OPR_A); + mcpwm_set_signal_high(MCPWM_UNIT(motor), MCPWM_TIMER(motor), MCPWM_OPR_B); } else { - - mcpwm_set_signal_low(MCPWM_UNIT_1, MCPWM_TIMER_1, MCPWM_OPR_B); - mcpwm_set_signal_high(MCPWM_UNIT_1, MCPWM_TIMER_1, MCPWM_OPR_A); + // Stop + mcpwm_set_signal_low(MCPWM_UNIT(motor), MCPWM_TIMER(motor), MCPWM_OPR_A); + mcpwm_set_signal_low(MCPWM_UNIT(motor), MCPWM_TIMER(motor), MCPWM_OPR_B); } - - mMotorSpeed[motor] = 100; // Save it - mMotorForward[motor] = true; - - debug ("Motor %u full forward", motor); } -// Motor set speed forward - -void ESP32MotorControl::motorForward(uint8_t motor, uint8_t speed) +void setMotorPWM(uint8_t motor, int8_t speed) { - if (!isMotorValid(motor)) { + if (speed == 0 || speed == -100 || speed == 100) { + setMotorNoPWM(motor, speed); return; } - if (speed == 100) { // Full speed - - motorFullForward(motor); - + if (speed > 0) { + mcpwm_set_signal_low(MCPWM_UNIT(motor), MCPWM_TIMER(motor), MCPWM_OPR_B); + mcpwm_set_duty(MCPWM_UNIT(motor), MCPWM_TIMER(motor), MCPWM_OPR_A, speed); + // call the following each time, in case we used mcpwm_set_signal_low/high + mcpwm_set_duty_type(MCPWM_UNIT(motor), MCPWM_TIMER(motor), MCPWM_OPR_A, MCPWM_DUTY_MODE_0); } else { - - // Set speed -> PWM duty 0-100 - - if (motor == 0) { - - mcpwm_set_signal_low(MCPWM_UNIT_0, MCPWM_TIMER_0, MCPWM_OPR_B); - mcpwm_set_duty(MCPWM_UNIT_0, MCPWM_TIMER_0, MCPWM_OPR_A, speed); - mcpwm_set_duty_type(MCPWM_UNIT_0, MCPWM_TIMER_0, MCPWM_OPR_A, MCPWM_DUTY_MODE_0); //call this each time, if operator was previously in low/high state - - } else { - - mcpwm_set_signal_low(MCPWM_UNIT_1, MCPWM_TIMER_1, MCPWM_OPR_B); - mcpwm_set_duty(MCPWM_UNIT_1, MCPWM_TIMER_1, MCPWM_OPR_A, speed); - mcpwm_set_duty_type(MCPWM_UNIT_1, MCPWM_TIMER_1, MCPWM_OPR_A, MCPWM_DUTY_MODE_0); //call this each time, if operator was previously in low/high state - - } - - mMotorSpeed[motor] = speed; // Save it - mMotorForward[motor] = true; - - debug("Motor %u forward speed %u", motor, speed); + mcpwm_set_signal_low(MCPWM_UNIT(motor), MCPWM_TIMER(motor), MCPWM_OPR_A); + mcpwm_set_duty(MCPWM_UNIT(motor), MCPWM_TIMER(motor), MCPWM_OPR_B, -speed); + // call the following each time, in case we used mcpwm_set_signal_low/high + mcpwm_set_duty_type(MCPWM_UNIT(motor), MCPWM_TIMER(motor), MCPWM_OPR_B, MCPWM_DUTY_MODE_0); } } -void ESP32MotorControl::motorFullReverse(uint8_t motor) -{ - if (!isMotorValid(motor)) { - return; - } - - // Full forward - - if (motor == 0) { +} // namespace - mcpwm_set_signal_low(MCPWM_UNIT_0, MCPWM_TIMER_0, MCPWM_OPR_A); - mcpwm_set_signal_high(MCPWM_UNIT_0, MCPWM_TIMER_0, MCPWM_OPR_B); - - } else { - - mcpwm_set_signal_low(MCPWM_UNIT_1, MCPWM_TIMER_1, MCPWM_OPR_A); - mcpwm_set_signal_high(MCPWM_UNIT_1, MCPWM_TIMER_1, MCPWM_OPR_B); - } - - mMotorSpeed[motor] = 100; // Save it - mMotorForward[motor] = false; - - debug ("Motor %u full reverse", motor); +void ESP32MotorControl::attachMotor(uint8_t gpioIn1, uint8_t gpioIn2, uint32_t frequencyHz) +{ + attachMotors(gpioIn1, gpioIn2, 0, 0, frequencyHz); } -// Motor set speed reverse - -void ESP32MotorControl::motorReverse(uint8_t motor, uint8_t speed) +void ESP32MotorControl::attachMotors(uint8_t gpioIn1, uint8_t gpioIn2, uint8_t gpioIn3, + uint8_t gpioIn4, uint32_t frequencyHz) { - if (!isMotorValid(motor)) { - return; - } - - if (speed == 100) { // Full speed - - motorFullReverse(motor); - - } else { - - - // Set speed -> PWM duty 0-100 - - if (motor == 0) { - - mcpwm_set_signal_low(MCPWM_UNIT_0, MCPWM_TIMER_0, MCPWM_OPR_A); - mcpwm_set_duty(MCPWM_UNIT_0, MCPWM_TIMER_0, MCPWM_OPR_B, speed); - mcpwm_set_duty_type(MCPWM_UNIT_0, MCPWM_TIMER_0, MCPWM_OPR_B, MCPWM_DUTY_MODE_0); //call this each time, if operator was previously in low/high state - - } else { - - mcpwm_set_signal_low(MCPWM_UNIT_1, MCPWM_TIMER_1, MCPWM_OPR_A); - mcpwm_set_duty(MCPWM_UNIT_1, MCPWM_TIMER_1, MCPWM_OPR_B, speed); - mcpwm_set_duty_type(MCPWM_UNIT_1, MCPWM_TIMER_1, MCPWM_OPR_B, MCPWM_DUTY_MODE_0); //call this each time, if operator was previously in low/high state - - } - - mMotorSpeed[motor] = speed; // Save it - mMotorForward[motor] = false; - - debug("Motor %u reverse speed %u", motor, speed); - } -} + // Attach motor 0 input pins. + mcpwm_gpio_init(MCPWM_UNIT_0, MCPWM0A, gpioIn1); + mcpwm_gpio_init(MCPWM_UNIT_0, MCPWM0B, gpioIn2); + // Indicate the motor 0 is attached. + this->mMotorAttached_[0] = true; -// Motor stop + if (!(gpioIn3 == 0 && gpioIn4 == 0)) { + // Attach motor 1 input pins. + mcpwm_gpio_init(MCPWM_UNIT_1, MCPWM1A, gpioIn3); + mcpwm_gpio_init(MCPWM_UNIT_1, MCPWM1B, gpioIn4); -void ESP32MotorControl::motorStop(uint8_t motor) -{ - if (!isMotorValid(motor)) { - return; + // Indicate the motor 1 is attached. + this->mMotorAttached_[1] = true; } - // Motor stop + // Initial MCPWM configuration + mcpwm_config_t cfg; + cfg.frequency = frequencyHz; + cfg.cmpr_a = 0; + cfg.cmpr_b = 0; + cfg.counter_mode = MCPWM_UP_COUNTER; + cfg.duty_mode = MCPWM_DUTY_MODE_0; - if (motor == 0) { + // Configure PWM0A & PWM0B with above settings + mcpwm_init(MCPWM_UNIT_0, MCPWM_TIMER_0, &cfg); - mcpwm_set_signal_low(MCPWM_UNIT_0, MCPWM_TIMER_0, MCPWM_OPR_A); - mcpwm_set_signal_low(MCPWM_UNIT_0, MCPWM_TIMER_0, MCPWM_OPR_B); + // Configure PWM1A & PWM1B with above settings + mcpwm_init(MCPWM_UNIT_1, MCPWM_TIMER_1, &cfg); +} - } else { +void ESP32MotorControl::motorForward(uint8_t motor, uint8_t speed) { setMotor_(motor, speed); } - mcpwm_set_signal_low(MCPWM_UNIT_1, MCPWM_TIMER_1, MCPWM_OPR_A); - mcpwm_set_signal_low(MCPWM_UNIT_1, MCPWM_TIMER_1, MCPWM_OPR_B); +void ESP32MotorControl::motorReverse(uint8_t motor, uint8_t speed) { setMotor_(motor, -speed); } - } +void ESP32MotorControl::motorFullForward(uint8_t motor) { setMotor_(motor, 100); } - mMotorSpeed[motor] = 0; // Save it - mMotorForward[motor] = true; // For stop +void ESP32MotorControl::motorFullReverse(uint8_t motor) { setMotor_(motor, -100); } - debug("Motor %u stop", motor); -} - -// Motors stop +void ESP32MotorControl::motorStop(uint8_t motor) { setMotor_(motor, 0); } void ESP32MotorControl::motorsStop() { - motorStop(0); - motorStop(1); - - debug("Motors stop"); + setMotor_(0, 0); + setMotor_(1, 0); } -// Get motor speed - -uint8_t ESP32MotorControl::getMotorSpeed(uint8_t motor) { +void ESP32MotorControl::motorsSet(int8_t speed0, int8_t speed1) +{ + setMotor_(0, speed0); + setMotor_(1, speed1); +} - if (!isMotorValid(motor)) { +uint8_t ESP32MotorControl::getMotorSpeed(uint8_t motor) +{ + if (!isMotorValid_(motor)) return false; - } - return mMotorSpeed[motor]; + return mMotorSpeed[motor]; } -// Is motor in forward ? - -boolean ESP32MotorControl::isMotorForward(uint8_t motor) { - - if (!isMotorValid(motor)) { +boolean ESP32MotorControl::isMotorForward(uint8_t motor) +{ + if (!isMotorValid_(motor) || isMotorStopped(motor)) return false; - } - if (isMotorStopped(motor)) { - return false; - } else { - return mMotorForward[motor]; - } + return mMotorForward[motor]; } -// Is motor stopped ? - -boolean ESP32MotorControl::isMotorStopped(uint8_t motor) { - - - if (!isMotorValid(motor)) { +boolean ESP32MotorControl::isMotorStopped(uint8_t motor) +{ + if (!isMotorValid_(motor)) return true; - } + return (mMotorSpeed[motor] == 0); } -//// Privates - -// Is motor valid ? +void ESP32MotorControl::setMotor_(uint8_t motor, int8_t speed) +{ + if (!isMotorValid_(motor) || speed > 100 || speed < -100) + return; -boolean ESP32MotorControl::isMotorValid(uint8_t motor) { + setMotorPWM(motor, speed); + mMotorSpeed[motor] = std::abs(speed); + mMotorForward[motor] = speed > 0; +} - if (motor > 1) { +boolean ESP32MotorControl::isMotorValid_(uint8_t motor) +{ + if (motor > 1) return false; - } - return mMotorAttached[motor]; + return mMotorAttached_[motor]; } - - -///// End diff --git a/ESP32MotorControl.h b/ESP32MotorControl.h old mode 100755 new mode 100644 index d0efc8c..2ce7a7b --- a/ESP32MotorControl.h +++ b/ESP32MotorControl.h @@ -1,4 +1,6 @@ /* Header for ESP32MotorControl + * + * Copyright (C) 2021 Karol Pieniacy https://github.com/pieniacy/ESP32MotorControl * * Copyright (C) 2018 Joao Lopes https://github.com/JoaoLopesF/ESP32MotorControl * @@ -23,53 +25,48 @@ #include "Arduino.h" -//////// Defines - #ifndef ESP32 - #error "this library is only for ESP32" +#error "this library is only for ESP32" #endif -#define PWM_FREQ 1000 // PWM Frequency - -//////// Class - -class ESP32MotorControl -{ +class ESP32MotorControl { public: - - // Fields - + // Fields: uint16_t mMotorSpeed[2] = {0, 0}; boolean mMotorForward[2] = {true, true}; // Methods: - void attachMotor(uint8_t gpioIn1, uint8_t gpioIn2); - void attachMotors(uint8_t gpioIn1, uint8_t gpioIn2, uint8_t gpioIn3, uint8_t gpioIn4); + // Attach one motor + void attachMotor(uint8_t gpioIn1, uint8_t gpioIn2, uint32_t frequencyHz = 1000); + // Attach two motors + void attachMotors(uint8_t gpioIn1, uint8_t gpioIn2, uint8_t gpioIn3, uint8_t gpioIn4, + uint32_t frequencyHz = 1000); - void motorFullForward(uint8_t motor); + // Set speed -> PWM duty in the range 0-100 void motorForward(uint8_t motor, uint8_t speed); - void motorFullReverse(uint8_t motor); void motorReverse(uint8_t motor, uint8_t speed); + // Set full speed + void motorFullForward(uint8_t motor); + void motorFullReverse(uint8_t motor); + // Stop specific motor void motorStop(uint8_t motor); - + // Stop both motors void motorsStop(); - - void handle(); + // Set speed values of [-100 : 100] to both motors + void motorsSet(int8_t speed0, int8_t speed1); uint8_t getMotorSpeed(uint8_t motor); boolean isMotorForward(uint8_t motor); boolean isMotorStopped(uint8_t motor); private: - // Fields: + boolean mMotorAttached_[2] = {false, false}; - boolean mMotorAttached[2] = {false, false}; - - // Methods - - boolean isMotorValid(uint8_t motor); + // Methods: + void setMotor_(uint8_t motor, int8_t speed); + boolean isMotorValid_(uint8_t motor); }; -#endif // ESP32MotorControl_H +#endif // ESP32MotorControl_H diff --git a/README.md b/README.md index 4f66f01..3ad091d 100644 --- a/README.md +++ b/README.md @@ -1,16 +1,12 @@ # ESP32MotorControl Motor control using ESP32 MCPWM -![build badge](https://img.shields.io/badge/version-v0.1.0-blue.svg) -![GitHub](https://img.shields.io/github/license/mashape/apistatus.svg) - ### A library to ESP32 control motors using MCPWM -#### Works only with ESP32. +#### Works only with ESP32. ## Contents - [About](#about) - - [Wishlist](#wishlist) - [Using](#usage) - [Releases](#releases) @@ -43,7 +39,7 @@ ESP32MotorControl MotorControl = ESP32MotorControl(); ``` ###setup -- In the setup function +- In the setup function ```cpp // Attach 2 motors @@ -65,6 +61,7 @@ MotorControl.motorForward(0, speed); MotorControl.motorReverse(0, speed); MotorControl.motorForward(1, speed); MotorControl.motorReverse(1, speed); +MotorControl.motorsSet(75, -75); // To get info about motors @@ -78,4 +75,6 @@ stopped = isMotorStopped(0); #### 0.1 - First Beta +#### 0.2 +- Revision by Karol PieniÄ…cy diff --git a/library.json b/library.json index 5bf663a..b65b082 100644 --- a/library.json +++ b/library.json @@ -7,7 +7,7 @@ "type": "git", "url": "https://github.com/JoaoLopesF/ESP32MotorControl.git" }, - "version": "0.1.0", + "version": "0.2.0", "frameworks": "arduino", "platforms": "*" } diff --git a/library.properties b/library.properties index 7b73a03..c13ceba 100644 --- a/library.properties +++ b/library.properties @@ -1,6 +1,6 @@ name=ESP32MotorControl -version=0.1.0 -author=Joao Lopes +version=0.2.0 +author=Joao Lopes, Karol Pieniacy maintainer=Joao Lopes sentence=Motor control using ESP32 MCPWM paragraph=To control up 2 DC motors