2 // MESSAGE EFI_STATUS PACKING
4 #define MAVLINK_MSG_ID_EFI_STATUS 225
7 typedef struct __mavlink_efi_status_t
{
8 float ecu_index
; /*< ECU index*/
10 float fuel_consumed
; /*< [cm^3] Fuel consumed*/
11 float fuel_flow
; /*< [cm^3/min] Fuel flow rate*/
12 float engine_load
; /*< [%] Engine load*/
13 float throttle_position
; /*< [%] Throttle position*/
14 float spark_dwell_time
; /*< [ms] Spark dwell time*/
15 float barometric_pressure
; /*< [kPa] Barometric pressure*/
16 float intake_manifold_pressure
; /*< [kPa] Intake manifold pressure(*/
17 float intake_manifold_temperature
; /*< [degC] Intake manifold temperature*/
18 float cylinder_head_temperature
; /*< [degC] Cylinder head temperature*/
19 float ignition_timing
; /*< [deg] Ignition timing (Crank angle degrees)*/
20 float injection_time
; /*< [ms] Injection time*/
21 float exhaust_gas_temperature
; /*< [degC] Exhaust gas temperature*/
22 float throttle_out
; /*< [%] Output throttle*/
23 float pt_compensation
; /*< Pressure/temperature compensation*/
24 uint8_t health
; /*< EFI health status*/
25 } mavlink_efi_status_t
;
27 #define MAVLINK_MSG_ID_EFI_STATUS_LEN 65
28 #define MAVLINK_MSG_ID_EFI_STATUS_MIN_LEN 65
29 #define MAVLINK_MSG_ID_225_LEN 65
30 #define MAVLINK_MSG_ID_225_MIN_LEN 65
32 #define MAVLINK_MSG_ID_EFI_STATUS_CRC 208
33 #define MAVLINK_MSG_ID_225_CRC 208
37 #if MAVLINK_COMMAND_24BIT
38 #define MAVLINK_MESSAGE_INFO_EFI_STATUS { \
42 { { "health", NULL, MAVLINK_TYPE_UINT8_T, 0, 64, offsetof(mavlink_efi_status_t, health) }, \
43 { "ecu_index", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_efi_status_t, ecu_index) }, \
44 { "rpm", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_efi_status_t, rpm) }, \
45 { "fuel_consumed", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_efi_status_t, fuel_consumed) }, \
46 { "fuel_flow", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_efi_status_t, fuel_flow) }, \
47 { "engine_load", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_efi_status_t, engine_load) }, \
48 { "throttle_position", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_efi_status_t, throttle_position) }, \
49 { "spark_dwell_time", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_efi_status_t, spark_dwell_time) }, \
50 { "barometric_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_efi_status_t, barometric_pressure) }, \
51 { "intake_manifold_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_efi_status_t, intake_manifold_pressure) }, \
52 { "intake_manifold_temperature", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_efi_status_t, intake_manifold_temperature) }, \
53 { "cylinder_head_temperature", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_efi_status_t, cylinder_head_temperature) }, \
54 { "ignition_timing", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_efi_status_t, ignition_timing) }, \
55 { "injection_time", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_efi_status_t, injection_time) }, \
56 { "exhaust_gas_temperature", NULL, MAVLINK_TYPE_FLOAT, 0, 52, offsetof(mavlink_efi_status_t, exhaust_gas_temperature) }, \
57 { "throttle_out", NULL, MAVLINK_TYPE_FLOAT, 0, 56, offsetof(mavlink_efi_status_t, throttle_out) }, \
58 { "pt_compensation", NULL, MAVLINK_TYPE_FLOAT, 0, 60, offsetof(mavlink_efi_status_t, pt_compensation) }, \
62 #define MAVLINK_MESSAGE_INFO_EFI_STATUS { \
65 { { "health", NULL, MAVLINK_TYPE_UINT8_T, 0, 64, offsetof(mavlink_efi_status_t, health) }, \
66 { "ecu_index", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_efi_status_t, ecu_index) }, \
67 { "rpm", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_efi_status_t, rpm) }, \
68 { "fuel_consumed", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_efi_status_t, fuel_consumed) }, \
69 { "fuel_flow", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_efi_status_t, fuel_flow) }, \
70 { "engine_load", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_efi_status_t, engine_load) }, \
71 { "throttle_position", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_efi_status_t, throttle_position) }, \
72 { "spark_dwell_time", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_efi_status_t, spark_dwell_time) }, \
73 { "barometric_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_efi_status_t, barometric_pressure) }, \
74 { "intake_manifold_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_efi_status_t, intake_manifold_pressure) }, \
75 { "intake_manifold_temperature", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_efi_status_t, intake_manifold_temperature) }, \
76 { "cylinder_head_temperature", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_efi_status_t, cylinder_head_temperature) }, \
77 { "ignition_timing", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_efi_status_t, ignition_timing) }, \
78 { "injection_time", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_efi_status_t, injection_time) }, \
79 { "exhaust_gas_temperature", NULL, MAVLINK_TYPE_FLOAT, 0, 52, offsetof(mavlink_efi_status_t, exhaust_gas_temperature) }, \
80 { "throttle_out", NULL, MAVLINK_TYPE_FLOAT, 0, 56, offsetof(mavlink_efi_status_t, throttle_out) }, \
81 { "pt_compensation", NULL, MAVLINK_TYPE_FLOAT, 0, 60, offsetof(mavlink_efi_status_t, pt_compensation) }, \
87 * @brief Pack a efi_status message
88 * @param system_id ID of this system
89 * @param component_id ID of this component (e.g. 200 for IMU)
90 * @param msg The MAVLink message to compress the data into
92 * @param health EFI health status
93 * @param ecu_index ECU index
95 * @param fuel_consumed [cm^3] Fuel consumed
96 * @param fuel_flow [cm^3/min] Fuel flow rate
97 * @param engine_load [%] Engine load
98 * @param throttle_position [%] Throttle position
99 * @param spark_dwell_time [ms] Spark dwell time
100 * @param barometric_pressure [kPa] Barometric pressure
101 * @param intake_manifold_pressure [kPa] Intake manifold pressure(
102 * @param intake_manifold_temperature [degC] Intake manifold temperature
103 * @param cylinder_head_temperature [degC] Cylinder head temperature
104 * @param ignition_timing [deg] Ignition timing (Crank angle degrees)
105 * @param injection_time [ms] Injection time
106 * @param exhaust_gas_temperature [degC] Exhaust gas temperature
107 * @param throttle_out [%] Output throttle
108 * @param pt_compensation Pressure/temperature compensation
109 * @return length of the message in bytes (excluding serial stream start sign)
111 static inline uint16_t mavlink_msg_efi_status_pack(uint8_t system_id
, uint8_t component_id
, mavlink_message_t
* msg
,
112 uint8_t health
, float ecu_index
, float rpm
, float fuel_consumed
, float fuel_flow
, float engine_load
, float throttle_position
, float spark_dwell_time
, float barometric_pressure
, float intake_manifold_pressure
, float intake_manifold_temperature
, float cylinder_head_temperature
, float ignition_timing
, float injection_time
, float exhaust_gas_temperature
, float throttle_out
, float pt_compensation
)
114 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
115 char buf
[MAVLINK_MSG_ID_EFI_STATUS_LEN
];
116 _mav_put_float(buf
, 0, ecu_index
);
117 _mav_put_float(buf
, 4, rpm
);
118 _mav_put_float(buf
, 8, fuel_consumed
);
119 _mav_put_float(buf
, 12, fuel_flow
);
120 _mav_put_float(buf
, 16, engine_load
);
121 _mav_put_float(buf
, 20, throttle_position
);
122 _mav_put_float(buf
, 24, spark_dwell_time
);
123 _mav_put_float(buf
, 28, barometric_pressure
);
124 _mav_put_float(buf
, 32, intake_manifold_pressure
);
125 _mav_put_float(buf
, 36, intake_manifold_temperature
);
126 _mav_put_float(buf
, 40, cylinder_head_temperature
);
127 _mav_put_float(buf
, 44, ignition_timing
);
128 _mav_put_float(buf
, 48, injection_time
);
129 _mav_put_float(buf
, 52, exhaust_gas_temperature
);
130 _mav_put_float(buf
, 56, throttle_out
);
131 _mav_put_float(buf
, 60, pt_compensation
);
132 _mav_put_uint8_t(buf
, 64, health
);
134 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), buf
, MAVLINK_MSG_ID_EFI_STATUS_LEN
);
136 mavlink_efi_status_t packet
;
137 packet
.ecu_index
= ecu_index
;
139 packet
.fuel_consumed
= fuel_consumed
;
140 packet
.fuel_flow
= fuel_flow
;
141 packet
.engine_load
= engine_load
;
142 packet
.throttle_position
= throttle_position
;
143 packet
.spark_dwell_time
= spark_dwell_time
;
144 packet
.barometric_pressure
= barometric_pressure
;
145 packet
.intake_manifold_pressure
= intake_manifold_pressure
;
146 packet
.intake_manifold_temperature
= intake_manifold_temperature
;
147 packet
.cylinder_head_temperature
= cylinder_head_temperature
;
148 packet
.ignition_timing
= ignition_timing
;
149 packet
.injection_time
= injection_time
;
150 packet
.exhaust_gas_temperature
= exhaust_gas_temperature
;
151 packet
.throttle_out
= throttle_out
;
152 packet
.pt_compensation
= pt_compensation
;
153 packet
.health
= health
;
155 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), &packet
, MAVLINK_MSG_ID_EFI_STATUS_LEN
);
158 msg
->msgid
= MAVLINK_MSG_ID_EFI_STATUS
;
159 return mavlink_finalize_message(msg
, system_id
, component_id
, MAVLINK_MSG_ID_EFI_STATUS_MIN_LEN
, MAVLINK_MSG_ID_EFI_STATUS_LEN
, MAVLINK_MSG_ID_EFI_STATUS_CRC
);
163 * @brief Pack a efi_status message on a channel
164 * @param system_id ID of this system
165 * @param component_id ID of this component (e.g. 200 for IMU)
166 * @param chan The MAVLink channel this message will be sent over
167 * @param msg The MAVLink message to compress the data into
168 * @param health EFI health status
169 * @param ecu_index ECU index
171 * @param fuel_consumed [cm^3] Fuel consumed
172 * @param fuel_flow [cm^3/min] Fuel flow rate
173 * @param engine_load [%] Engine load
174 * @param throttle_position [%] Throttle position
175 * @param spark_dwell_time [ms] Spark dwell time
176 * @param barometric_pressure [kPa] Barometric pressure
177 * @param intake_manifold_pressure [kPa] Intake manifold pressure(
178 * @param intake_manifold_temperature [degC] Intake manifold temperature
179 * @param cylinder_head_temperature [degC] Cylinder head temperature
180 * @param ignition_timing [deg] Ignition timing (Crank angle degrees)
181 * @param injection_time [ms] Injection time
182 * @param exhaust_gas_temperature [degC] Exhaust gas temperature
183 * @param throttle_out [%] Output throttle
184 * @param pt_compensation Pressure/temperature compensation
185 * @return length of the message in bytes (excluding serial stream start sign)
187 static inline uint16_t mavlink_msg_efi_status_pack_chan(uint8_t system_id
, uint8_t component_id
, uint8_t chan
,
188 mavlink_message_t
* msg
,
189 uint8_t health
,float ecu_index
,float rpm
,float fuel_consumed
,float fuel_flow
,float engine_load
,float throttle_position
,float spark_dwell_time
,float barometric_pressure
,float intake_manifold_pressure
,float intake_manifold_temperature
,float cylinder_head_temperature
,float ignition_timing
,float injection_time
,float exhaust_gas_temperature
,float throttle_out
,float pt_compensation
)
191 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
192 char buf
[MAVLINK_MSG_ID_EFI_STATUS_LEN
];
193 _mav_put_float(buf
, 0, ecu_index
);
194 _mav_put_float(buf
, 4, rpm
);
195 _mav_put_float(buf
, 8, fuel_consumed
);
196 _mav_put_float(buf
, 12, fuel_flow
);
197 _mav_put_float(buf
, 16, engine_load
);
198 _mav_put_float(buf
, 20, throttle_position
);
199 _mav_put_float(buf
, 24, spark_dwell_time
);
200 _mav_put_float(buf
, 28, barometric_pressure
);
201 _mav_put_float(buf
, 32, intake_manifold_pressure
);
202 _mav_put_float(buf
, 36, intake_manifold_temperature
);
203 _mav_put_float(buf
, 40, cylinder_head_temperature
);
204 _mav_put_float(buf
, 44, ignition_timing
);
205 _mav_put_float(buf
, 48, injection_time
);
206 _mav_put_float(buf
, 52, exhaust_gas_temperature
);
207 _mav_put_float(buf
, 56, throttle_out
);
208 _mav_put_float(buf
, 60, pt_compensation
);
209 _mav_put_uint8_t(buf
, 64, health
);
211 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), buf
, MAVLINK_MSG_ID_EFI_STATUS_LEN
);
213 mavlink_efi_status_t packet
;
214 packet
.ecu_index
= ecu_index
;
216 packet
.fuel_consumed
= fuel_consumed
;
217 packet
.fuel_flow
= fuel_flow
;
218 packet
.engine_load
= engine_load
;
219 packet
.throttle_position
= throttle_position
;
220 packet
.spark_dwell_time
= spark_dwell_time
;
221 packet
.barometric_pressure
= barometric_pressure
;
222 packet
.intake_manifold_pressure
= intake_manifold_pressure
;
223 packet
.intake_manifold_temperature
= intake_manifold_temperature
;
224 packet
.cylinder_head_temperature
= cylinder_head_temperature
;
225 packet
.ignition_timing
= ignition_timing
;
226 packet
.injection_time
= injection_time
;
227 packet
.exhaust_gas_temperature
= exhaust_gas_temperature
;
228 packet
.throttle_out
= throttle_out
;
229 packet
.pt_compensation
= pt_compensation
;
230 packet
.health
= health
;
232 memcpy(_MAV_PAYLOAD_NON_CONST(msg
), &packet
, MAVLINK_MSG_ID_EFI_STATUS_LEN
);
235 msg
->msgid
= MAVLINK_MSG_ID_EFI_STATUS
;
236 return mavlink_finalize_message_chan(msg
, system_id
, component_id
, chan
, MAVLINK_MSG_ID_EFI_STATUS_MIN_LEN
, MAVLINK_MSG_ID_EFI_STATUS_LEN
, MAVLINK_MSG_ID_EFI_STATUS_CRC
);
240 * @brief Encode a efi_status struct
242 * @param system_id ID of this system
243 * @param component_id ID of this component (e.g. 200 for IMU)
244 * @param msg The MAVLink message to compress the data into
245 * @param efi_status C-struct to read the message contents from
247 static inline uint16_t mavlink_msg_efi_status_encode(uint8_t system_id
, uint8_t component_id
, mavlink_message_t
* msg
, const mavlink_efi_status_t
* efi_status
)
249 return mavlink_msg_efi_status_pack(system_id
, component_id
, msg
, efi_status
->health
, efi_status
->ecu_index
, efi_status
->rpm
, efi_status
->fuel_consumed
, efi_status
->fuel_flow
, efi_status
->engine_load
, efi_status
->throttle_position
, efi_status
->spark_dwell_time
, efi_status
->barometric_pressure
, efi_status
->intake_manifold_pressure
, efi_status
->intake_manifold_temperature
, efi_status
->cylinder_head_temperature
, efi_status
->ignition_timing
, efi_status
->injection_time
, efi_status
->exhaust_gas_temperature
, efi_status
->throttle_out
, efi_status
->pt_compensation
);
253 * @brief Encode a efi_status struct on a channel
255 * @param system_id ID of this system
256 * @param component_id ID of this component (e.g. 200 for IMU)
257 * @param chan The MAVLink channel this message will be sent over
258 * @param msg The MAVLink message to compress the data into
259 * @param efi_status C-struct to read the message contents from
261 static inline uint16_t mavlink_msg_efi_status_encode_chan(uint8_t system_id
, uint8_t component_id
, uint8_t chan
, mavlink_message_t
* msg
, const mavlink_efi_status_t
* efi_status
)
263 return mavlink_msg_efi_status_pack_chan(system_id
, component_id
, chan
, msg
, efi_status
->health
, efi_status
->ecu_index
, efi_status
->rpm
, efi_status
->fuel_consumed
, efi_status
->fuel_flow
, efi_status
->engine_load
, efi_status
->throttle_position
, efi_status
->spark_dwell_time
, efi_status
->barometric_pressure
, efi_status
->intake_manifold_pressure
, efi_status
->intake_manifold_temperature
, efi_status
->cylinder_head_temperature
, efi_status
->ignition_timing
, efi_status
->injection_time
, efi_status
->exhaust_gas_temperature
, efi_status
->throttle_out
, efi_status
->pt_compensation
);
267 * @brief Send a efi_status message
268 * @param chan MAVLink channel to send the message
270 * @param health EFI health status
271 * @param ecu_index ECU index
273 * @param fuel_consumed [cm^3] Fuel consumed
274 * @param fuel_flow [cm^3/min] Fuel flow rate
275 * @param engine_load [%] Engine load
276 * @param throttle_position [%] Throttle position
277 * @param spark_dwell_time [ms] Spark dwell time
278 * @param barometric_pressure [kPa] Barometric pressure
279 * @param intake_manifold_pressure [kPa] Intake manifold pressure(
280 * @param intake_manifold_temperature [degC] Intake manifold temperature
281 * @param cylinder_head_temperature [degC] Cylinder head temperature
282 * @param ignition_timing [deg] Ignition timing (Crank angle degrees)
283 * @param injection_time [ms] Injection time
284 * @param exhaust_gas_temperature [degC] Exhaust gas temperature
285 * @param throttle_out [%] Output throttle
286 * @param pt_compensation Pressure/temperature compensation
288 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
290 static inline void mavlink_msg_efi_status_send(mavlink_channel_t chan
, uint8_t health
, float ecu_index
, float rpm
, float fuel_consumed
, float fuel_flow
, float engine_load
, float throttle_position
, float spark_dwell_time
, float barometric_pressure
, float intake_manifold_pressure
, float intake_manifold_temperature
, float cylinder_head_temperature
, float ignition_timing
, float injection_time
, float exhaust_gas_temperature
, float throttle_out
, float pt_compensation
)
292 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
293 char buf
[MAVLINK_MSG_ID_EFI_STATUS_LEN
];
294 _mav_put_float(buf
, 0, ecu_index
);
295 _mav_put_float(buf
, 4, rpm
);
296 _mav_put_float(buf
, 8, fuel_consumed
);
297 _mav_put_float(buf
, 12, fuel_flow
);
298 _mav_put_float(buf
, 16, engine_load
);
299 _mav_put_float(buf
, 20, throttle_position
);
300 _mav_put_float(buf
, 24, spark_dwell_time
);
301 _mav_put_float(buf
, 28, barometric_pressure
);
302 _mav_put_float(buf
, 32, intake_manifold_pressure
);
303 _mav_put_float(buf
, 36, intake_manifold_temperature
);
304 _mav_put_float(buf
, 40, cylinder_head_temperature
);
305 _mav_put_float(buf
, 44, ignition_timing
);
306 _mav_put_float(buf
, 48, injection_time
);
307 _mav_put_float(buf
, 52, exhaust_gas_temperature
);
308 _mav_put_float(buf
, 56, throttle_out
);
309 _mav_put_float(buf
, 60, pt_compensation
);
310 _mav_put_uint8_t(buf
, 64, health
);
312 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_EFI_STATUS
, buf
, MAVLINK_MSG_ID_EFI_STATUS_MIN_LEN
, MAVLINK_MSG_ID_EFI_STATUS_LEN
, MAVLINK_MSG_ID_EFI_STATUS_CRC
);
314 mavlink_efi_status_t packet
;
315 packet
.ecu_index
= ecu_index
;
317 packet
.fuel_consumed
= fuel_consumed
;
318 packet
.fuel_flow
= fuel_flow
;
319 packet
.engine_load
= engine_load
;
320 packet
.throttle_position
= throttle_position
;
321 packet
.spark_dwell_time
= spark_dwell_time
;
322 packet
.barometric_pressure
= barometric_pressure
;
323 packet
.intake_manifold_pressure
= intake_manifold_pressure
;
324 packet
.intake_manifold_temperature
= intake_manifold_temperature
;
325 packet
.cylinder_head_temperature
= cylinder_head_temperature
;
326 packet
.ignition_timing
= ignition_timing
;
327 packet
.injection_time
= injection_time
;
328 packet
.exhaust_gas_temperature
= exhaust_gas_temperature
;
329 packet
.throttle_out
= throttle_out
;
330 packet
.pt_compensation
= pt_compensation
;
331 packet
.health
= health
;
333 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_EFI_STATUS
, (const char *)&packet
, MAVLINK_MSG_ID_EFI_STATUS_MIN_LEN
, MAVLINK_MSG_ID_EFI_STATUS_LEN
, MAVLINK_MSG_ID_EFI_STATUS_CRC
);
338 * @brief Send a efi_status message
339 * @param chan MAVLink channel to send the message
340 * @param struct The MAVLink struct to serialize
342 static inline void mavlink_msg_efi_status_send_struct(mavlink_channel_t chan
, const mavlink_efi_status_t
* efi_status
)
344 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
345 mavlink_msg_efi_status_send(chan
, efi_status
->health
, efi_status
->ecu_index
, efi_status
->rpm
, efi_status
->fuel_consumed
, efi_status
->fuel_flow
, efi_status
->engine_load
, efi_status
->throttle_position
, efi_status
->spark_dwell_time
, efi_status
->barometric_pressure
, efi_status
->intake_manifold_pressure
, efi_status
->intake_manifold_temperature
, efi_status
->cylinder_head_temperature
, efi_status
->ignition_timing
, efi_status
->injection_time
, efi_status
->exhaust_gas_temperature
, efi_status
->throttle_out
, efi_status
->pt_compensation
);
347 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_EFI_STATUS
, (const char *)efi_status
, MAVLINK_MSG_ID_EFI_STATUS_MIN_LEN
, MAVLINK_MSG_ID_EFI_STATUS_LEN
, MAVLINK_MSG_ID_EFI_STATUS_CRC
);
351 #if MAVLINK_MSG_ID_EFI_STATUS_LEN <= MAVLINK_MAX_PAYLOAD_LEN
353 This varient of _send() can be used to save stack space by re-using
354 memory from the receive buffer. The caller provides a
355 mavlink_message_t which is the size of a full mavlink message. This
356 is usually the receive buffer for the channel, and allows a reply to an
357 incoming message with minimum stack space usage.
359 static inline void mavlink_msg_efi_status_send_buf(mavlink_message_t
*msgbuf
, mavlink_channel_t chan
, uint8_t health
, float ecu_index
, float rpm
, float fuel_consumed
, float fuel_flow
, float engine_load
, float throttle_position
, float spark_dwell_time
, float barometric_pressure
, float intake_manifold_pressure
, float intake_manifold_temperature
, float cylinder_head_temperature
, float ignition_timing
, float injection_time
, float exhaust_gas_temperature
, float throttle_out
, float pt_compensation
)
361 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
362 char *buf
= (char *)msgbuf
;
363 _mav_put_float(buf
, 0, ecu_index
);
364 _mav_put_float(buf
, 4, rpm
);
365 _mav_put_float(buf
, 8, fuel_consumed
);
366 _mav_put_float(buf
, 12, fuel_flow
);
367 _mav_put_float(buf
, 16, engine_load
);
368 _mav_put_float(buf
, 20, throttle_position
);
369 _mav_put_float(buf
, 24, spark_dwell_time
);
370 _mav_put_float(buf
, 28, barometric_pressure
);
371 _mav_put_float(buf
, 32, intake_manifold_pressure
);
372 _mav_put_float(buf
, 36, intake_manifold_temperature
);
373 _mav_put_float(buf
, 40, cylinder_head_temperature
);
374 _mav_put_float(buf
, 44, ignition_timing
);
375 _mav_put_float(buf
, 48, injection_time
);
376 _mav_put_float(buf
, 52, exhaust_gas_temperature
);
377 _mav_put_float(buf
, 56, throttle_out
);
378 _mav_put_float(buf
, 60, pt_compensation
);
379 _mav_put_uint8_t(buf
, 64, health
);
381 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_EFI_STATUS
, buf
, MAVLINK_MSG_ID_EFI_STATUS_MIN_LEN
, MAVLINK_MSG_ID_EFI_STATUS_LEN
, MAVLINK_MSG_ID_EFI_STATUS_CRC
);
383 mavlink_efi_status_t
*packet
= (mavlink_efi_status_t
*)msgbuf
;
384 packet
->ecu_index
= ecu_index
;
386 packet
->fuel_consumed
= fuel_consumed
;
387 packet
->fuel_flow
= fuel_flow
;
388 packet
->engine_load
= engine_load
;
389 packet
->throttle_position
= throttle_position
;
390 packet
->spark_dwell_time
= spark_dwell_time
;
391 packet
->barometric_pressure
= barometric_pressure
;
392 packet
->intake_manifold_pressure
= intake_manifold_pressure
;
393 packet
->intake_manifold_temperature
= intake_manifold_temperature
;
394 packet
->cylinder_head_temperature
= cylinder_head_temperature
;
395 packet
->ignition_timing
= ignition_timing
;
396 packet
->injection_time
= injection_time
;
397 packet
->exhaust_gas_temperature
= exhaust_gas_temperature
;
398 packet
->throttle_out
= throttle_out
;
399 packet
->pt_compensation
= pt_compensation
;
400 packet
->health
= health
;
402 _mav_finalize_message_chan_send(chan
, MAVLINK_MSG_ID_EFI_STATUS
, (const char *)packet
, MAVLINK_MSG_ID_EFI_STATUS_MIN_LEN
, MAVLINK_MSG_ID_EFI_STATUS_LEN
, MAVLINK_MSG_ID_EFI_STATUS_CRC
);
409 // MESSAGE EFI_STATUS UNPACKING
413 * @brief Get field health from efi_status message
415 * @return EFI health status
417 static inline uint8_t mavlink_msg_efi_status_get_health(const mavlink_message_t
* msg
)
419 return _MAV_RETURN_uint8_t(msg
, 64);
423 * @brief Get field ecu_index from efi_status message
427 static inline float mavlink_msg_efi_status_get_ecu_index(const mavlink_message_t
* msg
)
429 return _MAV_RETURN_float(msg
, 0);
433 * @brief Get field rpm from efi_status message
437 static inline float mavlink_msg_efi_status_get_rpm(const mavlink_message_t
* msg
)
439 return _MAV_RETURN_float(msg
, 4);
443 * @brief Get field fuel_consumed from efi_status message
445 * @return [cm^3] Fuel consumed
447 static inline float mavlink_msg_efi_status_get_fuel_consumed(const mavlink_message_t
* msg
)
449 return _MAV_RETURN_float(msg
, 8);
453 * @brief Get field fuel_flow from efi_status message
455 * @return [cm^3/min] Fuel flow rate
457 static inline float mavlink_msg_efi_status_get_fuel_flow(const mavlink_message_t
* msg
)
459 return _MAV_RETURN_float(msg
, 12);
463 * @brief Get field engine_load from efi_status message
465 * @return [%] Engine load
467 static inline float mavlink_msg_efi_status_get_engine_load(const mavlink_message_t
* msg
)
469 return _MAV_RETURN_float(msg
, 16);
473 * @brief Get field throttle_position from efi_status message
475 * @return [%] Throttle position
477 static inline float mavlink_msg_efi_status_get_throttle_position(const mavlink_message_t
* msg
)
479 return _MAV_RETURN_float(msg
, 20);
483 * @brief Get field spark_dwell_time from efi_status message
485 * @return [ms] Spark dwell time
487 static inline float mavlink_msg_efi_status_get_spark_dwell_time(const mavlink_message_t
* msg
)
489 return _MAV_RETURN_float(msg
, 24);
493 * @brief Get field barometric_pressure from efi_status message
495 * @return [kPa] Barometric pressure
497 static inline float mavlink_msg_efi_status_get_barometric_pressure(const mavlink_message_t
* msg
)
499 return _MAV_RETURN_float(msg
, 28);
503 * @brief Get field intake_manifold_pressure from efi_status message
505 * @return [kPa] Intake manifold pressure(
507 static inline float mavlink_msg_efi_status_get_intake_manifold_pressure(const mavlink_message_t
* msg
)
509 return _MAV_RETURN_float(msg
, 32);
513 * @brief Get field intake_manifold_temperature from efi_status message
515 * @return [degC] Intake manifold temperature
517 static inline float mavlink_msg_efi_status_get_intake_manifold_temperature(const mavlink_message_t
* msg
)
519 return _MAV_RETURN_float(msg
, 36);
523 * @brief Get field cylinder_head_temperature from efi_status message
525 * @return [degC] Cylinder head temperature
527 static inline float mavlink_msg_efi_status_get_cylinder_head_temperature(const mavlink_message_t
* msg
)
529 return _MAV_RETURN_float(msg
, 40);
533 * @brief Get field ignition_timing from efi_status message
535 * @return [deg] Ignition timing (Crank angle degrees)
537 static inline float mavlink_msg_efi_status_get_ignition_timing(const mavlink_message_t
* msg
)
539 return _MAV_RETURN_float(msg
, 44);
543 * @brief Get field injection_time from efi_status message
545 * @return [ms] Injection time
547 static inline float mavlink_msg_efi_status_get_injection_time(const mavlink_message_t
* msg
)
549 return _MAV_RETURN_float(msg
, 48);
553 * @brief Get field exhaust_gas_temperature from efi_status message
555 * @return [degC] Exhaust gas temperature
557 static inline float mavlink_msg_efi_status_get_exhaust_gas_temperature(const mavlink_message_t
* msg
)
559 return _MAV_RETURN_float(msg
, 52);
563 * @brief Get field throttle_out from efi_status message
565 * @return [%] Output throttle
567 static inline float mavlink_msg_efi_status_get_throttle_out(const mavlink_message_t
* msg
)
569 return _MAV_RETURN_float(msg
, 56);
573 * @brief Get field pt_compensation from efi_status message
575 * @return Pressure/temperature compensation
577 static inline float mavlink_msg_efi_status_get_pt_compensation(const mavlink_message_t
* msg
)
579 return _MAV_RETURN_float(msg
, 60);
583 * @brief Decode a efi_status message into a struct
585 * @param msg The message to decode
586 * @param efi_status C-struct to decode the message contents into
588 static inline void mavlink_msg_efi_status_decode(const mavlink_message_t
* msg
, mavlink_efi_status_t
* efi_status
)
590 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
591 efi_status
->ecu_index
= mavlink_msg_efi_status_get_ecu_index(msg
);
592 efi_status
->rpm
= mavlink_msg_efi_status_get_rpm(msg
);
593 efi_status
->fuel_consumed
= mavlink_msg_efi_status_get_fuel_consumed(msg
);
594 efi_status
->fuel_flow
= mavlink_msg_efi_status_get_fuel_flow(msg
);
595 efi_status
->engine_load
= mavlink_msg_efi_status_get_engine_load(msg
);
596 efi_status
->throttle_position
= mavlink_msg_efi_status_get_throttle_position(msg
);
597 efi_status
->spark_dwell_time
= mavlink_msg_efi_status_get_spark_dwell_time(msg
);
598 efi_status
->barometric_pressure
= mavlink_msg_efi_status_get_barometric_pressure(msg
);
599 efi_status
->intake_manifold_pressure
= mavlink_msg_efi_status_get_intake_manifold_pressure(msg
);
600 efi_status
->intake_manifold_temperature
= mavlink_msg_efi_status_get_intake_manifold_temperature(msg
);
601 efi_status
->cylinder_head_temperature
= mavlink_msg_efi_status_get_cylinder_head_temperature(msg
);
602 efi_status
->ignition_timing
= mavlink_msg_efi_status_get_ignition_timing(msg
);
603 efi_status
->injection_time
= mavlink_msg_efi_status_get_injection_time(msg
);
604 efi_status
->exhaust_gas_temperature
= mavlink_msg_efi_status_get_exhaust_gas_temperature(msg
);
605 efi_status
->throttle_out
= mavlink_msg_efi_status_get_throttle_out(msg
);
606 efi_status
->pt_compensation
= mavlink_msg_efi_status_get_pt_compensation(msg
);
607 efi_status
->health
= mavlink_msg_efi_status_get_health(msg
);
609 uint8_t len
= msg
->len
< MAVLINK_MSG_ID_EFI_STATUS_LEN
? msg
->len
: MAVLINK_MSG_ID_EFI_STATUS_LEN
;
610 memset(efi_status
, 0, MAVLINK_MSG_ID_EFI_STATUS_LEN
);
611 memcpy(efi_status
, _MAV_PAYLOAD(msg
), len
);