From 1621f3a638c7df2f61b435db8299f00a92f208f1 Mon Sep 17 00:00:00 2001 From: Jason Short Date: Sat, 26 Nov 2011 13:19:11 -0800 Subject: [PATCH] allow CH7 to be set via params --- ArduCopter/Parameters.h | 3 +++ 1 file changed, 3 insertions(+) diff --git a/ArduCopter/Parameters.h b/ArduCopter/Parameters.h index e862a67c4e..fa53b80206 100644 --- a/ArduCopter/Parameters.h +++ b/ArduCopter/Parameters.h @@ -104,6 +104,7 @@ public: k_param_optflow_enabled, k_param_input_voltage, k_param_low_voltage, + k_param_ch7_option, // // 160: Navigation parameters @@ -237,6 +238,7 @@ public: AP_Int8 radio_tuning; AP_Int8 frame_orientation; AP_Float top_bottom_ratio; + AP_Int8 ch7_option; #if FRAME_CONFIG == HELI_FRAME @@ -341,6 +343,7 @@ public: radio_tuning (0, k_param_radio_tuning, PSTR("TUNE")), frame_orientation (FRAME_ORIENTATION, k_param_frame_orientation, PSTR("FRAME")), top_bottom_ratio (TOP_BOTTOM_RATIO, k_param_top_bottom_ratio, PSTR("TB_RATIO")), + ch7_option (CH7_SAVE_WP, k_param_ch7_option, PSTR("CH7_OPT")), #if FRAME_CONFIG == HELI_FRAME heli_servo_1 (k_param_heli_servo_1, PSTR("HS1_")),