#pragma once // MESSAGE VK_ENGINE_ECU_STAUS PACKING #define MAVLINK_MSG_ID_VK_ENGINE_ECU_STAUS 53005 typedef struct __mavlink_vk_engine_ecu_staus_t { uint32_t timestamp; /*< [ms] Timestamp in ms from system boot.*/ uint32_t total_runtime; /*< [min] range extender output voltage*/ uint16_t spd_rpm; /*< rotational speed in rpm*/ int16_t cylinderA_temp; /*< [degC] CylinderA head temperature*/ int16_t cylinderB_temp; /*< [degC] CylinderB head temperature*/ int16_t coolant_temp; /*< [degC] coolant head temperature*/ uint16_t fuel_remain; /*< engine index*/ uint16_t alarm; /*< range extender alarm bitmap*/ uint16_t runtime; /*< [min] range extender output voltage*/ uint16_t service_time; /*< [min] left time for service*/ uint16_t output_volt; /*< [dV] range extender output voltage*/ uint16_t output_curr; /*< [dA] range extender output current*/ uint8_t thr_pos; /*< [%] throttle position */ uint8_t fuel_pos; /*< [%] fuel position*/ uint8_t fault; /*< engine fault*/ uint8_t engine_state; /*< engine state*/ uint8_t index; /*< engine index*/ uint8_t reserve[4]; /*< engine state*/ } mavlink_vk_engine_ecu_staus_t; #define MAVLINK_MSG_ID_VK_ENGINE_ECU_STAUS_LEN 37 #define MAVLINK_MSG_ID_VK_ENGINE_ECU_STAUS_MIN_LEN 37 #define MAVLINK_MSG_ID_53005_LEN 37 #define MAVLINK_MSG_ID_53005_MIN_LEN 37 #define MAVLINK_MSG_ID_VK_ENGINE_ECU_STAUS_CRC 145 #define MAVLINK_MSG_ID_53005_CRC 145 #define MAVLINK_MSG_VK_ENGINE_ECU_STAUS_FIELD_RESERVE_LEN 4 #if MAVLINK_COMMAND_24BIT #define MAVLINK_MESSAGE_INFO_VK_ENGINE_ECU_STAUS { \ 53005, \ "VK_ENGINE_ECU_STAUS", \ 18, \ { { "timestamp", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_vk_engine_ecu_staus_t, timestamp) }, \ { "spd_rpm", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_vk_engine_ecu_staus_t, spd_rpm) }, \ { "thr_pos", NULL, MAVLINK_TYPE_UINT8_T, 0, 28, offsetof(mavlink_vk_engine_ecu_staus_t, thr_pos) }, \ { "fuel_pos", NULL, MAVLINK_TYPE_UINT8_T, 0, 29, offsetof(mavlink_vk_engine_ecu_staus_t, fuel_pos) }, \ { "cylinderA_temp", NULL, MAVLINK_TYPE_INT16_T, 0, 10, offsetof(mavlink_vk_engine_ecu_staus_t, cylinderA_temp) }, \ { "cylinderB_temp", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_vk_engine_ecu_staus_t, cylinderB_temp) }, \ { "coolant_temp", NULL, MAVLINK_TYPE_INT16_T, 0, 14, offsetof(mavlink_vk_engine_ecu_staus_t, coolant_temp) }, \ { "fuel_remain", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_vk_engine_ecu_staus_t, fuel_remain) }, \ { "alarm", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_vk_engine_ecu_staus_t, alarm) }, \ { "total_runtime", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_vk_engine_ecu_staus_t, total_runtime) }, \ { "runtime", NULL, MAVLINK_TYPE_UINT16_T, 0, 20, offsetof(mavlink_vk_engine_ecu_staus_t, runtime) }, \ { "service_time", NULL, MAVLINK_TYPE_UINT16_T, 0, 22, offsetof(mavlink_vk_engine_ecu_staus_t, service_time) }, \ { "output_volt", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_vk_engine_ecu_staus_t, output_volt) }, \ { "output_curr", NULL, MAVLINK_TYPE_UINT16_T, 0, 26, offsetof(mavlink_vk_engine_ecu_staus_t, output_curr) }, \ { "fault", NULL, MAVLINK_TYPE_UINT8_T, 0, 30, offsetof(mavlink_vk_engine_ecu_staus_t, fault) }, \ { "engine_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 31, offsetof(mavlink_vk_engine_ecu_staus_t, engine_state) }, \ { "index", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_vk_engine_ecu_staus_t, index) }, \ { "reserve", NULL, MAVLINK_TYPE_UINT8_T, 4, 33, offsetof(mavlink_vk_engine_ecu_staus_t, reserve) }, \ } \ } #else #define MAVLINK_MESSAGE_INFO_VK_ENGINE_ECU_STAUS { \ "VK_ENGINE_ECU_STAUS", \ 18, \ { { "timestamp", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_vk_engine_ecu_staus_t, timestamp) }, \ { "spd_rpm", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_vk_engine_ecu_staus_t, spd_rpm) }, \ { "thr_pos", NULL, MAVLINK_TYPE_UINT8_T, 0, 28, offsetof(mavlink_vk_engine_ecu_staus_t, thr_pos) }, \ { "fuel_pos", NULL, MAVLINK_TYPE_UINT8_T, 0, 29, offsetof(mavlink_vk_engine_ecu_staus_t, fuel_pos) }, \ { "cylinderA_temp", NULL, MAVLINK_TYPE_INT16_T, 0, 10, offsetof(mavlink_vk_engine_ecu_staus_t, cylinderA_temp) }, \ { "cylinderB_temp", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_vk_engine_ecu_staus_t, cylinderB_temp) }, \ { "coolant_temp", NULL, MAVLINK_TYPE_INT16_T, 0, 14, offsetof(mavlink_vk_engine_ecu_staus_t, coolant_temp) }, \ { "fuel_remain", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_vk_engine_ecu_staus_t, fuel_remain) }, \ { "alarm", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_vk_engine_ecu_staus_t, alarm) }, \ { "total_runtime", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_vk_engine_ecu_staus_t, total_runtime) }, \ { "runtime", NULL, MAVLINK_TYPE_UINT16_T, 0, 20, offsetof(mavlink_vk_engine_ecu_staus_t, runtime) }, \ { "service_time", NULL, MAVLINK_TYPE_UINT16_T, 0, 22, offsetof(mavlink_vk_engine_ecu_staus_t, service_time) }, \ { "output_volt", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_vk_engine_ecu_staus_t, output_volt) }, \ { "output_curr", NULL, MAVLINK_TYPE_UINT16_T, 0, 26, offsetof(mavlink_vk_engine_ecu_staus_t, output_curr) }, \ { "fault", NULL, MAVLINK_TYPE_UINT8_T, 0, 30, offsetof(mavlink_vk_engine_ecu_staus_t, fault) }, \ { "engine_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 31, offsetof(mavlink_vk_engine_ecu_staus_t, engine_state) }, \ { "index", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_vk_engine_ecu_staus_t, index) }, \ { "reserve", NULL, MAVLINK_TYPE_UINT8_T, 4, 33, offsetof(mavlink_vk_engine_ecu_staus_t, reserve) }, \ } \ } #endif /** * @brief Pack a vk_engine_ecu_staus message * @param system_id ID of this system * @param component_id ID of this component (e.g. 200 for IMU) * @param msg The MAVLink message to compress the data into * * @param timestamp [ms] Timestamp in ms from system boot. * @param spd_rpm rotational speed in rpm * @param thr_pos [%] throttle position * @param fuel_pos [%] fuel position * @param cylinderA_temp [degC] CylinderA head temperature * @param cylinderB_temp [degC] CylinderB head temperature * @param coolant_temp [degC] coolant head temperature * @param fuel_remain engine index * @param alarm range extender alarm bitmap * @param total_runtime [min] range extender output voltage * @param runtime [min] range extender output voltage * @param service_time [min] left time for service * @param output_volt [dV] range extender output voltage * @param output_curr [dA] range extender output current * @param fault engine fault * @param engine_state engine state * @param index engine index * @param reserve engine state * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_vk_engine_ecu_staus_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, uint32_t timestamp, uint16_t spd_rpm, uint8_t thr_pos, uint8_t fuel_pos, int16_t cylinderA_temp, int16_t cylinderB_temp, int16_t coolant_temp, uint16_t fuel_remain, uint16_t alarm, uint32_t total_runtime, uint16_t runtime, uint16_t service_time, uint16_t output_volt, uint16_t output_curr, uint8_t fault, uint8_t engine_state, uint8_t index, const uint8_t *reserve) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS char buf[MAVLINK_MSG_ID_VK_ENGINE_ECU_STAUS_LEN]; _mav_put_uint32_t(buf, 0, timestamp); _mav_put_uint32_t(buf, 4, total_runtime); _mav_put_uint16_t(buf, 8, spd_rpm); _mav_put_int16_t(buf, 10, cylinderA_temp); _mav_put_int16_t(buf, 12, cylinderB_temp); _mav_put_int16_t(buf, 14, coolant_temp); _mav_put_uint16_t(buf, 16, fuel_remain); _mav_put_uint16_t(buf, 18, alarm); _mav_put_uint16_t(buf, 20, runtime); _mav_put_uint16_t(buf, 22, service_time); _mav_put_uint16_t(buf, 24, output_volt); _mav_put_uint16_t(buf, 26, output_curr); _mav_put_uint8_t(buf, 28, thr_pos); _mav_put_uint8_t(buf, 29, fuel_pos); _mav_put_uint8_t(buf, 30, fault); _mav_put_uint8_t(buf, 31, engine_state); _mav_put_uint8_t(buf, 32, index); _mav_put_uint8_t_array(buf, 33, reserve, 4); memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VK_ENGINE_ECU_STAUS_LEN); #else mavlink_vk_engine_ecu_staus_t packet; packet.timestamp = timestamp; packet.total_runtime = total_runtime; packet.spd_rpm = spd_rpm; packet.cylinderA_temp = cylinderA_temp; packet.cylinderB_temp = cylinderB_temp; packet.coolant_temp = coolant_temp; packet.fuel_remain = fuel_remain; packet.alarm = alarm; packet.runtime = runtime; packet.service_time = service_time; packet.output_volt = output_volt; packet.output_curr = output_curr; packet.thr_pos = thr_pos; packet.fuel_pos = fuel_pos; packet.fault = fault; packet.engine_state = engine_state; packet.index = index; mav_array_memcpy(packet.reserve, reserve, sizeof(uint8_t)*4); memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_VK_ENGINE_ECU_STAUS_LEN); #endif msg->msgid = MAVLINK_MSG_ID_VK_ENGINE_ECU_STAUS; return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_VK_ENGINE_ECU_STAUS_MIN_LEN, MAVLINK_MSG_ID_VK_ENGINE_ECU_STAUS_LEN, MAVLINK_MSG_ID_VK_ENGINE_ECU_STAUS_CRC); } /** * @brief Pack a vk_engine_ecu_staus message * @param system_id ID of this system * @param component_id ID of this component (e.g. 200 for IMU) * @param status MAVLink status structure * @param msg The MAVLink message to compress the data into * * @param timestamp [ms] Timestamp in ms from system boot. * @param spd_rpm rotational speed in rpm * @param thr_pos [%] throttle position * @param fuel_pos [%] fuel position * @param cylinderA_temp [degC] CylinderA head temperature * @param cylinderB_temp [degC] CylinderB head temperature * @param coolant_temp [degC] coolant head temperature * @param fuel_remain engine index * @param alarm range extender alarm bitmap * @param total_runtime [min] range extender output voltage * @param runtime [min] range extender output voltage * @param service_time [min] left time for service * @param output_volt [dV] range extender output voltage * @param output_curr [dA] range extender output current * @param fault engine fault * @param engine_state engine state * @param index engine index * @param reserve engine state * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_vk_engine_ecu_staus_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg, uint32_t timestamp, uint16_t spd_rpm, uint8_t thr_pos, uint8_t fuel_pos, int16_t cylinderA_temp, int16_t cylinderB_temp, int16_t coolant_temp, uint16_t fuel_remain, uint16_t alarm, uint32_t total_runtime, uint16_t runtime, uint16_t service_time, uint16_t output_volt, uint16_t output_curr, uint8_t fault, uint8_t engine_state, uint8_t index, const uint8_t *reserve) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS char buf[MAVLINK_MSG_ID_VK_ENGINE_ECU_STAUS_LEN]; _mav_put_uint32_t(buf, 0, timestamp); _mav_put_uint32_t(buf, 4, total_runtime); _mav_put_uint16_t(buf, 8, spd_rpm); _mav_put_int16_t(buf, 10, cylinderA_temp); _mav_put_int16_t(buf, 12, cylinderB_temp); _mav_put_int16_t(buf, 14, coolant_temp); _mav_put_uint16_t(buf, 16, fuel_remain); _mav_put_uint16_t(buf, 18, alarm); _mav_put_uint16_t(buf, 20, runtime); _mav_put_uint16_t(buf, 22, service_time); _mav_put_uint16_t(buf, 24, output_volt); _mav_put_uint16_t(buf, 26, output_curr); _mav_put_uint8_t(buf, 28, thr_pos); _mav_put_uint8_t(buf, 29, fuel_pos); _mav_put_uint8_t(buf, 30, fault); _mav_put_uint8_t(buf, 31, engine_state); _mav_put_uint8_t(buf, 32, index); _mav_put_uint8_t_array(buf, 33, reserve, 4); memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VK_ENGINE_ECU_STAUS_LEN); #else mavlink_vk_engine_ecu_staus_t packet; packet.timestamp = timestamp; packet.total_runtime = total_runtime; packet.spd_rpm = spd_rpm; packet.cylinderA_temp = cylinderA_temp; packet.cylinderB_temp = cylinderB_temp; packet.coolant_temp = coolant_temp; packet.fuel_remain = fuel_remain; packet.alarm = alarm; packet.runtime = runtime; packet.service_time = service_time; packet.output_volt = output_volt; packet.output_curr = output_curr; packet.thr_pos = thr_pos; packet.fuel_pos = fuel_pos; packet.fault = fault; packet.engine_state = engine_state; packet.index = index; mav_array_memcpy(packet.reserve, reserve, sizeof(uint8_t)*4); memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_VK_ENGINE_ECU_STAUS_LEN); #endif msg->msgid = MAVLINK_MSG_ID_VK_ENGINE_ECU_STAUS; #if MAVLINK_CRC_EXTRA return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_VK_ENGINE_ECU_STAUS_MIN_LEN, MAVLINK_MSG_ID_VK_ENGINE_ECU_STAUS_LEN, MAVLINK_MSG_ID_VK_ENGINE_ECU_STAUS_CRC); #else return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_VK_ENGINE_ECU_STAUS_MIN_LEN, MAVLINK_MSG_ID_VK_ENGINE_ECU_STAUS_LEN); #endif } /** * @brief Pack a vk_engine_ecu_staus message on a channel * @param system_id ID of this system * @param component_id ID of this component (e.g. 200 for IMU) * @param chan The MAVLink channel this message will be sent over * @param msg The MAVLink message to compress the data into * @param timestamp [ms] Timestamp in ms from system boot. * @param spd_rpm rotational speed in rpm * @param thr_pos [%] throttle position * @param fuel_pos [%] fuel position * @param cylinderA_temp [degC] CylinderA head temperature * @param cylinderB_temp [degC] CylinderB head temperature * @param coolant_temp [degC] coolant head temperature * @param fuel_remain engine index * @param alarm range extender alarm bitmap * @param total_runtime [min] range extender output voltage * @param runtime [min] range extender output voltage * @param service_time [min] left time for service * @param output_volt [dV] range extender output voltage * @param output_curr [dA] range extender output current * @param fault engine fault * @param engine_state engine state * @param index engine index * @param reserve engine state * @return length of the message in bytes (excluding serial stream start sign) */ static inline uint16_t mavlink_msg_vk_engine_ecu_staus_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, uint32_t timestamp,uint16_t spd_rpm,uint8_t thr_pos,uint8_t fuel_pos,int16_t cylinderA_temp,int16_t cylinderB_temp,int16_t coolant_temp,uint16_t fuel_remain,uint16_t alarm,uint32_t total_runtime,uint16_t runtime,uint16_t service_time,uint16_t output_volt,uint16_t output_curr,uint8_t fault,uint8_t engine_state,uint8_t index,const uint8_t *reserve) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS char buf[MAVLINK_MSG_ID_VK_ENGINE_ECU_STAUS_LEN]; _mav_put_uint32_t(buf, 0, timestamp); _mav_put_uint32_t(buf, 4, total_runtime); _mav_put_uint16_t(buf, 8, spd_rpm); _mav_put_int16_t(buf, 10, cylinderA_temp); _mav_put_int16_t(buf, 12, cylinderB_temp); _mav_put_int16_t(buf, 14, coolant_temp); _mav_put_uint16_t(buf, 16, fuel_remain); _mav_put_uint16_t(buf, 18, alarm); _mav_put_uint16_t(buf, 20, runtime); _mav_put_uint16_t(buf, 22, service_time); _mav_put_uint16_t(buf, 24, output_volt); _mav_put_uint16_t(buf, 26, output_curr); _mav_put_uint8_t(buf, 28, thr_pos); _mav_put_uint8_t(buf, 29, fuel_pos); _mav_put_uint8_t(buf, 30, fault); _mav_put_uint8_t(buf, 31, engine_state); _mav_put_uint8_t(buf, 32, index); _mav_put_uint8_t_array(buf, 33, reserve, 4); memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VK_ENGINE_ECU_STAUS_LEN); #else mavlink_vk_engine_ecu_staus_t packet; packet.timestamp = timestamp; packet.total_runtime = total_runtime; packet.spd_rpm = spd_rpm; packet.cylinderA_temp = cylinderA_temp; packet.cylinderB_temp = cylinderB_temp; packet.coolant_temp = coolant_temp; packet.fuel_remain = fuel_remain; packet.alarm = alarm; packet.runtime = runtime; packet.service_time = service_time; packet.output_volt = output_volt; packet.output_curr = output_curr; packet.thr_pos = thr_pos; packet.fuel_pos = fuel_pos; packet.fault = fault; packet.engine_state = engine_state; packet.index = index; mav_array_memcpy(packet.reserve, reserve, sizeof(uint8_t)*4); memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_VK_ENGINE_ECU_STAUS_LEN); #endif msg->msgid = MAVLINK_MSG_ID_VK_ENGINE_ECU_STAUS; return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_VK_ENGINE_ECU_STAUS_MIN_LEN, MAVLINK_MSG_ID_VK_ENGINE_ECU_STAUS_LEN, MAVLINK_MSG_ID_VK_ENGINE_ECU_STAUS_CRC); } /** * @brief Encode a vk_engine_ecu_staus struct * * @param system_id ID of this system * @param component_id ID of this component (e.g. 200 for IMU) * @param msg The MAVLink message to compress the data into * @param vk_engine_ecu_staus C-struct to read the message contents from */ static inline uint16_t mavlink_msg_vk_engine_ecu_staus_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_vk_engine_ecu_staus_t* vk_engine_ecu_staus) { return mavlink_msg_vk_engine_ecu_staus_pack(system_id, component_id, msg, vk_engine_ecu_staus->timestamp, vk_engine_ecu_staus->spd_rpm, vk_engine_ecu_staus->thr_pos, vk_engine_ecu_staus->fuel_pos, vk_engine_ecu_staus->cylinderA_temp, vk_engine_ecu_staus->cylinderB_temp, vk_engine_ecu_staus->coolant_temp, vk_engine_ecu_staus->fuel_remain, vk_engine_ecu_staus->alarm, vk_engine_ecu_staus->total_runtime, vk_engine_ecu_staus->runtime, vk_engine_ecu_staus->service_time, vk_engine_ecu_staus->output_volt, vk_engine_ecu_staus->output_curr, vk_engine_ecu_staus->fault, vk_engine_ecu_staus->engine_state, vk_engine_ecu_staus->index, vk_engine_ecu_staus->reserve); } /** * @brief Encode a vk_engine_ecu_staus struct on a channel * * @param system_id ID of this system * @param component_id ID of this component (e.g. 200 for IMU) * @param chan The MAVLink channel this message will be sent over * @param msg The MAVLink message to compress the data into * @param vk_engine_ecu_staus C-struct to read the message contents from */ static inline uint16_t mavlink_msg_vk_engine_ecu_staus_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_vk_engine_ecu_staus_t* vk_engine_ecu_staus) { return mavlink_msg_vk_engine_ecu_staus_pack_chan(system_id, component_id, chan, msg, vk_engine_ecu_staus->timestamp, vk_engine_ecu_staus->spd_rpm, vk_engine_ecu_staus->thr_pos, vk_engine_ecu_staus->fuel_pos, vk_engine_ecu_staus->cylinderA_temp, vk_engine_ecu_staus->cylinderB_temp, vk_engine_ecu_staus->coolant_temp, vk_engine_ecu_staus->fuel_remain, vk_engine_ecu_staus->alarm, vk_engine_ecu_staus->total_runtime, vk_engine_ecu_staus->runtime, vk_engine_ecu_staus->service_time, vk_engine_ecu_staus->output_volt, vk_engine_ecu_staus->output_curr, vk_engine_ecu_staus->fault, vk_engine_ecu_staus->engine_state, vk_engine_ecu_staus->index, vk_engine_ecu_staus->reserve); } /** * @brief Encode a vk_engine_ecu_staus struct with provided status structure * * @param system_id ID of this system * @param component_id ID of this component (e.g. 200 for IMU) * @param status MAVLink status structure * @param msg The MAVLink message to compress the data into * @param vk_engine_ecu_staus C-struct to read the message contents from */ static inline uint16_t mavlink_msg_vk_engine_ecu_staus_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_vk_engine_ecu_staus_t* vk_engine_ecu_staus) { return mavlink_msg_vk_engine_ecu_staus_pack_status(system_id, component_id, _status, msg, vk_engine_ecu_staus->timestamp, vk_engine_ecu_staus->spd_rpm, vk_engine_ecu_staus->thr_pos, vk_engine_ecu_staus->fuel_pos, vk_engine_ecu_staus->cylinderA_temp, vk_engine_ecu_staus->cylinderB_temp, vk_engine_ecu_staus->coolant_temp, vk_engine_ecu_staus->fuel_remain, vk_engine_ecu_staus->alarm, vk_engine_ecu_staus->total_runtime, vk_engine_ecu_staus->runtime, vk_engine_ecu_staus->service_time, vk_engine_ecu_staus->output_volt, vk_engine_ecu_staus->output_curr, vk_engine_ecu_staus->fault, vk_engine_ecu_staus->engine_state, vk_engine_ecu_staus->index, vk_engine_ecu_staus->reserve); } /** * @brief Send a vk_engine_ecu_staus message * @param chan MAVLink channel to send the message * * @param timestamp [ms] Timestamp in ms from system boot. * @param spd_rpm rotational speed in rpm * @param thr_pos [%] throttle position * @param fuel_pos [%] fuel position * @param cylinderA_temp [degC] CylinderA head temperature * @param cylinderB_temp [degC] CylinderB head temperature * @param coolant_temp [degC] coolant head temperature * @param fuel_remain engine index * @param alarm range extender alarm bitmap * @param total_runtime [min] range extender output voltage * @param runtime [min] range extender output voltage * @param service_time [min] left time for service * @param output_volt [dV] range extender output voltage * @param output_curr [dA] range extender output current * @param fault engine fault * @param engine_state engine state * @param index engine index * @param reserve engine state */ #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS static inline void mavlink_msg_vk_engine_ecu_staus_send(mavlink_channel_t chan, uint32_t timestamp, uint16_t spd_rpm, uint8_t thr_pos, uint8_t fuel_pos, int16_t cylinderA_temp, int16_t cylinderB_temp, int16_t coolant_temp, uint16_t fuel_remain, uint16_t alarm, uint32_t total_runtime, uint16_t runtime, uint16_t service_time, uint16_t output_volt, uint16_t output_curr, uint8_t fault, uint8_t engine_state, uint8_t index, const uint8_t *reserve) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS char buf[MAVLINK_MSG_ID_VK_ENGINE_ECU_STAUS_LEN]; _mav_put_uint32_t(buf, 0, timestamp); _mav_put_uint32_t(buf, 4, total_runtime); _mav_put_uint16_t(buf, 8, spd_rpm); _mav_put_int16_t(buf, 10, cylinderA_temp); _mav_put_int16_t(buf, 12, cylinderB_temp); _mav_put_int16_t(buf, 14, coolant_temp); _mav_put_uint16_t(buf, 16, fuel_remain); _mav_put_uint16_t(buf, 18, alarm); _mav_put_uint16_t(buf, 20, runtime); _mav_put_uint16_t(buf, 22, service_time); _mav_put_uint16_t(buf, 24, output_volt); _mav_put_uint16_t(buf, 26, output_curr); _mav_put_uint8_t(buf, 28, thr_pos); _mav_put_uint8_t(buf, 29, fuel_pos); _mav_put_uint8_t(buf, 30, fault); _mav_put_uint8_t(buf, 31, engine_state); _mav_put_uint8_t(buf, 32, index); _mav_put_uint8_t_array(buf, 33, reserve, 4); _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VK_ENGINE_ECU_STAUS, buf, MAVLINK_MSG_ID_VK_ENGINE_ECU_STAUS_MIN_LEN, MAVLINK_MSG_ID_VK_ENGINE_ECU_STAUS_LEN, MAVLINK_MSG_ID_VK_ENGINE_ECU_STAUS_CRC); #else mavlink_vk_engine_ecu_staus_t packet; packet.timestamp = timestamp; packet.total_runtime = total_runtime; packet.spd_rpm = spd_rpm; packet.cylinderA_temp = cylinderA_temp; packet.cylinderB_temp = cylinderB_temp; packet.coolant_temp = coolant_temp; packet.fuel_remain = fuel_remain; packet.alarm = alarm; packet.runtime = runtime; packet.service_time = service_time; packet.output_volt = output_volt; packet.output_curr = output_curr; packet.thr_pos = thr_pos; packet.fuel_pos = fuel_pos; packet.fault = fault; packet.engine_state = engine_state; packet.index = index; mav_array_memcpy(packet.reserve, reserve, sizeof(uint8_t)*4); _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VK_ENGINE_ECU_STAUS, (const char *)&packet, MAVLINK_MSG_ID_VK_ENGINE_ECU_STAUS_MIN_LEN, MAVLINK_MSG_ID_VK_ENGINE_ECU_STAUS_LEN, MAVLINK_MSG_ID_VK_ENGINE_ECU_STAUS_CRC); #endif } /** * @brief Send a vk_engine_ecu_staus message * @param chan MAVLink channel to send the message * @param struct The MAVLink struct to serialize */ static inline void mavlink_msg_vk_engine_ecu_staus_send_struct(mavlink_channel_t chan, const mavlink_vk_engine_ecu_staus_t* vk_engine_ecu_staus) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS mavlink_msg_vk_engine_ecu_staus_send(chan, vk_engine_ecu_staus->timestamp, vk_engine_ecu_staus->spd_rpm, vk_engine_ecu_staus->thr_pos, vk_engine_ecu_staus->fuel_pos, vk_engine_ecu_staus->cylinderA_temp, vk_engine_ecu_staus->cylinderB_temp, vk_engine_ecu_staus->coolant_temp, vk_engine_ecu_staus->fuel_remain, vk_engine_ecu_staus->alarm, vk_engine_ecu_staus->total_runtime, vk_engine_ecu_staus->runtime, vk_engine_ecu_staus->service_time, vk_engine_ecu_staus->output_volt, vk_engine_ecu_staus->output_curr, vk_engine_ecu_staus->fault, vk_engine_ecu_staus->engine_state, vk_engine_ecu_staus->index, vk_engine_ecu_staus->reserve); #else _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VK_ENGINE_ECU_STAUS, (const char *)vk_engine_ecu_staus, MAVLINK_MSG_ID_VK_ENGINE_ECU_STAUS_MIN_LEN, MAVLINK_MSG_ID_VK_ENGINE_ECU_STAUS_LEN, MAVLINK_MSG_ID_VK_ENGINE_ECU_STAUS_CRC); #endif } #if MAVLINK_MSG_ID_VK_ENGINE_ECU_STAUS_LEN <= MAVLINK_MAX_PAYLOAD_LEN /* This variant of _send() can be used to save stack space by re-using memory from the receive buffer. The caller provides a mavlink_message_t which is the size of a full mavlink message. This is usually the receive buffer for the channel, and allows a reply to an incoming message with minimum stack space usage. */ static inline void mavlink_msg_vk_engine_ecu_staus_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t timestamp, uint16_t spd_rpm, uint8_t thr_pos, uint8_t fuel_pos, int16_t cylinderA_temp, int16_t cylinderB_temp, int16_t coolant_temp, uint16_t fuel_remain, uint16_t alarm, uint32_t total_runtime, uint16_t runtime, uint16_t service_time, uint16_t output_volt, uint16_t output_curr, uint8_t fault, uint8_t engine_state, uint8_t index, const uint8_t *reserve) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS char *buf = (char *)msgbuf; _mav_put_uint32_t(buf, 0, timestamp); _mav_put_uint32_t(buf, 4, total_runtime); _mav_put_uint16_t(buf, 8, spd_rpm); _mav_put_int16_t(buf, 10, cylinderA_temp); _mav_put_int16_t(buf, 12, cylinderB_temp); _mav_put_int16_t(buf, 14, coolant_temp); _mav_put_uint16_t(buf, 16, fuel_remain); _mav_put_uint16_t(buf, 18, alarm); _mav_put_uint16_t(buf, 20, runtime); _mav_put_uint16_t(buf, 22, service_time); _mav_put_uint16_t(buf, 24, output_volt); _mav_put_uint16_t(buf, 26, output_curr); _mav_put_uint8_t(buf, 28, thr_pos); _mav_put_uint8_t(buf, 29, fuel_pos); _mav_put_uint8_t(buf, 30, fault); _mav_put_uint8_t(buf, 31, engine_state); _mav_put_uint8_t(buf, 32, index); _mav_put_uint8_t_array(buf, 33, reserve, 4); _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VK_ENGINE_ECU_STAUS, buf, MAVLINK_MSG_ID_VK_ENGINE_ECU_STAUS_MIN_LEN, MAVLINK_MSG_ID_VK_ENGINE_ECU_STAUS_LEN, MAVLINK_MSG_ID_VK_ENGINE_ECU_STAUS_CRC); #else mavlink_vk_engine_ecu_staus_t *packet = (mavlink_vk_engine_ecu_staus_t *)msgbuf; packet->timestamp = timestamp; packet->total_runtime = total_runtime; packet->spd_rpm = spd_rpm; packet->cylinderA_temp = cylinderA_temp; packet->cylinderB_temp = cylinderB_temp; packet->coolant_temp = coolant_temp; packet->fuel_remain = fuel_remain; packet->alarm = alarm; packet->runtime = runtime; packet->service_time = service_time; packet->output_volt = output_volt; packet->output_curr = output_curr; packet->thr_pos = thr_pos; packet->fuel_pos = fuel_pos; packet->fault = fault; packet->engine_state = engine_state; packet->index = index; mav_array_memcpy(packet->reserve, reserve, sizeof(uint8_t)*4); _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VK_ENGINE_ECU_STAUS, (const char *)packet, MAVLINK_MSG_ID_VK_ENGINE_ECU_STAUS_MIN_LEN, MAVLINK_MSG_ID_VK_ENGINE_ECU_STAUS_LEN, MAVLINK_MSG_ID_VK_ENGINE_ECU_STAUS_CRC); #endif } #endif #endif // MESSAGE VK_ENGINE_ECU_STAUS UNPACKING /** * @brief Get field timestamp from vk_engine_ecu_staus message * * @return [ms] Timestamp in ms from system boot. */ static inline uint32_t mavlink_msg_vk_engine_ecu_staus_get_timestamp(const mavlink_message_t* msg) { return _MAV_RETURN_uint32_t(msg, 0); } /** * @brief Get field spd_rpm from vk_engine_ecu_staus message * * @return rotational speed in rpm */ static inline uint16_t mavlink_msg_vk_engine_ecu_staus_get_spd_rpm(const mavlink_message_t* msg) { return _MAV_RETURN_uint16_t(msg, 8); } /** * @brief Get field thr_pos from vk_engine_ecu_staus message * * @return [%] throttle position */ static inline uint8_t mavlink_msg_vk_engine_ecu_staus_get_thr_pos(const mavlink_message_t* msg) { return _MAV_RETURN_uint8_t(msg, 28); } /** * @brief Get field fuel_pos from vk_engine_ecu_staus message * * @return [%] fuel position */ static inline uint8_t mavlink_msg_vk_engine_ecu_staus_get_fuel_pos(const mavlink_message_t* msg) { return _MAV_RETURN_uint8_t(msg, 29); } /** * @brief Get field cylinderA_temp from vk_engine_ecu_staus message * * @return [degC] CylinderA head temperature */ static inline int16_t mavlink_msg_vk_engine_ecu_staus_get_cylinderA_temp(const mavlink_message_t* msg) { return _MAV_RETURN_int16_t(msg, 10); } /** * @brief Get field cylinderB_temp from vk_engine_ecu_staus message * * @return [degC] CylinderB head temperature */ static inline int16_t mavlink_msg_vk_engine_ecu_staus_get_cylinderB_temp(const mavlink_message_t* msg) { return _MAV_RETURN_int16_t(msg, 12); } /** * @brief Get field coolant_temp from vk_engine_ecu_staus message * * @return [degC] coolant head temperature */ static inline int16_t mavlink_msg_vk_engine_ecu_staus_get_coolant_temp(const mavlink_message_t* msg) { return _MAV_RETURN_int16_t(msg, 14); } /** * @brief Get field fuel_remain from vk_engine_ecu_staus message * * @return engine index */ static inline uint16_t mavlink_msg_vk_engine_ecu_staus_get_fuel_remain(const mavlink_message_t* msg) { return _MAV_RETURN_uint16_t(msg, 16); } /** * @brief Get field alarm from vk_engine_ecu_staus message * * @return range extender alarm bitmap */ static inline uint16_t mavlink_msg_vk_engine_ecu_staus_get_alarm(const mavlink_message_t* msg) { return _MAV_RETURN_uint16_t(msg, 18); } /** * @brief Get field total_runtime from vk_engine_ecu_staus message * * @return [min] range extender output voltage */ static inline uint32_t mavlink_msg_vk_engine_ecu_staus_get_total_runtime(const mavlink_message_t* msg) { return _MAV_RETURN_uint32_t(msg, 4); } /** * @brief Get field runtime from vk_engine_ecu_staus message * * @return [min] range extender output voltage */ static inline uint16_t mavlink_msg_vk_engine_ecu_staus_get_runtime(const mavlink_message_t* msg) { return _MAV_RETURN_uint16_t(msg, 20); } /** * @brief Get field service_time from vk_engine_ecu_staus message * * @return [min] left time for service */ static inline uint16_t mavlink_msg_vk_engine_ecu_staus_get_service_time(const mavlink_message_t* msg) { return _MAV_RETURN_uint16_t(msg, 22); } /** * @brief Get field output_volt from vk_engine_ecu_staus message * * @return [dV] range extender output voltage */ static inline uint16_t mavlink_msg_vk_engine_ecu_staus_get_output_volt(const mavlink_message_t* msg) { return _MAV_RETURN_uint16_t(msg, 24); } /** * @brief Get field output_curr from vk_engine_ecu_staus message * * @return [dA] range extender output current */ static inline uint16_t mavlink_msg_vk_engine_ecu_staus_get_output_curr(const mavlink_message_t* msg) { return _MAV_RETURN_uint16_t(msg, 26); } /** * @brief Get field fault from vk_engine_ecu_staus message * * @return engine fault */ static inline uint8_t mavlink_msg_vk_engine_ecu_staus_get_fault(const mavlink_message_t* msg) { return _MAV_RETURN_uint8_t(msg, 30); } /** * @brief Get field engine_state from vk_engine_ecu_staus message * * @return engine state */ static inline uint8_t mavlink_msg_vk_engine_ecu_staus_get_engine_state(const mavlink_message_t* msg) { return _MAV_RETURN_uint8_t(msg, 31); } /** * @brief Get field index from vk_engine_ecu_staus message * * @return engine index */ static inline uint8_t mavlink_msg_vk_engine_ecu_staus_get_index(const mavlink_message_t* msg) { return _MAV_RETURN_uint8_t(msg, 32); } /** * @brief Get field reserve from vk_engine_ecu_staus message * * @return engine state */ static inline uint16_t mavlink_msg_vk_engine_ecu_staus_get_reserve(const mavlink_message_t* msg, uint8_t *reserve) { return _MAV_RETURN_uint8_t_array(msg, reserve, 4, 33); } /** * @brief Decode a vk_engine_ecu_staus message into a struct * * @param msg The message to decode * @param vk_engine_ecu_staus C-struct to decode the message contents into */ static inline void mavlink_msg_vk_engine_ecu_staus_decode(const mavlink_message_t* msg, mavlink_vk_engine_ecu_staus_t* vk_engine_ecu_staus) { #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS vk_engine_ecu_staus->timestamp = mavlink_msg_vk_engine_ecu_staus_get_timestamp(msg); vk_engine_ecu_staus->total_runtime = mavlink_msg_vk_engine_ecu_staus_get_total_runtime(msg); vk_engine_ecu_staus->spd_rpm = mavlink_msg_vk_engine_ecu_staus_get_spd_rpm(msg); vk_engine_ecu_staus->cylinderA_temp = mavlink_msg_vk_engine_ecu_staus_get_cylinderA_temp(msg); vk_engine_ecu_staus->cylinderB_temp = mavlink_msg_vk_engine_ecu_staus_get_cylinderB_temp(msg); vk_engine_ecu_staus->coolant_temp = mavlink_msg_vk_engine_ecu_staus_get_coolant_temp(msg); vk_engine_ecu_staus->fuel_remain = mavlink_msg_vk_engine_ecu_staus_get_fuel_remain(msg); vk_engine_ecu_staus->alarm = mavlink_msg_vk_engine_ecu_staus_get_alarm(msg); vk_engine_ecu_staus->runtime = mavlink_msg_vk_engine_ecu_staus_get_runtime(msg); vk_engine_ecu_staus->service_time = mavlink_msg_vk_engine_ecu_staus_get_service_time(msg); vk_engine_ecu_staus->output_volt = mavlink_msg_vk_engine_ecu_staus_get_output_volt(msg); vk_engine_ecu_staus->output_curr = mavlink_msg_vk_engine_ecu_staus_get_output_curr(msg); vk_engine_ecu_staus->thr_pos = mavlink_msg_vk_engine_ecu_staus_get_thr_pos(msg); vk_engine_ecu_staus->fuel_pos = mavlink_msg_vk_engine_ecu_staus_get_fuel_pos(msg); vk_engine_ecu_staus->fault = mavlink_msg_vk_engine_ecu_staus_get_fault(msg); vk_engine_ecu_staus->engine_state = mavlink_msg_vk_engine_ecu_staus_get_engine_state(msg); vk_engine_ecu_staus->index = mavlink_msg_vk_engine_ecu_staus_get_index(msg); mavlink_msg_vk_engine_ecu_staus_get_reserve(msg, vk_engine_ecu_staus->reserve); #else uint8_t len = msg->len < MAVLINK_MSG_ID_VK_ENGINE_ECU_STAUS_LEN? msg->len : MAVLINK_MSG_ID_VK_ENGINE_ECU_STAUS_LEN; memset(vk_engine_ecu_staus, 0, MAVLINK_MSG_ID_VK_ENGINE_ECU_STAUS_LEN); memcpy(vk_engine_ecu_staus, _MAV_PAYLOAD(msg), len); #endif }