123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554 |
- #pragma once
- // MESSAGE VK_BMS_STATUS PACKING
- #define MAVLINK_MSG_ID_VK_BMS_STATUS 53003
- typedef struct __mavlink_vk_bms_status_t {
- uint32_t time_boot_ms; /*< [ms] Timestamp in ms from system boot.*/
- uint32_t voltage; /*< [mV] BMS voltage in mV*/
- uint32_t err_code; /*< BMS error code,
- 0 means no error*/
- int16_t current; /*< [cA] BMS current in cA, negative value means in
- charging*/
- int16_t temperature; /*< [degC] BMS temperature in degC*/
- uint16_t cell_num; /*< BMS cell numbers*/
- uint16_t cell_volt[30]; /*< [mV] BMS cell voltage in mV*/
- uint16_t cyc_cnt; /*< charge and discharge times */
- int8_t cap_percent; /*< [%] BMS remaining power in percentage*/
- uint8_t bat_id; /*< BMS id, start from
- 0*/
- uint8_t health; /*< battery healthiness in
- percentage*/
- } mavlink_vk_bms_status_t;
- #define MAVLINK_MSG_ID_VK_BMS_STATUS_LEN 83
- #define MAVLINK_MSG_ID_VK_BMS_STATUS_MIN_LEN 83
- #define MAVLINK_MSG_ID_53003_LEN 83
- #define MAVLINK_MSG_ID_53003_MIN_LEN 83
- #define MAVLINK_MSG_ID_VK_BMS_STATUS_CRC 200
- #define MAVLINK_MSG_ID_53003_CRC 200
- #define MAVLINK_MSG_VK_BMS_STATUS_FIELD_CELL_VOLT_LEN 30
- #if MAVLINK_COMMAND_24BIT
- #define MAVLINK_MESSAGE_INFO_VK_BMS_STATUS { \
- 53003, \
- "VK_BMS_STATUS", \
- 11, \
- { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_vk_bms_status_t, time_boot_ms) }, \
- { "voltage", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_vk_bms_status_t, voltage) }, \
- { "current", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_vk_bms_status_t, current) }, \
- { "temperature", NULL, MAVLINK_TYPE_INT16_T, 0, 14, offsetof(mavlink_vk_bms_status_t, temperature) }, \
- { "cap_percent", NULL, MAVLINK_TYPE_INT8_T, 0, 80, offsetof(mavlink_vk_bms_status_t, cap_percent) }, \
- { "bat_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 81, offsetof(mavlink_vk_bms_status_t, bat_id) }, \
- { "err_code", "0x%04x", MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_vk_bms_status_t, err_code) }, \
- { "cell_num", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_vk_bms_status_t, cell_num) }, \
- { "cell_volt", NULL, MAVLINK_TYPE_UINT16_T, 30, 18, offsetof(mavlink_vk_bms_status_t, cell_volt) }, \
- { "cyc_cnt", NULL, MAVLINK_TYPE_UINT16_T, 0, 78, offsetof(mavlink_vk_bms_status_t, cyc_cnt) }, \
- { "health", NULL, MAVLINK_TYPE_UINT8_T, 0, 82, offsetof(mavlink_vk_bms_status_t, health) }, \
- } \
- }
- #else
- #define MAVLINK_MESSAGE_INFO_VK_BMS_STATUS { \
- "VK_BMS_STATUS", \
- 11, \
- { { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_vk_bms_status_t, time_boot_ms) }, \
- { "voltage", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_vk_bms_status_t, voltage) }, \
- { "current", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_vk_bms_status_t, current) }, \
- { "temperature", NULL, MAVLINK_TYPE_INT16_T, 0, 14, offsetof(mavlink_vk_bms_status_t, temperature) }, \
- { "cap_percent", NULL, MAVLINK_TYPE_INT8_T, 0, 80, offsetof(mavlink_vk_bms_status_t, cap_percent) }, \
- { "bat_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 81, offsetof(mavlink_vk_bms_status_t, bat_id) }, \
- { "err_code", "0x%04x", MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_vk_bms_status_t, err_code) }, \
- { "cell_num", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_vk_bms_status_t, cell_num) }, \
- { "cell_volt", NULL, MAVLINK_TYPE_UINT16_T, 30, 18, offsetof(mavlink_vk_bms_status_t, cell_volt) }, \
- { "cyc_cnt", NULL, MAVLINK_TYPE_UINT16_T, 0, 78, offsetof(mavlink_vk_bms_status_t, cyc_cnt) }, \
- { "health", NULL, MAVLINK_TYPE_UINT8_T, 0, 82, offsetof(mavlink_vk_bms_status_t, health) }, \
- } \
- }
- #endif
- /**
- * @brief Pack a vk_bms_status 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 time_boot_ms [ms] Timestamp in ms from system boot.
- * @param voltage [mV] BMS voltage in mV
- * @param current [cA] BMS current in cA, negative value means in
- charging
- * @param temperature [degC] BMS temperature in degC
- * @param cap_percent [%] BMS remaining power in percentage
- * @param bat_id BMS id, start from
- 0
- * @param err_code BMS error code,
- 0 means no error
- * @param cell_num BMS cell numbers
- * @param cell_volt [mV] BMS cell voltage in mV
- * @param cyc_cnt charge and discharge times
- * @param health battery healthiness in
- percentage
- * @return length of the message in bytes (excluding serial stream start sign)
- */
- static inline uint16_t mavlink_msg_vk_bms_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
- uint32_t time_boot_ms, uint32_t voltage, int16_t current, int16_t temperature, int8_t cap_percent, uint8_t bat_id, uint32_t err_code, uint16_t cell_num, const uint16_t *cell_volt, uint16_t cyc_cnt, uint8_t health)
- {
- #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_VK_BMS_STATUS_LEN];
- _mav_put_uint32_t(buf, 0, time_boot_ms);
- _mav_put_uint32_t(buf, 4, voltage);
- _mav_put_uint32_t(buf, 8, err_code);
- _mav_put_int16_t(buf, 12, current);
- _mav_put_int16_t(buf, 14, temperature);
- _mav_put_uint16_t(buf, 16, cell_num);
- _mav_put_uint16_t(buf, 78, cyc_cnt);
- _mav_put_int8_t(buf, 80, cap_percent);
- _mav_put_uint8_t(buf, 81, bat_id);
- _mav_put_uint8_t(buf, 82, health);
- _mav_put_uint16_t_array(buf, 18, cell_volt, 30);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VK_BMS_STATUS_LEN);
- #else
- mavlink_vk_bms_status_t packet;
- packet.time_boot_ms = time_boot_ms;
- packet.voltage = voltage;
- packet.err_code = err_code;
- packet.current = current;
- packet.temperature = temperature;
- packet.cell_num = cell_num;
- packet.cyc_cnt = cyc_cnt;
- packet.cap_percent = cap_percent;
- packet.bat_id = bat_id;
- packet.health = health;
- mav_array_memcpy(packet.cell_volt, cell_volt, sizeof(uint16_t)*30);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_VK_BMS_STATUS_LEN);
- #endif
- msg->msgid = MAVLINK_MSG_ID_VK_BMS_STATUS;
- return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_VK_BMS_STATUS_MIN_LEN, MAVLINK_MSG_ID_VK_BMS_STATUS_LEN, MAVLINK_MSG_ID_VK_BMS_STATUS_CRC);
- }
- /**
- * @brief Pack a vk_bms_status 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 time_boot_ms [ms] Timestamp in ms from system boot.
- * @param voltage [mV] BMS voltage in mV
- * @param current [cA] BMS current in cA, negative value means in
- charging
- * @param temperature [degC] BMS temperature in degC
- * @param cap_percent [%] BMS remaining power in percentage
- * @param bat_id BMS id, start from
- 0
- * @param err_code BMS error code,
- 0 means no error
- * @param cell_num BMS cell numbers
- * @param cell_volt [mV] BMS cell voltage in mV
- * @param cyc_cnt charge and discharge times
- * @param health battery healthiness in
- percentage
- * @return length of the message in bytes (excluding serial stream start sign)
- */
- static inline uint16_t mavlink_msg_vk_bms_status_pack_status(uint8_t system_id, uint8_t component_id, mavlink_status_t *_status, mavlink_message_t* msg,
- uint32_t time_boot_ms, uint32_t voltage, int16_t current, int16_t temperature, int8_t cap_percent, uint8_t bat_id, uint32_t err_code, uint16_t cell_num, const uint16_t *cell_volt, uint16_t cyc_cnt, uint8_t health)
- {
- #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_VK_BMS_STATUS_LEN];
- _mav_put_uint32_t(buf, 0, time_boot_ms);
- _mav_put_uint32_t(buf, 4, voltage);
- _mav_put_uint32_t(buf, 8, err_code);
- _mav_put_int16_t(buf, 12, current);
- _mav_put_int16_t(buf, 14, temperature);
- _mav_put_uint16_t(buf, 16, cell_num);
- _mav_put_uint16_t(buf, 78, cyc_cnt);
- _mav_put_int8_t(buf, 80, cap_percent);
- _mav_put_uint8_t(buf, 81, bat_id);
- _mav_put_uint8_t(buf, 82, health);
- _mav_put_uint16_t_array(buf, 18, cell_volt, 30);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VK_BMS_STATUS_LEN);
- #else
- mavlink_vk_bms_status_t packet;
- packet.time_boot_ms = time_boot_ms;
- packet.voltage = voltage;
- packet.err_code = err_code;
- packet.current = current;
- packet.temperature = temperature;
- packet.cell_num = cell_num;
- packet.cyc_cnt = cyc_cnt;
- packet.cap_percent = cap_percent;
- packet.bat_id = bat_id;
- packet.health = health;
- mav_array_memcpy(packet.cell_volt, cell_volt, sizeof(uint16_t)*30);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_VK_BMS_STATUS_LEN);
- #endif
- msg->msgid = MAVLINK_MSG_ID_VK_BMS_STATUS;
- #if MAVLINK_CRC_EXTRA
- return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_VK_BMS_STATUS_MIN_LEN, MAVLINK_MSG_ID_VK_BMS_STATUS_LEN, MAVLINK_MSG_ID_VK_BMS_STATUS_CRC);
- #else
- return mavlink_finalize_message_buffer(msg, system_id, component_id, _status, MAVLINK_MSG_ID_VK_BMS_STATUS_MIN_LEN, MAVLINK_MSG_ID_VK_BMS_STATUS_LEN);
- #endif
- }
- /**
- * @brief Pack a vk_bms_status 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 time_boot_ms [ms] Timestamp in ms from system boot.
- * @param voltage [mV] BMS voltage in mV
- * @param current [cA] BMS current in cA, negative value means in
- charging
- * @param temperature [degC] BMS temperature in degC
- * @param cap_percent [%] BMS remaining power in percentage
- * @param bat_id BMS id, start from
- 0
- * @param err_code BMS error code,
- 0 means no error
- * @param cell_num BMS cell numbers
- * @param cell_volt [mV] BMS cell voltage in mV
- * @param cyc_cnt charge and discharge times
- * @param health battery healthiness in
- percentage
- * @return length of the message in bytes (excluding serial stream start sign)
- */
- static inline uint16_t mavlink_msg_vk_bms_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
- mavlink_message_t* msg,
- uint32_t time_boot_ms,uint32_t voltage,int16_t current,int16_t temperature,int8_t cap_percent,uint8_t bat_id,uint32_t err_code,uint16_t cell_num,const uint16_t *cell_volt,uint16_t cyc_cnt,uint8_t health)
- {
- #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_VK_BMS_STATUS_LEN];
- _mav_put_uint32_t(buf, 0, time_boot_ms);
- _mav_put_uint32_t(buf, 4, voltage);
- _mav_put_uint32_t(buf, 8, err_code);
- _mav_put_int16_t(buf, 12, current);
- _mav_put_int16_t(buf, 14, temperature);
- _mav_put_uint16_t(buf, 16, cell_num);
- _mav_put_uint16_t(buf, 78, cyc_cnt);
- _mav_put_int8_t(buf, 80, cap_percent);
- _mav_put_uint8_t(buf, 81, bat_id);
- _mav_put_uint8_t(buf, 82, health);
- _mav_put_uint16_t_array(buf, 18, cell_volt, 30);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_VK_BMS_STATUS_LEN);
- #else
- mavlink_vk_bms_status_t packet;
- packet.time_boot_ms = time_boot_ms;
- packet.voltage = voltage;
- packet.err_code = err_code;
- packet.current = current;
- packet.temperature = temperature;
- packet.cell_num = cell_num;
- packet.cyc_cnt = cyc_cnt;
- packet.cap_percent = cap_percent;
- packet.bat_id = bat_id;
- packet.health = health;
- mav_array_memcpy(packet.cell_volt, cell_volt, sizeof(uint16_t)*30);
- memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_VK_BMS_STATUS_LEN);
- #endif
- msg->msgid = MAVLINK_MSG_ID_VK_BMS_STATUS;
- return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_VK_BMS_STATUS_MIN_LEN, MAVLINK_MSG_ID_VK_BMS_STATUS_LEN, MAVLINK_MSG_ID_VK_BMS_STATUS_CRC);
- }
- /**
- * @brief Encode a vk_bms_status 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_bms_status C-struct to read the message contents from
- */
- static inline uint16_t mavlink_msg_vk_bms_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_vk_bms_status_t* vk_bms_status)
- {
- return mavlink_msg_vk_bms_status_pack(system_id, component_id, msg, vk_bms_status->time_boot_ms, vk_bms_status->voltage, vk_bms_status->current, vk_bms_status->temperature, vk_bms_status->cap_percent, vk_bms_status->bat_id, vk_bms_status->err_code, vk_bms_status->cell_num, vk_bms_status->cell_volt, vk_bms_status->cyc_cnt, vk_bms_status->health);
- }
- /**
- * @brief Encode a vk_bms_status 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_bms_status C-struct to read the message contents from
- */
- static inline uint16_t mavlink_msg_vk_bms_status_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_vk_bms_status_t* vk_bms_status)
- {
- return mavlink_msg_vk_bms_status_pack_chan(system_id, component_id, chan, msg, vk_bms_status->time_boot_ms, vk_bms_status->voltage, vk_bms_status->current, vk_bms_status->temperature, vk_bms_status->cap_percent, vk_bms_status->bat_id, vk_bms_status->err_code, vk_bms_status->cell_num, vk_bms_status->cell_volt, vk_bms_status->cyc_cnt, vk_bms_status->health);
- }
- /**
- * @brief Encode a vk_bms_status 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_bms_status C-struct to read the message contents from
- */
- static inline uint16_t mavlink_msg_vk_bms_status_encode_status(uint8_t system_id, uint8_t component_id, mavlink_status_t* _status, mavlink_message_t* msg, const mavlink_vk_bms_status_t* vk_bms_status)
- {
- return mavlink_msg_vk_bms_status_pack_status(system_id, component_id, _status, msg, vk_bms_status->time_boot_ms, vk_bms_status->voltage, vk_bms_status->current, vk_bms_status->temperature, vk_bms_status->cap_percent, vk_bms_status->bat_id, vk_bms_status->err_code, vk_bms_status->cell_num, vk_bms_status->cell_volt, vk_bms_status->cyc_cnt, vk_bms_status->health);
- }
- /**
- * @brief Send a vk_bms_status message
- * @param chan MAVLink channel to send the message
- *
- * @param time_boot_ms [ms] Timestamp in ms from system boot.
- * @param voltage [mV] BMS voltage in mV
- * @param current [cA] BMS current in cA, negative value means in
- charging
- * @param temperature [degC] BMS temperature in degC
- * @param cap_percent [%] BMS remaining power in percentage
- * @param bat_id BMS id, start from
- 0
- * @param err_code BMS error code,
- 0 means no error
- * @param cell_num BMS cell numbers
- * @param cell_volt [mV] BMS cell voltage in mV
- * @param cyc_cnt charge and discharge times
- * @param health battery healthiness in
- percentage
- */
- #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
- static inline void mavlink_msg_vk_bms_status_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint32_t voltage, int16_t current, int16_t temperature, int8_t cap_percent, uint8_t bat_id, uint32_t err_code, uint16_t cell_num, const uint16_t *cell_volt, uint16_t cyc_cnt, uint8_t health)
- {
- #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char buf[MAVLINK_MSG_ID_VK_BMS_STATUS_LEN];
- _mav_put_uint32_t(buf, 0, time_boot_ms);
- _mav_put_uint32_t(buf, 4, voltage);
- _mav_put_uint32_t(buf, 8, err_code);
- _mav_put_int16_t(buf, 12, current);
- _mav_put_int16_t(buf, 14, temperature);
- _mav_put_uint16_t(buf, 16, cell_num);
- _mav_put_uint16_t(buf, 78, cyc_cnt);
- _mav_put_int8_t(buf, 80, cap_percent);
- _mav_put_uint8_t(buf, 81, bat_id);
- _mav_put_uint8_t(buf, 82, health);
- _mav_put_uint16_t_array(buf, 18, cell_volt, 30);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VK_BMS_STATUS, buf, MAVLINK_MSG_ID_VK_BMS_STATUS_MIN_LEN, MAVLINK_MSG_ID_VK_BMS_STATUS_LEN, MAVLINK_MSG_ID_VK_BMS_STATUS_CRC);
- #else
- mavlink_vk_bms_status_t packet;
- packet.time_boot_ms = time_boot_ms;
- packet.voltage = voltage;
- packet.err_code = err_code;
- packet.current = current;
- packet.temperature = temperature;
- packet.cell_num = cell_num;
- packet.cyc_cnt = cyc_cnt;
- packet.cap_percent = cap_percent;
- packet.bat_id = bat_id;
- packet.health = health;
- mav_array_memcpy(packet.cell_volt, cell_volt, sizeof(uint16_t)*30);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VK_BMS_STATUS, (const char *)&packet, MAVLINK_MSG_ID_VK_BMS_STATUS_MIN_LEN, MAVLINK_MSG_ID_VK_BMS_STATUS_LEN, MAVLINK_MSG_ID_VK_BMS_STATUS_CRC);
- #endif
- }
- /**
- * @brief Send a vk_bms_status message
- * @param chan MAVLink channel to send the message
- * @param struct The MAVLink struct to serialize
- */
- static inline void mavlink_msg_vk_bms_status_send_struct(mavlink_channel_t chan, const mavlink_vk_bms_status_t* vk_bms_status)
- {
- #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- mavlink_msg_vk_bms_status_send(chan, vk_bms_status->time_boot_ms, vk_bms_status->voltage, vk_bms_status->current, vk_bms_status->temperature, vk_bms_status->cap_percent, vk_bms_status->bat_id, vk_bms_status->err_code, vk_bms_status->cell_num, vk_bms_status->cell_volt, vk_bms_status->cyc_cnt, vk_bms_status->health);
- #else
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VK_BMS_STATUS, (const char *)vk_bms_status, MAVLINK_MSG_ID_VK_BMS_STATUS_MIN_LEN, MAVLINK_MSG_ID_VK_BMS_STATUS_LEN, MAVLINK_MSG_ID_VK_BMS_STATUS_CRC);
- #endif
- }
- #if MAVLINK_MSG_ID_VK_BMS_STATUS_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_bms_status_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, uint32_t voltage, int16_t current, int16_t temperature, int8_t cap_percent, uint8_t bat_id, uint32_t err_code, uint16_t cell_num, const uint16_t *cell_volt, uint16_t cyc_cnt, uint8_t health)
- {
- #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- char *buf = (char *)msgbuf;
- _mav_put_uint32_t(buf, 0, time_boot_ms);
- _mav_put_uint32_t(buf, 4, voltage);
- _mav_put_uint32_t(buf, 8, err_code);
- _mav_put_int16_t(buf, 12, current);
- _mav_put_int16_t(buf, 14, temperature);
- _mav_put_uint16_t(buf, 16, cell_num);
- _mav_put_uint16_t(buf, 78, cyc_cnt);
- _mav_put_int8_t(buf, 80, cap_percent);
- _mav_put_uint8_t(buf, 81, bat_id);
- _mav_put_uint8_t(buf, 82, health);
- _mav_put_uint16_t_array(buf, 18, cell_volt, 30);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VK_BMS_STATUS, buf, MAVLINK_MSG_ID_VK_BMS_STATUS_MIN_LEN, MAVLINK_MSG_ID_VK_BMS_STATUS_LEN, MAVLINK_MSG_ID_VK_BMS_STATUS_CRC);
- #else
- mavlink_vk_bms_status_t *packet = (mavlink_vk_bms_status_t *)msgbuf;
- packet->time_boot_ms = time_boot_ms;
- packet->voltage = voltage;
- packet->err_code = err_code;
- packet->current = current;
- packet->temperature = temperature;
- packet->cell_num = cell_num;
- packet->cyc_cnt = cyc_cnt;
- packet->cap_percent = cap_percent;
- packet->bat_id = bat_id;
- packet->health = health;
- mav_array_memcpy(packet->cell_volt, cell_volt, sizeof(uint16_t)*30);
- _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VK_BMS_STATUS, (const char *)packet, MAVLINK_MSG_ID_VK_BMS_STATUS_MIN_LEN, MAVLINK_MSG_ID_VK_BMS_STATUS_LEN, MAVLINK_MSG_ID_VK_BMS_STATUS_CRC);
- #endif
- }
- #endif
- #endif
- // MESSAGE VK_BMS_STATUS UNPACKING
- /**
- * @brief Get field time_boot_ms from vk_bms_status message
- *
- * @return [ms] Timestamp in ms from system boot.
- */
- static inline uint32_t mavlink_msg_vk_bms_status_get_time_boot_ms(const mavlink_message_t* msg)
- {
- return _MAV_RETURN_uint32_t(msg, 0);
- }
- /**
- * @brief Get field voltage from vk_bms_status message
- *
- * @return [mV] BMS voltage in mV
- */
- static inline uint32_t mavlink_msg_vk_bms_status_get_voltage(const mavlink_message_t* msg)
- {
- return _MAV_RETURN_uint32_t(msg, 4);
- }
- /**
- * @brief Get field current from vk_bms_status message
- *
- * @return [cA] BMS current in cA, negative value means in
- charging
- */
- static inline int16_t mavlink_msg_vk_bms_status_get_current(const mavlink_message_t* msg)
- {
- return _MAV_RETURN_int16_t(msg, 12);
- }
- /**
- * @brief Get field temperature from vk_bms_status message
- *
- * @return [degC] BMS temperature in degC
- */
- static inline int16_t mavlink_msg_vk_bms_status_get_temperature(const mavlink_message_t* msg)
- {
- return _MAV_RETURN_int16_t(msg, 14);
- }
- /**
- * @brief Get field cap_percent from vk_bms_status message
- *
- * @return [%] BMS remaining power in percentage
- */
- static inline int8_t mavlink_msg_vk_bms_status_get_cap_percent(const mavlink_message_t* msg)
- {
- return _MAV_RETURN_int8_t(msg, 80);
- }
- /**
- * @brief Get field bat_id from vk_bms_status message
- *
- * @return BMS id, start from
- 0
- */
- static inline uint8_t mavlink_msg_vk_bms_status_get_bat_id(const mavlink_message_t* msg)
- {
- return _MAV_RETURN_uint8_t(msg, 81);
- }
- /**
- * @brief Get field err_code from vk_bms_status message
- *
- * @return BMS error code,
- 0 means no error
- */
- static inline uint32_t mavlink_msg_vk_bms_status_get_err_code(const mavlink_message_t* msg)
- {
- return _MAV_RETURN_uint32_t(msg, 8);
- }
- /**
- * @brief Get field cell_num from vk_bms_status message
- *
- * @return BMS cell numbers
- */
- static inline uint16_t mavlink_msg_vk_bms_status_get_cell_num(const mavlink_message_t* msg)
- {
- return _MAV_RETURN_uint16_t(msg, 16);
- }
- /**
- * @brief Get field cell_volt from vk_bms_status message
- *
- * @return [mV] BMS cell voltage in mV
- */
- static inline uint16_t mavlink_msg_vk_bms_status_get_cell_volt(const mavlink_message_t* msg, uint16_t *cell_volt)
- {
- return _MAV_RETURN_uint16_t_array(msg, cell_volt, 30, 18);
- }
- /**
- * @brief Get field cyc_cnt from vk_bms_status message
- *
- * @return charge and discharge times
- */
- static inline uint16_t mavlink_msg_vk_bms_status_get_cyc_cnt(const mavlink_message_t* msg)
- {
- return _MAV_RETURN_uint16_t(msg, 78);
- }
- /**
- * @brief Get field health from vk_bms_status message
- *
- * @return battery healthiness in
- percentage
- */
- static inline uint8_t mavlink_msg_vk_bms_status_get_health(const mavlink_message_t* msg)
- {
- return _MAV_RETURN_uint8_t(msg, 82);
- }
- /**
- * @brief Decode a vk_bms_status message into a struct
- *
- * @param msg The message to decode
- * @param vk_bms_status C-struct to decode the message contents into
- */
- static inline void mavlink_msg_vk_bms_status_decode(const mavlink_message_t* msg, mavlink_vk_bms_status_t* vk_bms_status)
- {
- #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
- vk_bms_status->time_boot_ms = mavlink_msg_vk_bms_status_get_time_boot_ms(msg);
- vk_bms_status->voltage = mavlink_msg_vk_bms_status_get_voltage(msg);
- vk_bms_status->err_code = mavlink_msg_vk_bms_status_get_err_code(msg);
- vk_bms_status->current = mavlink_msg_vk_bms_status_get_current(msg);
- vk_bms_status->temperature = mavlink_msg_vk_bms_status_get_temperature(msg);
- vk_bms_status->cell_num = mavlink_msg_vk_bms_status_get_cell_num(msg);
- mavlink_msg_vk_bms_status_get_cell_volt(msg, vk_bms_status->cell_volt);
- vk_bms_status->cyc_cnt = mavlink_msg_vk_bms_status_get_cyc_cnt(msg);
- vk_bms_status->cap_percent = mavlink_msg_vk_bms_status_get_cap_percent(msg);
- vk_bms_status->bat_id = mavlink_msg_vk_bms_status_get_bat_id(msg);
- vk_bms_status->health = mavlink_msg_vk_bms_status_get_health(msg);
- #else
- uint8_t len = msg->len < MAVLINK_MSG_ID_VK_BMS_STATUS_LEN? msg->len : MAVLINK_MSG_ID_VK_BMS_STATUS_LEN;
- memset(vk_bms_status, 0, MAVLINK_MSG_ID_VK_BMS_STATUS_LEN);
- memcpy(vk_bms_status, _MAV_PAYLOAD(msg), len);
- #endif
- }
|