Go to the documentation of this file.
2 #include "../../../utilities/Utilities.hpp"
7 const int kMaxPwm = 255;
17 : kForwardPin{ forwardPin }
18 , kBackwardPin{ backwardPin }
19 , kEnablePin{ enablePin }
21 , kOutput{ mRuntime.getOutputState() }
22 , kLow{ mRuntime.getLowState() }
23 , kHigh{ mRuntime.getHighState() }
61 mRuntime.
setPWM(kEnablePin,
65 void BrushedMotor::attach()
Helper class to represent brushed motor pins.
BrushedMotor(Runtime &runtime, uint8_t forwardPin, uint8_t backwardPin, uint8_t enablePin)
Constructs a brushed DC motor instance.
virtual void setPinState(uint8_t pin, uint8_t state)=0
Set pin state, equivalent of digitalWrite in Arduino.
const int kIdleMotorSpeed
constexpr AnyNumber getMap(AnyNumber valueToMap, AnyNumber fromLow, AnyNumber fromHigh, AnyNumber toLow, AnyNumber toHigh)
Maps a value from a range to another.
constexpr AnyNumber getAbsolute(AnyNumber number)
Gets the absolute of the supplied number.
virtual void setPWM(uint8_t pin, int dutyCycle)=0
Set PWM state, equivalent of analogWrite in Arduino.
void setSpeed(int speed) override
Sets the motor speed and direction as the percentage of the maximum possible speed,...
constexpr AnyNumber getConstrain(AnyNumber number, AnyNumber min, AnyNumber max)
Limit the number between a range.
virtual void setPinDirection(uint8_t pin, uint8_t direction)=0
Set pin direction, equivalent of pinMode in Arduino.