Go to the source code of this file.
Classes | |
struct | __mavlink_battery_status_t |
Macros | |
#define | MAVLINK_MESSAGE_INFO_BATTERY_STATUS |
#define | MAVLINK_MSG_BATTERY_STATUS_FIELD_VOLTAGES_LEN 10 |
#define | MAVLINK_MSG_ID_147_CRC 154 |
#define | MAVLINK_MSG_ID_147_LEN 36 |
#define | MAVLINK_MSG_ID_BATTERY_STATUS 147 |
#define | MAVLINK_MSG_ID_BATTERY_STATUS_CRC 154 |
#define | MAVLINK_MSG_ID_BATTERY_STATUS_LEN 36 |
Typedefs | |
typedef struct __mavlink_battery_status_t | mavlink_battery_status_t |
Functions | |
static void | mavlink_msg_battery_status_decode (const mavlink_message_t *msg, mavlink_battery_status_t *battery_status) |
Decode a battery_status message into a struct. More... | |
static 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) |
Encode a battery_status struct. More... | |
static 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) |
Encode a battery_status struct on a channel. More... | |
static uint8_t | mavlink_msg_battery_status_get_battery_function (const mavlink_message_t *msg) |
Get field battery_function from battery_status message. More... | |
static int8_t | mavlink_msg_battery_status_get_battery_remaining (const mavlink_message_t *msg) |
Get field battery_remaining from battery_status message. More... | |
static int16_t | mavlink_msg_battery_status_get_current_battery (const mavlink_message_t *msg) |
Get field current_battery from battery_status message. More... | |
static int32_t | mavlink_msg_battery_status_get_current_consumed (const mavlink_message_t *msg) |
Get field current_consumed from battery_status message. More... | |
static int32_t | mavlink_msg_battery_status_get_energy_consumed (const mavlink_message_t *msg) |
Get field energy_consumed from battery_status message. More... | |
static uint8_t | mavlink_msg_battery_status_get_id (const mavlink_message_t *msg) |
Send a battery_status message. More... | |
static int16_t | mavlink_msg_battery_status_get_temperature (const mavlink_message_t *msg) |
Get field temperature from battery_status message. More... | |
static uint8_t | mavlink_msg_battery_status_get_type (const mavlink_message_t *msg) |
Get field type from battery_status message. More... | |
static uint16_t | mavlink_msg_battery_status_get_voltages (const mavlink_message_t *msg, uint16_t *voltages) |
Get field voltages from battery_status message. More... | |
static uint16_t | mavlink_msg_battery_status_pack (uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, 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) |
Pack a battery_status message. More... | |
static uint16_t | mavlink_msg_battery_status_pack_chan (uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, 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) |
Pack a battery_status message on a channel. More... | |
#define MAVLINK_MESSAGE_INFO_BATTERY_STATUS |
Definition at line 26 of file mavlink_msg_battery_status.h.
#define MAVLINK_MSG_BATTERY_STATUS_FIELD_VOLTAGES_LEN 10 |
Definition at line 24 of file mavlink_msg_battery_status.h.
#define MAVLINK_MSG_ID_147_CRC 154 |
Definition at line 22 of file mavlink_msg_battery_status.h.
#define MAVLINK_MSG_ID_147_LEN 36 |
Definition at line 19 of file mavlink_msg_battery_status.h.
#define MAVLINK_MSG_ID_BATTERY_STATUS 147 |
Definition at line 3 of file mavlink_msg_battery_status.h.
#define MAVLINK_MSG_ID_BATTERY_STATUS_CRC 154 |
Definition at line 21 of file mavlink_msg_battery_status.h.
#define MAVLINK_MSG_ID_BATTERY_STATUS_LEN 36 |
Definition at line 18 of file mavlink_msg_battery_status.h.
typedef struct __mavlink_battery_status_t mavlink_battery_status_t |
|
inlinestatic |
Decode a battery_status message into a struct.
msg | The message to decode |
battery_status | C-struct to decode the message contents into |
Definition at line 378 of file mavlink_msg_battery_status.h.
|
inlinestatic |
Encode a battery_status struct.
system_id | ID of this system |
component_id | ID of this component (e.g. 200 for IMU) |
msg | The MAVLink message to compress the data into |
battery_status | C-struct to read the message contents from |
Definition at line 159 of file mavlink_msg_battery_status.h.
|
inlinestatic |
Encode a battery_status struct on a channel.
system_id | ID of this system |
component_id | ID of this component (e.g. 200 for IMU) |
chan | The MAVLink channel this message will be sent over |
msg | The MAVLink message to compress the data into |
battery_status | C-struct to read the message contents from |
Definition at line 173 of file mavlink_msg_battery_status.h.
|
inlinestatic |
Get field battery_function from battery_status message.
Definition at line 297 of file mavlink_msg_battery_status.h.
|
inlinestatic |
Get field battery_remaining from battery_status message.
Definition at line 367 of file mavlink_msg_battery_status.h.
|
inlinestatic |
Get field current_battery from battery_status message.
Definition at line 337 of file mavlink_msg_battery_status.h.
|
inlinestatic |
Get field current_consumed from battery_status message.
Definition at line 347 of file mavlink_msg_battery_status.h.
|
inlinestatic |
Get field energy_consumed from battery_status message.
Definition at line 357 of file mavlink_msg_battery_status.h.
|
inlinestatic |
Send a battery_status message.
chan | MAVLink channel to send the message |
id | Battery ID |
battery_function | Function of the battery |
type | Type (chemistry) of the battery |
temperature | Temperature of the battery in centi-degrees celsius. INT16_MAX for unknown temperature. |
voltages | Battery voltage of cells, in millivolts (1 = 1 millivolt). Cells above the valid cell count for this battery should have the UINT16_MAX value. |
current_battery | Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current |
current_consumed | Consumed charge, in milliampere hours (1 = 1 mAh), -1: autopilot does not provide mAh consumption estimate |
energy_consumed | Consumed energy, in 100*Joules (intergrated U*I*dt) (1 = 100 Joule), -1: autopilot does not provide energy consumption estimate |
battery_remaining | Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot does not estimate the remaining battery Get field id from battery_status message |
Definition at line 287 of file mavlink_msg_battery_status.h.
|
inlinestatic |
Get field temperature from battery_status message.
Definition at line 317 of file mavlink_msg_battery_status.h.
|
inlinestatic |
Get field type from battery_status message.
Definition at line 307 of file mavlink_msg_battery_status.h.
|
inlinestatic |
Get field voltages from battery_status message.
Definition at line 327 of file mavlink_msg_battery_status.h.
|
inlinestatic |
Pack a battery_status message.
system_id | ID of this system |
component_id | ID of this component (e.g. 200 for IMU) |
msg | The MAVLink message to compress the data into |
id | Battery ID |
battery_function | Function of the battery |
type | Type (chemistry) of the battery |
temperature | Temperature of the battery in centi-degrees celsius. INT16_MAX for unknown temperature. |
voltages | Battery voltage of cells, in millivolts (1 = 1 millivolt). Cells above the valid cell count for this battery should have the UINT16_MAX value. |
current_battery | Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current |
current_consumed | Consumed charge, in milliampere hours (1 = 1 mAh), -1: autopilot does not provide mAh consumption estimate |
energy_consumed | Consumed energy, in 100*Joules (intergrated U*I*dt) (1 = 100 Joule), -1: autopilot does not provide energy consumption estimate |
battery_remaining | Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot does not estimate the remaining battery |
Definition at line 59 of file mavlink_msg_battery_status.h.
|
inlinestatic |
Pack a battery_status message on a channel.
system_id | ID of this system |
component_id | ID of this component (e.g. 200 for IMU) |
chan | The MAVLink channel this message will be sent over |
msg | The MAVLink message to compress the data into |
id | Battery ID |
battery_function | Function of the battery |
type | Type (chemistry) of the battery |
temperature | Temperature of the battery in centi-degrees celsius. INT16_MAX for unknown temperature. |
voltages | Battery voltage of cells, in millivolts (1 = 1 millivolt). Cells above the valid cell count for this battery should have the UINT16_MAX value. |
current_battery | Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current |
current_consumed | Consumed charge, in milliampere hours (1 = 1 mAh), -1: autopilot does not provide mAh consumption estimate |
energy_consumed | Consumed energy, in 100*Joules (intergrated U*I*dt) (1 = 100 Joule), -1: autopilot does not provide energy consumption estimate |
battery_remaining | Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot does not estimate the remaining battery |
Definition at line 113 of file mavlink_msg_battery_status.h.