Copter: update CH7_OPT, CH8_OPT to include Multi Mode
This commit is contained in:
parent
38239c652a
commit
8c99936431
@ -408,14 +408,14 @@ const AP_Param::Info var_info[] PROGMEM = {
|
|||||||
// @Param: CH7_OPT
|
// @Param: CH7_OPT
|
||||||
// @DisplayName: Channel 7 option
|
// @DisplayName: Channel 7 option
|
||||||
// @Description: Select which function if performed when CH7 is above 1800 pwm
|
// @Description: Select which function if performed when CH7 is above 1800 pwm
|
||||||
// @Values: 0:Do Nothing, 2:Flip, 3:Simple Mode, 4:RTL, 5:Save Trim, 7:Save WP, 9:Camera Trigger, 10:Sonar
|
// @Values: 0:Do Nothing, 2:Flip, 3:Simple Mode, 4:RTL, 5:Save Trim, 7:Save WP, 8:Multi Mode, 9:Camera Trigger, 10:Sonar
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
GSCALAR(ch7_option, "CH7_OPT", CH7_OPTION),
|
GSCALAR(ch7_option, "CH7_OPT", CH7_OPTION),
|
||||||
|
|
||||||
// @Param: CH8_OPT
|
// @Param: CH8_OPT
|
||||||
// @DisplayName: Channel 8 option
|
// @DisplayName: Channel 8 option
|
||||||
// @Description: Select which function if performed when CH8 is above 1800 pwm
|
// @Description: Select which function if performed when CH8 is above 1800 pwm
|
||||||
// @Values: 0:Do Nothing, 2:Flip, 3:Simple Mode, 4:RTL, 5:Save Trim, 7:Save WP, 9:Camera Trigger, 10:Sonar
|
// @Values: 0:Do Nothing, 2:Flip, 3:Simple Mode, 4:RTL, 5:Save Trim, 7:Save WP, 8:Multi Mode, 9:Camera Trigger, 10:Sonar
|
||||||
// @User: Standard
|
// @User: Standard
|
||||||
GSCALAR(ch8_option, "CH8_OPT", CH8_OPTION),
|
GSCALAR(ch8_option, "CH8_OPT", CH8_OPTION),
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user