L293 motor driver chip: https://www.ti.com/lit/ds/symlink/l293.pdf.
More...
#include <JMotorDriverAvrL293.h>
|
| JMotorDriverAvrL293 (byte _en, byte _i1, byte _i2, bool _breakOn=true, bool breakWhenDisabled=false, bool _reverse=false) |
| constructor, sets pins
|
|
bool | set (float val) |
| set motor power
|
|
bool | setEnable (bool _enable) |
| use to enable or disable a motor, and sets up pin states
|
|
bool | getEnable () |
| get the enable state of the driver
|
|
float | getMaxRange () |
| high end of the range
|
|
float | getMinRange () |
| low end of the range
|
|
bool | enable () |
| enable motor
|
|
bool | disable () |
| disable motor
|
|
L293 motor driver chip: https://www.ti.com/lit/ds/symlink/l293.pdf.
- Note
- compatible with all boards that support analogWrite()
◆ JMotorDriverAvrL293()
JMotorDriverAvrL293::JMotorDriverAvrL293 |
( |
byte |
_en, |
|
|
byte |
_i1, |
|
|
byte |
_i2, |
|
|
bool |
_breakOn = true , |
|
|
bool |
breakWhenDisabled = false , |
|
|
bool |
_reverse = false |
|
) |
| |
|
inline |
constructor, sets pins
- Parameters
-
_en | enable(speed) pin on driver |
_i1 | input pin 1 (direction) |
_i2 | input pin 2 (direction) |
_breakOn | = true: if true (default), add extra resistance to motor when set to 0 power (by shorting motor terminals) |
breakWhenDisabled | = false: if false (default) turn off break when disabled, if true, keep electrically breaking |
_reverse | (bool) default=false, reverse direction of driver |
◆ getEnable()
bool JMotorDriverAvrL293::getEnable |
( |
| ) |
|
|
inlinevirtual |
get the enable state of the driver
- Return values
-
(bool) | true if enabled, false if disabled |
Reimplemented from JMotorDriver.
◆ getMaxRange()
float JMotorDriverAvrL293::getMaxRange |
( |
| ) |
|
|
inlinevirtual |
high end of the range
- Note
- usually 1.0
- Return values
-
Reimplemented from JMotorDriver.
◆ getMinRange()
float JMotorDriverAvrL293::getMinRange |
( |
| ) |
|
|
inlinevirtual |
low end of the range
- Note
- usually -1.0, if 0, that indicates a motor controller with no reverse function
- Return values
-
Reimplemented from JMotorDriver.
◆ set()
bool JMotorDriverAvrL293::set |
( |
float |
val | ) |
|
|
inlinevirtual |
set motor power
- Note
- val should be between getMinRange and getMaxRange, but constrained internally
- Parameters
-
- Return values
-
(bool) | false if at end of power range, true otherwise |
Reimplemented from JMotorDriver.
◆ setEnable()
bool JMotorDriverAvrL293::setEnable |
( |
bool |
_enable | ) |
|
|
inlinevirtual |
use to enable or disable a motor, and sets up pin states
- Note
- setEnable(true) must be called before a motor driver will activate
- Parameters
-
_enable | (bool) true=enable, false=disable |
- Return values
-
(bool) | true if state changed, false if state already set |
Reimplemented from JMotorDriver.
◆ breakOn
bool JMotorDriverAvrL293::breakOn |
◆ pwmDriver
◆ reverse
bool JMotorDriverAvrL293::reverse |
The documentation for this class was generated from the following file: