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
This commit is contained in:
tridge60@gmail.com 2011-03-03 11:40:13 +00:00
parent b2bec2ccdc
commit b7be7bc41a
1 changed files with 1 additions and 1 deletions

View File

@ -239,7 +239,7 @@ public:
throttle_fs_value (THROTTLE_FS_VALUE, k_param_throttle_fs_value, PSTR("THR_FS_VALUE")), 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")), 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")), flight_modes (k_param_flight_modes, PSTR("FLIGHT_MODES")),
pitch_max (PITCH_MAX * 100, k_param_pitch_max, PSTR("PITCH_MAX")), pitch_max (PITCH_MAX * 100, k_param_pitch_max, PSTR("PITCH_MAX")),