Book a Demo!
CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutPoliciesSign UpSign In
Ardupilot
GitHub Repository: Ardupilot/ardupilot
Path: blob/master/libraries/AP_EFI/AP_EFI.cpp
9534 views
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
#include "AP_EFI.h"
17
18
#if HAL_EFI_ENABLED
19
20
#include "AP_EFI_Serial_MS.h"
21
#include "AP_EFI_Serial_Lutan.h"
22
#include "AP_EFI_NWPMU.h"
23
#include "AP_EFI_DroneCAN.h"
24
#include "AP_EFI_Currawong_ECU.h"
25
#include "AP_EFI_Serial_Hirth.h"
26
#include "AP_EFI_Loweheiser.h"
27
#include "AP_EFI_Scripting.h"
28
#include "AP_EFI_MAV.h"
29
30
#include <AP_Logger/AP_Logger.h>
31
#include <GCS_MAVLink/GCS.h>
32
#include <AP_Math/AP_Math.h>
33
34
#if HAL_MAX_CAN_PROTOCOL_DRIVERS
35
#include <AP_CANManager/AP_CANManager.h>
36
#endif
37
38
extern const AP_HAL::HAL& hal;
39
40
// table of user settable parameters
41
const AP_Param::GroupInfo AP_EFI::var_info[] = {
42
// @Param: _TYPE
43
// @DisplayName: EFI communication type
44
// @Description: What method of communication is used for EFI #1
45
// @Values: 0:None,1:Serial-MS,2:NWPMU,3:Serial-Lutan,4:Loweheiser,5:DroneCAN,6:Currawong-ECU,7:Scripting,8:Hirth,9:MAVLink
46
// @User: Advanced
47
// @RebootRequired: True
48
AP_GROUPINFO_FLAGS("_TYPE", 1, AP_EFI, type, 0, AP_PARAM_FLAG_ENABLE),
49
50
// @Param: _COEF1
51
// @DisplayName: EFI Calibration Coefficient 1
52
// @Description: Used to calibrate fuel flow for MS protocol (Slope). This should be calculated from a log at constant fuel usage rate. Plot (ECYL[0].InjT*EFI.Rpm)/600.0 to get the duty_cycle. Measure actual fuel usage in cm^3/min, and set EFI_COEF1 = fuel_usage_cm3permin / duty_cycle
53
// @Range: 0 1
54
// @User: Advanced
55
AP_GROUPINFO("_COEF1", 2, AP_EFI, coef1, 0),
56
57
// @Param: _COEF2
58
// @DisplayName: EFI Calibration Coefficient 2
59
// @Description: Used to calibrate fuel flow for MS protocol (Offset). This can be used to correct for a non-zero offset in the fuel consumption calculation of EFI_COEF1
60
// @Range: 0 10
61
// @User: Advanced
62
AP_GROUPINFO("_COEF2", 3, AP_EFI, coef2, 0),
63
64
// @Param: _FUEL_DENS
65
// @DisplayName: ECU Fuel Density
66
// @Description: Used to calculate fuel consumption
67
// @Units: kg/m/m/m
68
// @Range: 0 10000
69
// @User: Advanced
70
AP_GROUPINFO("_FUEL_DENS", 4, AP_EFI, ecu_fuel_density, 0),
71
72
#if AP_EFI_THROTTLE_LINEARISATION_ENABLED
73
// @Group: _THRLIN
74
// @Path: AP_EFI_ThrottleLinearisation.cpp
75
AP_SUBGROUPINFO(throttle_linearisation, "_THRLIN", 5, AP_EFI, AP_EFI_ThrLin),
76
#endif
77
78
AP_GROUPEND
79
};
80
81
AP_EFI *AP_EFI::singleton;
82
83
// Initialize parameters
84
AP_EFI::AP_EFI()
85
{
86
singleton = this;
87
AP_Param::setup_object_defaults(this, var_info);
88
}
89
90
// Initialize backends based on existing params
91
void AP_EFI::init(void)
92
{
93
if (backend != nullptr) {
94
// Init called twice, perhaps
95
return;
96
}
97
switch ((Type)type.get()) {
98
case Type::NONE:
99
break;
100
#if AP_EFI_SERIAL_MS_ENABLED
101
case Type::MegaSquirt:
102
backend = NEW_NOTHROW AP_EFI_Serial_MS(*this);
103
break;
104
#endif
105
#if AP_EFI_SERIAL_LUTAN_ENABLED
106
case Type::Lutan:
107
backend = NEW_NOTHROW AP_EFI_Serial_Lutan(*this);
108
break;
109
#endif
110
#if AP_EFI_LOWEHEISER_ENABLED
111
case Type::LOWEHEISER:
112
backend = NEW_NOTHROW AP_EFI_Loweheiser(*this);
113
break;
114
#endif
115
#if AP_EFI_NWPWU_ENABLED
116
case Type::NWPMU:
117
backend = NEW_NOTHROW AP_EFI_NWPMU(*this);
118
break;
119
#endif
120
#if AP_EFI_DRONECAN_ENABLED
121
case Type::DroneCAN:
122
backend = NEW_NOTHROW AP_EFI_DroneCAN(*this);
123
break;
124
#endif
125
#if AP_EFI_CURRAWONG_ECU_ENABLED
126
case Type::CurrawongECU:
127
backend = NEW_NOTHROW AP_EFI_Currawong_ECU(*this);
128
break;
129
#endif
130
#if AP_EFI_SCRIPTING_ENABLED
131
case Type::SCRIPTING:
132
backend = NEW_NOTHROW AP_EFI_Scripting(*this);
133
break;
134
#endif
135
#if AP_EFI_SERIAL_HIRTH_ENABLED
136
case Type::Hirth:
137
backend = NEW_NOTHROW AP_EFI_Serial_Hirth(*this);
138
break;
139
#endif
140
#if AP_EFI_MAV_ENABLED
141
case Type::MAV:
142
backend = NEW_NOTHROW AP_EFI_MAV(*this);
143
break;
144
#endif
145
default:
146
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Unknown EFI type");
147
break;
148
}
149
}
150
151
// Ask all backends to update the frontend
152
void AP_EFI::update()
153
{
154
if (backend) {
155
backend->update();
156
#if HAL_LOGGING_ENABLED
157
log_status();
158
#endif
159
}
160
}
161
162
bool AP_EFI::is_healthy(void) const
163
{
164
if (backend == nullptr) {
165
return false;
166
}
167
return backend->healthy();
168
}
169
170
#if HAL_LOGGING_ENABLED
171
/*
172
write status to log
173
*/
174
void AP_EFI::log_status(void)
175
{
176
// @LoggerMessage: EFI
177
// @Description: Electronic Fuel Injection system data
178
// @Field: TimeUS: Time since system startup
179
// @Field: LP: Reported engine load
180
// @Field: Rpm: Reported engine RPM
181
// @Field: SDT: Spark Dwell Time
182
// @Field: ATM: Atmospheric pressure
183
// @Field: IMP: Intake manifold pressure
184
// @Field: IMT: Intake manifold temperature
185
// @Field: ECT: Engine Coolant Temperature
186
// @Field: OilP: Oil Pressure
187
// @Field: OilT: Oil temperature
188
// @Field: FP: Fuel Pressure
189
// @Field: FCR: Fuel Consumption Rate
190
// @Field: CFV: Consumed fuel volume
191
// @Field: TPS: Throttle Position
192
// @Field: IDX: Index of the publishing ECU
193
AP::logger().WriteStreaming("EFI",
194
"TimeUS,LP,Rpm,SDT,ATM,IMP,IMT,ECT,OilP,OilT,FP,FCR,CFV,TPS,IDX",
195
"s%qsPPOOPOP--%-",
196
"F00C--00-0-0000",
197
"QBIffffffffffBB",
198
AP_HAL::micros64(),
199
uint8_t(state.engine_load_percent),
200
uint32_t(state.engine_speed_rpm),
201
float(state.spark_dwell_time_ms),
202
float(state.atmospheric_pressure_kpa),
203
float(state.intake_manifold_pressure_kpa),
204
float(state.intake_manifold_temperature),
205
float(state.coolant_temperature),
206
float(state.oil_pressure),
207
float(state.oil_temperature),
208
float(state.fuel_pressure),
209
float(state.fuel_consumption_rate_cm3pm),
210
float(state.estimated_consumed_fuel_volume_cm3),
211
uint8_t(state.throttle_position_percent),
212
uint8_t(state.ecu_index));
213
214
// @LoggerMessage: EFI2
215
// @Description: Electronic Fuel Injection system data - redux
216
// @Field: TimeUS: Time since system startup
217
// @Field: Healthy: True if EFI is healthy
218
// @Field: ES: Engine state
219
// @Field: GE: General error
220
// @Field: CSE: Crankshaft sensor status
221
// @Field: TS: Temperature status
222
// @Field: FPS: Fuel pressure status
223
// @Field: OPS: Oil pressure status
224
// @Field: DS: Detonation status
225
// @Field: MS: Misfire status
226
// @Field: DebS: Debris status
227
// @Field: SPU: Spark plug usage
228
// @Field: IDX: Index of the publishing ECU
229
AP::logger().WriteStreaming("EFI2",
230
"TimeUS,Healthy,ES,GE,CSE,TS,FPS,OPS,DS,MS,DebS,SPU,IDX",
231
"s------------",
232
"F------------",
233
"QBBBBBBBBBBBB",
234
AP_HAL::micros64(),
235
uint8_t(is_healthy()),
236
uint8_t(state.engine_state),
237
uint8_t(state.general_error),
238
uint8_t(state.crankshaft_sensor_status),
239
uint8_t(state.temperature_status),
240
uint8_t(state.fuel_pressure_status),
241
uint8_t(state.oil_pressure_status),
242
uint8_t(state.detonation_status),
243
uint8_t(state.misfire_status),
244
uint8_t(state.debris_status),
245
uint8_t(state.spark_plug_usage),
246
uint8_t(state.ecu_index));
247
248
// @LoggerMessage: ECYL
249
// @Description: EFI per-cylinder information
250
// @Field: TimeUS: Time since system startup
251
// @Field: Inst: Cylinder this data belongs to
252
// @Field: IgnT: Ignition timing
253
// @Field: InjT: Injection time
254
// @Field: CHT: Cylinder head temperature
255
// @Field: EGT: Exhaust gas temperature
256
// @Field: Lambda: Estimated lambda coefficient (dimensionless ratio)
257
// @Field: CHT2: Cylinder2 head temperature
258
// @Field: EGT2: Cylinder2 Exhaust gas temperature
259
// @Field: IDX: Index of the publishing ECU
260
AP::logger().WriteStreaming("ECYL",
261
"TimeUS,Inst,IgnT,InjT,CHT,EGT,Lambda,CHT2,EGT2,IDX",
262
"s#dsOO-OO-",
263
"F-0C000000",
264
"QBffffffff",
265
AP_HAL::micros64(),
266
0,
267
state.cylinder_status.ignition_timing_deg,
268
state.cylinder_status.injection_time_ms,
269
KELVIN_TO_C(state.cylinder_status.cylinder_head_temperature),
270
KELVIN_TO_C(state.cylinder_status.exhaust_gas_temperature),
271
state.cylinder_status.lambda_coefficient,
272
KELVIN_TO_C(state.cylinder_status.cylinder_head_temperature2),
273
KELVIN_TO_C(state.cylinder_status.exhaust_gas_temperature2),
274
state.ecu_index);
275
}
276
#endif // LOGGING_ENABLED
277
278
/*
279
send EFI_STATUS
280
*/
281
void AP_EFI::send_mavlink_status(mavlink_channel_t chan)
282
{
283
if (!backend) {
284
return;
285
}
286
287
float ignition_voltage;
288
if (isnan(state.ignition_voltage) ||
289
is_equal(state.ignition_voltage, -1.0f)) {
290
// zero means "unknown" in mavlink, 0.0001 means 0 volts
291
ignition_voltage = 0;
292
} else if (is_zero(state.ignition_voltage)) {
293
// zero means "unknown" in mavlink, 0.0001 means 0 volts
294
ignition_voltage = 0.0001f;
295
} else {
296
ignition_voltage = state.ignition_voltage;
297
};
298
299
// If fuel pressure is supported, but is exactly zero, shift it to 0.0001
300
// to indicate that it is supported.
301
float fuel_pressure = state.fuel_pressure;
302
if (is_zero(fuel_pressure) && state.fuel_pressure_status != Fuel_Pressure_Status::NOT_SUPPORTED) {
303
fuel_pressure = 0.0001;
304
}
305
306
mavlink_msg_efi_status_send(
307
chan,
308
AP_EFI::is_healthy(),
309
state.ecu_index,
310
state.engine_speed_rpm,
311
state.estimated_consumed_fuel_volume_cm3,
312
state.fuel_consumption_rate_cm3pm,
313
state.engine_load_percent,
314
state.throttle_position_percent,
315
state.spark_dwell_time_ms,
316
state.atmospheric_pressure_kpa,
317
state.intake_manifold_pressure_kpa,
318
KELVIN_TO_C(state.intake_manifold_temperature),
319
KELVIN_TO_C(state.cylinder_status.cylinder_head_temperature),
320
state.cylinder_status.ignition_timing_deg,
321
state.cylinder_status.injection_time_ms,
322
KELVIN_TO_C(state.cylinder_status.exhaust_gas_temperature),
323
state.throttle_out,
324
state.pt_compensation,
325
ignition_voltage,
326
fuel_pressure
327
);
328
}
329
330
// get a copy of state structure
331
void AP_EFI::get_state(EFI_State &_state)
332
{
333
WITH_SEMAPHORE(sem);
334
_state = state;
335
}
336
337
void AP_EFI::handle_EFI_message(const mavlink_message_t &msg) {
338
if (backend != nullptr) {
339
backend->handle_EFI_message(msg);
340
}
341
}
342
343
namespace AP {
344
AP_EFI *EFI()
345
{
346
return AP_EFI::get_singleton();
347
}
348
}
349
350
#endif // HAL_EFI_ENABLED
351
352
353