Book a Demo!
CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutPoliciesSign UpSign In
Ardupilot
GitHub Repository: Ardupilot/ardupilot
Path: blob/master/libraries/AP_EFI/AP_EFI_Loweheiser.cpp
4182 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_Loweheiser.h"
17
18
#if AP_EFI_LOWEHEISER_ENABLED
19
20
#include <AP_Generator/AP_Generator.h>
21
#include <AP_Generator/AP_Generator_Loweheiser.h>
22
23
// The Loweheiser EFI backend can be unhealthy not simply because
24
// we've not gotten an update, but also because it is rejecting our
25
// (mavlink) commands:
26
bool AP_EFI_Loweheiser::healthy() const
27
{
28
AP_Generator *gen = AP::generator();
29
if (gen == nullptr) {
30
return false;
31
}
32
33
AP_Generator_Loweheiser *backend = gen->get_loweheiser();
34
if (backend == nullptr) {
35
return false;
36
}
37
38
if (!backend->good_ack) {
39
return false;
40
}
41
42
return AP_EFI_Backend::healthy();
43
}
44
45
void AP_EFI_Loweheiser::update()
46
{
47
AP_Generator *gen = AP::generator();
48
if (gen == nullptr) {
49
return;
50
}
51
52
AP_Generator_Loweheiser *backend = gen->get_loweheiser();
53
if (backend == nullptr) {
54
return;
55
}
56
57
if (backend->last_packet_received_ms == internal_state.last_updated_ms) {
58
return;
59
}
60
61
// AP_Generator_Loweheiser remembers the last packet we got from
62
// the generator as a convenient way of storing data we may wish
63
// to relay:
64
const mavlink_loweheiser_gov_efi_t &pkt = backend->packet;
65
66
// this list is ordered by the field order in the
67
// LOWEHEISER_GOV_EFI message. These fields become NaN when the
68
// EFI is powered off. This is the case when the generator
69
// control switch is in the "don't run" position.
70
if (isnan(pkt.throttle)) {
71
// this is an integer field in internal_state
72
internal_state.throttle_out = 0;
73
} else {
74
internal_state.throttle_out = pkt.throttle;
75
}
76
// pkt.efi_batt is used in battery monitoring
77
if (isnan(pkt.efi_rpm)) {
78
// this is an integer field in internal_state
79
internal_state.engine_speed_rpm = 0;
80
} else {
81
internal_state.engine_speed_rpm = pkt.efi_rpm;
82
}
83
internal_state.cylinder_status.injection_time_ms = pkt.efi_pw;
84
// we convert to cubic-cm-per-minute here from litres/second here:
85
internal_state.fuel_consumption_rate_cm3pm = pkt.efi_fuel_flow*(1000/60.0);
86
internal_state.estimated_consumed_fuel_volume_cm3 = backend->fuel_consumed() * 1000;;
87
internal_state.intake_manifold_pressure_kpa = pkt.efi_baro;
88
internal_state.intake_manifold_temperature = C_TO_KELVIN(pkt.efi_mat);
89
internal_state.cylinder_status.cylinder_head_temperature = C_TO_KELVIN(pkt.efi_clt);
90
internal_state.cylinder_status.exhaust_gas_temperature = C_TO_KELVIN(pkt.efi_exhaust_gas_temperature);
91
if (isnan(pkt.efi_tps)) {
92
// this is an integer field in internal_state
93
internal_state.throttle_position_percent = 0;
94
} else {
95
internal_state.throttle_position_percent = pkt.efi_tps;
96
}
97
internal_state.ignition_voltage = pkt.efi_batt;
98
99
internal_state.last_updated_ms = backend->last_packet_received_ms;
100
101
// copy the data to the front end
102
copy_to_frontend();
103
}
104
105
#endif // AP_EFI_LOWEHEISER_ENABLED
106
107