diff --git a/Tools/autotest/arduplane.py b/Tools/autotest/arduplane.py index a580e70d5e7af..abbb1d27c914c 100644 --- a/Tools/autotest/arduplane.py +++ b/Tools/autotest/arduplane.py @@ -8,7 +8,6 @@ import math import os import signal -import sys import time from pymavlink import quaternion @@ -4199,24 +4198,81 @@ def ForcedDCM(self): self.fly_home_land_and_disarm() - def MegaSquirt(self): - '''Test MegaSquirt EFI''' + def EFITest(self, efi_type, name, sim_name, check_fuel_flow=True): + '''method to be called by EFI tests''' + self.start_subtest("EFI Test for (%s)" % name) self.assert_not_receiving_message('EFI_STATUS') self.set_parameters({ - 'SIM_EFI_TYPE': 1, - 'EFI_TYPE': 1, + 'SIM_EFI_TYPE': efi_type, + 'EFI_TYPE': efi_type, 'SERIAL5_PROTOCOL': 24, + 'RPM1_TYPE': 10, }) - self.customise_SITL_commandline(["--uartF=sim:megasquirt"]) - self.delay_sim_time(5) - m = self.assert_receive_message('EFI_STATUS') - mavutil.dump_message_verbose(sys.stdout, m) - if m.throttle_out != 0: - raise NotAchievedException("Expected zero throttle") - if m.health != 1: - raise NotAchievedException("Not healthy") - if m.intake_manifold_temperature < 20: - raise NotAchievedException("Bad intake manifold temperature") + + self.customise_SITL_commandline( + ["--uartF=sim:%s" % sim_name, + ], + ) + self.wait_ready_to_arm() + + baro_m = self.assert_receive_message("SCALED_PRESSURE") + self.progress(self.dump_message_verbose(baro_m)) + baro_temperature = baro_m.temperature / 100.0 # cDeg->deg + m = self.assert_received_message_field_values("EFI_STATUS", { + "throttle_out": 0, + "health": 1, + }, very_verbose=1) + + if abs(baro_temperature - m.intake_manifold_temperature) > 1: + raise NotAchievedException( + "Bad intake manifold temperature (want=%f got=%f)" % + (baro_temperature, m.intake_manifold_temperature)) + + self.arm_vehicle() + + self.set_rc(3, 1300) + + tstart = self.get_sim_time() + while True: + now = self.get_sim_time_cached() + if now - tstart > 10: + raise NotAchievedException("RPM1 and EFI_STATUS.rpm did not match") + rpm_m = self.assert_receive_message("RPM", verbose=1) + want_rpm = 1000 + if rpm_m.rpm1 < want_rpm: + continue + + m = self.assert_receive_message("EFI_STATUS", verbose=1) + if abs(m.rpm - rpm_m.rpm1) > 100: + continue + + break + + self.progress("now we're started, check a few more values") + # note that megasquirt drver doesn't send throttle, so throttle_out is zero! + m = self.assert_received_message_field_values("EFI_STATUS", { + "health": 1, + }, very_verbose=1) + m = self.wait_message_field_values("EFI_STATUS", { + "throttle_position": 31, + "intake_manifold_temperature": 28, + }, very_verbose=1, epsilon=2) + if check_fuel_flow: + if abs(m.fuel_flow - 0.2) > 0.0001: + raise NotAchievedException("Expected fuel flow") + + self.disarm_vehicle() + + def MegaSquirt(self): + '''test MegaSquirt driver''' + self.EFITest( + 1, "MegaSquirt", "megasquirt", + check_fuel_flow=False, + ) + + def Hirth(self): + '''Test Hirth EFI''' + self.EFITest(6, "Hirth", "hirth") def GlideSlopeThresh(self): '''Test rebuild glide slope if above and climbing''' @@ -5313,6 +5369,7 @@ def tests(self): self.AUTOTUNE, self.AutotuneFiltering, self.MegaSquirt, + self.Hirth, self.MSP_DJI, self.SpeedToFly, self.GlideSlopeThresh, diff --git a/Tools/autotest/vehicle_test_suite.py b/Tools/autotest/vehicle_test_suite.py index 543bb6d5d0496..be940085b3b3d 100644 --- a/Tools/autotest/vehicle_test_suite.py +++ b/Tools/autotest/vehicle_test_suite.py @@ -3915,7 +3915,16 @@ def assert_received_message_field_values(self, return m # FIXME: try to use wait_and_maintain here? - def wait_message_field_values(self, message, fieldvalues, timeout=10, epsilon=None, instance=None, minimum_duration=None): + def wait_message_field_values(self, + message, + fieldvalues, + timeout=10, + epsilon=None, + instance=None, + minimum_duration=None, + verbose=False, + very_verbose=False, + ): tstart = self.get_sim_time_cached() pass_start = None @@ -3923,8 +3932,13 @@ def wait_message_field_values(self, message, fieldvalues, timeout=10, epsilon=No now = self.get_sim_time_cached() if now - tstart > timeout: raise NotAchievedException("Field never reached values") - m = self.assert_receive_message(message, instance=instance) - if self.message_has_field_values(m, fieldvalues, epsilon=epsilon): + m = self.assert_receive_message( + message, + instance=instance, + verbose=verbose, + very_verbose=very_verbose, + ) + if self.message_has_field_values(m, fieldvalues, epsilon=epsilon, verbose=verbose): if minimum_duration is not None: if pass_start is None: pass_start = now diff --git a/libraries/AP_HAL/SIMState.h b/libraries/AP_HAL/SIMState.h index b86c0282d4543..af62741110f2d 100644 --- a/libraries/AP_HAL/SIMState.h +++ b/libraries/AP_HAL/SIMState.h @@ -33,6 +33,8 @@ #include #include +#include + #include #include #include @@ -206,6 +208,9 @@ class AP_HAL::SIMState { // simulated EFI MegaSquirt device: SITL::EFI_MegaSquirt *efi_ms; + // simulated EFI Hirth device: + SITL::EFI_Hirth *efi_hirth; + #if CONFIG_HAL_BOARD == HAL_BOARD_SITL // output socket for flightgear viewing SocketAPM fg_socket{true}; diff --git a/libraries/AP_HAL_SITL/SITL_State_common.cpp b/libraries/AP_HAL_SITL/SITL_State_common.cpp index 320fcf9615f78..017e97022e530 100644 --- a/libraries/AP_HAL_SITL/SITL_State_common.cpp +++ b/libraries/AP_HAL_SITL/SITL_State_common.cpp @@ -245,6 +245,12 @@ SITL::SerialDevice *SITL_State_Common::create_serial_sim(const char *name, const } efi_ms = new SITL::EFI_MegaSquirt(); return efi_ms; + } else if (streq(name, "hirth")) { + if (efi_hirth != nullptr) { + AP_HAL::panic("Only one hirth at a time"); + } + efi_hirth = new SITL::EFI_Hirth(); + return efi_hirth; } else if (streq(name, "VectorNav")) { if (vectornav != nullptr) { AP_HAL::panic("Only one VectorNav at a time"); @@ -363,6 +369,9 @@ void SITL_State_Common::sim_update(void) if (efi_ms != nullptr) { efi_ms->update(); } + if (efi_hirth != nullptr) { + efi_hirth->update(); + } if (frsky_d != nullptr) { frsky_d->update(); diff --git a/libraries/AP_HAL_SITL/SITL_State_common.h b/libraries/AP_HAL_SITL/SITL_State_common.h index dab0cb0e5aba7..428aaff946194 100644 --- a/libraries/AP_HAL_SITL/SITL_State_common.h +++ b/libraries/AP_HAL_SITL/SITL_State_common.h @@ -11,6 +11,7 @@ #include #include #include +#include #include #include #include @@ -209,6 +210,9 @@ class HALSITL::SITL_State_Common { // simulated EFI MegaSquirt device: SITL::EFI_MegaSquirt *efi_ms; + // simulated EFI MegaSquirt device: + SITL::EFI_Hirth *efi_hirth; + // output socket for flightgear viewing SocketAPM fg_socket{true}; diff --git a/libraries/AP_Math/crc.cpp b/libraries/AP_Math/crc.cpp index bc059535daefc..5798e15abdbfb 100644 --- a/libraries/AP_Math/crc.cpp +++ b/libraries/AP_Math/crc.cpp @@ -578,3 +578,14 @@ uint8_t parity(uint8_t byte) return p; } + +// sums the bytes in the supplied buffer, returns that sum mod 256 +// (i.e. shoved into a uint8_t) +uint8_t sum_of_bytes_in_buffer_mod_256(uint8_t *data, uint16_t count) +{ + uint8_t ret = 0; + for (uint8_t i=0; i. + */ +/* + simulate Hirth EFI system +*/ + +#include "SIM_Aircraft.h" +#include +#include +#include +#include "SIM_EFI_Hirth.h" + +using namespace SITL; + +void EFI_Hirth::update_receive() +{ + const ssize_t num_bytes_read = read_from_autopilot((char*)&receive_buf[receive_buf_ofs], ARRAY_SIZE(receive_buf) - receive_buf_ofs); + if (num_bytes_read < 0) { + return; + } + receive_buf_ofs += num_bytes_read; + + if (receive_buf_ofs < 1) { + return; + } + + const uint8_t expected_bytes_in_message = receive_buf[0]; + + if (expected_bytes_in_message == 0) { + AP_HAL::panic("zero bytes expected is unexpected"); + } + + if (expected_bytes_in_message > ARRAY_SIZE(receive_buf)) { + AP_HAL::panic("Unexpectedly large byte count"); + } + + if (receive_buf_ofs < expected_bytes_in_message) { + return; + } + + // checksum is sum of all bytes except the received checksum: + const uint8_t expected_checksum = 256 - sum_of_bytes_in_buffer_mod_256(receive_buf, expected_bytes_in_message-1); + const uint8_t received_checksum = receive_buf[expected_bytes_in_message-1]; + if (expected_checksum == received_checksum) { + PacketCode received_packet_code = PacketCode(receive_buf[1]); + if (received_packet_code == PacketCode::SetValues) { + // do this synchronously for now + handle_set_values(); + } else { + assert_receive_size(3); + if (requested_data_record.time_ms != 0) { + AP_HAL::panic("Requesting too fast?"); + } + requested_data_record.code = received_packet_code; + requested_data_record.time_ms = AP_HAL::millis(); + } + } else { + AP_HAL::panic("checksum failed"); + // simply throw these bytes away. What the actual device does in the + // face of weird data is unknown. + } + memmove(&receive_buf[0], &receive_buf[expected_bytes_in_message], receive_buf_ofs - expected_bytes_in_message); + receive_buf_ofs -= expected_bytes_in_message; +} + +void EFI_Hirth::assert_receive_size(uint8_t receive_size) +{ + if (receive_buf[0] != receive_size) { + AP_HAL::panic("Expected %u message size, got %u message size", receive_size, receive_buf[0]); + } +} + +void EFI_Hirth::handle_set_values() +{ + assert_receive_size(23); + static_assert(sizeof(settings) == 20, "correct number of bytes in settings"); + memcpy((void*)&settings, &receive_buf[2], sizeof(settings)); +} + +void EFI_Hirth::update_send() +{ + if (requested_data_record.time_ms == 0) { + // no outstanding request + return; + } + if (AP_HAL::millis() - requested_data_record.time_ms < 20) { + // 20ms to service a request + return; + } + requested_data_record.time_ms = 0; + + switch (requested_data_record.code) { + case PacketCode::DataRecord1: + send_record1(); + break; + case PacketCode::DataRecord2: + send_record2(); + break; + case PacketCode::DataRecord3: + send_record3(); + break; + default: + AP_HAL::panic("Unknown data record (%u) requested", (unsigned)requested_data_record.code); + } +} + +void EFI_Hirth::update_engine_model() +{ + auto sitl = AP::sitl(); + + // FIXME: this should come from simulation, not baro. baro gets + // warmed by the simulated electronics! + const float ambient = AP::baro().get_temperature(); + + const uint32_t now_ms = AP_HAL::millis(); + + const float delta_t = (now_ms - engine.last_update_ms) * 1e-6; + engine.last_update_ms = now_ms; + + // lose heat to environment (air-cooling due to airspeed and prop + // airflow could be taken into account here) + const float ENV_LOSS_FACTOR = 25; + engine.cht1_temperature -= (engine.cht1_temperature - ambient) * delta_t * ENV_LOSS_FACTOR; + engine.cht2_temperature -= (engine.cht2_temperature - ambient) * delta_t * ENV_LOSS_FACTOR; + + const float rpm = sitl->state.rpm[2]; + const float RPM_GAIN_FACTOR_CHT1 = 10; + const float RPM_GAIN_FACTOR_CHT2 = 8; + engine.cht1_temperature += rpm * delta_t * RPM_GAIN_FACTOR_CHT1; + engine.cht2_temperature += rpm * delta_t * RPM_GAIN_FACTOR_CHT2; +} + +void EFI_Hirth::init() +{ + // auto sitl = AP::sitl(); + + if (is_zero(AP::baro().get_temperature())) { + // defer until the baro has had a chance to update.... + return; + } + + engine.cht1_temperature = AP::baro().get_temperature(); + engine.cht2_temperature = AP::baro().get_temperature(); + + init_done = true; +} + +void EFI_Hirth::update() +{ + auto sitl = AP::sitl(); + if (!sitl || sitl->efi_type != SIM::EFI_TYPE_HIRTH) { + return; + } + + if (!init_done) { + init(); + } + + // update throttle; interim thing to make life a little more interesting + throttle = 0.9 * throttle + 0.1 * settings.throttle/10; + + update_engine_model(); + + update_receive(); + update_send(); +} + +uint16_t EFI_Hirth::engine_status_field_value() const +{ + return ( + 0U << 0 | // engine temperature sensor + 1U << 1 | // air temperature sensor + 1U << 2 | // air pressure sensor + 1U << 3 // throttle sensor OK + ); +} + +void SITL::EFI_Hirth::send_record1() +{ + const auto *sitl = AP::sitl(); + + // notionally the field updates should happen in the update() + // method, but here to save CPU for now: + auto &r = packed_record1.record; + r.engine_status = engine_status_field_value(); + r.rpm = sitl->state.rpm[0]; + r.air_temperature = AP::baro().get_temperature(); + r.throttle = settings.throttle / 10; // just echo this back + + packed_record1.update_checksum(); + + write_to_autopilot((char*)&packed_record1, sizeof(packed_record1)); + + assert_storage_size _assert_storage_size_Record1; + (void)_assert_storage_size_Record1; +} + +void SITL::EFI_Hirth::send_record2() +{ + const auto *sitl = AP::sitl(); + + // notionally the field updates should happen in the update() + // method, but here to save CPU for now: + auto &r = packed_record2.record; + r.throttle_percent_times_10 = throttle * 10.0; + r.fuel_consumption = ((MAX(sitl->state.rpm[0] - 1500.0, 0)) /2200.0) * 10; // from log, very rough + + packed_record2.update_checksum(); + + write_to_autopilot((char*)&packed_record2, sizeof(packed_record2)); + + assert_storage_size _assert_storage_size_Record2; + (void)_assert_storage_size_Record2; +} + + +void SITL::EFI_Hirth::send_record3() +{ + // notionally the field updates should happen in the update() + // method, but here to save CPU for now: + auto &r = packed_record3.record; + r.excess_temperature_1 = engine.cht1_temperature; // cht1 + r.excess_temperature_2 = engine.cht2_temperature; // cht2 + r.excess_temperature_3 = 39; // egt1 + r.excess_temperature_4 = 41; // egt2 + + packed_record3.update_checksum(); + + write_to_autopilot((char*)&packed_record3, sizeof(packed_record3)); + + assert_storage_size _assert_storage_size_Record3; + (void)_assert_storage_size_Record3; +} diff --git a/libraries/SITL/SIM_EFI_Hirth.h b/libraries/SITL/SIM_EFI_Hirth.h new file mode 100644 index 0000000000000..309ddef6dc6bb --- /dev/null +++ b/libraries/SITL/SIM_EFI_Hirth.h @@ -0,0 +1,240 @@ +/* + This program is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + This program is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with this program. If not, see . + */ +/* + simulate Hirth EFI system + +./Tools/autotest/sim_vehicle.py --gdb --debug -v ArduPlane -A --uartF=sim:hirth --speedup=1 +param set SERIAL5_PROTOCOL 24 +param set SIM_EFI_TYPE 6 +param set EFI_TYPE 6 +reboot +status EFI_STATUS + +./Tools/autotest/autotest.py --gdb --debug build.Plane test.Plane.Hirth + +*/ + +#pragma once + +#include +#include +#include "SIM_SerialDevice.h" + +namespace SITL { + +class EFI_Hirth : public SerialDevice { +public: + + using SerialDevice::SerialDevice; + + void update(); + +private: + + void update_receive(); + void update_send(); + + void assert_receive_size(uint8_t receive_size); + + void handle_set_values(); + + // maps from an on-wire number to a record number: + enum class PacketCode : uint8_t { + DataRecord1 = 4, + DataRecord2 = 11, + DataRecord3 = 13, + SetValues = 201, + }; + + template + class PACKED PackedRecord { + public: + PackedRecord(PacketCode _code, T _record) : + code(uint8_t(_code)), + record(_record) + { } + const uint8_t length { sizeof(T) + 3 }; // 1 each of length, code and checksum + const uint8_t code; + T record; + uint8_t checksum; + + void update() { + record.update(); + update_checksum(); + } + + void update_checksum() { + checksum = 256 - sum_of_bytes_in_buffer_mod_256((uint8_t*)this, length-1); + } + }; + + void send_record1(); + void send_record2(); + void send_record3(); + + class PACKED Record1 { + public: + uint8_t reserved1[2]; + uint16_t save_in_flash; // "1 = data are saved in flash automatically" + uint8_t reserved2[4]; + uint16_t engine_status; + uint16_t rpm; + uint8_t reserved3[12]; + uint16_t number_of_interfering_pulses; + uint16_t reserved4[2]; + uint16_t number_of_speed_errors; + uint16_t injection_time; + uint16_t ignition_angle; + uint16_t reserved5; + uint16_t voltage_throttle; + uint16_t reserved6; + uint8_t reserved7[2]; + uint16_t voltage_engine_temperature; + uint16_t voltage_air_temperature; + uint8_t reserved8[2]; + uint16_t voltage_int_air_pressure; + uint8_t reserved9[20]; + int16_t throttle; + int16_t engine_temperature; + int16_t battery_temperature; + int16_t air_temperature; + int16_t reserved10; + uint16_t sensor_ok; + + void update(); + }; + + class PACKED Record2 { + public: + uint8_t reserved1[12]; + int16_t injection_rate_from_basic_graphic_map; + int16_t reserved2; + int16_t basic_injection_map; + int16_t injection_rate_from_air_correction; + int16_t reserved3; + int16_t injection_rate_from_warming_up_characteristic_curve; + int16_t injection_rate_from_acceleration_enrichment; + int16_t turn_on_time_of_intake_valves; + int16_t injection_rate_from_race_switch; + int16_t reserved4; + int16_t injection_angle_from_ignition_angle_map; + int16_t injection_angle_from_air_temperature_characteristic_curve; + int16_t injection_angle_from_air_pressure_characteristic_curve; + int16_t ignition_angle_from_engine_temperature_characteristic_curve; + int16_t ignition_angle_from_acceleration; + int16_t ignition_angle_from_race_switch; + uint32_t total_time_in_26ms; + uint32_t total_number_of_rotations; + uint16_t fuel_consumption; + uint16_t number_of_errors_in_error_memory; + int16_t voltage_input1_throttle_target; + int16_t reserved5; + int16_t position_throttle_target; + uint16_t throttle_percent_times_10; // percent * 10 + int16_t reserved6[3]; + uint16_t time_of_injector_opening_percent_times_10; + uint8_t reserved7[10]; + uint32_t no_of_logged_data; + uint8_t reserved8[12]; + }; + + class PACKED Record3 { + public: + uint16_t voltage_excess_temperature_1; + uint16_t voltage_excess_temperature_2; + uint16_t voltage_excess_temperature_3; + uint16_t voltage_excess_temperature_4; + uint16_t voltage_excess_temperature_5; + uint8_t reserved1[6]; + uint16_t excess_temperature_1; // cht1 + uint16_t excess_temperature_2; // cht2 + uint16_t excess_temperature_3; // egt1 + uint16_t excess_temperature_4; // egt2 + uint16_t excess_temperature_5; + uint8_t reserved2[6]; + uint16_t enrichment_excess_temperature_cylinder_1; + uint16_t enrichment_excess_temperature_cylinder_2; + uint16_t enrichment_excess_temperature_cylinder_3; + uint16_t enrichment_excess_temperature_cylinder_4; + uint8_t reserved3[6]; + uint16_t enrichment_excess_temperature_bitfield; + uint16_t mixing_ratio_oil_pump1; + uint16_t mixing_ratio_oil_pump2; + uint16_t ouput_value_water_pump; + uint16_t ouput_value_fuel_pump; + uint16_t ouput_value_exhaust_valve; + uint16_t ouput_value_air_vane; + uint16_t ouput_value_e_throttle; + uint16_t number_of_injections_oil_pump_1; + uint32_t system_time_in_ms; + uint16_t number_of_injections_oil_pump_2; + uint16_t target_rpm; + uint16_t FPC; + // these appear to be duplicates of the above; one is probably + // voltage? + uint16_t xenrichment_excess_temperature_cylinder_1; + uint16_t xenrichment_excess_temperature_cylinder_2; + uint16_t xenrichment_excess_temperature_cylinder_3; + uint16_t xenrichment_excess_temperature_cylinder_4; + uint16_t voltage_input_temperature_crankshaft_housing; + uint16_t temperature_crankshaft_housing; + uint8_t reserved4[14]; + }; + + class PACKED SetValues { + public: + int16_t throttle; // percent * 10 + int16_t rpm;; + int8_t reserved1[16]; + }; + + // these records are just used for initial values of the fields; + // they aren't used past that. + Record1 record1; + Record2 record2; + Record3 record3; + + + SetValues settings; + + PackedRecord packed_record1{PacketCode::DataRecord1, record1}; + PackedRecord packed_record2{PacketCode::DataRecord2, record2}; + PackedRecord packed_record3{PacketCode::DataRecord3, record3}; + + struct { + PacketCode code; // code which was requested by driver + uint32_t time_ms; // time that code was requested by driver + } requested_data_record; + + uint8_t receive_buf[32]; + uint8_t receive_buf_ofs; + + float throttle; + + uint16_t engine_status_field_value() const; + + void init(); + bool init_done = false; + + // engine model: + void update_engine_model(); + struct { + float cht1_temperature; // engine reports in deg-C + float cht2_temperature; + uint32_t last_update_ms; + } engine; +}; + +} diff --git a/libraries/SITL/SIM_EFI_MegaSquirt.cpp b/libraries/SITL/SIM_EFI_MegaSquirt.cpp index 7aa29ff22911c..2935024ce0b0a 100644 --- a/libraries/SITL/SIM_EFI_MegaSquirt.cpp +++ b/libraries/SITL/SIM_EFI_MegaSquirt.cpp @@ -20,6 +20,7 @@ #include #include #include +#include "SIM_EFI_MegaSquirt.h" using namespace SITL; @@ -37,19 +38,21 @@ static uint32_t CRC32_MS(const uint8_t *buf, uint32_t len) void EFI_MegaSquirt::update() { auto sitl = AP::sitl(); - if (!sitl || sitl->efi_type == SIM::EFI_TYPE_NONE) { + if (!sitl || sitl->efi_type != SIM::EFI_TYPE_MS) { return; } - float rpm = sitl->state.rpm[0]; + const float rpm = sitl->state.rpm[2]; + + tps = 0.9 * tps + 0.1 * (rpm / 7000) * 100; table7.rpm = rpm; table7.fuelload = 20; table7.dwell = 2.0; table7.baro_hPa = 1000; table7.map_hPa = 895; - table7.mat_cF = 3013; + table7.mat_cF = C_TO_F(AP::baro().get_temperature()) * 10; table7.fuelPressure = 6280; - table7.throttle_pos = 580; + table7.throttle_pos = tps * 10; table7.ct_cF = 3940; table7.afr_target1 = 148; diff --git a/libraries/SITL/SIM_EFI_MegaSquirt.h b/libraries/SITL/SIM_EFI_MegaSquirt.h index f957a296c751f..813e22e5e65d9 100644 --- a/libraries/SITL/SIM_EFI_MegaSquirt.h +++ b/libraries/SITL/SIM_EFI_MegaSquirt.h @@ -96,6 +96,8 @@ class EFI_MegaSquirt : public SerialDevice { uint8_t pad[128-67]; uint16_t fuelPressure; } table7; + + float tps; }; } diff --git a/libraries/SITL/SITL.h b/libraries/SITL/SITL.h index 4209fe06d1475..6c51f016753e9 100644 --- a/libraries/SITL/SITL.h +++ b/libraries/SITL/SITL.h @@ -296,6 +296,7 @@ class SIM { enum EFIType { EFI_TYPE_NONE = 0, EFI_TYPE_MS = 1, + EFI_TYPE_HIRTH = 6, }; AP_Int8 efi_type;