AP_HAL: allow motor poles to be recorded

enable ESC telemetry for SITL
This commit is contained in:
Andy Piper 2021-03-01 20:40:15 +00:00 committed by Andrew Tridgell
parent 6d50549476
commit 4f547d2acc
2 changed files with 5 additions and 0 deletions

View File

@ -277,6 +277,10 @@ public:
If not already done flush any dshot commands still pending
*/
virtual bool prepare_for_arming() { return true; }
/*
set the number of motor poles to be used in rpm calculations
*/
virtual void set_motor_poles(uint8_t poles) {}
/*
setup serial led output for a given channel number, with

View File

@ -6,6 +6,7 @@
#define HAL_OS_POSIX_IO 1
#define HAL_OS_SOCKETS 1
#define HAL_DSHOT_ALARM 0
#define HAL_WITH_ESC_TELEM 1
#define AP_FLASHSTORAGE_TYPE 3