Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Path: blob/master/libraries/AP_EFI/AP_EFI_Serial_Hirth.h
Views: 1798
/*1This program is free software: you can redistribute it and/or modify2it under the terms of the GNU General Public License as published by3the Free Software Foundation, either version 3 of the License, or4(at your option) any later version.56This program is distributed in the hope that it will be useful,7but WITHOUT ANY WARRANTY; without even the implied warranty of8MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the9GNU General Public License for more details.1011You should have received a copy of the GNU General Public License12along with this program. If not, see <http://www.gnu.org/licenses/>.13*/141516#pragma once1718#include "AP_EFI_config.h"1920#if AP_EFI_SERIAL_HIRTH_ENABLED21#include "AP_EFI.h"22#include "AP_EFI_Backend.h"2324/*!25* class definition for Hirth 4103 ECU26*/27class AP_EFI_Serial_Hirth: public AP_EFI_Backend {28public:29AP_EFI_Serial_Hirth(AP_EFI &_frontend);3031void update() override;3233enum class Error_Excess_Temp_Bitfield : uint16_t {34CHT_1_LOW = 1U<<0, // true if CHT1 is too low35CHT_1_HIGH = 1U<<1, // true if CHT1 is too high36CHT_1_ENRC_ACTIVE = 1U<<2, // true if CHT1 Enrichment is active37CHT_2_LOW = 1U<<3, // true if CHT2 is too low38CHT_2_HIGH = 1U<<4, // true if CHT2 is too high39CHT_2_ENRC_ACTIVE = 1U<<5, // true if CHT2 Enrichment is active40EGT_1_LOW = 1U<<6, // true if EGT1 is too low41EGT_1_HIGH = 1U<<7, // true if EGT1 is too high42EGT_1_ENRC_ACTIVE = 1U<<8, // true if EGT1 Enrichment is active43EGT_2_LOW = 1U<<9, // true if EGT2 is too low44EGT_2_HIGH = 1U<<10, // true if EGT2 is too high45EGT_2_ENRC_ACTIVE = 1U<<11, // true if EGT2 Enrichment is active46};4748enum class Sensor_Status_Bitfield : uint8_t {49ENGINE_TEMP_SENSOR_OK = 1U<<1, // true if engine temperature sensor is OK50AIR_TEMP_SENSOR_OK = 1U<<2, // true if air temperature sensor is OK51AIR_PRESSURE_SENSOR_OK = 1U<<3, // true if intake air pressure sensor is OK52THROTTLE_SENSOR_OK = 1U<<4, // true if throttle sensor is OK53};5455private:56// serial port instance57AP_HAL::UARTDriver *port;5859// periodic refresh60uint32_t last_request_ms;61uint32_t last_packet_ms;62uint32_t last_req_send_throttle_ms;6364// raw bytes - max size65uint8_t raw_data[256];6667// request and response data68uint8_t requested_code;6970// meta-data for a response71struct {72uint8_t quantity;73uint8_t code;74uint8_t checksum;75} res_data;7677// TRUE - Request is sent; waiting for response78// FALSE - Response is already received79bool waiting_response;8081// Expected bytes from response82uint8_t expected_bytes;8384// Throttle values85uint16_t last_throttle;86uint16_t throttle_to_hirth;8788uint32_t last_fuel_integration_ms;8990// custom status for Hirth91uint16_t sensor_status;9293uint16_t error_excess_temperature;94uint32_t crc_fail_cnt;95uint32_t uptime;96uint32_t ack_fail_cnt;9798struct PACKED Record1 {99uint8_t reserved1[2];100uint16_t save_in_flash; // "1 = data are saved in flash automatically"101uint8_t reserved2[4];102uint16_t engine_status;103uint16_t rpm;104uint8_t reserved3[12];105uint16_t number_of_interfering_pulses;106uint16_t reserved4[2];107uint16_t number_of_speed_errors;108uint16_t injection_time;109uint16_t ignition_angle;110uint16_t reserved5;111uint16_t voltage_throttle;112uint16_t reserved6;113uint8_t reserved7[2];114uint16_t voltage_engine_temperature;115uint16_t voltage_air_temperature;116uint8_t reserved8[2];117uint16_t voltage_int_air_pressure;118uint8_t reserved9[20];119int16_t throttle;120int16_t engine_temperature;121int16_t battery_voltage;122int16_t air_temperature;123int16_t reserved10;124uint16_t sensor_ok;125};126static_assert(sizeof(Record1) == 84, "incorrect Record1 length");127128struct PACKED Record2 {129uint8_t reserved1[12];130int16_t injection_rate_from_basic_graphic_map;131int16_t reserved2;132int16_t basic_injection_rate;133int16_t injection_rate_from_air_correction;134int16_t reserved3;135int16_t injection_rate_from_warming_up_characteristic_curve;136int16_t injection_rate_from_acceleration_enrichment;137int16_t turn_on_time_of_intake_valves;138int16_t injection_rate_from_race_switch;139int16_t reserved4;140int16_t injection_angle_from_ignition_graphic_map;141int16_t injection_angle_from_air_temperature_characteristic_curve;142int16_t injection_angle_from_air_pressure_characteristic_curve;143int16_t ignition_angle_from_engine_temperature_characteristic_curve;144int16_t ignition_angle_from_acceleration;145int16_t ignition_angle_from_race_switch;146uint32_t total_time_in_26ms;147uint32_t total_number_of_rotations;148uint16_t fuel_consumption;149uint16_t number_of_errors_in_error_memory;150int16_t voltage_input1_throttle_target;151int16_t reserved5;152int16_t position_throttle_target;153int16_t throttle_percent_times_10; // percent * 0.1154int16_t reserved6[3];155uint16_t time_of_injector_opening_percent_times_10;156uint8_t reserved7[10];157uint32_t no_of_logged_data;158uint8_t reserved8[12];159};160static_assert(sizeof(Record2) == 98, "incorrect Record2 length");161162struct PACKED Record3 {163int16_t voltage_excess_temperature_1;164int16_t voltage_excess_temperature_2;165int16_t voltage_excess_temperature_3;166int16_t voltage_excess_temperature_4;167int16_t voltage_excess_temperature_5;168uint8_t reserved1[6];169int16_t excess_temperature_1; // cht1170int16_t excess_temperature_2; // cht2171int16_t excess_temperature_3; // egt1172int16_t excess_temperature_4; // egt2173int16_t excess_temperature_5;174uint8_t reserved2[6];175int16_t enrichment_excess_temperature_cylinder_1;176int16_t enrichment_excess_temperature_cylinder_2;177int16_t enrichment_excess_temperature_cylinder_3;178int16_t enrichment_excess_temperature_cylinder_4;179uint8_t reserved3[6];180uint16_t error_excess_temperature_bitfield;181uint16_t mixing_ratio_oil_pump1;182uint16_t mixing_ratio_oil_pump2;183uint16_t ouput_value_water_pump;184uint16_t ouput_value_fuel_pump;185uint16_t ouput_value_exhaust_valve;186uint16_t ouput_value_air_vane;187uint16_t ouput_value_e_throttle;188uint16_t number_of_injections_oil_pump_1;189uint32_t system_time_in_ms;190int16_t number_of_injections_oil_pump_2;191uint16_t target_rpm;192uint16_t FPC;193uint16_t xenrichment_excess_temperature_cylinder_1;194uint16_t xenrichment_excess_temperature_cylinder_2;195uint16_t xenrichment_excess_temperature_cylinder_3;196uint16_t xenrichment_excess_temperature_cylinder_4;197uint16_t voltage_input_temperature_crankshaft_housing;198int16_t temperature_crankshaft_housing;199uint8_t reserved4[14];200};201static_assert(sizeof(Record3) == 100, "incorrect Record3 length");202203void check_response();204void send_request();205void decode_data();206bool send_request_status();207bool send_target_values(uint16_t);208void log_status();209};210211#endif // AP_EFI_SERIAL_HIRTH_ENABLED212213214