|
|
@ -86,7 +86,7 @@ void AP_EFI::init(void) |
|
|
|
#endif |
|
|
|
#endif |
|
|
|
break; |
|
|
|
break; |
|
|
|
default: |
|
|
|
default: |
|
|
|
gcs().send_text(MAV_SEVERITY_INFO, "Unknown EFI type"); |
|
|
|
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Unknown EFI type"); |
|
|
|
break; |
|
|
|
break; |
|
|
|
} |
|
|
|
} |
|
|
|
} |
|
|
|
} |
|
|
@ -96,7 +96,9 @@ void AP_EFI::update() |
|
|
|
{ |
|
|
|
{ |
|
|
|
if (backend) { |
|
|
|
if (backend) { |
|
|
|
backend->update(); |
|
|
|
backend->update(); |
|
|
|
|
|
|
|
#if HAL_LOGGING_ENABLED |
|
|
|
log_status(); |
|
|
|
log_status(); |
|
|
|
|
|
|
|
#endif |
|
|
|
} |
|
|
|
} |
|
|
|
} |
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
@ -105,6 +107,7 @@ bool AP_EFI::is_healthy(void) const |
|
|
|
return (backend && (AP_HAL::millis() - state.last_updated_ms) < HEALTHY_LAST_RECEIVED_MS); |
|
|
|
return (backend && (AP_HAL::millis() - state.last_updated_ms) < HEALTHY_LAST_RECEIVED_MS); |
|
|
|
} |
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
#if HAL_LOGGING_ENABLED |
|
|
|
/*
|
|
|
|
/*
|
|
|
|
write status to log |
|
|
|
write status to log |
|
|
|
*/ |
|
|
|
*/ |
|
|
@ -208,6 +211,7 @@ void AP_EFI::log_status(void) |
|
|
|
state.ecu_index); |
|
|
|
state.ecu_index); |
|
|
|
} |
|
|
|
} |
|
|
|
} |
|
|
|
} |
|
|
|
|
|
|
|
#endif // LOGGING_ENABLED
|
|
|
|
|
|
|
|
|
|
|
|
/*
|
|
|
|
/*
|
|
|
|
send EFI_STATUS |
|
|
|
send EFI_STATUS |
|
|
@ -240,6 +244,13 @@ void AP_EFI::send_mavlink_status(mavlink_channel_t chan) |
|
|
|
); |
|
|
|
); |
|
|
|
} |
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
// get a copy of state structure
|
|
|
|
|
|
|
|
void AP_EFI::get_state(EFI_State &_state) |
|
|
|
|
|
|
|
{ |
|
|
|
|
|
|
|
WITH_SEMAPHORE(sem); |
|
|
|
|
|
|
|
_state = state; |
|
|
|
|
|
|
|
} |
|
|
|
|
|
|
|
|
|
|
|
namespace AP { |
|
|
|
namespace AP { |
|
|
|
AP_EFI *EFI() |
|
|
|
AP_EFI *EFI() |
|
|
|
{ |
|
|
|
{ |
|
|
|