JMotor
Loading...
Searching...
No Matches
JMotorDriver.h
Go to the documentation of this file.
1#ifndef J_MOTOR_DRIVER_H
2#define J_MOTOR_DRIVER_H
3#include <Arduino.h>
4
5//**********SEE BOTTOM OF THIS FILE FOR #INCLUDES OF SUBCLASSES**********//
11public:
18 virtual bool set(float val);
19
26 virtual bool setEnable(bool _enable);
27
32 virtual bool getEnable();
33
39 virtual float getMaxRange();
40
46 virtual float getMinRange();
47
53 bool enable()
54 {
55 return setEnable(true);
56 }
57
63 bool disable()
64 {
65 return setEnable(false);
66 }
67};
68
69#if defined(ESP32)
76#endif
77#if !defined(ESP32) || defined(J_MOTOR_DRIVER_FORCE_ANALOGWRITE) || defined(ESP8266)
79#include "JMotorDriverAvrL293.h"
80#include "JMotorDriverAvrPWM.h"
82#endif
83#if !defined(ESP32)
85#endif
86#include "JMotorDriverDual.h"
87#include "JMotorDriverServo.h"
90#include "JMotorDriverTMC7300.h"
91
92#endif
defines common interface for all types of JMotorDrivers
Definition JMotorDriver.h:10
virtual bool set(float val)
set motor power
virtual bool setEnable(bool _enable)
use to enable or disable a motor, and sets up pin states
virtual float getMaxRange()
high end of the range
virtual float getMinRange()
low end of the range
virtual bool getEnable()
get the enable state of the driver
bool disable()
disable motor
Definition JMotorDriver.h:63
bool enable()
enable motor
Definition JMotorDriver.h:53