ardupilot/ArduPlane/events.pde

126 lines
3.3 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(int16_t fstype)
{
2012-08-16 21:50:15 -03:00
// This is how to handle a short loss of control signal failsafe.
failsafe = fstype;
ch3_failsafe_timer = 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 FLY_BY_WIRE_A: // middle position
case FLY_BY_WIRE_B: // middle position
set_mode(CIRCLE);
break;
case AUTO:
case GUIDED:
case LOITER:
if(g.short_fs_action == 1) {
set_mode(RTL);
}
break;
case CIRCLE:
case RTL:
default:
break;
}
gcs_send_text_fmt(PSTR("flight mode = %u"), (unsigned)control_mode);
}
static void failsafe_long_on_event(int16_t 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();
2012-08-16 21:50:15 -03:00
failsafe = fstype;
switch(control_mode)
{
case MANUAL:
case STABILIZE:
case FLY_BY_WIRE_A: // middle position
case FLY_BY_WIRE_B: // middle position
case CIRCLE:
set_mode(RTL);
break;
case AUTO:
case GUIDED:
case LOITER:
if(g.long_fs_action == 1) {
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 = 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 ||
(g.short_fs_action == 1 && control_mode == RTL)) {
reset_control_switch();
}
}
#if BATTERY_EVENT == ENABLED
2012-02-13 17:53:54 -04:00
void low_battery_event(void)
{
2012-08-16 21:50:15 -03:00
gcs_send_text_P(SEVERITY_HIGH,PSTR("Low Battery!"));
set_mode(RTL);
g.throttle_cruise = THROTTLE_CRUISE;
}
#endif
////////////////////////////////////////////////////////////////////////////////
// repeating event control
/*
update state for MAV_CMD_DO_REPEAT_SERVO and MAV_CMD_DO_REPEAT_RELAY
*/
static void update_events(void)
{
if (event_state.repeat == 0 || (millis() - event_state.start_time_ms) < event_state.delay_ms) {
2012-08-16 21:50:15 -03:00
return;
}
// event_repeat = -1 means repeat forever
if (event_state.repeat != 0) {
event_state.start_time_ms = millis();
2012-08-16 21:50:15 -03:00
switch (event_state.type) {
case EVENT_TYPE_SERVO:
2012-12-04 18:22:21 -04:00
hal.rcout->enable_ch(event_state.rc_channel);
if (event_state.repeat & 1) {
2012-12-04 18:22:21 -04:00
hal.rcout->write(event_state.rc_channel, event_state.undo_value);
2012-08-16 21:50:15 -03:00
} else {
2012-12-04 18:22:21 -04:00
hal.rcout->write(event_state.rc_channel, event_state.servo_value);
2012-08-16 21:50:15 -03:00
}
break;
2012-08-16 21:50:15 -03:00
case EVENT_TYPE_RELAY:
2012-08-16 21:50:15 -03:00
relay.toggle();
break;
}
if (event_state.repeat > 0) {
event_state.repeat--;
2012-08-16 21:50:15 -03:00
}
}
}