mavlink_msg_efi_status.h 32 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663
  1. #pragma once
  2. // MESSAGE EFI_STATUS PACKING
  3. #define MAVLINK_MSG_ID_EFI_STATUS 225
  4. MAVPACKED(
  5. typedef struct __mavlink_efi_status_t {
  6. float ecu_index; /*< ECU index*/
  7. float rpm; /*< RPM*/
  8. float fuel_consumed; /*< [cm^3] Fuel consumed*/
  9. float fuel_flow; /*< [cm^3/min] Fuel flow rate*/
  10. float engine_load; /*< [%] Engine load*/
  11. float throttle_position; /*< [%] Throttle position*/
  12. float spark_dwell_time; /*< [ms] Spark dwell time*/
  13. float barometric_pressure; /*< [kPa] Barometric pressure*/
  14. float intake_manifold_pressure; /*< [kPa] Intake manifold pressure(*/
  15. float intake_manifold_temperature; /*< [degC] Intake manifold temperature*/
  16. float cylinder_head_temperature; /*< [degC] Cylinder head temperature*/
  17. float ignition_timing; /*< [deg] Ignition timing (Crank angle degrees)*/
  18. float injection_time; /*< [ms] Injection time*/
  19. float exhaust_gas_temperature; /*< [degC] Exhaust gas temperature*/
  20. float throttle_out; /*< [%] Output throttle*/
  21. float pt_compensation; /*< Pressure/temperature compensation*/
  22. uint8_t health; /*< EFI health status*/
  23. float ignition_voltage; /*< [V] Supply voltage to EFI sparking system. Zero in this value means "unknown", so if the supply voltage really is zero volts use 0.0001 instead.*/
  24. float fuel_pressure; /*< [kPa] Fuel pressure. Zero in this value means "unknown", so if the fuel pressure really is zero kPa use 0.0001 instead.*/
  25. }) mavlink_efi_status_t;
  26. #define MAVLINK_MSG_ID_EFI_STATUS_LEN 73
  27. #define MAVLINK_MSG_ID_EFI_STATUS_MIN_LEN 65
  28. #define MAVLINK_MSG_ID_225_LEN 73
  29. #define MAVLINK_MSG_ID_225_MIN_LEN 65
  30. #define MAVLINK_MSG_ID_EFI_STATUS_CRC 208
  31. #define MAVLINK_MSG_ID_225_CRC 208
  32. #if MAVLINK_COMMAND_24BIT
  33. #define MAVLINK_MESSAGE_INFO_EFI_STATUS { \
  34. 225, \
  35. "EFI_STATUS", \
  36. 19, \
  37. { { "health", NULL, MAVLINK_TYPE_UINT8_T, 0, 64, offsetof(mavlink_efi_status_t, health) }, \
  38. { "ecu_index", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_efi_status_t, ecu_index) }, \
  39. { "rpm", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_efi_status_t, rpm) }, \
  40. { "fuel_consumed", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_efi_status_t, fuel_consumed) }, \
  41. { "fuel_flow", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_efi_status_t, fuel_flow) }, \
  42. { "engine_load", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_efi_status_t, engine_load) }, \
  43. { "throttle_position", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_efi_status_t, throttle_position) }, \
  44. { "spark_dwell_time", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_efi_status_t, spark_dwell_time) }, \
  45. { "barometric_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_efi_status_t, barometric_pressure) }, \
  46. { "intake_manifold_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_efi_status_t, intake_manifold_pressure) }, \
  47. { "intake_manifold_temperature", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_efi_status_t, intake_manifold_temperature) }, \
  48. { "cylinder_head_temperature", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_efi_status_t, cylinder_head_temperature) }, \
  49. { "ignition_timing", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_efi_status_t, ignition_timing) }, \
  50. { "injection_time", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_efi_status_t, injection_time) }, \
  51. { "exhaust_gas_temperature", NULL, MAVLINK_TYPE_FLOAT, 0, 52, offsetof(mavlink_efi_status_t, exhaust_gas_temperature) }, \
  52. { "throttle_out", NULL, MAVLINK_TYPE_FLOAT, 0, 56, offsetof(mavlink_efi_status_t, throttle_out) }, \
  53. { "pt_compensation", NULL, MAVLINK_TYPE_FLOAT, 0, 60, offsetof(mavlink_efi_status_t, pt_compensation) }, \
  54. { "ignition_voltage", NULL, MAVLINK_TYPE_FLOAT, 0, 65, offsetof(mavlink_efi_status_t, ignition_voltage) }, \
  55. { "fuel_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 69, offsetof(mavlink_efi_status_t, fuel_pressure) }, \
  56. } \
  57. }
  58. #else
  59. #define MAVLINK_MESSAGE_INFO_EFI_STATUS { \
  60. "EFI_STATUS", \
  61. 19, \
  62. { { "health", NULL, MAVLINK_TYPE_UINT8_T, 0, 64, offsetof(mavlink_efi_status_t, health) }, \
  63. { "ecu_index", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_efi_status_t, ecu_index) }, \
  64. { "rpm", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_efi_status_t, rpm) }, \
  65. { "fuel_consumed", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_efi_status_t, fuel_consumed) }, \
  66. { "fuel_flow", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_efi_status_t, fuel_flow) }, \
  67. { "engine_load", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_efi_status_t, engine_load) }, \
  68. { "throttle_position", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_efi_status_t, throttle_position) }, \
  69. { "spark_dwell_time", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_efi_status_t, spark_dwell_time) }, \
  70. { "barometric_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_efi_status_t, barometric_pressure) }, \
  71. { "intake_manifold_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_efi_status_t, intake_manifold_pressure) }, \
  72. { "intake_manifold_temperature", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_efi_status_t, intake_manifold_temperature) }, \
  73. { "cylinder_head_temperature", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_efi_status_t, cylinder_head_temperature) }, \
  74. { "ignition_timing", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_efi_status_t, ignition_timing) }, \
  75. { "injection_time", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_efi_status_t, injection_time) }, \
  76. { "exhaust_gas_temperature", NULL, MAVLINK_TYPE_FLOAT, 0, 52, offsetof(mavlink_efi_status_t, exhaust_gas_temperature) }, \
  77. { "throttle_out", NULL, MAVLINK_TYPE_FLOAT, 0, 56, offsetof(mavlink_efi_status_t, throttle_out) }, \
  78. { "pt_compensation", NULL, MAVLINK_TYPE_FLOAT, 0, 60, offsetof(mavlink_efi_status_t, pt_compensation) }, \
  79. { "ignition_voltage", NULL, MAVLINK_TYPE_FLOAT, 0, 65, offsetof(mavlink_efi_status_t, ignition_voltage) }, \
  80. { "fuel_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 69, offsetof(mavlink_efi_status_t, fuel_pressure) }, \
  81. } \
  82. }
  83. #endif
  84. /**
  85. * @brief Pack a efi_status message
  86. * @param system_id ID of this system
  87. * @param component_id ID of this component (e.g. 200 for IMU)
  88. * @param msg The MAVLink message to compress the data into
  89. *
  90. * @param health EFI health status
  91. * @param ecu_index ECU index
  92. * @param rpm RPM
  93. * @param fuel_consumed [cm^3] Fuel consumed
  94. * @param fuel_flow [cm^3/min] Fuel flow rate
  95. * @param engine_load [%] Engine load
  96. * @param throttle_position [%] Throttle position
  97. * @param spark_dwell_time [ms] Spark dwell time
  98. * @param barometric_pressure [kPa] Barometric pressure
  99. * @param intake_manifold_pressure [kPa] Intake manifold pressure(
  100. * @param intake_manifold_temperature [degC] Intake manifold temperature
  101. * @param cylinder_head_temperature [degC] Cylinder head temperature
  102. * @param ignition_timing [deg] Ignition timing (Crank angle degrees)
  103. * @param injection_time [ms] Injection time
  104. * @param exhaust_gas_temperature [degC] Exhaust gas temperature
  105. * @param throttle_out [%] Output throttle
  106. * @param pt_compensation Pressure/temperature compensation
  107. * @param ignition_voltage [V] Supply voltage to EFI sparking system. Zero in this value means "unknown", so if the supply voltage really is zero volts use 0.0001 instead.
  108. * @param fuel_pressure [kPa] Fuel pressure. Zero in this value means "unknown", so if the fuel pressure really is zero kPa use 0.0001 instead.
  109. * @return length of the message in bytes (excluding serial stream start sign)
  110. */
  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, float ignition_voltage, float fuel_pressure)
  113. {
  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);
  133. _mav_put_float(buf, 65, ignition_voltage);
  134. _mav_put_float(buf, 69, fuel_pressure);
  135. memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_EFI_STATUS_LEN);
  136. #else
  137. mavlink_efi_status_t packet;
  138. packet.ecu_index = ecu_index;
  139. packet.rpm = rpm;
  140. packet.fuel_consumed = fuel_consumed;
  141. packet.fuel_flow = fuel_flow;
  142. packet.engine_load = engine_load;
  143. packet.throttle_position = throttle_position;
  144. packet.spark_dwell_time = spark_dwell_time;
  145. packet.barometric_pressure = barometric_pressure;
  146. packet.intake_manifold_pressure = intake_manifold_pressure;
  147. packet.intake_manifold_temperature = intake_manifold_temperature;
  148. packet.cylinder_head_temperature = cylinder_head_temperature;
  149. packet.ignition_timing = ignition_timing;
  150. packet.injection_time = injection_time;
  151. packet.exhaust_gas_temperature = exhaust_gas_temperature;
  152. packet.throttle_out = throttle_out;
  153. packet.pt_compensation = pt_compensation;
  154. packet.health = health;
  155. packet.ignition_voltage = ignition_voltage;
  156. packet.fuel_pressure = fuel_pressure;
  157. memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_EFI_STATUS_LEN);
  158. #endif
  159. msg->msgid = MAVLINK_MSG_ID_EFI_STATUS;
  160. 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);
  161. }
  162. /**
  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
  170. * @param rpm RPM
  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. * @param ignition_voltage [V] Supply voltage to EFI sparking system. Zero in this value means "unknown", so if the supply voltage really is zero volts use 0.0001 instead.
  186. * @param fuel_pressure [kPa] Fuel pressure. Zero in this value means "unknown", so if the fuel pressure really is zero kPa use 0.0001 instead.
  187. * @return length of the message in bytes (excluding serial stream start sign)
  188. */
  189. static inline uint16_t mavlink_msg_efi_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
  190. mavlink_message_t* msg,
  191. 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,float ignition_voltage,float fuel_pressure)
  192. {
  193. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  194. char buf[MAVLINK_MSG_ID_EFI_STATUS_LEN];
  195. _mav_put_float(buf, 0, ecu_index);
  196. _mav_put_float(buf, 4, rpm);
  197. _mav_put_float(buf, 8, fuel_consumed);
  198. _mav_put_float(buf, 12, fuel_flow);
  199. _mav_put_float(buf, 16, engine_load);
  200. _mav_put_float(buf, 20, throttle_position);
  201. _mav_put_float(buf, 24, spark_dwell_time);
  202. _mav_put_float(buf, 28, barometric_pressure);
  203. _mav_put_float(buf, 32, intake_manifold_pressure);
  204. _mav_put_float(buf, 36, intake_manifold_temperature);
  205. _mav_put_float(buf, 40, cylinder_head_temperature);
  206. _mav_put_float(buf, 44, ignition_timing);
  207. _mav_put_float(buf, 48, injection_time);
  208. _mav_put_float(buf, 52, exhaust_gas_temperature);
  209. _mav_put_float(buf, 56, throttle_out);
  210. _mav_put_float(buf, 60, pt_compensation);
  211. _mav_put_uint8_t(buf, 64, health);
  212. _mav_put_float(buf, 65, ignition_voltage);
  213. _mav_put_float(buf, 69, fuel_pressure);
  214. memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_EFI_STATUS_LEN);
  215. #else
  216. mavlink_efi_status_t packet;
  217. packet.ecu_index = ecu_index;
  218. packet.rpm = rpm;
  219. packet.fuel_consumed = fuel_consumed;
  220. packet.fuel_flow = fuel_flow;
  221. packet.engine_load = engine_load;
  222. packet.throttle_position = throttle_position;
  223. packet.spark_dwell_time = spark_dwell_time;
  224. packet.barometric_pressure = barometric_pressure;
  225. packet.intake_manifold_pressure = intake_manifold_pressure;
  226. packet.intake_manifold_temperature = intake_manifold_temperature;
  227. packet.cylinder_head_temperature = cylinder_head_temperature;
  228. packet.ignition_timing = ignition_timing;
  229. packet.injection_time = injection_time;
  230. packet.exhaust_gas_temperature = exhaust_gas_temperature;
  231. packet.throttle_out = throttle_out;
  232. packet.pt_compensation = pt_compensation;
  233. packet.health = health;
  234. packet.ignition_voltage = ignition_voltage;
  235. packet.fuel_pressure = fuel_pressure;
  236. memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_EFI_STATUS_LEN);
  237. #endif
  238. msg->msgid = MAVLINK_MSG_ID_EFI_STATUS;
  239. 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. }
  241. /**
  242. * @brief Encode a efi_status struct
  243. *
  244. * @param system_id ID of this system
  245. * @param component_id ID of this component (e.g. 200 for IMU)
  246. * @param msg The MAVLink message to compress the data into
  247. * @param efi_status C-struct to read the message contents from
  248. */
  249. 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)
  250. {
  251. 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, efi_status->ignition_voltage, efi_status->fuel_pressure);
  252. }
  253. /**
  254. * @brief Encode a efi_status struct on a channel
  255. *
  256. * @param system_id ID of this system
  257. * @param component_id ID of this component (e.g. 200 for IMU)
  258. * @param chan The MAVLink channel this message will be sent over
  259. * @param msg The MAVLink message to compress the data into
  260. * @param efi_status C-struct to read the message contents from
  261. */
  262. 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. {
  264. 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, efi_status->ignition_voltage, efi_status->fuel_pressure);
  265. }
  266. /**
  267. * @brief Send a efi_status message
  268. * @param chan MAVLink channel to send the message
  269. *
  270. * @param health EFI health status
  271. * @param ecu_index ECU index
  272. * @param rpm RPM
  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
  287. * @param ignition_voltage [V] Supply voltage to EFI sparking system. Zero in this value means "unknown", so if the supply voltage really is zero volts use 0.0001 instead.
  288. * @param fuel_pressure [kPa] Fuel pressure. Zero in this value means "unknown", so if the fuel pressure really is zero kPa use 0.0001 instead.
  289. */
  290. #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
  291. 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, float ignition_voltage, float fuel_pressure)
  292. {
  293. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  294. char buf[MAVLINK_MSG_ID_EFI_STATUS_LEN];
  295. _mav_put_float(buf, 0, ecu_index);
  296. _mav_put_float(buf, 4, rpm);
  297. _mav_put_float(buf, 8, fuel_consumed);
  298. _mav_put_float(buf, 12, fuel_flow);
  299. _mav_put_float(buf, 16, engine_load);
  300. _mav_put_float(buf, 20, throttle_position);
  301. _mav_put_float(buf, 24, spark_dwell_time);
  302. _mav_put_float(buf, 28, barometric_pressure);
  303. _mav_put_float(buf, 32, intake_manifold_pressure);
  304. _mav_put_float(buf, 36, intake_manifold_temperature);
  305. _mav_put_float(buf, 40, cylinder_head_temperature);
  306. _mav_put_float(buf, 44, ignition_timing);
  307. _mav_put_float(buf, 48, injection_time);
  308. _mav_put_float(buf, 52, exhaust_gas_temperature);
  309. _mav_put_float(buf, 56, throttle_out);
  310. _mav_put_float(buf, 60, pt_compensation);
  311. _mav_put_uint8_t(buf, 64, health);
  312. _mav_put_float(buf, 65, ignition_voltage);
  313. _mav_put_float(buf, 69, fuel_pressure);
  314. _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);
  315. #else
  316. mavlink_efi_status_t packet;
  317. packet.ecu_index = ecu_index;
  318. packet.rpm = rpm;
  319. packet.fuel_consumed = fuel_consumed;
  320. packet.fuel_flow = fuel_flow;
  321. packet.engine_load = engine_load;
  322. packet.throttle_position = throttle_position;
  323. packet.spark_dwell_time = spark_dwell_time;
  324. packet.barometric_pressure = barometric_pressure;
  325. packet.intake_manifold_pressure = intake_manifold_pressure;
  326. packet.intake_manifold_temperature = intake_manifold_temperature;
  327. packet.cylinder_head_temperature = cylinder_head_temperature;
  328. packet.ignition_timing = ignition_timing;
  329. packet.injection_time = injection_time;
  330. packet.exhaust_gas_temperature = exhaust_gas_temperature;
  331. packet.throttle_out = throttle_out;
  332. packet.pt_compensation = pt_compensation;
  333. packet.health = health;
  334. packet.ignition_voltage = ignition_voltage;
  335. packet.fuel_pressure = fuel_pressure;
  336. _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);
  337. #endif
  338. }
  339. /**
  340. * @brief Send a efi_status message
  341. * @param chan MAVLink channel to send the message
  342. * @param struct The MAVLink struct to serialize
  343. */
  344. static inline void mavlink_msg_efi_status_send_struct(mavlink_channel_t chan, const mavlink_efi_status_t* efi_status)
  345. {
  346. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  347. 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, efi_status->ignition_voltage, efi_status->fuel_pressure);
  348. #else
  349. _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);
  350. #endif
  351. }
  352. #if MAVLINK_MSG_ID_EFI_STATUS_LEN <= MAVLINK_MAX_PAYLOAD_LEN
  353. /*
  354. This variant of _send() can be used to save stack space by re-using
  355. memory from the receive buffer. The caller provides a
  356. mavlink_message_t which is the size of a full mavlink message. This
  357. is usually the receive buffer for the channel, and allows a reply to an
  358. incoming message with minimum stack space usage.
  359. */
  360. 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, float ignition_voltage, float fuel_pressure)
  361. {
  362. #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
  363. char *buf = (char *)msgbuf;
  364. _mav_put_float(buf, 0, ecu_index);
  365. _mav_put_float(buf, 4, rpm);
  366. _mav_put_float(buf, 8, fuel_consumed);
  367. _mav_put_float(buf, 12, fuel_flow);
  368. _mav_put_float(buf, 16, engine_load);
  369. _mav_put_float(buf, 20, throttle_position);
  370. _mav_put_float(buf, 24, spark_dwell_time);
  371. _mav_put_float(buf, 28, barometric_pressure);
  372. _mav_put_float(buf, 32, intake_manifold_pressure);
  373. _mav_put_float(buf, 36, intake_manifold_temperature);
  374. _mav_put_float(buf, 40, cylinder_head_temperature);
  375. _mav_put_float(buf, 44, ignition_timing);
  376. _mav_put_float(buf, 48, injection_time);
  377. _mav_put_float(buf, 52, exhaust_gas_temperature);
  378. _mav_put_float(buf, 56, throttle_out);
  379. _mav_put_float(buf, 60, pt_compensation);
  380. _mav_put_uint8_t(buf, 64, health);
  381. _mav_put_float(buf, 65, ignition_voltage);
  382. _mav_put_float(buf, 69, fuel_pressure);
  383. _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);
  384. #else
  385. mavlink_efi_status_t *packet = (mavlink_efi_status_t *)msgbuf;
  386. packet->ecu_index = ecu_index;
  387. packet->rpm = rpm;
  388. packet->fuel_consumed = fuel_consumed;
  389. packet->fuel_flow = fuel_flow;
  390. packet->engine_load = engine_load;
  391. packet->throttle_position = throttle_position;
  392. packet->spark_dwell_time = spark_dwell_time;
  393. packet->barometric_pressure = barometric_pressure;
  394. packet->intake_manifold_pressure = intake_manifold_pressure;
  395. packet->intake_manifold_temperature = intake_manifold_temperature;
  396. packet->cylinder_head_temperature = cylinder_head_temperature;
  397. packet->ignition_timing = ignition_timing;
  398. packet->injection_time = injection_time;
  399. packet->exhaust_gas_temperature = exhaust_gas_temperature;
  400. packet->throttle_out = throttle_out;
  401. packet->pt_compensation = pt_compensation;
  402. packet->health = health;
  403. packet->ignition_voltage = ignition_voltage;
  404. packet->fuel_pressure = fuel_pressure;
  405. _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);
  406. #endif
  407. }
  408. #endif
  409. #endif
  410. // MESSAGE EFI_STATUS UNPACKING
  411. /**
  412. * @brief Get field health from efi_status message
  413. *
  414. * @return EFI health status
  415. */
  416. static inline uint8_t mavlink_msg_efi_status_get_health(const mavlink_message_t* msg)
  417. {
  418. return _MAV_RETURN_uint8_t(msg, 64);
  419. }
  420. /**
  421. * @brief Get field ecu_index from efi_status message
  422. *
  423. * @return ECU index
  424. */
  425. static inline float mavlink_msg_efi_status_get_ecu_index(const mavlink_message_t* msg)
  426. {
  427. return _MAV_RETURN_float(msg, 0);
  428. }
  429. /**
  430. * @brief Get field rpm from efi_status message
  431. *
  432. * @return RPM
  433. */
  434. static inline float mavlink_msg_efi_status_get_rpm(const mavlink_message_t* msg)
  435. {
  436. return _MAV_RETURN_float(msg, 4);
  437. }
  438. /**
  439. * @brief Get field fuel_consumed from efi_status message
  440. *
  441. * @return [cm^3] Fuel consumed
  442. */
  443. static inline float mavlink_msg_efi_status_get_fuel_consumed(const mavlink_message_t* msg)
  444. {
  445. return _MAV_RETURN_float(msg, 8);
  446. }
  447. /**
  448. * @brief Get field fuel_flow from efi_status message
  449. *
  450. * @return [cm^3/min] Fuel flow rate
  451. */
  452. static inline float mavlink_msg_efi_status_get_fuel_flow(const mavlink_message_t* msg)
  453. {
  454. return _MAV_RETURN_float(msg, 12);
  455. }
  456. /**
  457. * @brief Get field engine_load from efi_status message
  458. *
  459. * @return [%] Engine load
  460. */
  461. static inline float mavlink_msg_efi_status_get_engine_load(const mavlink_message_t* msg)
  462. {
  463. return _MAV_RETURN_float(msg, 16);
  464. }
  465. /**
  466. * @brief Get field throttle_position from efi_status message
  467. *
  468. * @return [%] Throttle position
  469. */
  470. static inline float mavlink_msg_efi_status_get_throttle_position(const mavlink_message_t* msg)
  471. {
  472. return _MAV_RETURN_float(msg, 20);
  473. }
  474. /**
  475. * @brief Get field spark_dwell_time from efi_status message
  476. *
  477. * @return [ms] Spark dwell time
  478. */
  479. static inline float mavlink_msg_efi_status_get_spark_dwell_time(const mavlink_message_t* msg)
  480. {
  481. return _MAV_RETURN_float(msg, 24);
  482. }
  483. /**
  484. * @brief Get field barometric_pressure from efi_status message
  485. *
  486. * @return [kPa] Barometric pressure
  487. */
  488. static inline float mavlink_msg_efi_status_get_barometric_pressure(const mavlink_message_t* msg)
  489. {
  490. return _MAV_RETURN_float(msg, 28);
  491. }
  492. /**
  493. * @brief Get field intake_manifold_pressure from efi_status message
  494. *
  495. * @return [kPa] Intake manifold pressure(
  496. */
  497. static inline float mavlink_msg_efi_status_get_intake_manifold_pressure(const mavlink_message_t* msg)
  498. {
  499. return _MAV_RETURN_float(msg, 32);
  500. }
  501. /**
  502. * @brief Get field intake_manifold_temperature from efi_status message
  503. *
  504. * @return [degC] Intake manifold temperature
  505. */
  506. static inline float mavlink_msg_efi_status_get_intake_manifold_temperature(const mavlink_message_t* msg)
  507. {
  508. return _MAV_RETURN_float(msg, 36);
  509. }
  510. /**
  511. * @brief Get field cylinder_head_temperature from efi_status message
  512. *
  513. * @return [degC] Cylinder head temperature
  514. */
  515. static inline float mavlink_msg_efi_status_get_cylinder_head_temperature(const mavlink_message_t* msg)
  516. {
  517. return _MAV_RETURN_float(msg, 40);
  518. }
  519. /**
  520. * @brief Get field ignition_timing from efi_status message
  521. *
  522. * @return [deg] Ignition timing (Crank angle degrees)
  523. */
  524. static inline float mavlink_msg_efi_status_get_ignition_timing(const mavlink_message_t* msg)
  525. {
  526. return _MAV_RETURN_float(msg, 44);
  527. }
  528. /**
  529. * @brief Get field injection_time from efi_status message
  530. *
  531. * @return [ms] Injection time
  532. */
  533. static inline float mavlink_msg_efi_status_get_injection_time(const mavlink_message_t* msg)
  534. {
  535. return _MAV_RETURN_float(msg, 48);
  536. }
  537. /**
  538. * @brief Get field exhaust_gas_temperature from efi_status message
  539. *
  540. * @return [degC] Exhaust gas temperature
  541. */
  542. static inline float mavlink_msg_efi_status_get_exhaust_gas_temperature(const mavlink_message_t* msg)
  543. {
  544. return _MAV_RETURN_float(msg, 52);
  545. }
  546. /**
  547. * @brief Get field throttle_out from efi_status message
  548. *
  549. * @return [%] Output throttle
  550. */
  551. static inline float mavlink_msg_efi_status_get_throttle_out(const mavlink_message_t* msg)
  552. {
  553. return _MAV_RETURN_float(msg, 56);
  554. }
  555. /**
  556. * @brief Get field pt_compensation from efi_status message
  557. *
  558. * @return Pressure/temperature compensation
  559. */
  560. static inline float mavlink_msg_efi_status_get_pt_compensation(const mavlink_message_t* msg)
  561. {
  562. return _MAV_RETURN_float(msg, 60);
  563. }
  564. /**
  565. * @brief Get field ignition_voltage from efi_status message
  566. *
  567. * @return [V] Supply voltage to EFI sparking system. Zero in this value means "unknown", so if the supply voltage really is zero volts use 0.0001 instead.
  568. */
  569. static inline float mavlink_msg_efi_status_get_ignition_voltage(const mavlink_message_t* msg)
  570. {
  571. return _MAV_RETURN_float(msg, 65);
  572. }
  573. /**
  574. * @brief Get field fuel_pressure from efi_status message
  575. *
  576. * @return [kPa] Fuel pressure. Zero in this value means "unknown", so if the fuel pressure really is zero kPa use 0.0001 instead.
  577. */
  578. static inline float mavlink_msg_efi_status_get_fuel_pressure(const mavlink_message_t* msg)
  579. {
  580. return _MAV_RETURN_float(msg, 69);
  581. }
  582. /**
  583. * @brief Decode a efi_status message into a struct
  584. *
  585. * @param msg The message to decode
  586. * @param efi_status C-struct to decode the message contents into
  587. */
  588. static inline void mavlink_msg_efi_status_decode(const mavlink_message_t* msg, mavlink_efi_status_t* efi_status)
  589. {
  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);
  608. efi_status->ignition_voltage = mavlink_msg_efi_status_get_ignition_voltage(msg);
  609. efi_status->fuel_pressure = mavlink_msg_efi_status_get_fuel_pressure(msg);
  610. #else
  611. uint8_t len = msg->len < MAVLINK_MSG_ID_EFI_STATUS_LEN? msg->len : MAVLINK_MSG_ID_EFI_STATUS_LEN;
  612. memset(efi_status, 0, MAVLINK_MSG_ID_EFI_STATUS_LEN);
  613. memcpy(efi_status, _MAV_PAYLOAD(msg), len);
  614. #endif
  615. }