Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Added : Implementation for HBridge Control of Motor #4

Merged
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
3 changes: 3 additions & 0 deletions examples/basic_dshot/arduino-ci.yml
Original file line number Diff line number Diff line change
@@ -0,0 +1,3 @@
compile:
platforms:
- esp32
2 changes: 1 addition & 1 deletion library.properties
Original file line number Diff line number Diff line change
Expand Up @@ -10,4 +10,4 @@ maintainer=Witty Wizard <shashankmarch27@gmail.com>
license=GPL-3.0-only
frameworks=arduino
platforms=espressif32
architectures=esp32
architectures=esp32, avr
5 changes: 4 additions & 1 deletion src/DriveMaster.cpp
Original file line number Diff line number Diff line change
@@ -1,12 +1,15 @@
#include "DriveMaster.h"

DriveMaster::DriveMaster(int pin) : _pin(pin) {}
DriveMaster::DriveMaster(int pin) : _pin(pin), _dir_pin(-1) {}

DriveMaster::DriveMaster(int pin, int dir_pin) : _pin(pin), _dir_pin(dir_pin) {}

DriveMaster::~DriveMaster() {}

void DriveMaster::begin() {}

void DriveMaster::write(uint16_t value, bool telemetery) {}
void DriveMaster::write(int16_t value) {}

void DriveMaster::sendCommand(uint16_t value) {}
void DriveMaster::sendValue(uint16_t value) {}
31 changes: 28 additions & 3 deletions src/DriveMaster.h
Original file line number Diff line number Diff line change
Expand Up @@ -12,40 +12,65 @@
/**
* @brief Base class for motor control.
*/
class DriveMaster {
class DriveMaster
{
public:
/**
* @brief Construct a new DriveMaster object with the specified pin.
* @brief Construct a new DriveMaster object with only the pin.
* @param pin The pin number for motor control.
*/
DriveMaster(int pin);

/**
* @brief Construct a new DriveMaster object with the specified pin and direction pin.
* @param pin The pin number for motor control.
* @param dir_pin The pin number for direction control.
*/
DriveMaster(int pin, int dir_pin);

/**
* @brief Destroy the DriveMaster object.
*/
virtual ~DriveMaster();

/**
* @brief Initialize the motor control.
*/
virtual void begin();

/**
* @brief Write a command to the motor.
* @param value The command value to write.
* @param telemetry Flag indicating telemetry presence.
*/
virtual void write(uint16_t value, bool telemetery = false);

/**
* @brief Write a command to the motor using an 8-bit signed integer value.
* The value ranges from -255 to 255, where:
* - 255 is full speed forward
* - -255 is full speed reverse
* - 0 is stop
* @param value The signed 8-bit command value to write (-255 to 255).
*/
virtual void write(int16_t value);

/**
* @brief Send a command to the motor.
* @param value The command value to send.
*/
virtual void sendCommand(uint16_t value);

/**
* @brief Send a value to the motor.
* @param value The value to send.
*/
virtual void sendValue(uint16_t value);

protected:
int _pin; /**< Pin number for motor control. */
int _pin; /**< Pin number for motor control. */
int _dir_pin; /**< Pin number for direction control. */
};
#include "dshot.h"
#include "HBridge.h"
#endif
26 changes: 26 additions & 0 deletions src/HBridge.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,26 @@
#include <HBridge.h>

HBridge::HBridge(int pin, int dir_pin) : DriveMaster(pin, dir_pin)
{
}

void HBridge::begin()
{
pinMode(_pin, OUTPUT);
pinMode(_dir_pin, OUTPUT);
}

void HBridge::write(int16_t value)
{
value = value % 256;
if (value >= 0)
{
digitalWrite(_dir_pin, LOW);
}
else
{
digitalWrite(_dir_pin, HIGH);
value = 255 + value;
}
analogWrite(_pin, value);
}
21 changes: 21 additions & 0 deletions src/HBridge.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,21 @@
/**
* @file HBridge.h
* @brief Header file for the HBridge class.
*/

#pragma once
#ifndef HBRIDGE_H
#define HBRIDGE_H

#include "DriveMaster.h"

class HBridge : public DriveMaster{
private:

public:
explicit HBridge(int pin, int dir_pin);
void begin() override;
void write(int16_t value) override;
};

#endif
5 changes: 4 additions & 1 deletion src/dshot.cpp
Original file line number Diff line number Diff line change
@@ -1,5 +1,7 @@
#include "dshot.h"

#if defined(ARDUINO_ARCH_ESP32)

dshot::dshot(int pin, DShotType type) : DriveMaster(pin) {
switch (type) {
case DSHOT_150:
Expand Down Expand Up @@ -44,4 +46,5 @@ uint8_t dshot::calculateCrc(uint16_t value) {
}

void dshot::sendCommand(uint16_t value) { write(value, true); }
void dshot::sendValue(uint16_t value) { write(value, false); }
void dshot::sendValue(uint16_t value) { write(value, false); }
#endif
10 changes: 7 additions & 3 deletions src/dshot.h
Original file line number Diff line number Diff line change
Expand Up @@ -8,21 +8,25 @@
#define DSHOT_H

#include "DriveMaster.h"

#if defined(ARDUINO_ARCH_ESP32)
#include <esp32-hal-rmt.h>
#define DSHOT_FRAME_LENGTH 16

/**
* @brief Enumeration for different DShot types.
*/
enum DShotType {
enum DShotType
{
DSHOT_150, /**< DShot150 protocol */
DSHOT_300 /**< DShot300 protocol */
};

/**
* @brief Class representing DShot communication.
*/
class dshot : public DriveMaster {
class dshot : public DriveMaster
{
private:
rmt_data_t _data[DSHOT_FRAME_LENGTH]; /**< RMT data array for DShot frames */
uint16_t _timingDuration0; /**< Timing duration for logic 0 */
Expand Down Expand Up @@ -68,5 +72,5 @@ class dshot : public DriveMaster {
*/
void sendValue(uint16_t value) override;
};

#endif
#endif