ArduCopter: fixes to allow AP_Mount to work on APM1 with original default channels and fix to reenable support for 3-axis gimbals on APM2.

Channels 5 to 11 changed to RC_Channel_aux.
Removed channel 9 because APM_RC doesn't support it in any case.
Updated EEPROM format version to 119 because of the change to RC_Channel_aux and because k_param_rc_11 moved to be after k_param_rc_10.
This commit is contained in:
rmackay9 2012-09-02 12:51:23 +09:00
parent 9013d9be43
commit c9d34c1737
4 changed files with 16 additions and 23 deletions

View File

@ -1339,7 +1339,7 @@ static void slow_loop()
read_control_switch();
#if MOUNT == ENABLED
update_aux_servo_function(&g.rc_9, &g.rc_10, &g.rc_11);
update_aux_servo_function(&g.rc_5, &g.rc_6, &g.rc_7, &g.rc_8, &g.rc_10, &g.rc_11);
#endif
enable_aux_servos();

View File

@ -17,7 +17,7 @@ public:
// The increment will prevent old parameters from being used incorrectly
// by newer code.
//
static const uint16_t k_format_version = 118;
static const uint16_t k_format_version = 119;
// The parameter software_type is set up solely for ground station use
// and identifies the software type (eg ArduPilotMega versus
@ -147,8 +147,8 @@ public:
k_param_rc_6,
k_param_rc_7,
k_param_rc_8,
k_param_rc_9,
k_param_rc_10,
k_param_rc_11,
k_param_throttle_min,
k_param_throttle_max,
k_param_throttle_fs_enabled,
@ -160,7 +160,6 @@ public:
k_param_radio_tuning_high,
k_param_radio_tuning_low,
k_param_rc_speed = 192,
k_param_rc_11 = 193,
//
// 200: flight modes
@ -317,13 +316,12 @@ public:
RC_Channel rc_2;
RC_Channel rc_3;
RC_Channel rc_4;
RC_Channel rc_5;
RC_Channel rc_6;
RC_Channel rc_7;
RC_Channel rc_8;
RC_Channel_aux rc_5;
RC_Channel_aux rc_6;
RC_Channel_aux rc_7;
RC_Channel_aux rc_8;
#if MOUNT == ENABLED
RC_Channel_aux rc_9;
RC_Channel_aux rc_10;
RC_Channel_aux rc_11;
#endif
@ -375,7 +373,6 @@ public:
rc_7 (CH_7),
rc_8 (CH_8),
#if MOUNT == ENABLED
rc_9 (CH_9),
rc_10 (CH_10),
rc_11 (CH_11),
#endif

View File

@ -224,23 +224,19 @@ const AP_Param::Info var_info[] PROGMEM = {
// @Path: ../libraries/RC_Channel/RC_Channel.cpp
GGROUP(rc_4, "RC4_", RC_Channel),
// @Group: RC5_
// @Path: ../libraries/RC_Channel/RC_Channel.cpp
GGROUP(rc_5, "RC5_", RC_Channel),
// @Path: ../libraries/RC_Channel/RC_Channel_aux.cpp
GGROUP(rc_5, "RC5_", RC_Channel_aux),
// @Group: RC6_
// @Path: ../libraries/RC_Channel/RC_Channel.cpp
GGROUP(rc_6, "RC6_", RC_Channel),
// @Path: ../libraries/RC_Channel/RC_Channel_aux.cpp
GGROUP(rc_6, "RC6_", RC_Channel_aux),
// @Group: RC7_
// @Path: ../libraries/RC_Channel/RC_Channel.cpp
GGROUP(rc_7, "RC7_", RC_Channel),
// @Path: ../libraries/RC_Channel/RC_Channel_aux.cpp
GGROUP(rc_7, "RC7_", RC_Channel_aux),
// @Group: RC8_
// @Path: ../libraries/RC_Channel/RC_Channel.cpp
GGROUP(rc_8, "RC8_", RC_Channel),
// @Path: ../libraries/RC_Channel/RC_Channel_aux.cpp
GGROUP(rc_8, "RC8_", RC_Channel_aux),
#if MOUNT == ENABLED
// @Group: RC9_
// @Path: ../libraries/RC_Channel/RC_Channel_aux.cpp
GGROUP(rc_9, "RC9_", RC_Channel_aux),
// @Group: RC10_
// @Path: ../libraries/RC_Channel/RC_Channel_aux.cpp
GGROUP(rc_10, "RC10_", RC_Channel_aux),

View File

@ -56,7 +56,7 @@ static void init_rc_in()
g.rc_8.set_range(0,1000);
#if MOUNT == ENABLED
update_aux_servo_function(&g.rc_9, &g.rc_10, &g.rc_11);
update_aux_servo_function(&g.rc_5, &g.rc_6, &g.rc_7, &g.rc_8, &g.rc_10, &g.rc_11);
#endif
}