mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 09:28:31 -04:00
ACM: don't set defaults in APM_Config.h
defaults set here prevent Makefile overrides, which breaks autotest for non-default frame types
This commit is contained in:
parent
eab1ae59d0
commit
9d1c4ecfcd
@ -7,7 +7,7 @@
|
|||||||
//#define MAG_ORIENTATION AP_COMPASS_COMPONENTS_DOWN_PINS_FORWARD
|
//#define MAG_ORIENTATION AP_COMPASS_COMPONENTS_DOWN_PINS_FORWARD
|
||||||
//#define HIL_MODE HIL_MODE_ATTITUDE
|
//#define HIL_MODE HIL_MODE_ATTITUDE
|
||||||
|
|
||||||
#define FRAME_CONFIG QUAD_FRAME
|
//#define FRAME_CONFIG QUAD_FRAME
|
||||||
/*
|
/*
|
||||||
options:
|
options:
|
||||||
QUAD_FRAME
|
QUAD_FRAME
|
||||||
@ -18,7 +18,7 @@
|
|||||||
HELI_FRAME
|
HELI_FRAME
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#define FRAME_ORIENTATION X_FRAME
|
//#define FRAME_ORIENTATION X_FRAME
|
||||||
/*
|
/*
|
||||||
PLUS_FRAME
|
PLUS_FRAME
|
||||||
X_FRAME
|
X_FRAME
|
||||||
|
Loading…
Reference in New Issue
Block a user