mirror of https://github.com/ArduPilot/ardupilot
Rover: check for failed RC input
loss of RC for 2s is considered a throttle failsafe
This commit is contained in:
parent
a4af83d454
commit
b72ea5435b
|
@ -354,6 +354,7 @@ static struct {
|
|||
uint32_t rc_override_timer;
|
||||
uint32_t start_time;
|
||||
uint8_t triggered;
|
||||
uint32_t last_valid_rc_ms;
|
||||
} failsafe;
|
||||
|
||||
// notification object for LEDs, buzzers etc (parameter set to false disables external leds)
|
||||
|
|
|
@ -45,6 +45,13 @@ static void init_rc_out()
|
|||
|
||||
static void read_radio()
|
||||
{
|
||||
if (!hal.rcin->valid_channels()) {
|
||||
control_failsafe(channel_throttle->radio_in);
|
||||
return;
|
||||
}
|
||||
|
||||
failsafe.last_valid_rc_ms = hal.scheduler->millis();
|
||||
|
||||
for (uint8_t i=0; i<8; i++) {
|
||||
RC_Channel::rc_channel(i)->set_pwm(RC_Channel::rc_channel(i)->read());
|
||||
}
|
||||
|
@ -101,7 +108,11 @@ static void control_failsafe(uint16_t pwm)
|
|||
if (rc_override_active) {
|
||||
failsafe_trigger(FAILSAFE_EVENT_RC, (millis() - failsafe.rc_override_timer) > 1500);
|
||||
} else if (g.fs_throttle_enabled) {
|
||||
failsafe_trigger(FAILSAFE_EVENT_THROTTLE, pwm < (uint16_t)g.fs_throttle_value);
|
||||
bool failed = pwm < (uint16_t)g.fs_throttle_value;
|
||||
if (hal.scheduler->millis() - failsafe.last_valid_rc_ms > 2000) {
|
||||
failed = true;
|
||||
}
|
||||
failsafe_trigger(FAILSAFE_EVENT_THROTTLE, failed);
|
||||
}
|
||||
}
|
||||
|
||||
|
|
Loading…
Reference in New Issue