Implement a QPID_MotorDriver for TI's DRV8833 chip based modules. (Watch out for fake modules with the HR8833 chip, they didn't work well for me.)
More...
|
void | setPower (int16_t pow) |
| Start motor with given power, direction and currently set decay mode. More...
|
|
void | coast (void) |
| Stop motor in fast decay mode (spinning freely). Does not affect decay mode set by user.
|
|
void | brake (void) |
| Stop motor in slow decay mode (braking). Does not affect decay mode used in setPower() set by user.
|
|
void | setDecay (decayModeType mode) |
| Set decay mode (who would have thought that!) More...
|
|
void | setFrequency (uint8_t onoff) |
| Set PWM frequency. More...
|
|
void | enable (void) |
| Enable driver chip by pulling nSLEEP pin high. Only use this, if you've specified a pin for nSLEEP.
|
|
void | disable (void) |
| Disable driver chip by pulling nSLEEP pin low. Only use this, if you've specified a pin for nSLEEP.
|
|
void | init (int8_t a, int8_t b, int8_t s, int8_t f) |
| Define and initialize pins connected to DRV8833's IN1, IN2, nSLEEP, and nFAULT. More...
|
|
int8_t | hasFault (void) |
| Report DRV8833 FAULT pin state. More...
|
|
virtual void | update () |
| (abstract) Can be overridden by QPID subsystems which need to do their own polling. Will be called by QPID_Unit::update() for subsystems, and by firmware/client for QPID_Unit itself.
|
|
void | throwError (const char *invokedBy, const char *errorMessage) |
| Writes error message and error invoking class to Serial. More...
|
|
void | log (const char *logEntry) |
| Puts timestamped string into the system log (atm: writes it out to Serial). More...
|
|
|
bool | processMessage (uint8_t *m) override |
| (abstract) Interprets message handed down from QPID_Unit locally. Must be overridden in derived classes
|
|
| QPID_Object () |
| Constructor. Begins Serial with 115200 baud for logging and error reporting, if not done previously.
|
|
|
enum | decayModeType : uint8_t { decayModeFast = 0,
decayModeSlow = 1
} |
| Symbolic names for decay modes that should be used during inactive part of PWM phase, if the driver supports that functionality.
|
|
decayModeType | decayMode = decayModeSlow |
|
int16_t | currentPWM = 0 |
|
int16_t | maxPower |
|
int16_t | alwaysOnPWM |
|
Implement a QPID_MotorDriver for TI's DRV8833 chip based modules. (Watch out for fake modules with the HR8833 chip, they didn't work well for me.)
QPID_MotorDriver)
- Supports en/disable by nSLEEP pin and fault signaling by nFAULT pin.
- Note
- The current implementation is tailored for the ESP32, other platforms would have to be added with preprocessor directives.
◆ setPower()
void QPID_MotorDriver_DRV8833::setPower |
( |
int16_t |
pow | ) |
|
|
virtual |
Start motor with given power, direction and currently set decay mode.
- Parameters
-
pow | PWM value, sign indicates direction. |
- Note
- setPower(0) will also use current decay mode for both pins. Usually brake() or coast() are preferable.
Reimplemented from QPID_MotorDriver.
◆ setDecay()
◆ setFrequency()
void QPID_MotorDriver_DRV8833::setFrequency |
( |
uint8_t |
freq | ) |
|
|
virtual |
◆ init()
void QPID_MotorDriver_DRV8833::init |
( |
int8_t |
a, |
|
|
int8_t |
b, |
|
|
int8_t |
s, |
|
|
int8_t |
f |
|
) |
| |
Define and initialize pins connected to DRV8833's IN1, IN2, nSLEEP, and nFAULT.
- Parameters
-
a | pin IN1 |
b | pin IN2 |
s | pin nSLEEP (-1 if not used). Set to LOW (= disabled) initially, i.e. if you specify an nSLEEP pin, you have to call enable() before using the driver. |
f | pin nFAULT (-1 if not used). nFAULT is open drain, so the internal pullup is used. |
◆ hasFault()
int8_t QPID_MotorDriver_DRV8833::hasFault |
( |
void |
| ) |
|
|
virtual |
Report DRV8833 FAULT pin state.
- Returns
- true(1) for fault, false(0) for no fault
Reimplemented from QPID_MotorDriver.
The documentation for this class was generated from the following files: