Browse Source

AP_HAL: allow motor poles to be recorded

enable ESC telemetry for SITL
c415-sdk
Andy Piper 4 years ago committed by Andrew Tridgell
parent
commit
4f547d2acc
  1. 4
      libraries/AP_HAL/RCOutput.h
  2. 1
      libraries/AP_HAL/board/sitl.h

4
libraries/AP_HAL/RCOutput.h

@ -277,6 +277,10 @@ public: @@ -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

1
libraries/AP_HAL/board/sitl.h

@ -6,6 +6,7 @@ @@ -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

Loading…
Cancel
Save