ardupilot/ArduPlane/events.pde

122 lines
3.1 KiB
Plaintext
Raw Normal View History

// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
static void failsafe_short_on_event(enum failsafe_state fstype)
{
2012-08-16 21:50:15 -03:00
// This is how to handle a short loss of control signal failsafe.
failsafe.state = fstype;
failsafe.ch3_timer_ms = millis();
2011-12-09 12:06:45 -04:00
gcs_send_text_P(SEVERITY_LOW, PSTR("Failsafe - Short event on, "));
2012-08-16 21:50:15 -03:00
switch(control_mode)
{
case MANUAL:
case STABILIZE:
case ACRO:
case FLY_BY_WIRE_A:
case FLY_BY_WIRE_B:
case CRUISE:
case TRAINING:
failsafe.saved_mode = control_mode;
failsafe.saved_mode_set = 1;
if(g.short_fs_action == 2) {
set_mode(FLY_BY_WIRE_A);
} else {
set_mode(CIRCLE);
}
2012-08-16 21:50:15 -03:00
break;
case AUTO:
case GUIDED:
case LOITER:
if(g.short_fs_action != 0) {
failsafe.saved_mode = control_mode;
failsafe.saved_mode_set = 1;
if(g.short_fs_action == 2) {
set_mode(FLY_BY_WIRE_A);
} else {
set_mode(CIRCLE);
}
2012-08-16 21:50:15 -03:00
}
break;
case CIRCLE:
case RTL:
default:
break;
}
gcs_send_text_fmt(PSTR("flight mode = %u"), (unsigned)control_mode);
}
static void failsafe_long_on_event(enum failsafe_state fstype)
{
2012-08-16 21:50:15 -03:00
// This is how to handle a long loss of control signal failsafe.
gcs_send_text_P(SEVERITY_LOW, PSTR("Failsafe - Long event on, "));
2012-12-04 18:22:21 -04:00
// If the GCS is locked up we allow control to revert to RC
hal.rcin->clear_overrides();
failsafe.state = fstype;
2012-08-16 21:50:15 -03:00
switch(control_mode)
{
case MANUAL:
case STABILIZE:
case ACRO:
case FLY_BY_WIRE_A:
case FLY_BY_WIRE_B:
case CRUISE:
case TRAINING:
2012-08-16 21:50:15 -03:00
case CIRCLE:
if(g.long_fs_action == 2) {
set_mode(FLY_BY_WIRE_A);
} else {
set_mode(RTL);
}
2012-08-16 21:50:15 -03:00
break;
case AUTO:
case GUIDED:
case LOITER:
if(g.long_fs_action == 2) {
set_mode(FLY_BY_WIRE_A);
} else if (g.long_fs_action == 1) {
2012-08-16 21:50:15 -03:00
set_mode(RTL);
}
break;
case RTL:
default:
break;
}
2011-12-09 12:06:45 -04:00
gcs_send_text_fmt(PSTR("flight mode = %u"), (unsigned)control_mode);
}
static void failsafe_short_off_event()
{
2012-08-16 21:50:15 -03:00
// We're back in radio contact
gcs_send_text_P(SEVERITY_LOW, PSTR("Failsafe - Short event off"));
failsafe.state = FAILSAFE_NONE;
2012-08-16 21:50:15 -03:00
// re-read the switch so we can return to our preferred mode
// --------------------------------------------------------
if (control_mode == CIRCLE && failsafe.saved_mode_set) {
failsafe.saved_mode_set = 0;
set_mode(failsafe.saved_mode);
}
}
2012-02-13 17:53:54 -04:00
void low_battery_event(void)
{
2013-09-29 09:54:39 -03:00
if (failsafe.low_battery) {
return;
}
gcs_send_text_fmt(PSTR("Low Battery %.2fV Used %.0f mAh"),
2013-09-29 09:54:39 -03:00
battery.voltage(), battery.current_total_mah());
2012-08-16 21:50:15 -03:00
set_mode(RTL);
aparm.throttle_cruise.load();
2013-09-29 09:54:39 -03:00
failsafe.low_battery = true;
AP_Notify::flags.failsafe_battery = true;
}
static void update_events(void)
{
2014-01-20 00:36:31 -04:00
ServoRelayEvents.update_events();
}