AP_EFI: added more fields

fill in 3 remaining fields available in MAVLink
This commit is contained in:
Andrew Tridgell 2022-09-30 10:44:13 +10:00
parent b514f44b7a
commit 698c25a060
2 changed files with 11 additions and 3 deletions

View File

@ -264,9 +264,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
);
}

View File

@ -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;
};