From 9b789ac47f2cf5290585727f60cb3927dcde28b2 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 30 Sep 2022 10:44:13 +1000 Subject: [PATCH] AP_EFI: added more fields fill in 3 remaining fields available in MAVLink --- libraries/AP_EFI/AP_EFI.cpp | 6 +++--- libraries/AP_EFI/AP_EFI_State.h | 8 ++++++++ 2 files changed, 11 insertions(+), 3 deletions(-) diff --git a/libraries/AP_EFI/AP_EFI.cpp b/libraries/AP_EFI/AP_EFI.cpp index a7b74ae84a..c1ec7958d8 100644 --- a/libraries/AP_EFI/AP_EFI.cpp +++ b/libraries/AP_EFI/AP_EFI.cpp @@ -263,9 +263,9 @@ void AP_EFI::send_mavlink_status(mavlink_channel_t chan) state.cylinder_status.ignition_timing_deg, state.cylinder_status.injection_time_ms, state.cylinder_status.exhaust_gas_temperature, - 0, // throttle out - 0, // pressure/temperature compensation - 0 // ignition voltage (spark supply voltage) + state.throttle_out, + state.pt_compensation, + state.ignition_voltage ); } diff --git a/libraries/AP_EFI/AP_EFI_State.h b/libraries/AP_EFI/AP_EFI_State.h index 6c25add5e6..6b0abc93d2 100644 --- a/libraries/AP_EFI/AP_EFI_State.h +++ b/libraries/AP_EFI/AP_EFI_State.h @@ -198,4 +198,12 @@ struct EFI_State { // Status for each cylinder in the engine Cylinder_Status cylinder_status; + // ignition voltage in Volts + float ignition_voltage; + + // throttle output percentage + float throttle_out; + + // PT compensation + float pt_compensation; };