DC Motor
Description
DC motor drivers are available on the following module:
OI-Dc (x4)
Main characteristics
Bidirectional control: Supports both forward and reverse rotation.
Variable speed control: PWM-based speed regulation with duty cycle from 0% to 100%.
Current monitoring: Real-time current measurement for each motor.
Fault detection: Hardware fault pin monitoring for driver protection.
High current capability: Designed to drive DC motors with appropriate current ratings.
The OI-Dc module uses H-bridge motor drivers to control DC motors. Each motor driver has two control inputs (IN1 and IN2) that are controlled via PWM to regulate motor speed and direction, and a disable pin for enabling/disabling the motor.
Note
The motor drivers operate at a fixed PWM frequency of 5 kHz, which provides a good balance between motor performance and switching losses.
Characteristics
Parameter |
Value |
Remark |
|---|---|---|
Number of motors |
4 |
Independent control |
Power supply voltage |
9-30V DC |
Same as module supply |
PWM frequency |
5 kHz |
Fixed |
PWM resolution |
13 bits |
8192 steps |
Direction control |
Bidirectional |
Forward/Reverse |
Current monitoring |
Yes |
Per motor channel |
Code examples
The example code below demonstrates how to control a DC motor with the OI-Dc module:
/**
* @file DcMotorSimple.cpp
* @author Georges de Massol
* @brief Simple example for OI-DC (DC Motor Controller) module
*
* This example demonstrates basic motor control with the OpenIndus DC module:
* - Run motor forward at full speed
* - Measure current
* - Run motor backward at full speed
* - Measure current
* - Stop motor
* - Measure current (should be near 0A)
* Hardware Wiring Diagram:
*
* OI-DC Module Pinout & Test Configuration
* =========================================
*
* Power Supply (24V)
* + +----------------
* | | |
* | | |
* +----|-------------------------+-------+--------------+--------+----+ |
* | | | | | | | | | | |
* | 9V-30V 9V-30V /B2 /A2 | /B1 /A1 | | _____
* | VIN VIN DIN4 HB4_2 HB3_2 DIN2 HB2_2 HB1_2 | / \
* | | | M |
* | | \_____/
* | GND GND DIN3 HB4_1 HB3_1 DIN1 HB2_1 HB1_1 | |
* | | | B2 A2 | B1 A1 | | |
* | | | | | | | | | | |
* +----+-------------------------+-------+--------------+--------+----+ |
* | | |
* | | |
* - +----------------
* GND
*
* @date November 2025
*/
#include "OpenIndus.h"
#include "Arduino.h"
Dc dc; // Create DC motor controller object
static const char TAG[] = "Main";
void setup(void)
{
}
void loop(void)
{
float current;
// 1. Run motor forward at 100% speed
dc.run(MOTOR_1, FORWARD, 100);
current = dc.getCurrent(MOTOR_1);
ESP_LOGI(TAG, "MOTOR_1 FORWARD: Current = %.3f A", current);
delay(2000); // Run for 2 seconds
// 2. Run motor backward at 100% speed
dc.run(MOTOR_1, REVERSE, 100);
current = dc.getCurrent(MOTOR_1);
ESP_LOGI(TAG, "MOTOR_1 REVERSE: Current = %.3f A", current);
delay(2000); // Run for 2 seconds
// 3. Stop motor
dc.stop(MOTOR_1);
current = dc.getCurrent(MOTOR_1);
ESP_LOGI(TAG, "MOTOR_1 STOPPED: Current = %.3f A", current);
// Nothing to do in loop
delay(2000);
}
This example demonstrates basic motor control operations:
Starting a motor: Use run() with motor number, direction (FORWARD/REVERSE), and duty cycle (0-100%).
Reading current: Use getCurrent() to monitor motor load.
Stopping a motor: Use stop() to disable the motor driver.
Note
The duty cycle parameter in the run() function represents the percentage of maximum speed. A value of 100% corresponds to full speed, while 0% effectively stops the motor (though using stop() is preferred for this purpose).
Software API
-
class MotorDc : public Motor
DC Motor control class.
Public Static Functions
-
static void run(MotorNum_t motor, MotorDirection_t direction, float dutyCycle)
Run a DC motor with specified direction and duty cycle.
- Parameters:
motor – Motor number
direction – Motor direction (FORWARD/REVERSE)
dutyCycle – Duty cycle percentage (0..100)
-
static void stop(MotorNum_t motor)
Stop a DC motor.
- Parameters:
motor – Motor number
-
static void brake(MotorNum_t motor)
Brake a DC motor by calling run with speed 0.
- Parameters:
motor – Motor number
-
static float getCurrent(MotorNum_t motor)
Get current consumption of a DC motor.
- Parameters:
motor – Motor number
- Returns:
float current in A
-
static uint8_t getFault(MotorNum_t motor)
Get the current fault status from DRV8873 for a specific motor.
- Parameters:
motor – Motor number (0-3)
- Returns:
uint8_t Fault status register value (0 if no fault)
-
static esp_err_t clearFault(MotorNum_t motor)
Clear all faults in DRV8873 for a specific motor.
- Parameters:
motor – Motor number (0-3)
- Returns:
esp_err_t ESP_OK on success, error code otherwise
-
static esp_err_t setMode(drv8873_mode_t mode, MotorNum_t motor)
Set the control mode of DRV8873 for a specific motor.
- Parameters:
mode – Control mode to set (PH/EN, PWM, Independent, Disabled)
motor – Motor number (0-3)
- Returns:
esp_err_t ESP_OK on success, error code otherwise
-
static void run(MotorNum_t motor, MotorDirection_t direction, float dutyCycle)