mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-08 08:53:56 -04:00
Copter: enable inav xy by default
This commit is contained in:
parent
53ab1d5d9b
commit
b74da54c98
@ -43,9 +43,11 @@
|
|||||||
*/
|
*/
|
||||||
|
|
||||||
// Inertia based contollers
|
// Inertia based contollers
|
||||||
//#define INERTIAL_NAV_XY ENABLED
|
#define INERTIAL_NAV_XY ENABLED
|
||||||
//#define NAV_WP_ACTIVE NAV_WP_INAV
|
#define NAV_WP_ACTIVE NAV_WP_INAV
|
||||||
//#define NAV_LOITER_ACTIVE NAV_LOITER_INAV
|
#define NAV_LOITER_ACTIVE NAV_LOITER_INAV
|
||||||
|
#define RTL_YAW YAW_HOLD
|
||||||
|
|
||||||
#define INERTIAL_NAV_Z ENABLED
|
#define INERTIAL_NAV_Z ENABLED
|
||||||
|
|
||||||
//#define MOTORS_JD880
|
//#define MOTORS_JD880
|
||||||
|
Loading…
Reference in New Issue
Block a user