12#if defined(ARDUINO_ARCH_ESP32)
13#include <esp32-hal-rmt.h>
14#define DSHOT_FRAME_LENGTH 16
31 rmt_data_t _data[DSHOT_FRAME_LENGTH];
32 uint16_t _timingDuration0;
33 uint16_t _timingDuration1;
34 uint16_t _timingDurationBit;
41 uint8_t calculateCrc(uint16_t value);
47 void write(uint16_t value,
bool telemetery =
false);
55 explicit dshot(
int pin, DShotType type = DSHOT_300);
63 void begin()
override;
Header file for the DriveMaster class.
Base class for motor control.
Definition DriveMaster.h:16
virtual void sendCommand(uint16_t value)
Send a command to the motor.
Definition DriveMaster.cpp:14
virtual void write(uint16_t value, bool telemetery=false)
Write a command to the motor.
Definition DriveMaster.cpp:11
virtual void sendValue(uint16_t value)
Send a value to the motor.
Definition DriveMaster.cpp:15
virtual void begin()
Initialize the motor control.
Definition DriveMaster.cpp:9