ArduCopter: update comments related to CH7 switch options
This commit is contained in:
parent
75401756f2
commit
4ca27defb3
@ -39,14 +39,15 @@
|
||||
//#define CH7_OPTION CH7_SAVE_WP
|
||||
/*
|
||||
* CH7_DO_NOTHING
|
||||
* CH7_SET_HOVER
|
||||
* CH7_SET_HOVER // deprecated
|
||||
* CH7_FLIP
|
||||
* CH7_SIMPLE_MODE
|
||||
* CH7_RTL
|
||||
* CH7_AUTO_TRIM
|
||||
* CH7_ADC_FILTER (experimental)
|
||||
* CH7_SAVE_TRIM
|
||||
* CH7_ADC_FILTER // deprecated
|
||||
* CH7_SAVE_WP
|
||||
* CH7_MULTI_MODE
|
||||
* CH7_MULTI_MODE // deprecated
|
||||
* CH7_CAMERA_TRIGGER
|
||||
*/
|
||||
|
||||
//#define TOY_EDF ENABLED
|
||||
|
@ -274,6 +274,12 @@ const AP_Param::Info var_info[] PROGMEM = {
|
||||
GSCALAR(radio_tuning_low, "TUNE_LOW", 0),
|
||||
GSCALAR(radio_tuning_high, "TUNE_HIGH", 1000),
|
||||
GSCALAR(frame_orientation, "FRAME", FRAME_ORIENTATION),
|
||||
|
||||
// @Param: CH7_OPT
|
||||
// @DisplayName: Channel 7 option
|
||||
// @Description: Select which function if performed when CH7 is high
|
||||
// @Values: 0:Do Nothing, 2:Flip, 3:Simple Mode, 4:RTL, 5:Save Trim, 7:Save WP, 9:Camera Trigger
|
||||
// @User: Standard
|
||||
GSCALAR(ch7_option, "CH7_OPT", CH7_OPTION),
|
||||
|
||||
// @Param: AUTO_SLEW
|
||||
|
@ -48,15 +48,17 @@
|
||||
#define SONAR_SOURCE_ANALOG_PIN 2
|
||||
|
||||
// CH 7 control
|
||||
#define CH7_PWM_TRIGGER 1800 // pwm value above which the channel 7 option will be invoked
|
||||
#define CH7_DO_NOTHING 0
|
||||
#define CH7_SET_HOVER 1
|
||||
#define CH7_SET_HOVER 1 // deprecated
|
||||
#define CH7_FLIP 2
|
||||
#define CH7_SIMPLE_MODE 3
|
||||
#define CH7_RTL 4
|
||||
#define CH7_AUTO_TRIM 5
|
||||
#define CH7_ADC_FILTER 6
|
||||
#define CH7_SAVE_TRIM 5
|
||||
#define CH7_ADC_FILTER 6 // deprecated
|
||||
#define CH7_SAVE_WP 7
|
||||
#define CH7_MULTI_MODE 8
|
||||
#define CH7_MULTI_MODE 8 // deprecated
|
||||
#define CH7_CAMERA_TRIGGER 9
|
||||
|
||||
|
||||
// Frame types
|
||||
@ -77,11 +79,6 @@
|
||||
#define SAVE_TRIM_LEDS 1
|
||||
|
||||
|
||||
#define CH_7_PWM_TRIGGER 1800
|
||||
#define CH_6_PWM_TRIGGER_HIGH 1800
|
||||
#define CH_6_PWM_TRIGGER 1500
|
||||
#define CH_6_PWM_TRIGGER_LOW 1200
|
||||
|
||||
// Internal defines, don't edit and expect things to work
|
||||
// -------------------------------------------------------
|
||||
|
||||
@ -249,13 +246,7 @@
|
||||
#define RTL_STATE_LAND 3
|
||||
|
||||
//repeating events
|
||||
#define NO_REPEAT 0
|
||||
#define CH_5_TOGGLE 1
|
||||
#define CH_6_TOGGLE 2
|
||||
#define CH_7_TOGGLE 3
|
||||
#define CH_8_TOGGLE 4
|
||||
#define RELAY_TOGGLE 5
|
||||
#define STOP_REPEAT 10
|
||||
|
||||
// GCS Message ID's
|
||||
/// NOTE: to ensure we never block on sending MAVLink messages
|
||||
|
@ -147,16 +147,19 @@ apm_option("FRAME_ORIENTATION" TYPE STRING
|
||||
)
|
||||
|
||||
apm_option("CH7_OPTION" TYPE STRING
|
||||
DESCRIPTION "Channel 7 option? (ADC_FILTER is experimental)"
|
||||
DESCRIPTION "Channel 7 option?"
|
||||
DEFAULT "CH7_SAVE_WP"
|
||||
OPTIONS
|
||||
"CH7_DO_NOTHING"
|
||||
"CH7_SET_HOVER"
|
||||
"CH7_DO_NOTHING"
|
||||
"CH7_FLIP"
|
||||
"CH7_SIMPLE_MODE"
|
||||
"CH7_RTL"
|
||||
"CH7_AUTO_TRIM"
|
||||
"CH7_ADC_FILTER"
|
||||
"CH7_SAVE_WP")
|
||||
"CH7_SAVE_TRIM"
|
||||
"CH7_DO_NOTHING"
|
||||
"CH7_SAVE_WP"
|
||||
"CH7_DO_NOTHING"
|
||||
"CH7_CAMERA_TRIGGER")
|
||||
|
||||
apm_option("ACCEL_ALT_HOLD" TYPE BOOL ADVANCED
|
||||
DESCRIPTION "Disabled by default, work in progress."
|
||||
|
Loading…
Reference in New Issue
Block a user