mavlink_msg_battery_status.h
Go to the documentation of this file.
00001 // MESSAGE BATTERY_STATUS PACKING
00002 
00003 #define MAVLINK_MSG_ID_BATTERY_STATUS 147
00004 
00005 typedef struct __mavlink_battery_status_t
00006 {
00007  int32_t current_consumed; /*< Consumed charge, in milliampere hours (1 = 1 mAh), -1: autopilot does not provide mAh consumption estimate*/
00008  int32_t energy_consumed; /*< Consumed energy, in 100*Joules (intergrated U*I*dt)  (1 = 100 Joule), -1: autopilot does not provide energy consumption estimate*/
00009  int16_t temperature; /*< Temperature of the battery in centi-degrees celsius. INT16_MAX for unknown temperature.*/
00010  uint16_t voltages[10]; /*< Battery voltage of cells, in millivolts (1 = 1 millivolt)*/
00011  int16_t current_battery; /*< Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current*/
00012  uint8_t id; /*< Battery ID*/
00013  uint8_t battery_function; /*< Function of the battery*/
00014  uint8_t type; /*< Type (chemistry) of the battery*/
00015  int8_t battery_remaining; /*< Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot does not estimate the remaining battery*/
00016 } mavlink_battery_status_t;
00017 
00018 #define MAVLINK_MSG_ID_BATTERY_STATUS_LEN 36
00019 #define MAVLINK_MSG_ID_147_LEN 36
00020 
00021 #define MAVLINK_MSG_ID_BATTERY_STATUS_CRC 154
00022 #define MAVLINK_MSG_ID_147_CRC 154
00023 
00024 #define MAVLINK_MSG_BATTERY_STATUS_FIELD_VOLTAGES_LEN 10
00025 
00026 #define MAVLINK_MESSAGE_INFO_BATTERY_STATUS { \
00027         "BATTERY_STATUS", \
00028         9, \
00029         {  { "current_consumed", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_battery_status_t, current_consumed) }, \
00030          { "energy_consumed", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_battery_status_t, energy_consumed) }, \
00031          { "temperature", NULL, MAVLINK_TYPE_INT16_T, 0, 8, offsetof(mavlink_battery_status_t, temperature) }, \
00032          { "voltages", NULL, MAVLINK_TYPE_UINT16_T, 10, 10, offsetof(mavlink_battery_status_t, voltages) }, \
00033          { "current_battery", NULL, MAVLINK_TYPE_INT16_T, 0, 30, offsetof(mavlink_battery_status_t, current_battery) }, \
00034          { "id", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_battery_status_t, id) }, \
00035          { "battery_function", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_battery_status_t, battery_function) }, \
00036          { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_battery_status_t, type) }, \
00037          { "battery_remaining", NULL, MAVLINK_TYPE_INT8_T, 0, 35, offsetof(mavlink_battery_status_t, battery_remaining) }, \
00038          } \
00039 }
00040 
00041 
00059 static inline uint16_t mavlink_msg_battery_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
00060                                                        uint8_t id, uint8_t battery_function, uint8_t type, int16_t temperature, const uint16_t *voltages, int16_t current_battery, int32_t current_consumed, int32_t energy_consumed, int8_t battery_remaining)
00061 {
00062 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00063         char buf[MAVLINK_MSG_ID_BATTERY_STATUS_LEN];
00064         _mav_put_int32_t(buf, 0, current_consumed);
00065         _mav_put_int32_t(buf, 4, energy_consumed);
00066         _mav_put_int16_t(buf, 8, temperature);
00067         _mav_put_int16_t(buf, 30, current_battery);
00068         _mav_put_uint8_t(buf, 32, id);
00069         _mav_put_uint8_t(buf, 33, battery_function);
00070         _mav_put_uint8_t(buf, 34, type);
00071         _mav_put_int8_t(buf, 35, battery_remaining);
00072         _mav_put_uint16_t_array(buf, 10, voltages, 10);
00073         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_BATTERY_STATUS_LEN);
00074 #else
00075         mavlink_battery_status_t packet;
00076         packet.current_consumed = current_consumed;
00077         packet.energy_consumed = energy_consumed;
00078         packet.temperature = temperature;
00079         packet.current_battery = current_battery;
00080         packet.id = id;
00081         packet.battery_function = battery_function;
00082         packet.type = type;
00083         packet.battery_remaining = battery_remaining;
00084         mav_array_memcpy(packet.voltages, voltages, sizeof(uint16_t)*10);
00085         memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_BATTERY_STATUS_LEN);
00086 #endif
00087 
00088         msg->msgid = MAVLINK_MSG_ID_BATTERY_STATUS;
00089 #if MAVLINK_CRC_EXTRA
00090     return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_BATTERY_STATUS_LEN, MAVLINK_MSG_ID_BATTERY_STATUS_CRC);
00091 #else
00092     return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_BATTERY_STATUS_LEN);
00093 #endif
00094 }
00095 
00113 static inline uint16_t mavlink_msg_battery_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
00114                                                            mavlink_message_t* msg,
00115                                                            uint8_t id,uint8_t battery_function,uint8_t type,int16_t temperature,const uint16_t *voltages,int16_t current_battery,int32_t current_consumed,int32_t energy_consumed,int8_t battery_remaining)
00116 {
00117 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00118         char buf[MAVLINK_MSG_ID_BATTERY_STATUS_LEN];
00119         _mav_put_int32_t(buf, 0, current_consumed);
00120         _mav_put_int32_t(buf, 4, energy_consumed);
00121         _mav_put_int16_t(buf, 8, temperature);
00122         _mav_put_int16_t(buf, 30, current_battery);
00123         _mav_put_uint8_t(buf, 32, id);
00124         _mav_put_uint8_t(buf, 33, battery_function);
00125         _mav_put_uint8_t(buf, 34, type);
00126         _mav_put_int8_t(buf, 35, battery_remaining);
00127         _mav_put_uint16_t_array(buf, 10, voltages, 10);
00128         memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_BATTERY_STATUS_LEN);
00129 #else
00130         mavlink_battery_status_t packet;
00131         packet.current_consumed = current_consumed;
00132         packet.energy_consumed = energy_consumed;
00133         packet.temperature = temperature;
00134         packet.current_battery = current_battery;
00135         packet.id = id;
00136         packet.battery_function = battery_function;
00137         packet.type = type;
00138         packet.battery_remaining = battery_remaining;
00139         mav_array_memcpy(packet.voltages, voltages, sizeof(uint16_t)*10);
00140         memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_BATTERY_STATUS_LEN);
00141 #endif
00142 
00143         msg->msgid = MAVLINK_MSG_ID_BATTERY_STATUS;
00144 #if MAVLINK_CRC_EXTRA
00145     return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_BATTERY_STATUS_LEN, MAVLINK_MSG_ID_BATTERY_STATUS_CRC);
00146 #else
00147     return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_BATTERY_STATUS_LEN);
00148 #endif
00149 }
00150 
00159 static inline uint16_t mavlink_msg_battery_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_battery_status_t* battery_status)
00160 {
00161         return mavlink_msg_battery_status_pack(system_id, component_id, msg, battery_status->id, battery_status->battery_function, battery_status->type, battery_status->temperature, battery_status->voltages, battery_status->current_battery, battery_status->current_consumed, battery_status->energy_consumed, battery_status->battery_remaining);
00162 }
00163 
00173 static inline uint16_t mavlink_msg_battery_status_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_battery_status_t* battery_status)
00174 {
00175         return mavlink_msg_battery_status_pack_chan(system_id, component_id, chan, msg, battery_status->id, battery_status->battery_function, battery_status->type, battery_status->temperature, battery_status->voltages, battery_status->current_battery, battery_status->current_consumed, battery_status->energy_consumed, battery_status->battery_remaining);
00176 }
00177 
00192 #ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
00193 
00194 static inline void mavlink_msg_battery_status_send(mavlink_channel_t chan, uint8_t id, uint8_t battery_function, uint8_t type, int16_t temperature, const uint16_t *voltages, int16_t current_battery, int32_t current_consumed, int32_t energy_consumed, int8_t battery_remaining)
00195 {
00196 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00197         char buf[MAVLINK_MSG_ID_BATTERY_STATUS_LEN];
00198         _mav_put_int32_t(buf, 0, current_consumed);
00199         _mav_put_int32_t(buf, 4, energy_consumed);
00200         _mav_put_int16_t(buf, 8, temperature);
00201         _mav_put_int16_t(buf, 30, current_battery);
00202         _mav_put_uint8_t(buf, 32, id);
00203         _mav_put_uint8_t(buf, 33, battery_function);
00204         _mav_put_uint8_t(buf, 34, type);
00205         _mav_put_int8_t(buf, 35, battery_remaining);
00206         _mav_put_uint16_t_array(buf, 10, voltages, 10);
00207 #if MAVLINK_CRC_EXTRA
00208     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_BATTERY_STATUS, buf, MAVLINK_MSG_ID_BATTERY_STATUS_LEN, MAVLINK_MSG_ID_BATTERY_STATUS_CRC);
00209 #else
00210     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_BATTERY_STATUS, buf, MAVLINK_MSG_ID_BATTERY_STATUS_LEN);
00211 #endif
00212 #else
00213         mavlink_battery_status_t packet;
00214         packet.current_consumed = current_consumed;
00215         packet.energy_consumed = energy_consumed;
00216         packet.temperature = temperature;
00217         packet.current_battery = current_battery;
00218         packet.id = id;
00219         packet.battery_function = battery_function;
00220         packet.type = type;
00221         packet.battery_remaining = battery_remaining;
00222         mav_array_memcpy(packet.voltages, voltages, sizeof(uint16_t)*10);
00223 #if MAVLINK_CRC_EXTRA
00224     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_BATTERY_STATUS, (const char *)&packet, MAVLINK_MSG_ID_BATTERY_STATUS_LEN, MAVLINK_MSG_ID_BATTERY_STATUS_CRC);
00225 #else
00226     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_BATTERY_STATUS, (const char *)&packet, MAVLINK_MSG_ID_BATTERY_STATUS_LEN);
00227 #endif
00228 #endif
00229 }
00230 
00231 #if MAVLINK_MSG_ID_BATTERY_STATUS_LEN <= MAVLINK_MAX_PAYLOAD_LEN
00232 /*
00233   This varient of _send() can be used to save stack space by re-using
00234   memory from the receive buffer.  The caller provides a
00235   mavlink_message_t which is the size of a full mavlink message. This
00236   is usually the receive buffer for the channel, and allows a reply to an
00237   incoming message with minimum stack space usage.
00238  */
00239 static inline void mavlink_msg_battery_status_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan,  uint8_t id, uint8_t battery_function, uint8_t type, int16_t temperature, const uint16_t *voltages, int16_t current_battery, int32_t current_consumed, int32_t energy_consumed, int8_t battery_remaining)
00240 {
00241 #if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
00242         char *buf = (char *)msgbuf;
00243         _mav_put_int32_t(buf, 0, current_consumed);
00244         _mav_put_int32_t(buf, 4, energy_consumed);
00245         _mav_put_int16_t(buf, 8, temperature);
00246         _mav_put_int16_t(buf, 30, current_battery);
00247         _mav_put_uint8_t(buf, 32, id);
00248         _mav_put_uint8_t(buf, 33, battery_function);
00249         _mav_put_uint8_t(buf, 34, type);
00250         _mav_put_int8_t(buf, 35, battery_remaining);
00251         _mav_put_uint16_t_array(buf, 10, voltages, 10);
00252 #if MAVLINK_CRC_EXTRA
00253     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_BATTERY_STATUS, buf, MAVLINK_MSG_ID_BATTERY_STATUS_LEN, MAVLINK_MSG_ID_BATTERY_STATUS_CRC);
00254 #else
00255     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_BATTERY_STATUS, buf, MAVLINK_MSG_ID_BATTERY_STATUS_LEN);
00256 #endif
00257 #else
00258         mavlink_battery_status_t *packet = (mavlink_battery_status_t *)msgbuf;
00259         packet->current_consumed = current_consumed;
00260         packet->energy_consumed = energy_consumed;
00261         packet->temperature = temperature;
00262         packet->current_battery = current_battery;
00263         packet->id = id;
00264         packet->battery_function = battery_function;
00265         packet->type = type;
00266         packet->battery_remaining = battery_remaining;
00267         mav_array_memcpy(packet->voltages, voltages, sizeof(uint16_t)*10);
00268 #if MAVLINK_CRC_EXTRA
00269     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_BATTERY_STATUS, (const char *)packet, MAVLINK_MSG_ID_BATTERY_STATUS_LEN, MAVLINK_MSG_ID_BATTERY_STATUS_CRC);
00270 #else
00271     _mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_BATTERY_STATUS, (const char *)packet, MAVLINK_MSG_ID_BATTERY_STATUS_LEN);
00272 #endif
00273 #endif
00274 }
00275 #endif
00276 
00277 #endif
00278 
00279 // MESSAGE BATTERY_STATUS UNPACKING
00280 
00281 
00287 static inline uint8_t mavlink_msg_battery_status_get_id(const mavlink_message_t* msg)
00288 {
00289         return _MAV_RETURN_uint8_t(msg,  32);
00290 }
00291 
00297 static inline uint8_t mavlink_msg_battery_status_get_battery_function(const mavlink_message_t* msg)
00298 {
00299         return _MAV_RETURN_uint8_t(msg,  33);
00300 }
00301 
00307 static inline uint8_t mavlink_msg_battery_status_get_type(const mavlink_message_t* msg)
00308 {
00309         return _MAV_RETURN_uint8_t(msg,  34);
00310 }
00311 
00317 static inline int16_t mavlink_msg_battery_status_get_temperature(const mavlink_message_t* msg)
00318 {
00319         return _MAV_RETURN_int16_t(msg,  8);
00320 }
00321 
00327 static inline uint16_t mavlink_msg_battery_status_get_voltages(const mavlink_message_t* msg, uint16_t *voltages)
00328 {
00329         return _MAV_RETURN_uint16_t_array(msg, voltages, 10,  10);
00330 }
00331 
00337 static inline int16_t mavlink_msg_battery_status_get_current_battery(const mavlink_message_t* msg)
00338 {
00339         return _MAV_RETURN_int16_t(msg,  30);
00340 }
00341 
00347 static inline int32_t mavlink_msg_battery_status_get_current_consumed(const mavlink_message_t* msg)
00348 {
00349         return _MAV_RETURN_int32_t(msg,  0);
00350 }
00351 
00357 static inline int32_t mavlink_msg_battery_status_get_energy_consumed(const mavlink_message_t* msg)
00358 {
00359         return _MAV_RETURN_int32_t(msg,  4);
00360 }
00361 
00367 static inline int8_t mavlink_msg_battery_status_get_battery_remaining(const mavlink_message_t* msg)
00368 {
00369         return _MAV_RETURN_int8_t(msg,  35);
00370 }
00371 
00378 static inline void mavlink_msg_battery_status_decode(const mavlink_message_t* msg, mavlink_battery_status_t* battery_status)
00379 {
00380 #if MAVLINK_NEED_BYTE_SWAP
00381         battery_status->current_consumed = mavlink_msg_battery_status_get_current_consumed(msg);
00382         battery_status->energy_consumed = mavlink_msg_battery_status_get_energy_consumed(msg);
00383         battery_status->temperature = mavlink_msg_battery_status_get_temperature(msg);
00384         mavlink_msg_battery_status_get_voltages(msg, battery_status->voltages);
00385         battery_status->current_battery = mavlink_msg_battery_status_get_current_battery(msg);
00386         battery_status->id = mavlink_msg_battery_status_get_id(msg);
00387         battery_status->battery_function = mavlink_msg_battery_status_get_battery_function(msg);
00388         battery_status->type = mavlink_msg_battery_status_get_type(msg);
00389         battery_status->battery_remaining = mavlink_msg_battery_status_get_battery_remaining(msg);
00390 #else
00391         memcpy(battery_status, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_BATTERY_STATUS_LEN);
00392 #endif
00393 }


dji_sdk_dji2mav
Author(s):
autogenerated on Thu Jun 6 2019 17:55:35