Classes | Defines | Typedefs | Functions
mavlink_msg_power_status.h File Reference
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Classes

struct  __mavlink_power_status_t

Defines

#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

Typedefs

typedef struct
__mavlink_power_status_t 
mavlink_power_status_t

Functions

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.
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.
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.
static uint16_t mavlink_msg_power_status_get_flags (const mavlink_message_t *msg)
 Get field flags from power_status message.
static uint16_t mavlink_msg_power_status_get_Vcc (const mavlink_message_t *msg)
 Send a power_status message.
static uint16_t mavlink_msg_power_status_get_Vservo (const mavlink_message_t *msg)
 Get field Vservo from power_status message.
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.
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.

Define Documentation

Value:
{ \
        "POWER_STATUS", \
        3, \
        {  { "Vcc", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_power_status_t, Vcc) }, \
         { "Vservo", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_power_status_t, Vservo) }, \
         { "flags", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_power_status_t, flags) }, \
         } \
}

Definition at line 20 of file mavlink_msg_power_status.h.

#define MAVLINK_MSG_ID_125_CRC   203

Definition at line 16 of file mavlink_msg_power_status.h.

#define MAVLINK_MSG_ID_125_LEN   6

Definition at line 13 of file mavlink_msg_power_status.h.

#define MAVLINK_MSG_ID_POWER_STATUS   125

Definition at line 3 of file mavlink_msg_power_status.h.

Definition at line 15 of file mavlink_msg_power_status.h.

Definition at line 12 of file mavlink_msg_power_status.h.


Typedef Documentation


Function Documentation

static void mavlink_msg_power_status_decode ( const mavlink_message_t msg,
mavlink_power_status_t power_status 
) [inline, static]

Decode a power_status message into a struct.

Parameters:
msgThe message to decode
power_statusC-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 
) [inline, static]

Encode a power_status struct.

Parameters:
system_idID of this system
component_idID of this component (e.g. 200 for IMU)
msgThe MAVLink message to compress the data into
power_statusC-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 
) [inline, static]

Encode a power_status struct on a channel.

Parameters:
system_idID of this system
component_idID of this component (e.g. 200 for IMU)
chanThe MAVLink channel this message will be sent over
msgThe MAVLink message to compress the data into
power_statusC-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) [inline, static]

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) [inline, static]

Send a power_status message.

Parameters:
chanMAVLink channel to send the message
Vcc5V rail voltage in millivolts
Vservoservo rail voltage in millivolts
flagspower 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) [inline, static]

Get field Vservo from power_status message.

Returns:
servo rail voltage in millivolts

Definition at line 227 of file mavlink_msg_power_status.h.

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 
) [inline, static]

Pack a power_status message.

Parameters:
system_idID of this system
component_idID of this component (e.g. 200 for IMU)
msgThe MAVLink message to compress the data into
Vcc5V rail voltage in millivolts
Vservoservo rail voltage in millivolts
flagspower 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 
) [inline, static]

Pack a power_status message on a channel.

Parameters:
system_idID of this system
component_idID of this component (e.g. 200 for IMU)
chanThe MAVLink channel this message will be sent over
msgThe MAVLink message to compress the data into
Vcc5V rail voltage in millivolts
Vservoservo rail voltage in millivolts
flagspower 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.



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