|
|
|
@ -287,42 +287,42 @@ const AP_Param::Info var_info[] PROGMEM = {
@@ -287,42 +287,42 @@ const AP_Param::Info var_info[] PROGMEM = {
|
|
|
|
|
// @Param: FLTMODE1 |
|
|
|
|
// @DisplayName: Flight Mode 1 |
|
|
|
|
// @Description: Flight mode when Channel 5 pwm is <= 1230 |
|
|
|
|
// @Values: 0:Stabilize,1:Acro,2:AltHold,3:Auto,4:Guided,5:Loiter,6:RTL,7:Circle,9:Land,10:OF_Loiter,11:Drift,13:Sport,16:Hybrid |
|
|
|
|
// @Values: 0:Stabilize,1:Acro,2:AltHold,3:Auto,4:Guided,5:Loiter,6:RTL,7:Circle,9:Land,10:OF_Loiter,11:Drift,13:Sport,16:PosHold |
|
|
|
|
// @User: Standard |
|
|
|
|
GSCALAR(flight_mode1, "FLTMODE1", FLIGHT_MODE_1), |
|
|
|
|
|
|
|
|
|
// @Param: FLTMODE2 |
|
|
|
|
// @DisplayName: Flight Mode 2 |
|
|
|
|
// @Description: Flight mode when Channel 5 pwm is >1230, <= 1360 |
|
|
|
|
// @Values: 0:Stabilize,1:Acro,2:AltHold,3:Auto,4:Guided,5:Loiter,6:RTL,7:Circle,9:Land,10:OF_Loiter,11:Drift,13:Sport,16:Hybrid |
|
|
|
|
// @Values: 0:Stabilize,1:Acro,2:AltHold,3:Auto,4:Guided,5:Loiter,6:RTL,7:Circle,9:Land,10:OF_Loiter,11:Drift,13:Sport,16:PosHold |
|
|
|
|
// @User: Standard |
|
|
|
|
GSCALAR(flight_mode2, "FLTMODE2", FLIGHT_MODE_2), |
|
|
|
|
|
|
|
|
|
// @Param: FLTMODE3 |
|
|
|
|
// @DisplayName: Flight Mode 3 |
|
|
|
|
// @Description: Flight mode when Channel 5 pwm is >1360, <= 1490 |
|
|
|
|
// @Values: 0:Stabilize,1:Acro,2:AltHold,3:Auto,4:Guided,5:Loiter,6:RTL,7:Circle,9:Land,10:OF_Loiter,11:Drift,13:Sport,16:Hybrid |
|
|
|
|
// @Values: 0:Stabilize,1:Acro,2:AltHold,3:Auto,4:Guided,5:Loiter,6:RTL,7:Circle,9:Land,10:OF_Loiter,11:Drift,13:Sport,16:PosHold |
|
|
|
|
// @User: Standard |
|
|
|
|
GSCALAR(flight_mode3, "FLTMODE3", FLIGHT_MODE_3), |
|
|
|
|
|
|
|
|
|
// @Param: FLTMODE4 |
|
|
|
|
// @DisplayName: Flight Mode 4 |
|
|
|
|
// @Description: Flight mode when Channel 5 pwm is >1490, <= 1620 |
|
|
|
|
// @Values: 0:Stabilize,1:Acro,2:AltHold,3:Auto,4:Guided,5:Loiter,6:RTL,7:Circle,9:Land,10:OF_Loiter,11:Drift,13:Sport,16:Hybrid |
|
|
|
|
// @Values: 0:Stabilize,1:Acro,2:AltHold,3:Auto,4:Guided,5:Loiter,6:RTL,7:Circle,9:Land,10:OF_Loiter,11:Drift,13:Sport,16:PosHold |
|
|
|
|
// @User: Standard |
|
|
|
|
GSCALAR(flight_mode4, "FLTMODE4", FLIGHT_MODE_4), |
|
|
|
|
|
|
|
|
|
// @Param: FLTMODE5 |
|
|
|
|
// @DisplayName: Flight Mode 5 |
|
|
|
|
// @Description: Flight mode when Channel 5 pwm is >1620, <= 1749 |
|
|
|
|
// @Values: 0:Stabilize,1:Acro,2:AltHold,3:Auto,4:Guided,5:Loiter,6:RTL,7:Circle,9:Land,10:OF_Loiter,11:Drift,13:Sport,16:Hybrid |
|
|
|
|
// @Values: 0:Stabilize,1:Acro,2:AltHold,3:Auto,4:Guided,5:Loiter,6:RTL,7:Circle,9:Land,10:OF_Loiter,11:Drift,13:Sport,16:PosHold |
|
|
|
|
// @User: Standard |
|
|
|
|
GSCALAR(flight_mode5, "FLTMODE5", FLIGHT_MODE_5), |
|
|
|
|
|
|
|
|
|
// @Param: FLTMODE6 |
|
|
|
|
// @DisplayName: Flight Mode 6 |
|
|
|
|
// @Description: Flight mode when Channel 5 pwm is >=1750 |
|
|
|
|
// @Values: 0:Stabilize,1:Acro,2:AltHold,3:Auto,4:Guided,5:Loiter,6:RTL,7:Circle,9:Land,10:OF_Loiter,11:Drift,13:Sport,16:Hybrid |
|
|
|
|
// @Values: 0:Stabilize,1:Acro,2:AltHold,3:Auto,4:Guided,5:Loiter,6:RTL,7:Circle,9:Land,10:OF_Loiter,11:Drift,13:Sport,16:PosHold |
|
|
|
|
// @User: Standard |
|
|
|
|
GSCALAR(flight_mode6, "FLTMODE6", FLIGHT_MODE_6), |
|
|
|
|
|
|
|
|
@ -409,21 +409,21 @@ const AP_Param::Info var_info[] PROGMEM = {
@@ -409,21 +409,21 @@ const AP_Param::Info var_info[] PROGMEM = {
|
|
|
|
|
// @Values: 0:Very Soft, 25:Soft, 50:Medium, 75:Crisp, 100:Very Crisp |
|
|
|
|
GSCALAR(rc_feel_rp, "RC_FEEL_RP", RC_FEEL_RP_VERY_CRISP), |
|
|
|
|
|
|
|
|
|
#if HYBRID_ENABLED == ENABLED |
|
|
|
|
// @Param: HYBR_BRAKE_RATE |
|
|
|
|
// @DisplayName: Hybrid braking rate |
|
|
|
|
// @Description: hybrid flight mode's rotation rate during braking in deg/sec |
|
|
|
|
#if POSHOLD_ENABLED == ENABLED |
|
|
|
|
// @Param: PHLD_BRAKE_RATE |
|
|
|
|
// @DisplayName: PosHold braking rate |
|
|
|
|
// @Description: PosHold flight mode's rotation rate during braking in deg/sec |
|
|
|
|
// @Range: 4 12 |
|
|
|
|
// @User: Advanced |
|
|
|
|
GSCALAR(hybrid_brake_rate, "HYBR_BRAKE_RATE", HYBRID_BRAKE_RATE_DEFAULT), |
|
|
|
|
GSCALAR(poshold_brake_rate, "PHLD_BRAKE_RATE", POSHOLD_BRAKE_RATE_DEFAULT), |
|
|
|
|
|
|
|
|
|
// @Param: HYBR_BRAKE_ANGLE |
|
|
|
|
// @DisplayName: Hybrid braking angle max |
|
|
|
|
// @Description: hybrid flight mode's max lean angle during braking in centi-degrees |
|
|
|
|
// @Param: PHLD_BRAKE_ANGLE |
|
|
|
|
// @DisplayName: PosHold braking angle max |
|
|
|
|
// @Description: PosHold flight mode's max lean angle during braking in centi-degrees |
|
|
|
|
// @Units: Centi-degrees |
|
|
|
|
// @Range: 2000 4500 |
|
|
|
|
// @User: Advanced |
|
|
|
|
GSCALAR(hybrid_brake_angle_max, "HYBR_BRAKE_ANGLE", HYBRID_BRAKE_ANGLE_DEFAULT), |
|
|
|
|
GSCALAR(poshold_brake_angle_max, "PHLD_BRAKE_ANGLE", POSHOLD_BRAKE_ANGLE_DEFAULT), |
|
|
|
|
#endif |
|
|
|
|
|
|
|
|
|
// @Param: LAND_REPOSITION |
|
|
|
|