Go to the source code of this file.
|
static void | mavlink_msg_power_status_decode (const mavlink_message_t *msg, mavlink_power_status_t *power_status) |
| Decode a power_status message into a struct. More...
|
|
static uint16_t | mavlink_msg_power_status_encode (uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, const mavlink_power_status_t *power_status) |
| Encode a power_status struct. More...
|
|
static uint16_t | mavlink_msg_power_status_encode_chan (uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, const mavlink_power_status_t *power_status) |
| Encode a power_status struct on a channel. More...
|
|
static uint16_t | mavlink_msg_power_status_get_flags (const mavlink_message_t *msg) |
| Get field flags from power_status message. More...
|
|
static uint16_t | mavlink_msg_power_status_get_Vcc (const mavlink_message_t *msg) |
| Send a power_status message. More...
|
|
static uint16_t | mavlink_msg_power_status_get_Vservo (const mavlink_message_t *msg) |
| Get field Vservo from power_status message. More...
|
|
static uint16_t | mavlink_msg_power_status_pack (uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, uint16_t Vcc, uint16_t Vservo, uint16_t flags) |
| Pack a power_status message. More...
|
|
static uint16_t | mavlink_msg_power_status_pack_chan (uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, uint16_t Vcc, uint16_t Vservo, uint16_t flags) |
| Pack a power_status message on a channel. More...
|
|
#define MAVLINK_MESSAGE_INFO_POWER_STATUS |
#define MAVLINK_MSG_ID_125_CRC 203 |
#define MAVLINK_MSG_ID_125_LEN 6 |
#define MAVLINK_MSG_ID_POWER_STATUS 125 |
#define MAVLINK_MSG_ID_POWER_STATUS_CRC 203 |
#define MAVLINK_MSG_ID_POWER_STATUS_LEN 6 |
static void mavlink_msg_power_status_decode |
( |
const mavlink_message_t * |
msg, |
|
|
mavlink_power_status_t * |
power_status |
|
) |
| |
|
inlinestatic |
Decode a power_status message into a struct.
- Parameters
-
msg | The message to decode |
power_status | C-struct to decode the message contents into |
Definition at line 248 of file mavlink_msg_power_status.h.
static uint16_t mavlink_msg_power_status_encode |
( |
uint8_t |
system_id, |
|
|
uint8_t |
component_id, |
|
|
mavlink_message_t * |
msg, |
|
|
const mavlink_power_status_t * |
power_status |
|
) |
| |
|
inlinestatic |
Encode a power_status struct.
- Parameters
-
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 |
power_status | C-struct to read the message contents from |
Definition at line 115 of file mavlink_msg_power_status.h.
static uint16_t mavlink_msg_power_status_encode_chan |
( |
uint8_t |
system_id, |
|
|
uint8_t |
component_id, |
|
|
uint8_t |
chan, |
|
|
mavlink_message_t * |
msg, |
|
|
const mavlink_power_status_t * |
power_status |
|
) |
| |
|
inlinestatic |
Encode a power_status struct on a channel.
- Parameters
-
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 |
power_status | C-struct to read the message contents from |
Definition at line 129 of file mavlink_msg_power_status.h.
static uint16_t mavlink_msg_power_status_get_flags |
( |
const mavlink_message_t * |
msg | ) |
|
|
inlinestatic |
Get field flags from power_status message.
- Returns
- power supply status flags (see MAV_POWER_STATUS enum)
Definition at line 237 of file mavlink_msg_power_status.h.
static uint16_t mavlink_msg_power_status_get_Vcc |
( |
const mavlink_message_t * |
msg | ) |
|
|
inlinestatic |
Send a power_status message.
- Parameters
-
chan | MAVLink channel to send the message |
Vcc | 5V rail voltage in millivolts |
Vservo | servo rail voltage in millivolts |
flags | power supply status flags (see MAV_POWER_STATUS enum) Get field Vcc from power_status message |
- Returns
- 5V rail voltage in millivolts
Definition at line 217 of file mavlink_msg_power_status.h.
static uint16_t mavlink_msg_power_status_get_Vservo |
( |
const mavlink_message_t * |
msg | ) |
|
|
inlinestatic |
static uint16_t mavlink_msg_power_status_pack |
( |
uint8_t |
system_id, |
|
|
uint8_t |
component_id, |
|
|
mavlink_message_t * |
msg, |
|
|
uint16_t |
Vcc, |
|
|
uint16_t |
Vservo, |
|
|
uint16_t |
flags |
|
) |
| |
|
inlinestatic |
Pack a power_status message.
- Parameters
-
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 |
Vcc | 5V rail voltage in millivolts |
Vservo | servo rail voltage in millivolts |
flags | power supply status flags (see MAV_POWER_STATUS enum) |
- Returns
- length of the message in bytes (excluding serial stream start sign)
Definition at line 41 of file mavlink_msg_power_status.h.
static uint16_t mavlink_msg_power_status_pack_chan |
( |
uint8_t |
system_id, |
|
|
uint8_t |
component_id, |
|
|
uint8_t |
chan, |
|
|
mavlink_message_t * |
msg, |
|
|
uint16_t |
Vcc, |
|
|
uint16_t |
Vservo, |
|
|
uint16_t |
flags |
|
) |
| |
|
inlinestatic |
Pack a power_status message on a channel.
- Parameters
-
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 |
Vcc | 5V rail voltage in millivolts |
Vservo | servo rail voltage in millivolts |
flags | power supply status flags (see MAV_POWER_STATUS enum) |
- Returns
- length of the message in bytes (excluding serial stream start sign)
Definition at line 79 of file mavlink_msg_power_status.h.