Browse Source

RC_Channel: added setup_failsafe_trim_all() function

sets all channels to output trim values on FMU failure
master
Andrew Tridgell 11 years ago
parent
commit
7f4178d967
  1. 12
      libraries/RC_Channel/RC_Channel.cpp
  2. 1
      libraries/RC_Channel/RC_Channel.h

12
libraries/RC_Channel/RC_Channel.cpp

@ -410,6 +410,18 @@ void RC_Channel::output_trim_all() @@ -410,6 +410,18 @@ void RC_Channel::output_trim_all()
}
}
/*
setup the failsafe value to the trim value for all channels
*/
void RC_Channel::setup_failsafe_trim_all()
{
for (uint8_t i=0; i<RC_MAX_CHANNELS; i++) {
if (rc_ch[i] != NULL) {
hal.rcout->set_failsafe_pwm(1U<<i, rc_ch[i]->radio_trim);
}
}
}
void
RC_Channel::input()
{

1
libraries/RC_Channel/RC_Channel.h

@ -100,6 +100,7 @@ public: @@ -100,6 +100,7 @@ public:
void output() const;
void output_trim() const;
static void output_trim_all();
static void setup_failsafe_trim_all();
uint16_t read() const;
void input();
void enable_out();

Loading…
Cancel
Save