#pragma once #include "Thing.h" #include "Things/DifferentialDrive.h" namespace RoboidControl { namespace Arduino { /// @brief Support for a DRV8833 motor controller class DRV8833Motor : public Thing { public: /// @brief Motor turning direction enum class RotationDirection { Clockwise = 1, CounterClockwise = -1 }; /// @brief Setup the DC motor /// @param pinIn1 the pin number for the in1 signal /// @param pinIn2 the pin number for the in2 signal /// @param direction the forward turning direction of the motor DRV8833Motor(Participant* participant, unsigned char pinIn1, unsigned char pinIn2, bool reverse = false); void SetMaxRPM(unsigned int rpm); virtual void SetAngularVelocity(Spherical velocity) override; bool reverse = false; protected: unsigned char pinIn1 = 255; unsigned char pinIn2 = 255; unsigned int maxRpm = 200; }; class DRV8833 : public Thing { public: /// @brief Setup a DRV8833 motor controller /// @param pinAIn1 The pin number connected to the AIn1 port /// @param pinAIn2 The pin number connected to the AIn2 port /// @param pinBIn1 The pin number connected to the BIn1 port /// @param pinBIn2 The pin number connceted to the BIn2 port /// @param pinStandby The pin number connected to the standby port, 255 /// indicated that the port is not connected /// @param reverseA The forward turning direction of motor A /// @param reverseB The forward turning direction of motor B DRV8833(Participant* participant, unsigned char pinAIn1, unsigned char pinAIn2, unsigned char pinBIn1, unsigned char pinBIn2, unsigned char pinStandby = 255, bool reverseA = false, bool reverseB = false); DRV8833Motor* motorA = nullptr; DRV8833Motor* motorB = nullptr; protected: unsigned char pinStandby = 255; }; } // namespace Arduino } // namespace RoboidControl