mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_EFI: use degF_to_Kelvin for megasquirt
This commit is contained in:
parent
319592a148
commit
5cb0d5c188
@ -110,12 +110,12 @@ bool AP_EFI_Serial_MS::read_incoming_realtime_data()
|
||||
case MAT_MSB:
|
||||
temp_float = (float)((data << 8) + read_byte_CRC32())/10.0f;
|
||||
offset++;
|
||||
internal_state.intake_manifold_temperature = f_to_k(temp_float);
|
||||
internal_state.intake_manifold_temperature = degF_to_Kelvin(temp_float);
|
||||
break;
|
||||
case CHT_MSB:
|
||||
temp_float = (float)((data << 8) + read_byte_CRC32())/10.0f;
|
||||
offset++;
|
||||
internal_state.cylinder_status[0].cylinder_head_temperature = f_to_k(temp_float);
|
||||
internal_state.cylinder_status[0].cylinder_head_temperature = degF_to_Kelvin(temp_float);
|
||||
break;
|
||||
case TPS_MSB:
|
||||
temp_float = (float)((data << 8) + read_byte_CRC32())/10.0f;
|
||||
|
@ -36,8 +36,7 @@ private:
|
||||
void send_request(uint8_t table, uint16_t first_offset, uint16_t last_offset);
|
||||
uint8_t read_byte_CRC32();
|
||||
uint32_t CRC32_compute_byte(uint32_t inCrc32, uint8_t data);
|
||||
float f_to_k(float temp_f) { return (temp_f + 459.67f) * 0.55556f; };
|
||||
|
||||
|
||||
// Serial Protocol Variables
|
||||
uint32_t checksum;
|
||||
uint8_t step;
|
||||
|
Loading…
Reference in New Issue
Block a user