diff --git a/libraries/AP_HAL/AP_HAL_Boards.h b/libraries/AP_HAL/AP_HAL_Boards.h index 3fd919b2b5..ed37b01c2f 100644 --- a/libraries/AP_HAL/AP_HAL_Boards.h +++ b/libraries/AP_HAL/AP_HAL_Boards.h @@ -283,6 +283,22 @@ #define HAL_DSHOT_ALARM_ENABLED 0 #endif +#ifndef HAL_DSHOT_ENABLED +#define HAL_DSHOT_ENABLED 1 +#endif + +#ifndef HAL_SERIALLED_ENABLED +#define HAL_SERIALLED_ENABLED HAL_DSHOT_ENABLED +#endif + +#ifndef HAL_SERIAL_ESC_COMM_ENABLED +#ifdef DISABLE_SERIAL_ESC_COMM +#define HAL_SERIAL_ESC_COMM_ENABLED 0 +#else +#define HAL_SERIAL_ESC_COMM_ENABLED 1 +#endif +#endif + #ifndef HAL_HNF_MAX_FILTERS // On an F7 The difference in CPU load between 1 notch and 24 notches is about 2% // The difference in CPU load between 1Khz backend and 2Khz backend is about 10% @@ -316,10 +332,6 @@ #define HAL_USE_OCTOSPI 0 #endif -#ifndef HAL_ENABLE_DSHOT -#define HAL_ENABLE_DSHOT 1 -#endif - #ifndef __RAMFUNC__ #define __RAMFUNC__ #endif diff --git a/libraries/AP_HAL/RCOutput.h b/libraries/AP_HAL/RCOutput.h index dae1b69444..77c38d75c4 100644 --- a/libraries/AP_HAL/RCOutput.h +++ b/libraries/AP_HAL/RCOutput.h @@ -311,6 +311,12 @@ public: */ virtual void set_dshot_rate(uint8_t dshot_rate, uint16_t loop_rate_hz) {} + /* + Set the dshot period in us, only for use by the IOMCU + */ + virtual void set_dshot_period(uint32_t period_us, uint8_t dshot_rate) {} + virtual uint32_t get_dshot_period_us() const { return 0; } + /* Set the dshot ESC type */ @@ -372,7 +378,7 @@ public: * Options are (ticks, percentage): * 20/7/14, 35/70 * 11/4/8, 36/72 - * 8/3/6, 37/75 + * 8/3/6, 37/75 <-- this is the preferred duty cycle and has some support on the interwebs */ // bitwidths: 8/3/6 == 37%/75% static constexpr uint32_t DSHOT_BIT_WIDTH_TICKS_DEFAULT = 8;