
Go to the source code of this file.
| Classes | |
| struct | __mavlink_gps_inject_data_t | 
| Macros | |
| #define | MAVLINK_MESSAGE_INFO_GPS_INJECT_DATA | 
| #define | MAVLINK_MSG_GPS_INJECT_DATA_FIELD_DATA_LEN 110 | 
| #define | MAVLINK_MSG_ID_123_CRC 250 | 
| #define | MAVLINK_MSG_ID_123_LEN 113 | 
| #define | MAVLINK_MSG_ID_GPS_INJECT_DATA 123 | 
| #define | MAVLINK_MSG_ID_GPS_INJECT_DATA_CRC 250 | 
| #define | MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN 113 | 
| Typedefs | |
| typedef struct __mavlink_gps_inject_data_t | mavlink_gps_inject_data_t | 
| Functions | |
| static void | mavlink_msg_gps_inject_data_decode (const mavlink_message_t *msg, mavlink_gps_inject_data_t *gps_inject_data) | 
| Decode a gps_inject_data message into a struct.  More... | |
| static uint16_t | mavlink_msg_gps_inject_data_encode (uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, const mavlink_gps_inject_data_t *gps_inject_data) | 
| Encode a gps_inject_data struct.  More... | |
| static uint16_t | mavlink_msg_gps_inject_data_encode_chan (uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, const mavlink_gps_inject_data_t *gps_inject_data) | 
| Encode a gps_inject_data struct on a channel.  More... | |
| static uint16_t | mavlink_msg_gps_inject_data_get_data (const mavlink_message_t *msg, uint8_t *data) | 
| Get field data from gps_inject_data message.  More... | |
| static uint8_t | mavlink_msg_gps_inject_data_get_len (const mavlink_message_t *msg) | 
| Get field len from gps_inject_data message.  More... | |
| static uint8_t | mavlink_msg_gps_inject_data_get_target_component (const mavlink_message_t *msg) | 
| Get field target_component from gps_inject_data message.  More... | |
| static uint8_t | mavlink_msg_gps_inject_data_get_target_system (const mavlink_message_t *msg) | 
| Send a gps_inject_data message.  More... | |
| static uint16_t | mavlink_msg_gps_inject_data_pack (uint8_t system_id, uint8_t component_id, mavlink_message_t *msg, uint8_t target_system, uint8_t target_component, uint8_t len, const uint8_t *data) | 
| Pack a gps_inject_data message.  More... | |
| static uint16_t | mavlink_msg_gps_inject_data_pack_chan (uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t *msg, uint8_t target_system, uint8_t target_component, uint8_t len, const uint8_t *data) | 
| Pack a gps_inject_data message on a channel.  More... | |
| #define MAVLINK_MESSAGE_INFO_GPS_INJECT_DATA | 
Definition at line 21 of file mavlink_msg_gps_inject_data.h.
| #define MAVLINK_MSG_GPS_INJECT_DATA_FIELD_DATA_LEN 110 | 
Definition at line 19 of file mavlink_msg_gps_inject_data.h.
| #define MAVLINK_MSG_ID_123_CRC 250 | 
Definition at line 17 of file mavlink_msg_gps_inject_data.h.
| #define MAVLINK_MSG_ID_123_LEN 113 | 
Definition at line 14 of file mavlink_msg_gps_inject_data.h.
| #define MAVLINK_MSG_ID_GPS_INJECT_DATA 123 | 
Definition at line 3 of file mavlink_msg_gps_inject_data.h.
| #define MAVLINK_MSG_ID_GPS_INJECT_DATA_CRC 250 | 
Definition at line 16 of file mavlink_msg_gps_inject_data.h.
| #define MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN 113 | 
Definition at line 13 of file mavlink_msg_gps_inject_data.h.
| typedef struct __mavlink_gps_inject_data_t mavlink_gps_inject_data_t | 
| 
 | inlinestatic | 
Decode a gps_inject_data message into a struct.
| msg | The message to decode | 
| gps_inject_data | C-struct to decode the message contents into | 
Definition at line 263 of file mavlink_msg_gps_inject_data.h.
| 
 | inlinestatic | 
Encode a gps_inject_data 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 | 
| gps_inject_data | C-struct to read the message contents from | 
Definition at line 119 of file mavlink_msg_gps_inject_data.h.
| 
 | inlinestatic | 
Encode a gps_inject_data 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 | 
| gps_inject_data | C-struct to read the message contents from | 
Definition at line 133 of file mavlink_msg_gps_inject_data.h.
| 
 | inlinestatic | 
Get field data from gps_inject_data message.
Definition at line 252 of file mavlink_msg_gps_inject_data.h.
| 
 | inlinestatic | 
Get field len from gps_inject_data message.
Definition at line 242 of file mavlink_msg_gps_inject_data.h.
| 
 | inlinestatic | 
Get field target_component from gps_inject_data message.
Definition at line 232 of file mavlink_msg_gps_inject_data.h.
| 
 | inlinestatic | 
Send a gps_inject_data message.
| chan | MAVLink channel to send the message | 
| target_system | System ID | 
| target_component | Component ID | 
| len | data length | 
| data | raw data (110 is enough for 12 satellites of RTCMv2) Get field target_system from gps_inject_data message | 
Definition at line 222 of file mavlink_msg_gps_inject_data.h.
| 
 | inlinestatic | 
Pack a gps_inject_data 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 | 
| target_system | System ID | 
| target_component | Component ID | 
| len | data length | 
| data | raw data (110 is enough for 12 satellites of RTCMv2) | 
Definition at line 44 of file mavlink_msg_gps_inject_data.h.
| 
 | inlinestatic | 
Pack a gps_inject_data 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 | 
| target_system | System ID | 
| target_component | Component ID | 
| len | data length | 
| data | raw data (110 is enough for 12 satellites of RTCMv2) | 
Definition at line 83 of file mavlink_msg_gps_inject_data.h.