AP_HAL_ChibiOS: move rangefinder rotation default down into AP_Periph

This commit is contained in:
Peter Barker 2023-08-08 12:36:29 +10:00 committed by Andrew Tridgell
parent e9414d69ff
commit 68e3b1e79b

View File

@ -210,6 +210,11 @@
#define AP_RANGEFINDER_HC_SR04_ENABLED 0
#define AP_RANGEFINDER_PWM_ENABLED 0
// AP_Periph expects ROTATION_NONE
#ifndef AP_RANGEFINDER_DEFAULT_ORIENTATION
#define AP_RANGEFINDER_DEFAULT_ORIENTATION ROTATION_NONE
#endif
// no CAN manager in AP_Periph:
#define HAL_CANMANAGER_ENABLED 0