From b7be7bc41afce12708bce80b618ac2fbbf5af43f Mon Sep 17 00:00:00 2001 From: "tridge60@gmail.com" Date: Thu, 3 Mar 2011 11:40:13 +0000 Subject: [PATCH] fixed the flight mode channel parameter to match current APM trunk APM trunk now calls this parameter FLT_MODE_CH. This makes the ACM code compatible. git-svn-id: https://arducopter.googlecode.com/svn/trunk@1739 f9c3cf11-9bcb-44bc-f272-b75c42450872 --- ArduCopterMega/Parameters.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArduCopterMega/Parameters.h b/ArduCopterMega/Parameters.h index d32784da55..6bd76a5d95 100644 --- a/ArduCopterMega/Parameters.h +++ b/ArduCopterMega/Parameters.h @@ -239,7 +239,7 @@ public: throttle_fs_value (THROTTLE_FS_VALUE, k_param_throttle_fs_value, PSTR("THR_FS_VALUE")), throttle_cruise (THROTTLE_CRUISE, k_param_throttle_cruise, PSTR("TRIM_THROTTLE")), - flight_mode_channel (FLIGHT_MODE_CHANNEL, k_param_flight_mode_channel, PSTR("FLIGHT_MODE_CH")), + flight_mode_channel (FLIGHT_MODE_CHANNEL+1, k_param_flight_mode_channel, PSTR("FLT_MODE_CH")), flight_modes (k_param_flight_modes, PSTR("FLIGHT_MODES")), pitch_max (PITCH_MAX * 100, k_param_pitch_max, PSTR("PITCH_MAX")),