mirror of https://github.com/ArduPilot/ardupilot
AP_HAL: allow motor poles to be recorded
enable ESC telemetry for SITL
This commit is contained in:
parent
6d50549476
commit
4f547d2acc
|
@ -277,6 +277,10 @@ public:
|
||||||
If not already done flush any dshot commands still pending
|
If not already done flush any dshot commands still pending
|
||||||
*/
|
*/
|
||||||
virtual bool prepare_for_arming() { return true; }
|
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
|
setup serial led output for a given channel number, with
|
||||||
|
|
|
@ -6,6 +6,7 @@
|
||||||
#define HAL_OS_POSIX_IO 1
|
#define HAL_OS_POSIX_IO 1
|
||||||
#define HAL_OS_SOCKETS 1
|
#define HAL_OS_SOCKETS 1
|
||||||
#define HAL_DSHOT_ALARM 0
|
#define HAL_DSHOT_ALARM 0
|
||||||
|
#define HAL_WITH_ESC_TELEM 1
|
||||||
|
|
||||||
#define AP_FLASHSTORAGE_TYPE 3
|
#define AP_FLASHSTORAGE_TYPE 3
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue