mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_EFI: added more fields
fill in 3 remaining fields available in MAVLink
This commit is contained in:
parent
b514f44b7a
commit
698c25a060
@ -264,9 +264,9 @@ void AP_EFI::send_mavlink_status(mavlink_channel_t chan)
|
|||||||
state.cylinder_status.ignition_timing_deg,
|
state.cylinder_status.ignition_timing_deg,
|
||||||
state.cylinder_status.injection_time_ms,
|
state.cylinder_status.injection_time_ms,
|
||||||
state.cylinder_status.exhaust_gas_temperature,
|
state.cylinder_status.exhaust_gas_temperature,
|
||||||
0, // throttle out
|
state.throttle_out,
|
||||||
0, // pressure/temperature compensation
|
state.pt_compensation,
|
||||||
0 // ignition voltage (spark supply voltage)
|
state.ignition_voltage
|
||||||
);
|
);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -198,4 +198,12 @@ struct EFI_State {
|
|||||||
// Status for each cylinder in the engine
|
// Status for each cylinder in the engine
|
||||||
Cylinder_Status cylinder_status;
|
Cylinder_Status cylinder_status;
|
||||||
|
|
||||||
|
// ignition voltage in Volts
|
||||||
|
float ignition_voltage;
|
||||||
|
|
||||||
|
// throttle output percentage
|
||||||
|
float throttle_out;
|
||||||
|
|
||||||
|
// PT compensation
|
||||||
|
float pt_compensation;
|
||||||
};
|
};
|
||||||
|
Loading…
Reference in New Issue
Block a user