diff --git a/CytronMotorDriver.cpp b/CytronMotorDriver.cpp
index 450dec8..7fb9033 100644
--- a/CytronMotorDriver.cpp
+++ b/CytronMotorDriver.cpp
@@ -1,47 +1,79 @@
#include "CytronMotorDriver.h"
-CytronMD::CytronMD(MODE mode, uint8_t pin1, uint8_t pin2)
+CytronMD::CytronMD(MODE mode, uint8_t pin1, uint8_t pin2, uint8_t channel)
{
- _mode = mode;
- _pin1 = pin1;
- _pin2 = pin2;
-
- pinMode(_pin1, OUTPUT);
- pinMode(_pin2, OUTPUT);
-
- digitalWrite(_pin1, LOW);
- digitalWrite(_pin2, LOW);
+ _mode = mode;
+ _pin1 = pin1;
+ _pin2 = pin2;
+ _channel = channel;
+
+ pinMode(_pin1, OUTPUT);
+ pinMode(_pin2, OUTPUT);
+
+
+ #if defined(ARDUINO_ARCH_ESP32)
+ ledcSetup(_channel, 5000, 8);
+ ledcAttachPin(_pin1, _channel);
+ digitalWrite(_pin2, LOW);
+ #else
+ digitalWrite(_pin1, LOW);
+ digitalWrite(_pin2, LOW);
+ #endif
}
void CytronMD::setSpeed(int16_t speed)
{
- // Make sure the speed is within the limit.
- if (speed > 255) {
- speed = 255;
- } else if (speed < -255) {
- speed = -255;
- }
-
- // Set the speed and direction.
- switch (_mode) {
- case PWM_DIR:
- if (speed >= 0) {
- analogWrite(_pin1, speed);
- digitalWrite(_pin2, LOW);
- } else {
- analogWrite(_pin1, -speed);
- digitalWrite(_pin2, HIGH);
+ // Make sure the speed is within the limit.
+ if (speed > 255)
+ {
+ speed = 255;
}
- break;
-
- case PWM_PWM:
- if (speed >= 0) {
- analogWrite(_pin1, speed);
- analogWrite(_pin2, 0);
- } else {
- analogWrite(_pin1, 0);
- analogWrite(_pin2, -speed);
+ else if (speed < -255)
+ {
+ speed = -255;
}
- break;
- }
-}
+
+ // Set the speed and direction.
+ switch (_mode)
+ {
+ case PWM_DIR:
+ if (speed >= 0)
+ {
+ #if defined(ARDUINO_ARCH_ESP32)
+ ledcWrite(_channel, speed);
+ #else
+ analogWrite(_pin1, speed);
+ #endif
+ digitalWrite(_pin2, LOW);
+ }
+ else
+ {
+ #if defined(ARDUINO_ARCH_ESP32)
+ ledcWrite(_channel, -speed);
+ #else
+ analogWrite(_pin1, -speed);
+ #endif
+ digitalWrite(_pin2, HIGH);
+ }
+ break;
+
+ case PWM_PWM:
+ if (speed >= 0)
+ {
+ #if defined(ARDUINO_ARCH_ESP32)
+ #else
+ analogWrite(_pin1, speed);
+ analogWrite(_pin2, 0);
+ #endif
+ }
+ else
+ {
+ #if defined(ARDUINO_ARCH_ESP32)
+ #else
+ analogWrite(_pin1, 0);
+ analogWrite(_pin2, -speed);
+ #endif
+ }
+ break;
+ }
+}
\ No newline at end of file
diff --git a/CytronMotorDriver.h b/CytronMotorDriver.h
index d297f7b..1adf833 100644
--- a/CytronMotorDriver.h
+++ b/CytronMotorDriver.h
@@ -16,17 +16,16 @@ enum MODE {
class CytronMD
{
public:
- CytronMD(MODE mode, uint8_t pin1, uint8_t pin2);
+ CytronMD(MODE mode, uint8_t pin1, uint8_t pin2, uint8_t channel = 0);
void setSpeed(int16_t speed);
protected:
MODE _mode;
uint8_t _pin1;
uint8_t _pin2;
+ uint8_t _channel;
};
-
-
/* class CytronMD10C : public CytronMD
{
public:
diff --git a/README.md b/README.md
index a6fb197..5d3d490 100644
--- a/README.md
+++ b/README.md
@@ -3,6 +3,14 @@ This library provides functions for Cytron Motor Drivers.
Please refer to the examples on how to use the library.
Connection to the motor driver is described in the comment section of the examples.
+## Support
+This library is compatible with the following boards:
+
+- Arduino Uno in PWM_DIR and PWM_PWM mode.
+- ESP32 in PWM_DIR mode.
+
+Please note that the library may work with other Arduino-compatible boards as well, but it has been specifically tested and confirmed to work with Arduino Uno in both the modes and ESP32 in PWM_DIR mode.
+
## Installation
1. Open the Arduino IDE, select `Sketch` -> `Include Library` -> `Manage Libraries...`.
2. Search for `Cytron Motor Drivers Library`.
diff --git a/examples/PWM_DIR/PWM_DIR.ino b/examples/PWM_DIR/PWM_DIR.ino
index 0efb350..5323e22 100644
--- a/examples/PWM_DIR/PWM_DIR.ino
+++ b/examples/PWM_DIR/PWM_DIR.ino
@@ -11,12 +11,21 @@
* For dual channel motor driver, both channel work the same way.
*
*
- * CONNECTIONS:
+ * CONNECTIONS: Arduino Uno
*
* Arduino D3 - Motor Driver PWM Input
* Arduino D4 - Motor Driver DIR Input
* Arduino GND - Motor Driver GND
+ *
+ * CONNECTIONS: ESP32
+ *
+ * ESP32 D2 - Motor Driver PWM Input
+ * ESP32 D4 - Motor Driver DIR Input
+ * ESP32 GND - Motor Driver GND
*
+ * NOTE:
+ * 1. Default value for channel is 0.
+ * 2. Different channels (0 - 15) should be assigned for every CytronMD instance.
*
* AUTHOR : Kong Wai Weng
* COMPANY : Cytron Technologies Sdn Bhd
@@ -29,7 +38,7 @@
// Configure the motor driver.
-CytronMD motor(PWM_DIR, 3, 4); // PWM = Pin 3, DIR = Pin 4.
+CytronMD motor(PWM_DIR, 2, 4, 0); // PWM = Pin 2, DIR = Pin 4, CHANNEL = 0.
// The setup routine runs once when you press reset.
diff --git a/examples/PWM_DIR_DUAL/PWM_DIR_DUAL.ino b/examples/PWM_DIR_DUAL/PWM_DIR_DUAL.ino
index bc9cc84..efe9343 100644
--- a/examples/PWM_DIR_DUAL/PWM_DIR_DUAL.ino
+++ b/examples/PWM_DIR_DUAL/PWM_DIR_DUAL.ino
@@ -10,7 +10,7 @@
* 2-channel motor driver.
*
*
- * CONNECTIONS:
+ * CONNECTIONS: Arduino Uno
*
* Arduino D3 - Motor Driver PWM 1 Input
* Arduino D4 - Motor Driver DIR 1 Input
@@ -18,6 +18,17 @@
* Arduino D10 - Motor Driver DIR 2 Input
* Arduino GND - Motor Driver GND
*
+ * CONNECTIONS: ESP32
+ *
+ * Arduino D2 - Motor Driver PWM 1 Input
+ * Arduino D4 - Motor Driver DIR 1 Input
+ * Arduino D18 - Motor Driver PWM 2 Input
+ * Arduino D19 - Motor Driver DIR 2 Input
+ * ESP32 GND - Motor Driver GND
+ *
+ * NOTE:
+ * 1. Default value for channel is 0.
+ * 2. Different channels (0 - 15) should be assigned for every CytronMD instance.
*
* AUTHOR : Kong Wai Weng
* COMPANY : Cytron Technologies Sdn Bhd
@@ -30,8 +41,8 @@
// Configure the motor driver.
-CytronMD motor1(PWM_DIR, 3, 4); // PWM 1 = Pin 3, DIR 1 = Pin 4.
-CytronMD motor2(PWM_DIR, 9, 10); // PWM 2 = Pin 9, DIR 2 = Pin 10.
+CytronMD motor1(PWM_DIR, 2, 4, 0); // PWM 1 = Pin 3, DIR 1 = Pin 4, CHANNEL = 0
+CytronMD motor2(PWM_DIR, 18, 19, 1); // PWM 2 = Pin 9, DIR 2 = Pin 10, CHANNEL = 1
// The setup routine runs once when you press reset.