mirror of https://github.com/ArduPilot/ardupilot
AP_EFI: correct EFI ignition_voltage flag values
This commit is contained in:
parent
1d57ada441
commit
9b8a61c048
|
@ -247,6 +247,19 @@ void AP_EFI::send_mavlink_status(mavlink_channel_t chan)
|
|||
if (!backend) {
|
||||
return;
|
||||
}
|
||||
|
||||
float ignition_voltage;
|
||||
if (isnan(state.ignition_voltage) ||
|
||||
is_equal(state.ignition_voltage, -1.0f)) {
|
||||
// zero means "unknown" in mavlink, 0.0001 means 0 volts
|
||||
ignition_voltage = 0;
|
||||
} else if (is_zero(state.ignition_voltage)) {
|
||||
// zero means "unknown" in mavlink, 0.0001 means 0 volts
|
||||
ignition_voltage = 0.0001f;
|
||||
} else {
|
||||
ignition_voltage = state.ignition_voltage;
|
||||
};
|
||||
|
||||
mavlink_msg_efi_status_send(
|
||||
chan,
|
||||
AP_EFI::is_healthy(),
|
||||
|
@ -266,7 +279,7 @@ void AP_EFI::send_mavlink_status(mavlink_channel_t chan)
|
|||
KELVIN_TO_C(state.cylinder_status.exhaust_gas_temperature),
|
||||
state.throttle_out,
|
||||
state.pt_compensation,
|
||||
state.ignition_voltage
|
||||
ignition_voltage
|
||||
);
|
||||
}
|
||||
|
||||
|
|
|
@ -199,7 +199,7 @@ struct EFI_State {
|
|||
Cylinder_Status cylinder_status;
|
||||
|
||||
// ignition voltage in Volts
|
||||
float ignition_voltage;
|
||||
float ignition_voltage = -1; // -1 is "unknown";
|
||||
|
||||
// throttle output percentage
|
||||
float throttle_out;
|
||||
|
|
Loading…
Reference in New Issue