Browse Source

AP_HAL_ChibiOS: add and use AP_MOTORS_FRAME_DEFAULT_ENABLED

gps-1.3.1
Peter Barker 3 years ago committed by Andrew Tridgell
parent
commit
b88bfa962b
  1. 4
      libraries/AP_HAL_ChibiOS/hwdef/skyviper-v2450/hwdef.dat

4
libraries/AP_HAL_ChibiOS/hwdef/skyviper-v2450/hwdef.dat

@ -102,3 +102,7 @@ define WINCH_ENABLED 0 @@ -102,3 +102,7 @@ define WINCH_ENABLED 0
define AP_GPS_BACKEND_DEFAULT_ENABLED 0
define AP_GPS_UBLOX_ENABLED 1
define AP_GPS_MAV_ENABLED 1
# enable only the QUAD frame
define AP_MOTORS_FRAME_DEFAULT_ENABLED 0
define AP_MOTORS_FRAME_QUAD_ENABLED 1

Loading…
Cancel
Save