Plane: fixed secondary aileron and manual aux servos in failsafe

the servo value wasn't being written to APM_RC while in failsafe for
these aux channels
This commit is contained in:
Andrew Tridgell 2012-11-26 17:16:25 +11:00
parent 1a3a7d173a
commit 1059ef2a54
5 changed files with 18 additions and 3 deletions

View File

@ -46,6 +46,7 @@ void failsafe_check(uint32_t tnow)
for (uint8_t ch=start_ch; ch<4; ch++) {
APM_RC.OutputCh(ch, APM_RC.InputCh(ch));
}
RC_Channel_aux::copy_radio_in_out(RC_Channel_aux::k_manual);
RC_Channel_aux::copy_radio_in_out(RC_Channel_aux::k_manual, true);
RC_Channel_aux::copy_radio_in_out(RC_Channel_aux::k_aileron_with_input, true);
}
}

View File

@ -1,3 +1,4 @@
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
/*
* RC_Channel.cpp - Radio library for Arduino
* Code by Jason Short. DIYDrones.com
@ -324,6 +325,12 @@ RC_Channel::output()
_apm_rc->OutputCh(_ch_out, radio_out);
}
void
RC_Channel::input()
{
radio_in = _apm_rc->InputCh(_ch_out);
}
void
RC_Channel::enable_out()
{

View File

@ -88,6 +88,7 @@ public:
static void set_apm_rc(APM_RC_Class * apm_rc);
void output();
void input();
void enable_out();
static APM_RC_Class * _apm_rc;

View File

@ -172,11 +172,17 @@ RC_Channel_aux::set_radio_to_trim(RC_Channel_aux::Aux_servo_function_t function)
copy radio_in to radio_out for a given function
*/
void
RC_Channel_aux::copy_radio_in_out(RC_Channel_aux::Aux_servo_function_t function)
RC_Channel_aux::copy_radio_in_out(RC_Channel_aux::Aux_servo_function_t function, bool do_input_output)
{
for (uint8_t i = 0; i < 7; i++) {
if (_aux_channels[i] && _aux_channels[i]->function.get() == function) {
if (do_input_output) {
_aux_channels[i]->input();
}
_aux_channels[i]->radio_out = _aux_channels[i]->radio_in;
if (do_input_output) {
_aux_channels[i]->output();
}
}
}
}

View File

@ -67,7 +67,7 @@ public:
static void set_radio_to_trim(Aux_servo_function_t function);
// copy radio_in to radio_out
static void copy_radio_in_out(Aux_servo_function_t function);
static void copy_radio_in_out(Aux_servo_function_t function, bool do_input_output=false);
// set servo_out
static void set_servo_out(Aux_servo_function_t function, int16_t value);