87 lines
2.0 KiB
C++
87 lines
2.0 KiB
C++
#pragma once
|
|
|
|
#include <Arduino.h>
|
|
#include "Participants/IsolatedParticipant.h"
|
|
#include "Thing.h"
|
|
#include "Things/DifferentialDrive.h"
|
|
#include "Things/Motor.h"
|
|
|
|
namespace RoboidControl {
|
|
namespace Arduino {
|
|
|
|
class DRV8833Motor;
|
|
|
|
class DRV8833 : public Thing {
|
|
public:
|
|
struct Configuration {
|
|
int AIn1;
|
|
int AIn2;
|
|
int BIn1;
|
|
int BIn2;
|
|
};
|
|
|
|
/// @brief Setup a DRV8833 motor controller
|
|
DRV8833(Configuration config, Participant* owner = nullptr);
|
|
DRV8833(Configuration config, Thing* parent);
|
|
|
|
DRV8833Motor* motorA = nullptr;
|
|
DRV8833Motor* motorB = nullptr;
|
|
|
|
protected:
|
|
unsigned char pinStandby = 255;
|
|
|
|
public:
|
|
class DifferentialDrive;
|
|
};
|
|
|
|
#pragma region Differential drive
|
|
|
|
class DRV8833::DifferentialDrive : public RoboidControl::DifferentialDrive {
|
|
public:
|
|
DifferentialDrive(DRV8833::Configuration config,
|
|
Participant* participant = nullptr);
|
|
DifferentialDrive(DRV8833::Configuration config, Thing* parent);
|
|
|
|
virtual void Update(bool recurse = false) override;
|
|
|
|
protected:
|
|
DRV8833 drv8833;
|
|
};
|
|
|
|
#pragma endregion Differential drive
|
|
|
|
#pragma region Motor
|
|
|
|
/// @brief Support for a DRV8833 motor controller
|
|
class DRV8833Motor : public Motor {
|
|
public:
|
|
/// @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(DRV8833* driver,
|
|
unsigned char pinIn1,
|
|
unsigned char pinIn2,
|
|
bool reverse = false);
|
|
// void SetMaxRPM(unsigned int rpm);
|
|
|
|
// virtual void SetAngularVelocity(Spherical velocity) override;
|
|
virtual void SetTargetSpeed(float targetSpeed) override;
|
|
// bool reverse = false;
|
|
|
|
protected:
|
|
unsigned char pinIn1 = 255;
|
|
unsigned char pinIn2 = 255;
|
|
// unsigned int maxRpm = 200;
|
|
|
|
#if (ESP32)
|
|
uint8_t in1Ch;
|
|
uint8_t in2Ch;
|
|
static uint8_t nextAvailablePwmChannel;
|
|
#endif
|
|
};
|
|
|
|
#pragma endregion Moto
|
|
|
|
} // namespace Arduino
|
|
} // namespace RoboidControl
|