mirror of https://github.com/ArduPilot/ardupilot
Quad frame - X is default
added wind comp stability option to config - off by default
This commit is contained in:
parent
6678edf243
commit
06e032db68
|
@ -65,10 +65,10 @@
|
|||
// FRAME_CONFIG
|
||||
//
|
||||
#ifndef FRAME_CONFIG
|
||||
# define FRAME_CONFIG QUAD_FRAME
|
||||
# define FRAME_CONFIG QUAD_FRAME
|
||||
#endif
|
||||
#ifndef FRAME_ORIENTATION
|
||||
# define FRAME_ORIENTATION PLUS_FRAME
|
||||
# define FRAME_ORIENTATION X_FRAME
|
||||
#endif
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
|
@ -468,6 +468,11 @@
|
|||
#endif
|
||||
|
||||
|
||||
// experimental feature for
|
||||
#ifndef WIND_COMP_STAB
|
||||
# define WIND_COMP_STAB 0
|
||||
#endif
|
||||
|
||||
|
||||
|
||||
//////////////////////////////////////////////////////////////////////////////
|
||||
|
|
Loading…
Reference in New Issue