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/Tools/AP_Periph/efi.cpp
Views: 1798
1
#include "AP_Periph.h"
2
3
#ifdef HAL_PERIPH_ENABLE_EFI
4
5
/*
6
EFI support
7
*/
8
9
#include <dronecan_msgs.h>
10
11
#ifndef AP_PERIPH_EFI_MAX_RATE
12
// default to 2x the AP_Vehicle rate
13
#define AP_PERIPH_EFI_MAX_RATE 100U
14
#endif
15
16
/*
17
update CAN EFI
18
*/
19
void AP_Periph_FW::can_efi_update(void)
20
{
21
if (!efi.enabled()) {
22
return;
23
}
24
25
#if AP_PERIPH_EFI_MAX_RATE > 0
26
const uint32_t now_ms = AP_HAL::millis();
27
if (now_ms - last_efi_update_ms < (1000U / AP_PERIPH_EFI_MAX_RATE)) {
28
return;
29
}
30
last_efi_update_ms = now_ms;
31
#endif
32
33
efi.update();
34
const uint32_t update_ms = efi.get_last_update_ms();
35
if (!efi.is_healthy() || efi_update_ms == update_ms) {
36
return;
37
}
38
efi_update_ms = update_ms;
39
EFI_State state;
40
efi.get_state(state);
41
42
{
43
/*
44
send status packet
45
*/
46
uavcan_equipment_ice_reciprocating_Status pkt {};
47
48
// state maps 1:1 from Engine_State
49
pkt.state = uint8_t(state.engine_state);
50
51
switch (state.crankshaft_sensor_status) {
52
case Crankshaft_Sensor_Status::NOT_SUPPORTED:
53
break;
54
case Crankshaft_Sensor_Status::OK:
55
pkt.flags |= UAVCAN_EQUIPMENT_ICE_RECIPROCATING_STATUS_FLAG_CRANKSHAFT_SENSOR_ERROR_SUPPORTED;
56
break;
57
case Crankshaft_Sensor_Status::ERROR:
58
pkt.flags |=
59
UAVCAN_EQUIPMENT_ICE_RECIPROCATING_STATUS_FLAG_CRANKSHAFT_SENSOR_ERROR_SUPPORTED |
60
UAVCAN_EQUIPMENT_ICE_RECIPROCATING_STATUS_FLAG_CRANKSHAFT_SENSOR_ERROR;
61
break;
62
}
63
64
switch (state.temperature_status) {
65
case Temperature_Status::NOT_SUPPORTED:
66
break;
67
case Temperature_Status::OK:
68
pkt.flags |= UAVCAN_EQUIPMENT_ICE_RECIPROCATING_STATUS_FLAG_TEMPERATURE_SUPPORTED;
69
break;
70
case Temperature_Status::BELOW_NOMINAL:
71
pkt.flags |=
72
UAVCAN_EQUIPMENT_ICE_RECIPROCATING_STATUS_FLAG_TEMPERATURE_SUPPORTED |
73
UAVCAN_EQUIPMENT_ICE_RECIPROCATING_STATUS_FLAG_TEMPERATURE_BELOW_NOMINAL;
74
break;
75
case Temperature_Status::ABOVE_NOMINAL:
76
pkt.flags |=
77
UAVCAN_EQUIPMENT_ICE_RECIPROCATING_STATUS_FLAG_TEMPERATURE_SUPPORTED |
78
UAVCAN_EQUIPMENT_ICE_RECIPROCATING_STATUS_FLAG_TEMPERATURE_ABOVE_NOMINAL;
79
break;
80
case Temperature_Status::OVERHEATING:
81
pkt.flags |=
82
UAVCAN_EQUIPMENT_ICE_RECIPROCATING_STATUS_FLAG_TEMPERATURE_SUPPORTED |
83
UAVCAN_EQUIPMENT_ICE_RECIPROCATING_STATUS_FLAG_TEMPERATURE_OVERHEATING;
84
break;
85
case Temperature_Status::EGT_ABOVE_NOMINAL:
86
pkt.flags |=
87
UAVCAN_EQUIPMENT_ICE_RECIPROCATING_STATUS_FLAG_TEMPERATURE_SUPPORTED |
88
UAVCAN_EQUIPMENT_ICE_RECIPROCATING_STATUS_FLAG_TEMPERATURE_EGT_ABOVE_NOMINAL;
89
break;
90
}
91
92
switch (state.fuel_pressure_status) {
93
case Fuel_Pressure_Status::NOT_SUPPORTED:
94
break;
95
case Fuel_Pressure_Status::OK:
96
pkt.flags |= UAVCAN_EQUIPMENT_ICE_RECIPROCATING_STATUS_FLAG_FUEL_PRESSURE_SUPPORTED;
97
break;
98
case Fuel_Pressure_Status::BELOW_NOMINAL:
99
pkt.flags |=
100
UAVCAN_EQUIPMENT_ICE_RECIPROCATING_STATUS_FLAG_FUEL_PRESSURE_SUPPORTED |
101
UAVCAN_EQUIPMENT_ICE_RECIPROCATING_STATUS_FLAG_FUEL_PRESSURE_BELOW_NOMINAL;
102
break;
103
case Fuel_Pressure_Status::ABOVE_NOMINAL:
104
pkt.flags |=
105
UAVCAN_EQUIPMENT_ICE_RECIPROCATING_STATUS_FLAG_FUEL_PRESSURE_SUPPORTED |
106
UAVCAN_EQUIPMENT_ICE_RECIPROCATING_STATUS_FLAG_FUEL_PRESSURE_ABOVE_NOMINAL;
107
break;
108
}
109
110
switch (state.oil_pressure_status) {
111
case Oil_Pressure_Status::NOT_SUPPORTED:
112
break;
113
case Oil_Pressure_Status::OK:
114
pkt.flags |= UAVCAN_EQUIPMENT_ICE_RECIPROCATING_STATUS_FLAG_OIL_PRESSURE_SUPPORTED;
115
break;
116
case Oil_Pressure_Status::BELOW_NOMINAL:
117
pkt.flags |=
118
UAVCAN_EQUIPMENT_ICE_RECIPROCATING_STATUS_FLAG_OIL_PRESSURE_SUPPORTED |
119
UAVCAN_EQUIPMENT_ICE_RECIPROCATING_STATUS_FLAG_OIL_PRESSURE_BELOW_NOMINAL;
120
break;
121
case Oil_Pressure_Status::ABOVE_NOMINAL:
122
pkt.flags |=
123
UAVCAN_EQUIPMENT_ICE_RECIPROCATING_STATUS_FLAG_OIL_PRESSURE_SUPPORTED |
124
UAVCAN_EQUIPMENT_ICE_RECIPROCATING_STATUS_FLAG_OIL_PRESSURE_ABOVE_NOMINAL;
125
break;
126
}
127
128
switch (state.detonation_status) {
129
case Detonation_Status::NOT_SUPPORTED:
130
break;
131
case Detonation_Status::NOT_OBSERVED:
132
pkt.flags |=
133
UAVCAN_EQUIPMENT_ICE_RECIPROCATING_STATUS_FLAG_DETONATION_SUPPORTED;
134
break;
135
case Detonation_Status::OBSERVED:
136
pkt.flags |=
137
UAVCAN_EQUIPMENT_ICE_RECIPROCATING_STATUS_FLAG_DETONATION_SUPPORTED |
138
UAVCAN_EQUIPMENT_ICE_RECIPROCATING_STATUS_FLAG_DETONATION_OBSERVED;
139
break;
140
}
141
142
switch (state.misfire_status) {
143
case Misfire_Status::NOT_SUPPORTED:
144
break;
145
case Misfire_Status::NOT_OBSERVED:
146
pkt.flags |=
147
UAVCAN_EQUIPMENT_ICE_RECIPROCATING_STATUS_FLAG_MISFIRE_SUPPORTED;
148
break;
149
case Misfire_Status::OBSERVED:
150
pkt.flags |=
151
UAVCAN_EQUIPMENT_ICE_RECIPROCATING_STATUS_FLAG_MISFIRE_SUPPORTED |
152
UAVCAN_EQUIPMENT_ICE_RECIPROCATING_STATUS_FLAG_MISFIRE_OBSERVED;
153
break;
154
}
155
156
switch (state.debris_status) {
157
case Debris_Status::NOT_SUPPORTED:
158
break;
159
case Debris_Status::NOT_DETECTED:
160
pkt.flags |=
161
UAVCAN_EQUIPMENT_ICE_RECIPROCATING_STATUS_FLAG_DEBRIS_SUPPORTED;
162
break;
163
case Debris_Status::DETECTED:
164
pkt.flags |=
165
UAVCAN_EQUIPMENT_ICE_RECIPROCATING_STATUS_FLAG_DEBRIS_SUPPORTED |
166
UAVCAN_EQUIPMENT_ICE_RECIPROCATING_STATUS_FLAG_DEBRIS_DETECTED;
167
break;
168
}
169
170
pkt.engine_load_percent = state.engine_load_percent;
171
pkt.engine_speed_rpm = state.engine_speed_rpm;
172
pkt.spark_dwell_time_ms = state.spark_dwell_time_ms;
173
pkt.atmospheric_pressure_kpa = state.atmospheric_pressure_kpa;
174
pkt.intake_manifold_pressure_kpa = state.intake_manifold_pressure_kpa;
175
pkt.intake_manifold_temperature = state.intake_manifold_temperature;
176
pkt.coolant_temperature = state.coolant_temperature;
177
pkt.oil_pressure = state.oil_pressure;
178
pkt.oil_temperature = state.oil_temperature;
179
pkt.fuel_pressure = state.fuel_pressure;
180
pkt.fuel_consumption_rate_cm3pm = state.fuel_consumption_rate_cm3pm;
181
pkt.estimated_consumed_fuel_volume_cm3 = state.estimated_consumed_fuel_volume_cm3;
182
pkt.throttle_position_percent = state.throttle_position_percent;
183
pkt.ecu_index = state.ecu_index;
184
pkt.spark_plug_usage = uint8_t(state.spark_plug_usage);
185
186
// assume single set of cylinder status
187
pkt.cylinder_status.len = 1;
188
auto &c = pkt.cylinder_status.data[0];
189
const auto &state_c = state.cylinder_status;
190
c.ignition_timing_deg = state_c.ignition_timing_deg;
191
c.injection_time_ms = state_c.injection_time_ms;
192
c.cylinder_head_temperature = state_c.cylinder_head_temperature;
193
c.exhaust_gas_temperature = state_c.exhaust_gas_temperature;
194
c.lambda_coefficient = state_c.lambda_coefficient;
195
196
uint8_t buffer[UAVCAN_EQUIPMENT_ICE_RECIPROCATING_STATUS_MAX_SIZE];
197
const uint16_t total_size = uavcan_equipment_ice_reciprocating_Status_encode(&pkt, buffer, !canfdout());
198
199
canard_broadcast(UAVCAN_EQUIPMENT_ICE_RECIPROCATING_STATUS_SIGNATURE,
200
UAVCAN_EQUIPMENT_ICE_RECIPROCATING_STATUS_ID,
201
CANARD_TRANSFER_PRIORITY_LOW,
202
&buffer[0],
203
total_size);
204
}
205
}
206
207
#endif // HAL_PERIPH_ENABLE_EFI
208
209