mirror of https://github.com/ArduPilot/ardupilot
uncrustify ArduPlane/events.pde
This commit is contained in:
parent
0683be294b
commit
9b133019b3
|
@ -3,115 +3,115 @@
|
||||||
|
|
||||||
static void failsafe_short_on_event(int16_t fstype)
|
static void failsafe_short_on_event(int16_t fstype)
|
||||||
{
|
{
|
||||||
// This is how to handle a short loss of control signal failsafe.
|
// This is how to handle a short loss of control signal failsafe.
|
||||||
failsafe = fstype;
|
failsafe = fstype;
|
||||||
ch3_failsafe_timer = millis();
|
ch3_failsafe_timer = millis();
|
||||||
gcs_send_text_P(SEVERITY_LOW, PSTR("Failsafe - Short event on, "));
|
gcs_send_text_P(SEVERITY_LOW, PSTR("Failsafe - Short event on, "));
|
||||||
switch(control_mode)
|
switch(control_mode)
|
||||||
{
|
{
|
||||||
case MANUAL:
|
case MANUAL:
|
||||||
case STABILIZE:
|
case STABILIZE:
|
||||||
case FLY_BY_WIRE_A: // middle position
|
case FLY_BY_WIRE_A: // middle position
|
||||||
case FLY_BY_WIRE_B: // middle position
|
case FLY_BY_WIRE_B: // middle position
|
||||||
set_mode(CIRCLE);
|
set_mode(CIRCLE);
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case AUTO:
|
case AUTO:
|
||||||
case GUIDED:
|
case GUIDED:
|
||||||
case LOITER:
|
case LOITER:
|
||||||
if(g.short_fs_action == 1) {
|
if(g.short_fs_action == 1) {
|
||||||
set_mode(RTL);
|
set_mode(RTL);
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case CIRCLE:
|
case CIRCLE:
|
||||||
case RTL:
|
case RTL:
|
||||||
default:
|
default:
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
gcs_send_text_fmt(PSTR("flight mode = %u"), (unsigned)control_mode);
|
gcs_send_text_fmt(PSTR("flight mode = %u"), (unsigned)control_mode);
|
||||||
}
|
}
|
||||||
|
|
||||||
static void failsafe_long_on_event(int16_t fstype)
|
static void failsafe_long_on_event(int16_t fstype)
|
||||||
{
|
{
|
||||||
// This is how to handle a long loss of control signal failsafe.
|
// This is how to handle a long loss of control signal failsafe.
|
||||||
gcs_send_text_P(SEVERITY_LOW, PSTR("Failsafe - Long event on, "));
|
gcs_send_text_P(SEVERITY_LOW, PSTR("Failsafe - Long event on, "));
|
||||||
APM_RC.clearOverride(); // If the GCS is locked up we allow control to revert to RC
|
APM_RC.clearOverride(); // If the GCS is locked up we allow control to revert to RC
|
||||||
failsafe = fstype;
|
failsafe = fstype;
|
||||||
switch(control_mode)
|
switch(control_mode)
|
||||||
{
|
{
|
||||||
case MANUAL:
|
case MANUAL:
|
||||||
case STABILIZE:
|
case STABILIZE:
|
||||||
case FLY_BY_WIRE_A: // middle position
|
case FLY_BY_WIRE_A: // middle position
|
||||||
case FLY_BY_WIRE_B: // middle position
|
case FLY_BY_WIRE_B: // middle position
|
||||||
case CIRCLE:
|
case CIRCLE:
|
||||||
set_mode(RTL);
|
set_mode(RTL);
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case AUTO:
|
case AUTO:
|
||||||
case GUIDED:
|
case GUIDED:
|
||||||
case LOITER:
|
case LOITER:
|
||||||
if(g.long_fs_action == 1) {
|
if(g.long_fs_action == 1) {
|
||||||
set_mode(RTL);
|
set_mode(RTL);
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case RTL:
|
case RTL:
|
||||||
default:
|
default:
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
gcs_send_text_fmt(PSTR("flight mode = %u"), (unsigned)control_mode);
|
gcs_send_text_fmt(PSTR("flight mode = %u"), (unsigned)control_mode);
|
||||||
}
|
}
|
||||||
|
|
||||||
static void failsafe_short_off_event()
|
static void failsafe_short_off_event()
|
||||||
{
|
{
|
||||||
// We're back in radio contact
|
// We're back in radio contact
|
||||||
gcs_send_text_P(SEVERITY_LOW, PSTR("Failsafe - Short event off"));
|
gcs_send_text_P(SEVERITY_LOW, PSTR("Failsafe - Short event off"));
|
||||||
failsafe = FAILSAFE_NONE;
|
failsafe = FAILSAFE_NONE;
|
||||||
|
|
||||||
// re-read the switch so we can return to our preferred mode
|
// re-read the switch so we can return to our preferred mode
|
||||||
// --------------------------------------------------------
|
// --------------------------------------------------------
|
||||||
if (control_mode == CIRCLE ||
|
if (control_mode == CIRCLE ||
|
||||||
(g.short_fs_action == 1 && control_mode == RTL)) {
|
(g.short_fs_action == 1 && control_mode == RTL)) {
|
||||||
reset_control_switch();
|
reset_control_switch();
|
||||||
}
|
}
|
||||||
|
|
||||||
// Reset control integrators
|
// Reset control integrators
|
||||||
// ---------------------
|
// ---------------------
|
||||||
reset_I();
|
reset_I();
|
||||||
}
|
}
|
||||||
|
|
||||||
#if BATTERY_EVENT == ENABLED
|
#if BATTERY_EVENT == ENABLED
|
||||||
void low_battery_event(void)
|
void low_battery_event(void)
|
||||||
{
|
{
|
||||||
gcs_send_text_P(SEVERITY_HIGH,PSTR("Low Battery!"));
|
gcs_send_text_P(SEVERITY_HIGH,PSTR("Low Battery!"));
|
||||||
set_mode(RTL);
|
set_mode(RTL);
|
||||||
g.throttle_cruise = THROTTLE_CRUISE;
|
g.throttle_cruise = THROTTLE_CRUISE;
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
static void update_events(void) // Used for MAV_CMD_DO_REPEAT_SERVO and MAV_CMD_DO_REPEAT_RELAY
|
static void update_events(void) // Used for MAV_CMD_DO_REPEAT_SERVO and MAV_CMD_DO_REPEAT_RELAY
|
||||||
{
|
{
|
||||||
if(event_repeat == 0 || (millis() - event_timer_ms) < event_delay_ms)
|
if(event_repeat == 0 || (millis() - event_timer_ms) < event_delay_ms)
|
||||||
return;
|
return;
|
||||||
|
|
||||||
if (event_repeat > 0){
|
if (event_repeat > 0) {
|
||||||
event_repeat --;
|
event_repeat--;
|
||||||
}
|
}
|
||||||
|
|
||||||
if(event_repeat != 0) { // event_repeat = -1 means repeat forever
|
if(event_repeat != 0) { // event_repeat = -1 means repeat forever
|
||||||
event_timer_ms = millis();
|
event_timer_ms = millis();
|
||||||
|
|
||||||
if (event_id >= CH_5 && event_id <= CH_8) {
|
if (event_id >= CH_5 && event_id <= CH_8) {
|
||||||
if(event_repeat%2) {
|
if(event_repeat%2) {
|
||||||
APM_RC.OutputCh(event_id, event_value); // send to Servos
|
APM_RC.OutputCh(event_id, event_value); // send to Servos
|
||||||
} else {
|
} else {
|
||||||
APM_RC.OutputCh(event_id, event_undo_value);
|
APM_RC.OutputCh(event_id, event_undo_value);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
if (event_id == RELAY_TOGGLE) {
|
if (event_id == RELAY_TOGGLE) {
|
||||||
relay.toggle();
|
relay.toggle();
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
Loading…
Reference in New Issue