DRV8833 Dual Motor Driver - johnosbb/Automation GitHub Wiki

DRV8833 Dual Motor Driver 1A

DRV8833 Motor Driver

At the heart of the module is an integrated H-Bridge driver IC from Texas Instruments that is optimized for motor driving applications – The DRV8833.

drv8833 module hardware overview The DRV8833 features two NMOS H-bridge drivers, enabling it to control two DC brush motors, a bipolar stepper motor, solenoids, and other inductive loads.

It operates in a voltage range from 2.7 V to 10.8 V, and can continuously supply up to 1.2 A per channel. Additionally, it can tolerate peak currents up to 2 A per channel for a few seconds.

The DRV8833 also contains a number of protection features, such as under-voltage lockout, over-current, and over-temperature protection, offering a high level of reliability. Each of these events will disable the H-Bridge MOSFETs. After a fault condition has been removed, the device will resume its operation.

image

Sparcfun version

It also includes a low-power sleep mode, which lets you save power, especially when the motors are not in use.

Connections

Motor

Motor A should be connected to OUT1 and OUT2, while Motor B should be connected to OUT3, and OUT4. You can connect any brushed DC motor ranging from 2.7 V to 10.8 V to these pins.

Control Input Pins

Each motor has two control inputs; IN1 and IN2 are the control inputs for Motor A, while IN3 and IN4 are for Motor B. These control inputs allow you to control both the speed and spinning direction of the motor.

Direction Control

The spinning direction of the motor can be controlled by applying logic HIGH (5V) or logic LOW (Ground) to these inputs.The truth table below shows how the inputs affect the driver outputs.

image

Speed Control

If you want to control speed, you can use Pulse Width Modulation (PWM) on the pin that’s usually high. If speed control isn’t needed, just set them to either HIGH or LOW.

This Module has 16 pins:

VM: Motor voltage
GND: Ground – three ground connected to each other
AO1: Positive end for motor A
AO2: Negative end for motor A
BO1: Positive end for motor B
BO2: Negative end for motor B
AIN1: Control signal for motor A
AIN2: Control signal for motor A
BIN1: Control signal for motor B
BIN2: Control signal for motor B
STBY: To active Standby mode, it should be HIGH
NC: Not used

Possible Reference Code (not tested)

  • Map MOTOR_LEFT_DIRECTION_1/2 → AIN1/AIN2
  • Map MOTOR_RIGHT_DIRECTION_1/2 → BIN1/BIN2
  • MOTOR_LEFT_SPEED and MOTOR_RIGHT_SPEED are not used anymore (kept defined for compatibility)

Uses 4 LEDC channels: one per input (IN1/IN2 for each motor)

If your board breaks out STBY, set its pin below; otherwise leave it at -1 and the code will skip it

// ===============================
// DRV8833 Motor Driver Control
// ESP32 + LEDC PWM (uses your pin/LEDC config)
// ===============================

#include <Arduino.h>

// ------------------------------
// Pins definitions for the project
// ------------------------------
// Left Motor (use as DRV8833 AIN1/AIN2)
#define MOTOR_LEFT_DIRECTION_1  26
#define MOTOR_LEFT_DIRECTION_2  27
// Speed pins are unused with DRV8833 but kept for compatibility
#define MOTOR_LEFT_SPEED        14

// Right Motor (use as DRV8833 BIN1/BIN2)
#define MOTOR_RIGHT_DIRECTION_1 19
#define MOTOR_RIGHT_DIRECTION_2 18
#define MOTOR_RIGHT_SPEED       23

// Optional DRV8833 standby. If your board ties STBY high, leave as -1.
#define MOTOR_STBY             -1   // e.g., set to 33 if wired

// Infrared Receiver / Encoder (unchanged)
#define IR_RECEIVE_PIN 4
#define ENCODER_PIN    39

// PWM config (from your project)
#define FREQUENCY           30000
#define RESOLUTION          8            // 8-bit => duty 0..255
#define DEFAULT_DUTY_CYCLE  200
#define REDUCED_SPEED       200
#define HIGHER_SPEED        255

// We need 4 channels (one per input).
// New channel mapping:
#define CH_LEFT_IN1   0
#define CH_LEFT_IN2   1
#define CH_RIGHT_IN1  2
#define CH_RIGHT_IN2  3


extern void updateMotorStatus();
enum MotorStatus { STOPPING, MOVING_FORWARD, MOVING_REVERSE };
volatile MotorStatus motor_status;

// ------------------------------
// LEDC helpers
// ------------------------------
static inline void pwmWriteChannel(uint8_t channel, uint32_t duty) {
  ledcWrite(channel, duty);
}

static inline void attachPwmPin(uint8_t pin, uint8_t channel) {
  ledcSetup(channel, FREQUENCY, RESOLUTION);
  ledcAttachPin(pin, channel);
  ledcWrite(channel, 0);
}

// Ensure only one input is PWM’d at a time for a given motor
static void driveMotorForward(uint8_t in1_pin, uint8_t in2_pin,
                              uint8_t ch_in1,   uint8_t ch_in2,
                              uint32_t duty) {
  digitalWrite(in1_pin, LOW);      // non-PWM leg low
  pwmWriteChannel(ch_in1, 0);      // no PWM on IN1
  pwmWriteChannel(ch_in2, duty);   // PWM on IN2
}

static void driveMotorBackward(uint8_t in1_pin, uint8_t in2_pin,
                               uint8_t ch_in1,  uint8_t ch_in2,
                               uint32_t duty) {
  digitalWrite(in2_pin, LOW);      // non-PWM leg low
  pwmWriteChannel(ch_in2, 0);      // no PWM on IN2
  pwmWriteChannel(ch_in1, duty);   // PWM on IN1
}

static void coastMotor(uint8_t in1_pin, uint8_t in2_pin,
                       uint8_t ch_in1,  uint8_t ch_in2) {
  pwmWriteChannel(ch_in1, 0);
  pwmWriteChannel(ch_in2, 0);
  digitalWrite(in1_pin, LOW);
  digitalWrite(in2_pin, LOW);      // both LOW = coast
  // For active brake instead, set both HIGH:
  // digitalWrite(in1_pin, HIGH);
  // digitalWrite(in2_pin, HIGH);
}

// ------------------------------
// Setup 
// ------------------------------
void setupMotorControl() {
  // Configure I/O
  pinMode(MOTOR_LEFT_DIRECTION_1,  OUTPUT);
  pinMode(MOTOR_LEFT_DIRECTION_2,  OUTPUT);
  pinMode(MOTOR_RIGHT_DIRECTION_1, OUTPUT);
  pinMode(MOTOR_RIGHT_DIRECTION_2, OUTPUT);

  if (MOTOR_STBY >= 0) {
    pinMode(MOTOR_STBY, OUTPUT);
    digitalWrite(MOTOR_STBY, HIGH);  // enable driver
  }

  // LEDC: one channel per input
  attachPwmPin(MOTOR_LEFT_DIRECTION_1,  CH_LEFT_IN1);
  attachPwmPin(MOTOR_LEFT_DIRECTION_2,  CH_LEFT_IN2);
  attachPwmPin(MOTOR_RIGHT_DIRECTION_1, CH_RIGHT_IN1);
  attachPwmPin(MOTOR_RIGHT_DIRECTION_2, CH_RIGHT_IN2);

  // Start coasting
  coastMotor(MOTOR_LEFT_DIRECTION_1,  MOTOR_LEFT_DIRECTION_2,  CH_LEFT_IN1,  CH_LEFT_IN2);
  coastMotor(MOTOR_RIGHT_DIRECTION_1, MOTOR_RIGHT_DIRECTION_2, CH_RIGHT_IN1, CH_RIGHT_IN2);
}

// ------------------------------
// Movement primitives 
// ------------------------------
// Note: the pin parameters are ignored for DRV8833; we use fixed mapping.
void moveForward(int /*directionPin1*/, int /*directionPin2*/, int /*speedPin*/, int duty_cycle) {
  driveMotorForward(MOTOR_LEFT_DIRECTION_1,  MOTOR_LEFT_DIRECTION_2,
                    CH_LEFT_IN1,             CH_LEFT_IN2,
                    duty_cycle);

  driveMotorForward(MOTOR_RIGHT_DIRECTION_1, MOTOR_RIGHT_DIRECTION_2,
                    CH_RIGHT_IN1,            CH_RIGHT_IN2,
                    duty_cycle);

  motor_status = MOVING_FORWARD;
  updateMotorStatus();
}

void moveBackward(int /*directionPin1*/, int /*directionPin2*/, int /*speedPin*/, int duty_cycle) {
  driveMotorBackward(MOTOR_LEFT_DIRECTION_1,  MOTOR_LEFT_DIRECTION_2,
                     CH_LEFT_IN1,             CH_LEFT_IN2,
                     duty_cycle);

  driveMotorBackward(MOTOR_RIGHT_DIRECTION_1, MOTOR_RIGHT_DIRECTION_2,
                     CH_RIGHT_IN1,            CH_RIGHT_IN2,
                     duty_cycle);

  motor_status = MOVING_REVERSE;
  updateMotorStatus();
}

void stopMotor(int /*directionPin1*/, int /*directionPin2*/, int /*speedPin*/) {
  coastMotor(MOTOR_LEFT_DIRECTION_1,  MOTOR_LEFT_DIRECTION_2,  CH_LEFT_IN1,  CH_LEFT_IN2);
  coastMotor(MOTOR_RIGHT_DIRECTION_1, MOTOR_RIGHT_DIRECTION_2, CH_RIGHT_IN1, CH_RIGHT_IN2);

  motor_status = STOPPING;
  updateMotorStatus();
}

// ------------------------------
// Higher-level maneuvers 
// ------------------------------
void gentleTurnRight(int /*lD1*/, int /*lD2*/, int /*lSpeed*/,
                     int /*rD1*/, int /*rD2*/, int /*rSpeed*/) {
  driveMotorForward(MOTOR_LEFT_DIRECTION_1,  MOTOR_LEFT_DIRECTION_2,
                    CH_LEFT_IN1,             CH_LEFT_IN2,
                    HIGHER_SPEED);
  driveMotorForward(MOTOR_RIGHT_DIRECTION_1, MOTOR_RIGHT_DIRECTION_2,
                    CH_RIGHT_IN1,            CH_RIGHT_IN2,
                    REDUCED_SPEED);

  motor_status = MOVING_FORWARD;
  updateMotorStatus();
}

void gentleTurnLeft(int /*lD1*/, int /*lD2*/, int /*lSpeed*/,
                    int /*rD1*/, int /*rD2*/, int /*rSpeed*/) {
  driveMotorForward(MOTOR_LEFT_DIRECTION_1,  MOTOR_LEFT_DIRECTION_2,
                    CH_LEFT_IN1,             CH_LEFT_IN2,
                    REDUCED_SPEED);
  driveMotorForward(MOTOR_RIGHT_DIRECTION_1, MOTOR_RIGHT_DIRECTION_2,
                    CH_RIGHT_IN1,            CH_RIGHT_IN2,
                    HIGHER_SPEED);

  motor_status = MOVING_FORWARD;
  updateMotorStatus();
}

void rotateRight(int /*lD1*/, int /*lD2*/, int /*lSpeed*/,
                 int /*rD1*/, int /*rD2*/, int /*rSpeed*/, int duty_cycle) {
  driveMotorForward(MOTOR_LEFT_DIRECTION_1,  MOTOR_LEFT_DIRECTION_2,
                    CH_LEFT_IN1,             CH_LEFT_IN2,
                    duty_cycle);

  driveMotorBackward(MOTOR_RIGHT_DIRECTION_1, MOTOR_RIGHT_DIRECTION_2,
                     CH_RIGHT_IN1,            CH_RIGHT_IN2,
                     duty_cycle);

  motor_status = MOVING_FORWARD; // or a dedicated ROTATING state
  updateMotorStatus();
}

void rotateLeft(int /*lD1*/, int /*lD2*/, int /*lSpeed*/,
                int /*rD1*/, int /*rD2*/, int /*rSpeed*/, int duty_cycle) {
  driveMotorBackward(MOTOR_LEFT_DIRECTION_1,  MOTOR_LEFT_DIRECTION_2,
                     CH_LEFT_IN1,             CH_LEFT_IN2,
                     duty_cycle);

  driveMotorForward(MOTOR_RIGHT_DIRECTION_1, MOTOR_RIGHT_DIRECTION_2,
                    CH_RIGHT_IN1,            CH_RIGHT_IN2,
                    duty_cycle);

  motor_status = MOVING_FORWARD; // or ROTATING
  updateMotorStatus();
}

Direction + PWM rule for DRV8833

  • Forward: IN1=LOW, IN2=PWM(duty)
  • Reverse: IN2=LOW, IN1=PWM(duty)

Note: Only one input is PWM’d at a time for a motor.

STBY

If your breakout exposes STBY, wire it to a GPIO and set MOTOR_STBY to that pin; it must be HIGH to drive. If it’s hard-wired HIGH on your board, leave MOTOR_STBY as -1.

Frequency 30 kHz

FREQUENCY at 30 kHz is fine for DRV8833 and will be quiet.

Stop behavior

The code uses “coast” (both LOW). For hard braking, set both HIGH in coastMotor() as commented.

References

⚠️ **GitHub.com Fallback** ⚠️