Skip to content

Introduced compatibility for ESP32 boards. #12

New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Open
wants to merge 2 commits into
base: master
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
108 changes: 70 additions & 38 deletions CytronMotorDriver.cpp
Original file line number Diff line number Diff line change
@@ -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;
}
}
5 changes: 2 additions & 3 deletions CytronMotorDriver.h
Original file line number Diff line number Diff line change
Expand Up @@ -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:
Expand Down
8 changes: 8 additions & 0 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -3,6 +3,14 @@ This library provides functions for Cytron Motor Drivers.<br>
Please refer to the examples on how to use the library.<br>
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`.
Expand Down
13 changes: 11 additions & 2 deletions examples/PWM_DIR/PWM_DIR.ino
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand All @@ -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.
Expand Down
17 changes: 14 additions & 3 deletions examples/PWM_DIR_DUAL/PWM_DIR_DUAL.ino
Original file line number Diff line number Diff line change
Expand Up @@ -10,14 +10,25 @@
* 2-channel motor driver.
*
*
* CONNECTIONS:
* CONNECTIONS: Arduino Uno
*
* Arduino D3 - Motor Driver PWM 1 Input
* Arduino D4 - Motor Driver DIR 1 Input
* Arduino D9 - Motor Driver PWM 2 Input
* 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
Expand All @@ -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.
Expand Down