mirror of https://github.com/ArduPilot/ardupilot
Copter: allow override of default frame type
This commit is contained in:
parent
36180faab5
commit
3f58461839
|
@ -364,7 +364,7 @@ const AP_Param::Info Copter::var_info[] = {
|
|||
// @Values: 0:Plus, 1:X, 2:V, 3:H, 4:V-Tail, 5:A-Tail, 10:Y6B, 11:Y6F, 12:BetaFlightX, 13:DJIX, 14:ClockwiseX
|
||||
// @User: Standard
|
||||
// @RebootRequired: True
|
||||
GSCALAR(frame_type, "FRAME_TYPE", AP_Motors::MOTOR_FRAME_TYPE_X),
|
||||
GSCALAR(frame_type, "FRAME_TYPE", HAL_FRAME_TYPE_DEFAULT),
|
||||
|
||||
// @Group: ARMING_
|
||||
// @Path: ../libraries/AP_Arming/AP_Arming.cpp
|
||||
|
|
|
@ -744,3 +744,7 @@
|
|||
#ifndef OSD_ENABLED
|
||||
#define OSD_ENABLED DISABLED
|
||||
#endif
|
||||
|
||||
#ifndef HAL_FRAME_TYPE_DEFAULT
|
||||
#define HAL_FRAME_TYPE_DEFAULT AP_Motors::MOTOR_FRAME_TYPE_X
|
||||
#endif
|
||||
|
|
Loading…
Reference in New Issue