DriveMaster
Loading...
Searching...
No Matches
dshot.h
Go to the documentation of this file.
1
6#pragma once
7#ifndef DSHOT_H
8#define DSHOT_H
9
10#include "DriveMaster.h"
11
12#if defined(ARDUINO_ARCH_ESP32)
13#include <esp32-hal-rmt.h>
14#define DSHOT_FRAME_LENGTH 16
15
19enum DShotType
20{
21 DSHOT_150,
22 DSHOT_300
23};
24
28class dshot : public DriveMaster
29{
30private:
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);
48
49public:
55 explicit dshot(int pin, DShotType type = DSHOT_300);
59 ~dshot();
63 void begin() override;
68 void sendCommand(uint16_t value) override;
73 void sendValue(uint16_t value) override;
74};
75#endif
76#endif
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