Browse Source

Copter: allow override of default frame type

master
Andrew Tridgell 6 years ago
parent
commit
3f58461839
  1. 2
      ArduCopter/Parameters.cpp
  2. 4
      ArduCopter/config.h

2
ArduCopter/Parameters.cpp

@ -364,7 +364,7 @@ const AP_Param::Info Copter::var_info[] = { @@ -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

4
ArduCopter/config.h

@ -744,3 +744,7 @@ @@ -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…
Cancel
Save