wrapper for analogWrite()
More...
#include <JMotorDriverAvrPWM.h>
|
| JMotorDriverAvrPWM (byte _pin, bool _disableState=LOW) |
| 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
|
|
|
int | PWM_RANGE = 255 |
| change PWM_RANGE to match the range of analogWrite (change after using analogWriteResolution)
|
|
bool | disableState = LOW |
|
wrapper for analogWrite()
- Note
- compatible with all boards that support analogWrite()
◆ JMotorDriverAvrPWM()
JMotorDriverAvrPWM::JMotorDriverAvrPWM |
( |
byte |
_pin, |
|
|
bool |
_disableState = LOW |
|
) |
| |
|
inline |
constructor, sets pins
- Note
- make sure to check which pins on your board are PWM capable
- Parameters
-
_pin | what pin to use |
_disableState | = LOW: when disabled, set pin LOW(default) or HIGH |
◆ getEnable()
bool JMotorDriverAvrPWM::getEnable |
( |
| ) |
|
|
inlinevirtual |
get the enable state of the driver
- Return values
-
(bool) | true if enabled, false if disabled |
Reimplemented from JMotorDriver.
◆ getMaxRange()
float JMotorDriverAvrPWM::getMaxRange |
( |
| ) |
|
|
inlinevirtual |
high end of the range
- Note
- usually 1.0
- Return values
-
Reimplemented from JMotorDriver.
◆ getMinRange()
float JMotorDriverAvrPWM::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 JMotorDriverAvrPWM::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 JMotorDriverAvrPWM::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.
◆ disableState
bool JMotorDriverAvrPWM::disableState = LOW |
◆ PWM_RANGE
int JMotorDriverAvrPWM::PWM_RANGE = 255 |
change PWM_RANGE to match the range of analogWrite (change after using analogWriteResolution)
The documentation for this class was generated from the following file: