mirror of https://github.com/ArduPilot/ardupilot
More work on ch9, 10 and 11
This commit is contained in:
parent
95f2af6d2d
commit
9c1ac2d9e6
|
@ -5,7 +5,7 @@
|
|||
static int8_t failsafeCounter = 0; // we wait a second to take over the throttle and send the plane circling
|
||||
|
||||
|
||||
extern RC_Channel* rc_ch[8];
|
||||
extern RC_Channel* rc_ch[NUM_CHANNELS];
|
||||
|
||||
static void default_dead_zones()
|
||||
{
|
||||
|
@ -68,6 +68,9 @@ static void init_rc_out()
|
|||
APM_RC.enable_out(CH_9);
|
||||
APM_RC.enable_out(CH_10);
|
||||
APM_RC.enable_out(CH_11);
|
||||
APM_RC.OutputCh(CH_9, g.rc_9.radio_trim);
|
||||
APM_RC.OutputCh(CH_10, g.rc_10.radio_trim);
|
||||
APM_RC.OutputCh(CH_11, g.rc_11.radio_trim);
|
||||
#endif
|
||||
#if INSTANT_PWM == 1
|
||||
motors.set_update_rate(AP_MOTORS_SPEED_INSTANT_PWM);
|
||||
|
|
|
@ -421,6 +421,11 @@ static void set_servos(void)
|
|||
g.rc_6.output_ch(CH_6);
|
||||
g.rc_7.output_ch(CH_7);
|
||||
g.rc_8.output_ch(CH_8);
|
||||
# if CONFIG_APM_HARDWARE != APM_HARDWARE_APM1
|
||||
g.rc_9.output_ch(CH_9);
|
||||
g.rc_10.output_ch(CH_10);
|
||||
g.rc_11.output_ch(CH_11);
|
||||
# endif
|
||||
#endif
|
||||
}
|
||||
|
||||
|
|
|
@ -5,7 +5,7 @@
|
|||
static byte failsafeCounter = 0; // we wait a second to take over the throttle and send the plane circling
|
||||
|
||||
|
||||
extern RC_Channel* rc_ch[8];
|
||||
extern RC_Channel* rc_ch[NUM_CHANNELS];
|
||||
|
||||
static void init_rc_in()
|
||||
{
|
||||
|
|
|
@ -24,7 +24,7 @@
|
|||
|
||||
/// global array with pointers to all APM RC channels, will be used by AP_Mount and AP_Camera classes
|
||||
/// It points to RC input channels, both APM1 and APM2 only have 8 input channels.
|
||||
RC_Channel* rc_ch[8];
|
||||
RC_Channel* rc_ch[NUM_CHANNELS];
|
||||
|
||||
APM_RC_Class *RC_Channel::_apm_rc;
|
||||
|
||||
|
|
Loading…
Reference in New Issue