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_NWPMU.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*/14/*15* AP_EFI_NWPMU.h16*17* Author: Michael Du Breuil18*/1920#pragma once2122#include "AP_EFI_config.h"2324#if AP_EFI_NWPWU_ENABLED2526#include "AP_EFI.h"27#include "AP_EFI_Backend.h"2829class AP_EFI_NWPMU : public CANSensor, public AP_EFI_Backend {30public:31AP_EFI_NWPMU(AP_EFI &_frontend);3233void update() override;3435private:36void handle_frame(AP_HAL::CANFrame &frame) override;3738bool _emitted_version;3940enum class NWPMU_ID {41GCU = 0x0006C000, // output voltage and current consumption42ECU_1 = 0x0CFFF048, // rpm, tps, fuel open, ignition angle43ECU_2 = 0x0CFFF148, // baro, MAP, lambda, pressure type44ECU_3 = 0x0CFFF248, // analog input 1-445ECU_4 = 0x0CFFF348, // analog input 5-846ECU_5 = 0x0CFFF548, // battery voltage, air temp, coolant temp, temp type47ECU_6 = 0x0CFFF648, // analog input 5, 7, version48ECU_7 = 0x0CFFF848, // measured lambda 1-2, target lambda49ECU_8 = 0x0CFFF948, // PWM ACHT, Blank, Fuel50ECU_9 = 0x0CFFFB48, // ignition compensation, cut precent51ECU_10 = 0x0CFFFD48, // Fuel comp (accel, starting, air temp, coolant temp)52ECU_11 = 0x0CFFFE48, // Fuel comp (baro, MAP)53ECU_12 = 0x0CFFD048, // Ignition comp (air temp, cooland temp, MAP)54};5556enum class NWPMU_PRESSURE_TYPE {57psi = 0,58kPa = 1,59};6061enum class NWPMU_TEMPERATURE_TYPE {62F = 0,63C = 1,64};6566struct ecu_1 {67uint16_t rpm;68uint16_t tps;69uint16_t fuel_open_time; // 0.01 per bit (ms)70uint16_t ignition_angle; // 0.01 per bit (deg)71};7273struct ecu_2 {74uint16_t baro; // 0.01 per bit75uint16_t map; // 0.01 per bit76uint16_t lambda; // 0.01 per bit77uint8_t pressure_type; // bit 1 is set if kPa, otherwise is PSI78};7980struct ecu_3 {81uint16_t analog_1; // 0.001 per bit (v)82uint16_t analog_2; // 0.001 per bit (v)83uint16_t analog_afr; // 0.001 per bit (v)84uint16_t analog_blank; // 0.001 per bit (v)85};8687struct ecu_4 {88uint16_t analog_gen_temp; // 0.001 per bit89uint16_t analog_fuel_pres; // 0.001 per bit90uint16_t analog_fuel_level; // 0.001 per bit91uint16_t analog_baro_pres; // 0.001 per bit92};9394struct ecu_5 {95uint16_t batt_volt; // 0.01 per bit (v)96uint16_t air_temp; // 0.1 per bit97uint16_t coolant_temp; // 0.1 per bit98uint8_t temp_type; // 0 F, 1 C99};100101struct ecu_6 {102uint16_t analog_5; // 0.1 per bit103uint16_t analog_7; // 0.1 per bit104uint8_t firmware_major;105uint8_t firmware_minor;106uint8_t firmware_build;107};108};109110#endif // AP_EFI_NWPWU_ENABLED111112113114