hwdef: enable only BMI150 compass on SkyViper
This commit is contained in:
parent
e60e646a4e
commit
5f2b4c3144
@ -123,6 +123,9 @@ define AP_MOTORS_FRAME_QUAD_ENABLED 1
|
|||||||
|
|
||||||
# SkyViper isn't going to sprout new compasses:
|
# SkyViper isn't going to sprout new compasses:
|
||||||
define COMPASS_MAX_SENSORS 1
|
define COMPASS_MAX_SENSORS 1
|
||||||
|
define AP_COMPASS_BACKEND_DEFAULT_ENABLED 0
|
||||||
|
define AP_COMPASS_BMI150_ENABLED 1
|
||||||
|
|
||||||
define BARO_MAX_INSTANCES 1
|
define BARO_MAX_INSTANCES 1
|
||||||
define INS_MAX_INSTANCES 1
|
define INS_MAX_INSTANCES 1
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user