CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutSign UpSign In
Ardupilot

Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.

GitHub Repository: Ardupilot/ardupilot
Path: blob/master/libraries/AP_EFI/AP_EFI_NWPMU.h
Views: 1798
1
/*
2
This program is free software: you can redistribute it and/or modify
3
it under the terms of the GNU General Public License as published by
4
the Free Software Foundation, either version 3 of the License, or
5
(at your option) any later version.
6
7
This program is distributed in the hope that it will be useful,
8
but WITHOUT ANY WARRANTY; without even the implied warranty of
9
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
10
GNU General Public License for more details.
11
12
You should have received a copy of the GNU General Public License
13
along with this program. If not, see <http://www.gnu.org/licenses/>.
14
*/
15
/*
16
* AP_EFI_NWPMU.h
17
*
18
* Author: Michael Du Breuil
19
*/
20
21
#pragma once
22
23
#include "AP_EFI_config.h"
24
25
#if AP_EFI_NWPWU_ENABLED
26
27
#include "AP_EFI.h"
28
#include "AP_EFI_Backend.h"
29
30
class AP_EFI_NWPMU : public CANSensor, public AP_EFI_Backend {
31
public:
32
AP_EFI_NWPMU(AP_EFI &_frontend);
33
34
void update() override;
35
36
private:
37
void handle_frame(AP_HAL::CANFrame &frame) override;
38
39
bool _emitted_version;
40
41
enum class NWPMU_ID {
42
GCU = 0x0006C000, // output voltage and current consumption
43
ECU_1 = 0x0CFFF048, // rpm, tps, fuel open, ignition angle
44
ECU_2 = 0x0CFFF148, // baro, MAP, lambda, pressure type
45
ECU_3 = 0x0CFFF248, // analog input 1-4
46
ECU_4 = 0x0CFFF348, // analog input 5-8
47
ECU_5 = 0x0CFFF548, // battery voltage, air temp, coolant temp, temp type
48
ECU_6 = 0x0CFFF648, // analog input 5, 7, version
49
ECU_7 = 0x0CFFF848, // measured lambda 1-2, target lambda
50
ECU_8 = 0x0CFFF948, // PWM ACHT, Blank, Fuel
51
ECU_9 = 0x0CFFFB48, // ignition compensation, cut precent
52
ECU_10 = 0x0CFFFD48, // Fuel comp (accel, starting, air temp, coolant temp)
53
ECU_11 = 0x0CFFFE48, // Fuel comp (baro, MAP)
54
ECU_12 = 0x0CFFD048, // Ignition comp (air temp, cooland temp, MAP)
55
};
56
57
enum class NWPMU_PRESSURE_TYPE {
58
psi = 0,
59
kPa = 1,
60
};
61
62
enum class NWPMU_TEMPERATURE_TYPE {
63
F = 0,
64
C = 1,
65
};
66
67
struct ecu_1 {
68
uint16_t rpm;
69
uint16_t tps;
70
uint16_t fuel_open_time; // 0.01 per bit (ms)
71
uint16_t ignition_angle; // 0.01 per bit (deg)
72
};
73
74
struct ecu_2 {
75
uint16_t baro; // 0.01 per bit
76
uint16_t map; // 0.01 per bit
77
uint16_t lambda; // 0.01 per bit
78
uint8_t pressure_type; // bit 1 is set if kPa, otherwise is PSI
79
};
80
81
struct ecu_3 {
82
uint16_t analog_1; // 0.001 per bit (v)
83
uint16_t analog_2; // 0.001 per bit (v)
84
uint16_t analog_afr; // 0.001 per bit (v)
85
uint16_t analog_blank; // 0.001 per bit (v)
86
};
87
88
struct ecu_4 {
89
uint16_t analog_gen_temp; // 0.001 per bit
90
uint16_t analog_fuel_pres; // 0.001 per bit
91
uint16_t analog_fuel_level; // 0.001 per bit
92
uint16_t analog_baro_pres; // 0.001 per bit
93
};
94
95
struct ecu_5 {
96
uint16_t batt_volt; // 0.01 per bit (v)
97
uint16_t air_temp; // 0.1 per bit
98
uint16_t coolant_temp; // 0.1 per bit
99
uint8_t temp_type; // 0 F, 1 C
100
};
101
102
struct ecu_6 {
103
uint16_t analog_5; // 0.1 per bit
104
uint16_t analog_7; // 0.1 per bit
105
uint8_t firmware_major;
106
uint8_t firmware_minor;
107
uint8_t firmware_build;
108
};
109
};
110
111
#endif // AP_EFI_NWPWU_ENABLED
112
113
114