mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_EFI: allow EFI to be used in AP_Periph
This commit is contained in:
parent
25d231187f
commit
0fad35112f
@ -86,7 +86,7 @@ void AP_EFI::init(void)
|
||||
#endif
|
||||
break;
|
||||
default:
|
||||
gcs().send_text(MAV_SEVERITY_INFO, "Unknown EFI type");
|
||||
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Unknown EFI type");
|
||||
break;
|
||||
}
|
||||
}
|
||||
@ -96,7 +96,9 @@ void AP_EFI::update()
|
||||
{
|
||||
if (backend) {
|
||||
backend->update();
|
||||
#if HAL_LOGGING_ENABLED
|
||||
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);
|
||||
}
|
||||
|
||||
#if HAL_LOGGING_ENABLED
|
||||
/*
|
||||
write status to log
|
||||
*/
|
||||
@ -208,6 +211,7 @@ void AP_EFI::log_status(void)
|
||||
state.ecu_index);
|
||||
}
|
||||
}
|
||||
#endif // LOGGING_ENABLED
|
||||
|
||||
/*
|
||||
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 {
|
||||
AP_EFI *EFI()
|
||||
{
|
||||
|
@ -64,6 +64,14 @@ public:
|
||||
|
||||
bool is_healthy() const;
|
||||
|
||||
// return timestamp of last update
|
||||
uint32_t get_last_update_ms(void) const {
|
||||
return state.last_updated_ms;
|
||||
}
|
||||
|
||||
// get a copy of state structure
|
||||
void get_state(EFI_State &state);
|
||||
|
||||
// Parameter info
|
||||
static const struct AP_Param::GroupInfo var_info[];
|
||||
|
||||
@ -99,6 +107,9 @@ private:
|
||||
AP_EFI_Backend *backend;
|
||||
static AP_EFI *singleton;
|
||||
|
||||
// Semaphore for access to shared frontend data
|
||||
HAL_Semaphore sem;
|
||||
|
||||
// write to log
|
||||
void log_status();
|
||||
};
|
||||
|
@ -28,7 +28,7 @@ AP_EFI_Backend::AP_EFI_Backend(AP_EFI &_frontend) :
|
||||
|
||||
void AP_EFI_Backend::copy_to_frontend()
|
||||
{
|
||||
WITH_SEMAPHORE(sem);
|
||||
WITH_SEMAPHORE(frontend.sem);
|
||||
frontend.state = internal_state;
|
||||
}
|
||||
|
||||
|
@ -35,9 +35,6 @@ protected:
|
||||
// Copies internal state to the frontend state
|
||||
void copy_to_frontend();
|
||||
|
||||
// Semaphore for access to shared frontend data
|
||||
HAL_Semaphore sem;
|
||||
|
||||
// Internal state for this driver (before copying to frontend)
|
||||
EFI_State internal_state;
|
||||
|
||||
|
@ -36,7 +36,7 @@ void AP_EFI_NWPMU::handle_frame(AP_HAL::CANFrame &frame)
|
||||
{
|
||||
const uint32_t id = frame.id & AP_HAL::CANFrame::MaskExtID;
|
||||
|
||||
WITH_SEMAPHORE(sem);
|
||||
WITH_SEMAPHORE(frontend.sem);
|
||||
|
||||
switch ((NWPMU_ID)id) {
|
||||
case NWPMU_ID::ECU_1: {
|
||||
|
Loading…
Reference in New Issue
Block a user