Subversion Repositories Projects

Compare Revisions

Ignore whitespace Rev 1701 → Rev 1702

/C-OSD/arducam-osd/libraries/GCS_MAVLink/.gitignore
0,0 → 1,16
*~
doc/html
doc/*.log
 
include/mavlink/v0.9/slugs/
include/mavlink/v0.9/ualberta/
include/mavlink/v0.9/minimal/
include/mavlink/v0.9/test/
include/mavlink/v0.9/pixhawk/
 
include/mavlink/v1.0/slugs/
include/mavlink/v1.0/ualberta/
include/mavlink/v1.0/minimal/
include/mavlink/v1.0/test/
include/mavlink/v1.0/pixhawk/
include/mavlink/v1.0/sensoar/
/C-OSD/arducam-osd/libraries/GCS_MAVLink/GCS_MAVLink.h
0,0 → 1,130
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: t -*-
 
/// @file GCS_MAVLink.h
/// @brief One size fits all header for MAVLink integration.
 
#ifndef GCS_MAVLink_h
#define GCS_MAVLink_h
 
#include <BetterStream.h>
 
// we have separate helpers disabled to make it possible
// to select MAVLink 1.0 in the arduino GUI build
//#define MAVLINK_SEPARATE_HELPERS
 
#ifdef MAVLINK10
# include "include/mavlink/v1.0/ardupilotmega/version.h"
#else
# include "include/mavlink/v0.9/ardupilotmega/version.h"
#endif
 
// this allows us to make mavlink_message_t much smaller
#define MAVLINK_MAX_PAYLOAD_LEN MAVLINK_MAX_DIALECT_PAYLOAD_SIZE
 
#define MAVLINK_COMM_NUM_BUFFERS 2
#ifdef MAVLINK10
# include "include/mavlink/v1.0/mavlink_types.h"
#else
# include "include/mavlink/v0.9/mavlink_types.h"
#endif
 
/// MAVLink stream used for HIL interaction
extern BetterStream *mavlink_comm_0_port;
 
/// MAVLink stream used for ground control communication
extern BetterStream *mavlink_comm_1_port;
 
/// MAVLink system definition
extern mavlink_system_t mavlink_system;
 
/// Send a byte to the nominated MAVLink channel
///
/// @param chan Channel to send to
/// @param ch Byte to send
///
static inline void comm_send_ch(mavlink_channel_t chan, uint8_t ch)
{
switch(chan) {
case MAVLINK_COMM_0:
mavlink_comm_0_port->write(ch);
break;
case MAVLINK_COMM_1:
mavlink_comm_1_port->write(ch);
break;
default:
break;
}
}
 
/// Read a byte from the nominated MAVLink channel
///
/// @param chan Channel to receive on
/// @returns Byte read
///
static inline uint8_t comm_receive_ch(mavlink_channel_t chan)
{
uint8_t data = 0;
 
switch(chan) {
case MAVLINK_COMM_0:
data = mavlink_comm_0_port->read();
break;
case MAVLINK_COMM_1:
data = mavlink_comm_1_port->read();
break;
default:
break;
}
return data;
}
 
/// Check for available data on the nominated MAVLink channel
///
/// @param chan Channel to check
/// @returns Number of bytes available
static inline uint16_t comm_get_available(mavlink_channel_t chan)
{
uint16_t bytes = 0;
switch(chan) {
case MAVLINK_COMM_0:
bytes = mavlink_comm_0_port->available();
break;
case MAVLINK_COMM_1:
bytes = mavlink_comm_1_port->available();
break;
default:
break;
}
return bytes;
}
 
 
/// Check for available transmit space on the nominated MAVLink channel
///
/// @param chan Channel to check
/// @returns Number of bytes available, -1 for error
static inline int comm_get_txspace(mavlink_channel_t chan)
{
switch(chan) {
case MAVLINK_COMM_0:
return mavlink_comm_0_port->txspace();
break;
case MAVLINK_COMM_1:
return mavlink_comm_1_port->txspace();
break;
default:
break;
}
return -1;
}
 
#define MAVLINK_USE_CONVENIENCE_FUNCTIONS
#ifdef MAVLINK10
# include "include/mavlink/v1.0/ardupilotmega/mavlink.h"
#else
# include "include/mavlink/v0.9/ardupilotmega/mavlink.h"
#endif
 
uint8_t mavlink_check_target(uint8_t sysid, uint8_t compid);
 
#endif // GCS_MAVLink_h
/C-OSD/arducam-osd/libraries/GCS_MAVLink/Mavlink_compat.h
0,0 → 1,174
/*
compatibility header during transition to MAVLink 1.0
*/
 
#ifdef MAVLINK10
// in MAVLink 1.0 'waypoint' becomes 'mission'. We can remove these
// mappings once we are not trying to support both protocols
 
#define MAVLINK_MSG_ID_WAYPOINT_CURRENT MAVLINK_MSG_ID_MISSION_CURRENT
#define MAVLINK_MSG_ID_WAYPOINT_CURRENT_LEN MAVLINK_MSG_ID_MISSION_CURRENT_LEN
#define mavlink_msg_waypoint_current_send mavlink_msg_mission_current_send
#define mavlink_msg_waypoint_current_decode mavlink_msg_mission_current_decode
 
#define MAVLINK_MSG_ID_WAYPOINT_COUNT MAVLINK_MSG_ID_MISSION_COUNT
#define MAVLINK_MSG_ID_WAYPOINT_COUNT_LEN MAVLINK_MSG_ID_MISSION_COUNT_LEN
#define mavlink_msg_waypoint_count_send mavlink_msg_mission_count_send
#define mavlink_msg_waypoint_count_decode mavlink_msg_mission_count_decode
#define mavlink_waypoint_count_t mavlink_mission_count_t
 
#define MAVLINK_MSG_ID_WAYPOINT_REQUEST MAVLINK_MSG_ID_MISSION_REQUEST
#define MAVLINK_MSG_ID_WAYPOINT_REQUEST_LEN MAVLINK_MSG_ID_MISSION_REQUEST_LEN
#define mavlink_msg_waypoint_request_send mavlink_msg_mission_request_send
#define mavlink_msg_waypoint_request_decode mavlink_msg_mission_request_decode
#define mavlink_waypoint_request_t mavlink_mission_request_t
 
#define MAVLINK_MSG_ID_WAYPOINT_REQUEST_LIST MAVLINK_MSG_ID_MISSION_REQUEST_LIST
#define MAVLINK_MSG_ID_WAYPOINT_REQUEST_LIST_LEN MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN
#define mavlink_msg_waypoint_request_list_send mavlink_msg_mission_request_list_send
#define mavlink_msg_waypoint_request_list_decode mavlink_msg_mission_request_list_decode
#define mavlink_waypoint_request_list_t mavlink_mission_request_list_t
 
#define MAVLINK_MSG_ID_WAYPOINT MAVLINK_MSG_ID_MISSION_ITEM
#define MAVLINK_MSG_ID_WAYPOINT_LEN MAVLINK_MSG_ID_MISSION_ITEM_LEN
#define mavlink_msg_waypoint_send mavlink_msg_mission_item_send
#define mavlink_msg_waypoint_decode mavlink_msg_mission_item_decode
#define mavlink_waypoint_t mavlink_mission_item_t
 
#define MAVLINK_MSG_ID_WAYPOINT_ACK MAVLINK_MSG_ID_MISSION_ACK
#define MAVLINK_MSG_ID_WAYPOINT_ACK_LEN MAVLINK_MSG_ID_MISSION_ACK_LEN
#define mavlink_msg_waypoint_ack_send mavlink_msg_mission_ack_send
#define mavlink_msg_waypoint_ack_decode mavlink_msg_mission_ack_decode
#define mavlink_waypoint_ack_t mavlink_mission_ack_t
 
#define MAVLINK_MSG_ID_WAYPOINT_CLEAR_ALL MAVLINK_MSG_ID_MISSION_CLEAR_ALL
#define MAVLINK_MSG_ID_WAYPOINT_CLEAR_ALL_LEN MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN
#define mavlink_msg_waypoint_clear_all_send mavlink_msg_mission_clear_all_send
#define mavlink_msg_waypoint_clear_all_decode mavlink_msg_mission_clear_all_decode
#define mavlink_waypoint_clear_all_t mavlink_mission_clear_all_t
 
#define MAVLINK_MSG_ID_WAYPOINT_SET_CURRENT MAVLINK_MSG_ID_MISSION_SET_CURRENT
#define MAVLINK_MSG_ID_WAYPOINT_SET_CURRENT_LEN MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN
#define mavlink_msg_waypoint_set_current_send mavlink_msg_mission_set_current_send
#define mavlink_msg_waypoint_set_current_decode mavlink_msg_mission_set_current_decode
#define mavlink_waypoint_set_current_t mavlink_mission_set_current_t
 
#define MAV_CMD_DO_SET_ROI MAV_CMD_NAV_ROI
 
static uint8_t mav_var_type(enum ap_var_type t)
{
if (t == AP_PARAM_INT8) {
return MAV_VAR_INT8;
}
if (t == AP_PARAM_INT16) {
return MAV_VAR_INT16;
}
if (t == AP_PARAM_INT32) {
return MAV_VAR_INT32;
}
// treat any others as float
return MAV_VAR_FLOAT;
}
 
#define MAV_FIXED_WING MAV_TYPE_FIXED_WING
 
#else // MAVLINK10
 
static uint8_t mav_var_type(enum ap_var_type t)
{
return 0;
}
 
#define MAV_MISSION_ACCEPTED 0
#define MAV_MISSION_UNSUPPORTED 1
#define MAV_MISSION_UNSUPPORTED_FRAME 1
#define MAV_MISSION_ERROR 1
#define MAV_MISSION_INVALID_SEQUENCE 1
 
/*
some functions have some extra params in MAVLink 1.0
*/
 
static void mavlink_msg_global_position_int_send(mavlink_channel_t chan, uint32_t time_boot_ms, int32_t lat, int32_t lon,
int32_t alt, int32_t relative_alt, int16_t vx, int16_t vy,
int16_t vz, uint16_t hdg)
{
mavlink_msg_global_position_int_send(
chan,
lat,
lon,
alt,
vx, vy, vz);
}
 
static void mavlink_msg_rc_channels_scaled_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t port,
int16_t chan1_scaled, int16_t chan2_scaled, int16_t chan3_scaled,
int16_t chan4_scaled, int16_t chan5_scaled, int16_t chan6_scaled,
int16_t chan7_scaled, int16_t chan8_scaled, uint8_t rssi)
{
mavlink_msg_rc_channels_scaled_send(
chan,
chan1_scaled,
chan2_scaled,
chan3_scaled,
chan4_scaled,
chan5_scaled,
chan6_scaled,
chan7_scaled,
chan8_scaled,
rssi);
}
 
static void mavlink_msg_rc_channels_raw_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t port,
uint16_t chan1_raw, uint16_t chan2_raw, uint16_t chan3_raw,
uint16_t chan4_raw, uint16_t chan5_raw, uint16_t chan6_raw,
uint16_t chan7_raw, uint16_t chan8_raw, uint8_t rssi)
{
mavlink_msg_rc_channels_raw_send(
chan,
chan1_raw,
chan2_raw,
chan3_raw,
chan4_raw,
chan5_raw,
chan6_raw,
chan7_raw,
chan8_raw,
rssi);
}
 
 
static void mavlink_msg_servo_output_raw_send(mavlink_channel_t chan, uint32_t time_usec, uint8_t port,
uint16_t servo1_raw, uint16_t servo2_raw, uint16_t servo3_raw,
uint16_t servo4_raw, uint16_t servo5_raw, uint16_t servo6_raw,
uint16_t servo7_raw, uint16_t servo8_raw)
{
mavlink_msg_servo_output_raw_send(
chan,
servo1_raw,
servo2_raw,
servo3_raw,
servo4_raw,
servo5_raw,
servo6_raw,
servo7_raw,
servo8_raw);
}
 
static void mavlink_msg_statustext_send(mavlink_channel_t chan, uint8_t severity, const char *text)
{
mavlink_msg_statustext_send(chan, severity, (const int8_t*) text);
}
 
static void mavlink_msg_param_value_send(mavlink_channel_t chan, const char *param_id,
float param_value, uint8_t param_type,
uint16_t param_count, uint16_t param_index)
{
mavlink_msg_param_value_send(
chan,
(int8_t *)param_id,
param_value,
param_count,
param_index);
}
#endif // MAVLINK10
/C-OSD/arducam-osd/libraries/GCS_MAVLink/VERSION
0,0 → 1,0
1.0.7
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/config.h
0,0 → 1,0
#define MAVLINK_VERSION "1.0.7"
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v0.9/ardupilotmega/ardupilotmega.h
0,0 → 1,154
/** @file
* @brief MAVLink comm protocol generated from ardupilotmega.xml
* @see http://qgroundcontrol.org/mavlink/
*/
#ifndef ARDUPILOTMEGA_H
#define ARDUPILOTMEGA_H
 
#ifdef __cplusplus
extern "C" {
#endif
 
// MESSAGE LENGTHS AND CRCS
 
#ifndef MAVLINK_MESSAGE_LENGTHS
#define MAVLINK_MESSAGE_LENGTHS {3, 4, 8, 14, 8, 28, 3, 32, 0, 2, 3, 2, 2, 0, 0, 0, 0, 0, 0, 0, 19, 2, 23, 21, 0, 37, 26, 101, 26, 16, 32, 32, 37, 32, 11, 17, 17, 16, 18, 36, 4, 4, 2, 2, 4, 2, 2, 3, 14, 12, 18, 16, 8, 27, 25, 18, 18, 24, 24, 0, 0, 0, 26, 16, 36, 5, 6, 56, 26, 21, 18, 0, 0, 18, 20, 20, 8, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 18, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 36, 0, 0, 0, 0, 0, 0, 0, 0, 0, 42, 8, 4, 12, 15, 13, 6, 15, 14, 0, 12, 3, 8, 28, 36, 3, 9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 30, 14, 14, 51, 5}
#endif
 
#ifndef MAVLINK_MESSAGE_CRCS
#define MAVLINK_MESSAGE_CRCS {72, 39, 190, 92, 191, 217, 104, 119, 0, 219, 60, 186, 10, 0, 0, 0, 0, 0, 0, 0, 89, 159, 162, 121, 0, 149, 222, 110, 179, 136, 66, 126, 185, 147, 112, 252, 162, 215, 229, 128, 9, 106, 101, 213, 4, 229, 21, 214, 215, 14, 206, 50, 157, 126, 108, 213, 95, 5, 127, 0, 0, 0, 57, 126, 130, 119, 193, 191, 236, 158, 143, 0, 0, 104, 123, 131, 8, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 174, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 155, 0, 0, 0, 0, 0, 0, 0, 0, 0, 143, 29, 208, 188, 118, 242, 19, 97, 233, 0, 18, 68, 136, 127, 42, 21, 93, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 178, 224, 60, 106, 7}
#endif
 
#ifndef MAVLINK_MESSAGE_INFO
#define MAVLINK_MESSAGE_INFO {MAVLINK_MESSAGE_INFO_HEARTBEAT, MAVLINK_MESSAGE_INFO_BOOT, MAVLINK_MESSAGE_INFO_SYSTEM_TIME, MAVLINK_MESSAGE_INFO_PING, MAVLINK_MESSAGE_INFO_SYSTEM_TIME_UTC, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL_ACK, MAVLINK_MESSAGE_INFO_AUTH_KEY, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_ACTION_ACK, MAVLINK_MESSAGE_INFO_ACTION, MAVLINK_MESSAGE_INFO_SET_MODE, MAVLINK_MESSAGE_INFO_SET_NAV_MODE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_READ, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_LIST, MAVLINK_MESSAGE_INFO_PARAM_VALUE, MAVLINK_MESSAGE_INFO_PARAM_SET, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_GPS_RAW_INT, MAVLINK_MESSAGE_INFO_SCALED_IMU, MAVLINK_MESSAGE_INFO_GPS_STATUS, MAVLINK_MESSAGE_INFO_RAW_IMU, MAVLINK_MESSAGE_INFO_RAW_PRESSURE, MAVLINK_MESSAGE_INFO_ATTITUDE, MAVLINK_MESSAGE_INFO_LOCAL_POSITION, MAVLINK_MESSAGE_INFO_GPS_RAW, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION, MAVLINK_MESSAGE_INFO_SYS_STATUS, MAVLINK_MESSAGE_INFO_RC_CHANNELS_RAW, MAVLINK_MESSAGE_INFO_RC_CHANNELS_SCALED, MAVLINK_MESSAGE_INFO_SERVO_OUTPUT_RAW, MAVLINK_MESSAGE_INFO_SCALED_PRESSURE, MAVLINK_MESSAGE_INFO_WAYPOINT, MAVLINK_MESSAGE_INFO_WAYPOINT_REQUEST, MAVLINK_MESSAGE_INFO_WAYPOINT_SET_CURRENT, MAVLINK_MESSAGE_INFO_WAYPOINT_CURRENT, MAVLINK_MESSAGE_INFO_WAYPOINT_REQUEST_LIST, MAVLINK_MESSAGE_INFO_WAYPOINT_COUNT, MAVLINK_MESSAGE_INFO_WAYPOINT_CLEAR_ALL, MAVLINK_MESSAGE_INFO_WAYPOINT_REACHED, MAVLINK_MESSAGE_INFO_WAYPOINT_ACK, MAVLINK_MESSAGE_INFO_GPS_SET_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_GPS_LOCAL_ORIGIN_SET, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_SETPOINT_SET, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_SETPOINT, MAVLINK_MESSAGE_INFO_CONTROL_STATUS, MAVLINK_MESSAGE_INFO_SAFETY_SET_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SAFETY_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SET_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_SET_ROLL_PITCH_YAW_SPEED_THRUST, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_NAV_CONTROLLER_OUTPUT, MAVLINK_MESSAGE_INFO_POSITION_TARGET, MAVLINK_MESSAGE_INFO_STATE_CORRECTION, MAVLINK_MESSAGE_INFO_SET_ALTITUDE, MAVLINK_MESSAGE_INFO_REQUEST_DATA_STREAM, MAVLINK_MESSAGE_INFO_HIL_STATE, MAVLINK_MESSAGE_INFO_HIL_CONTROLS, MAVLINK_MESSAGE_INFO_MANUAL_CONTROL, MAVLINK_MESSAGE_INFO_RC_CHANNELS_OVERRIDE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_INT, MAVLINK_MESSAGE_INFO_VFR_HUD, MAVLINK_MESSAGE_INFO_COMMAND, MAVLINK_MESSAGE_INFO_COMMAND_ACK, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_OPTICAL_FLOW, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_OBJECT_DETECTION_EVENT, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_SENSOR_OFFSETS, MAVLINK_MESSAGE_INFO_SET_MAG_OFFSETS, MAVLINK_MESSAGE_INFO_MEMINFO, MAVLINK_MESSAGE_INFO_AP_ADC, MAVLINK_MESSAGE_INFO_DIGICAM_CONFIGURE, MAVLINK_MESSAGE_INFO_DIGICAM_CONTROL, MAVLINK_MESSAGE_INFO_MOUNT_CONFIGURE, MAVLINK_MESSAGE_INFO_MOUNT_CONTROL, MAVLINK_MESSAGE_INFO_MOUNT_STATUS, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_FENCE_POINT, MAVLINK_MESSAGE_INFO_FENCE_FETCH_POINT, MAVLINK_MESSAGE_INFO_FENCE_STATUS, MAVLINK_MESSAGE_INFO_AHRS, MAVLINK_MESSAGE_INFO_SIMSTATE, MAVLINK_MESSAGE_INFO_HWSTATUS, MAVLINK_MESSAGE_INFO_RADIO, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_DEBUG_VECT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_FLOAT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_INT, MAVLINK_MESSAGE_INFO_STATUSTEXT, MAVLINK_MESSAGE_INFO_DEBUG}
#endif
 
#include "../protocol.h"
 
#define MAVLINK_ENABLED_ARDUPILOTMEGA
 
// ENUM DEFINITIONS
 
 
/** @brief Enumeration of possible mount operation modes */
#ifndef HAVE_ENUM_MAV_MOUNT_MODE
#define HAVE_ENUM_MAV_MOUNT_MODE
enum MAV_MOUNT_MODE
{
MAV_MOUNT_MODE_RETRACT=0, /* Load and keep safe position (Roll,Pitch,Yaw) from EEPROM and stop stabilization | */
MAV_MOUNT_MODE_NEUTRAL=1, /* Load and keep neutral position (Roll,Pitch,Yaw) from EEPROM. | */
MAV_MOUNT_MODE_MAVLINK_TARGETING=2, /* Load neutral position and start MAVLink Roll,Pitch,Yaw control with stabilization | */
MAV_MOUNT_MODE_RC_TARGETING=3, /* Load neutral position and start RC Roll,Pitch,Yaw control with stabilization | */
MAV_MOUNT_MODE_GPS_POINT=4, /* Load neutral position and start to point to Lat,Lon,Alt | */
MAV_MOUNT_MODE_ENUM_END=5, /* | */
};
#endif
 
/** @brief */
#ifndef HAVE_ENUM_MAV_CMD
#define HAVE_ENUM_MAV_CMD
enum MAV_CMD
{
MAV_CMD_NAV_WAYPOINT=16, /* Navigate to waypoint. |Hold time in decimal seconds. (ignored by fixed wing, time to stay at waypoint for rotary wing)| Acceptance radius in meters (if the sphere with this radius is hit, the waypoint counts as reached)| 0 to pass through the WP, if > 0 radius in meters to pass by WP. Positive value for clockwise orbit, negative value for counter-clockwise orbit. Allows trajectory control.| Desired yaw angle at waypoint (rotary wing)| Latitude| Longitude| Altitude| */
MAV_CMD_NAV_LOITER_UNLIM=17, /* Loiter around this waypoint an unlimited amount of time |Empty| Empty| Radius around waypoint, in meters. If positive loiter clockwise, else counter-clockwise| Desired yaw angle.| Latitude| Longitude| Altitude| */
MAV_CMD_NAV_LOITER_TURNS=18, /* Loiter around this waypoint for X turns |Turns| Empty| Radius around waypoint, in meters. If positive loiter clockwise, else counter-clockwise| Desired yaw angle.| Latitude| Longitude| Altitude| */
MAV_CMD_NAV_LOITER_TIME=19, /* Loiter around this waypoint for X seconds |Seconds (decimal)| Empty| Radius around waypoint, in meters. If positive loiter clockwise, else counter-clockwise| Desired yaw angle.| Latitude| Longitude| Altitude| */
MAV_CMD_NAV_RETURN_TO_LAUNCH=20, /* Return to launch location |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */
MAV_CMD_NAV_LAND=21, /* Land at location |Empty| Empty| Empty| Desired yaw angle.| Latitude| Longitude| Altitude| */
MAV_CMD_NAV_TAKEOFF=22, /* Takeoff from ground / hand |Minimum pitch (if airspeed sensor present), desired pitch without sensor| Empty| Empty| Yaw angle (if magnetometer present), ignored without magnetometer| Latitude| Longitude| Altitude| */
MAV_CMD_NAV_ROI=80, /* Sets the region of interest (ROI) for a sensor set or the
vehicle itself. This can then be used by the vehicles control
system to control the vehicle attitude and the attitude of various
sensors such as cameras. |Region of intereset mode. (see MAV_ROI enum)| Waypoint index/ target ID. (see MAV_ROI enum)| ROI index (allows a vehicle to manage multiple ROI's)| Empty| x the location of the fixed ROI (see MAV_FRAME)| y| z| */
MAV_CMD_NAV_PATHPLANNING=81, /* Control autonomous path planning on the MAV. |0: Disable local obstacle avoidance / local path planning (without resetting map), 1: Enable local path planning, 2: Enable and reset local path planning| 0: Disable full path planning (without resetting map), 1: Enable, 2: Enable and reset map/occupancy grid, 3: Enable and reset planned route, but not occupancy grid| Empty| Yaw angle at goal, in compass degrees, [0..360]| Latitude/X of goal| Longitude/Y of goal| Altitude/Z of goal| */
MAV_CMD_NAV_LAST=95, /* NOP - This command is only used to mark the upper limit of the NAV/ACTION commands in the enumeration |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */
MAV_CMD_CONDITION_DELAY=112, /* Delay mission state machine. |Delay in seconds (decimal)| Empty| Empty| Empty| Empty| Empty| Empty| */
MAV_CMD_CONDITION_CHANGE_ALT=113, /* Ascend/descend at rate. Delay mission state machine until desired altitude reached. |Descent / Ascend rate (m/s)| Empty| Empty| Empty| Empty| Empty| Finish Altitude| */
MAV_CMD_CONDITION_DISTANCE=114, /* Delay mission state machine until within desired distance of next NAV point. |Distance (meters)| Empty| Empty| Empty| Empty| Empty| Empty| */
MAV_CMD_CONDITION_YAW=115, /* Reach a certain target angle. |target angle: [0-360], 0 is north| speed during yaw change:[deg per second]| direction: negative: counter clockwise, positive: clockwise [-1,1]| relative offset or absolute angle: [ 1,0]| Empty| Empty| Empty| */
MAV_CMD_CONDITION_LAST=159, /* NOP - This command is only used to mark the upper limit of the CONDITION commands in the enumeration |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */
MAV_CMD_DO_SET_MODE=176, /* Set system mode. |Mode, as defined by ENUM MAV_MODE| Empty| Empty| Empty| Empty| Empty| Empty| */
MAV_CMD_DO_JUMP=177, /* Jump to the desired command in the mission list. Repeat this action only the specified number of times |Sequence number| Repeat count| Empty| Empty| Empty| Empty| Empty| */
MAV_CMD_DO_CHANGE_SPEED=178, /* Change speed and/or throttle set points. |Speed type (0=Airspeed, 1=Ground Speed)| Speed (m/s, -1 indicates no change)| Throttle ( Percent, -1 indicates no change)| Empty| Empty| Empty| Empty| */
MAV_CMD_DO_SET_HOME=179, /* Changes the home location either to the current location or a specified location. |Use current (1=use current location, 0=use specified location)| Empty| Empty| Empty| Latitude| Longitude| Altitude| */
MAV_CMD_DO_SET_PARAMETER=180, /* Set a system parameter. Caution! Use of this command requires knowledge of the numeric enumeration value of the parameter. |Parameter number| Parameter value| Empty| Empty| Empty| Empty| Empty| */
MAV_CMD_DO_SET_RELAY=181, /* Set a relay to a condition. |Relay number| Setting (1=on, 0=off, others possible depending on system hardware)| Empty| Empty| Empty| Empty| Empty| */
MAV_CMD_DO_REPEAT_RELAY=182, /* Cycle a relay on and off for a desired number of cyles with a desired period. |Relay number| Cycle count| Cycle time (seconds, decimal)| Empty| Empty| Empty| Empty| */
MAV_CMD_DO_SET_SERVO=183, /* Set a servo to a desired PWM value. |Servo number| PWM (microseconds, 1000 to 2000 typical)| Empty| Empty| Empty| Empty| Empty| */
MAV_CMD_DO_REPEAT_SERVO=184, /* Cycle a between its nominal setting and a desired PWM for a desired number of cycles with a desired period. |Servo number| PWM (microseconds, 1000 to 2000 typical)| Cycle count| Cycle time (seconds)| Empty| Empty| Empty| */
MAV_CMD_DO_CONTROL_VIDEO=200, /* Control onboard camera capturing. |Camera ID (-1 for all)| Transmission: 0: disabled, 1: enabled compressed, 2: enabled raw| Transmission mode: 0: video stream, >0: single images every n seconds (decimal)| Recording: 0: disabled, 1: enabled compressed, 2: enabled raw| Empty| Empty| Empty| */
MAV_CMD_DO_SET_ROI=201, /* Sets the region of interest (ROI) for a sensor set or the
vehicle itself. This can then be used by the vehicles control
system to control the vehicle attitude and the attitude of various
devices such as cameras.
|Region of interest mode. (see MAV_ROI enum)| Waypoint index/ target ID. (see MAV_ROI enum)| ROI index (allows a vehicle to manage multiple cameras etc.)| Empty| x the location of the fixed ROI (see MAV_FRAME)| y| z| */
MAV_CMD_DO_DIGICAM_CONFIGURE=202, /* Mission command to configure an on-board camera controller system. |Modes: P, TV, AV, M, Etc| Shutter speed: Divisor number for one second| Aperture: F stop number| ISO number e.g. 80, 100, 200, Etc| Exposure type enumerator| Command Identity| Main engine cut-off time before camera trigger in seconds/10 (0 means no cut-off)| */
MAV_CMD_DO_DIGICAM_CONTROL=203, /* Mission command to control an on-board camera controller system. |Session control e.g. show/hide lens| Zoom's absolute position| Zooming step value to offset zoom from the current position| Focus Locking, Unlocking or Re-locking| Shooting Command| Command Identity| Empty| */
MAV_CMD_DO_MOUNT_CONFIGURE=204, /* Mission command to configure a camera or antenna mount |Mount operation mode (see MAV_MOUNT_MODE enum)| stabilize roll? (1 = yes, 0 = no)| stabilize pitch? (1 = yes, 0 = no)| stabilize yaw? (1 = yes, 0 = no)| Empty| Empty| Empty| */
MAV_CMD_DO_MOUNT_CONTROL=205, /* Mission command to control a camera or antenna mount |pitch(deg*100) or lat, depending on mount mode.| roll(deg*100) or lon depending on mount mode| yaw(deg*100) or alt (in cm) depending on mount mode| Empty| Empty| Empty| Empty| */
MAV_CMD_DO_LAST=240, /* NOP - This command is only used to mark the upper limit of the DO commands in the enumeration |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */
MAV_CMD_PREFLIGHT_CALIBRATION=241, /* Trigger calibration. This command will be only accepted if in pre-flight mode. |Gyro calibration: 0: no, 1: yes| Magnetometer calibration: 0: no, 1: yes| Ground pressure: 0: no, 1: yes| Radio calibration: 0: no, 1: yes| Empty| Empty| Empty| */
MAV_CMD_PREFLIGHT_STORAGE=245, /* Request storage of different parameter values and logs. This command will be only accepted if in pre-flight mode. |Parameter storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM| Mission storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM| Reserved| Reserved| Empty| Empty| Empty| */
MAV_CMD_ENUM_END=246, /* | */
};
#endif
 
/** @brief */
#ifndef HAVE_ENUM_FENCE_ACTION
#define HAVE_ENUM_FENCE_ACTION
enum FENCE_ACTION
{
FENCE_ACTION_NONE=0, /* Disable fenced mode | */
FENCE_ACTION_GUIDED=1, /* Switched to guided mode to return point (fence point 0) | */
FENCE_ACTION_ENUM_END=2, /* | */
};
#endif
 
/** @brief */
#ifndef HAVE_ENUM_FENCE_BREACH
#define HAVE_ENUM_FENCE_BREACH
enum FENCE_BREACH
{
FENCE_BREACH_NONE=0, /* No last fence breach | */
FENCE_BREACH_MINALT=1, /* Breached minimum altitude | */
FENCE_BREACH_MAXALT=2, /* Breached minimum altitude | */
FENCE_BREACH_BOUNDARY=3, /* Breached fence boundary | */
FENCE_BREACH_ENUM_END=4, /* | */
};
#endif
 
#include "../common/common.h"
 
// MAVLINK VERSION
 
#ifndef MAVLINK_VERSION
#define MAVLINK_VERSION 2
#endif
 
#if (MAVLINK_VERSION == 0)
#undef MAVLINK_VERSION
#define MAVLINK_VERSION 2
#endif
 
// MESSAGE DEFINITIONS
#include "./mavlink_msg_sensor_offsets.h"
#include "./mavlink_msg_set_mag_offsets.h"
#include "./mavlink_msg_meminfo.h"
#include "./mavlink_msg_ap_adc.h"
#include "./mavlink_msg_digicam_configure.h"
#include "./mavlink_msg_digicam_control.h"
#include "./mavlink_msg_mount_configure.h"
#include "./mavlink_msg_mount_control.h"
#include "./mavlink_msg_mount_status.h"
#include "./mavlink_msg_fence_point.h"
#include "./mavlink_msg_fence_fetch_point.h"
#include "./mavlink_msg_fence_status.h"
#include "./mavlink_msg_ahrs.h"
#include "./mavlink_msg_simstate.h"
#include "./mavlink_msg_hwstatus.h"
#include "./mavlink_msg_radio.h"
 
#ifdef __cplusplus
}
#endif // __cplusplus
#endif // ARDUPILOTMEGA_H
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v0.9/ardupilotmega/mavlink.h
0,0 → 1,27
/** @file
* @brief MAVLink comm protocol built from ardupilotmega.xml
* @see http://pixhawk.ethz.ch/software/mavlink
*/
#ifndef MAVLINK_H
#define MAVLINK_H
 
#ifndef MAVLINK_STX
#define MAVLINK_STX 85
#endif
 
#ifndef MAVLINK_ENDIAN
#define MAVLINK_ENDIAN MAVLINK_BIG_ENDIAN
#endif
 
#ifndef MAVLINK_ALIGNED_FIELDS
#define MAVLINK_ALIGNED_FIELDS 0
#endif
 
#ifndef MAVLINK_CRC_EXTRA
#define MAVLINK_CRC_EXTRA 0
#endif
 
#include "version.h"
#include "ardupilotmega.h"
 
#endif // MAVLINK_H
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v0.9/ardupilotmega/mavlink_msg_ahrs.h
0,0 → 1,276
// MESSAGE AHRS PACKING
 
#define MAVLINK_MSG_ID_AHRS 163
 
typedef struct __mavlink_ahrs_t
{
float omegaIx; ///< X gyro drift estimate rad/s
float omegaIy; ///< Y gyro drift estimate rad/s
float omegaIz; ///< Z gyro drift estimate rad/s
float accel_weight; ///< average accel_weight
float renorm_val; ///< average renormalisation value
float error_rp; ///< average error_roll_pitch value
float error_yaw; ///< average error_yaw value
} mavlink_ahrs_t;
 
#define MAVLINK_MSG_ID_AHRS_LEN 28
#define MAVLINK_MSG_ID_163_LEN 28
 
 
 
#define MAVLINK_MESSAGE_INFO_AHRS { \
"AHRS", \
7, \
{ { "omegaIx", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_ahrs_t, omegaIx) }, \
{ "omegaIy", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_ahrs_t, omegaIy) }, \
{ "omegaIz", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_ahrs_t, omegaIz) }, \
{ "accel_weight", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_ahrs_t, accel_weight) }, \
{ "renorm_val", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_ahrs_t, renorm_val) }, \
{ "error_rp", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_ahrs_t, error_rp) }, \
{ "error_yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_ahrs_t, error_yaw) }, \
} \
}
 
 
/**
* @brief Pack a ahrs message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param omegaIx X gyro drift estimate rad/s
* @param omegaIy Y gyro drift estimate rad/s
* @param omegaIz Z gyro drift estimate rad/s
* @param accel_weight average accel_weight
* @param renorm_val average renormalisation value
* @param error_rp average error_roll_pitch value
* @param error_yaw average error_yaw value
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_ahrs_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
float omegaIx, float omegaIy, float omegaIz, float accel_weight, float renorm_val, float error_rp, float error_yaw)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[28];
_mav_put_float(buf, 0, omegaIx);
_mav_put_float(buf, 4, omegaIy);
_mav_put_float(buf, 8, omegaIz);
_mav_put_float(buf, 12, accel_weight);
_mav_put_float(buf, 16, renorm_val);
_mav_put_float(buf, 20, error_rp);
_mav_put_float(buf, 24, error_yaw);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 28);
#else
mavlink_ahrs_t packet;
packet.omegaIx = omegaIx;
packet.omegaIy = omegaIy;
packet.omegaIz = omegaIz;
packet.accel_weight = accel_weight;
packet.renorm_val = renorm_val;
packet.error_rp = error_rp;
packet.error_yaw = error_yaw;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 28);
#endif
 
msg->msgid = MAVLINK_MSG_ID_AHRS;
return mavlink_finalize_message(msg, system_id, component_id, 28);
}
 
/**
* @brief Pack a ahrs message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param omegaIx X gyro drift estimate rad/s
* @param omegaIy Y gyro drift estimate rad/s
* @param omegaIz Z gyro drift estimate rad/s
* @param accel_weight average accel_weight
* @param renorm_val average renormalisation value
* @param error_rp average error_roll_pitch value
* @param error_yaw average error_yaw value
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_ahrs_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
float omegaIx,float omegaIy,float omegaIz,float accel_weight,float renorm_val,float error_rp,float error_yaw)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[28];
_mav_put_float(buf, 0, omegaIx);
_mav_put_float(buf, 4, omegaIy);
_mav_put_float(buf, 8, omegaIz);
_mav_put_float(buf, 12, accel_weight);
_mav_put_float(buf, 16, renorm_val);
_mav_put_float(buf, 20, error_rp);
_mav_put_float(buf, 24, error_yaw);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 28);
#else
mavlink_ahrs_t packet;
packet.omegaIx = omegaIx;
packet.omegaIy = omegaIy;
packet.omegaIz = omegaIz;
packet.accel_weight = accel_weight;
packet.renorm_val = renorm_val;
packet.error_rp = error_rp;
packet.error_yaw = error_yaw;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 28);
#endif
 
msg->msgid = MAVLINK_MSG_ID_AHRS;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 28);
}
 
/**
* @brief Encode a ahrs struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param ahrs C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_ahrs_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_ahrs_t* ahrs)
{
return mavlink_msg_ahrs_pack(system_id, component_id, msg, ahrs->omegaIx, ahrs->omegaIy, ahrs->omegaIz, ahrs->accel_weight, ahrs->renorm_val, ahrs->error_rp, ahrs->error_yaw);
}
 
/**
* @brief Send a ahrs message
* @param chan MAVLink channel to send the message
*
* @param omegaIx X gyro drift estimate rad/s
* @param omegaIy Y gyro drift estimate rad/s
* @param omegaIz Z gyro drift estimate rad/s
* @param accel_weight average accel_weight
* @param renorm_val average renormalisation value
* @param error_rp average error_roll_pitch value
* @param error_yaw average error_yaw value
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_ahrs_send(mavlink_channel_t chan, float omegaIx, float omegaIy, float omegaIz, float accel_weight, float renorm_val, float error_rp, float error_yaw)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[28];
_mav_put_float(buf, 0, omegaIx);
_mav_put_float(buf, 4, omegaIy);
_mav_put_float(buf, 8, omegaIz);
_mav_put_float(buf, 12, accel_weight);
_mav_put_float(buf, 16, renorm_val);
_mav_put_float(buf, 20, error_rp);
_mav_put_float(buf, 24, error_yaw);
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AHRS, buf, 28);
#else
mavlink_ahrs_t packet;
packet.omegaIx = omegaIx;
packet.omegaIy = omegaIy;
packet.omegaIz = omegaIz;
packet.accel_weight = accel_weight;
packet.renorm_val = renorm_val;
packet.error_rp = error_rp;
packet.error_yaw = error_yaw;
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AHRS, (const char *)&packet, 28);
#endif
}
 
#endif
 
// MESSAGE AHRS UNPACKING
 
 
/**
* @brief Get field omegaIx from ahrs message
*
* @return X gyro drift estimate rad/s
*/
static inline float mavlink_msg_ahrs_get_omegaIx(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 0);
}
 
/**
* @brief Get field omegaIy from ahrs message
*
* @return Y gyro drift estimate rad/s
*/
static inline float mavlink_msg_ahrs_get_omegaIy(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 4);
}
 
/**
* @brief Get field omegaIz from ahrs message
*
* @return Z gyro drift estimate rad/s
*/
static inline float mavlink_msg_ahrs_get_omegaIz(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 8);
}
 
/**
* @brief Get field accel_weight from ahrs message
*
* @return average accel_weight
*/
static inline float mavlink_msg_ahrs_get_accel_weight(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 12);
}
 
/**
* @brief Get field renorm_val from ahrs message
*
* @return average renormalisation value
*/
static inline float mavlink_msg_ahrs_get_renorm_val(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 16);
}
 
/**
* @brief Get field error_rp from ahrs message
*
* @return average error_roll_pitch value
*/
static inline float mavlink_msg_ahrs_get_error_rp(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 20);
}
 
/**
* @brief Get field error_yaw from ahrs message
*
* @return average error_yaw value
*/
static inline float mavlink_msg_ahrs_get_error_yaw(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 24);
}
 
/**
* @brief Decode a ahrs message into a struct
*
* @param msg The message to decode
* @param ahrs C-struct to decode the message contents into
*/
static inline void mavlink_msg_ahrs_decode(const mavlink_message_t* msg, mavlink_ahrs_t* ahrs)
{
#if MAVLINK_NEED_BYTE_SWAP
ahrs->omegaIx = mavlink_msg_ahrs_get_omegaIx(msg);
ahrs->omegaIy = mavlink_msg_ahrs_get_omegaIy(msg);
ahrs->omegaIz = mavlink_msg_ahrs_get_omegaIz(msg);
ahrs->accel_weight = mavlink_msg_ahrs_get_accel_weight(msg);
ahrs->renorm_val = mavlink_msg_ahrs_get_renorm_val(msg);
ahrs->error_rp = mavlink_msg_ahrs_get_error_rp(msg);
ahrs->error_yaw = mavlink_msg_ahrs_get_error_yaw(msg);
#else
memcpy(ahrs, _MAV_PAYLOAD(msg), 28);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v0.9/ardupilotmega/mavlink_msg_ap_adc.h
0,0 → 1,254
// MESSAGE AP_ADC PACKING
 
#define MAVLINK_MSG_ID_AP_ADC 153
 
typedef struct __mavlink_ap_adc_t
{
uint16_t adc1; ///< ADC output 1
uint16_t adc2; ///< ADC output 2
uint16_t adc3; ///< ADC output 3
uint16_t adc4; ///< ADC output 4
uint16_t adc5; ///< ADC output 5
uint16_t adc6; ///< ADC output 6
} mavlink_ap_adc_t;
 
#define MAVLINK_MSG_ID_AP_ADC_LEN 12
#define MAVLINK_MSG_ID_153_LEN 12
 
 
 
#define MAVLINK_MESSAGE_INFO_AP_ADC { \
"AP_ADC", \
6, \
{ { "adc1", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_ap_adc_t, adc1) }, \
{ "adc2", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_ap_adc_t, adc2) }, \
{ "adc3", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_ap_adc_t, adc3) }, \
{ "adc4", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_ap_adc_t, adc4) }, \
{ "adc5", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_ap_adc_t, adc5) }, \
{ "adc6", NULL, MAVLINK_TYPE_UINT16_T, 0, 10, offsetof(mavlink_ap_adc_t, adc6) }, \
} \
}
 
 
/**
* @brief Pack a ap_adc message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param adc1 ADC output 1
* @param adc2 ADC output 2
* @param adc3 ADC output 3
* @param adc4 ADC output 4
* @param adc5 ADC output 5
* @param adc6 ADC output 6
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_ap_adc_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint16_t adc1, uint16_t adc2, uint16_t adc3, uint16_t adc4, uint16_t adc5, uint16_t adc6)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[12];
_mav_put_uint16_t(buf, 0, adc1);
_mav_put_uint16_t(buf, 2, adc2);
_mav_put_uint16_t(buf, 4, adc3);
_mav_put_uint16_t(buf, 6, adc4);
_mav_put_uint16_t(buf, 8, adc5);
_mav_put_uint16_t(buf, 10, adc6);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 12);
#else
mavlink_ap_adc_t packet;
packet.adc1 = adc1;
packet.adc2 = adc2;
packet.adc3 = adc3;
packet.adc4 = adc4;
packet.adc5 = adc5;
packet.adc6 = adc6;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 12);
#endif
 
msg->msgid = MAVLINK_MSG_ID_AP_ADC;
return mavlink_finalize_message(msg, system_id, component_id, 12);
}
 
/**
* @brief Pack a ap_adc message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param adc1 ADC output 1
* @param adc2 ADC output 2
* @param adc3 ADC output 3
* @param adc4 ADC output 4
* @param adc5 ADC output 5
* @param adc6 ADC output 6
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_ap_adc_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint16_t adc1,uint16_t adc2,uint16_t adc3,uint16_t adc4,uint16_t adc5,uint16_t adc6)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[12];
_mav_put_uint16_t(buf, 0, adc1);
_mav_put_uint16_t(buf, 2, adc2);
_mav_put_uint16_t(buf, 4, adc3);
_mav_put_uint16_t(buf, 6, adc4);
_mav_put_uint16_t(buf, 8, adc5);
_mav_put_uint16_t(buf, 10, adc6);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 12);
#else
mavlink_ap_adc_t packet;
packet.adc1 = adc1;
packet.adc2 = adc2;
packet.adc3 = adc3;
packet.adc4 = adc4;
packet.adc5 = adc5;
packet.adc6 = adc6;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 12);
#endif
 
msg->msgid = MAVLINK_MSG_ID_AP_ADC;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 12);
}
 
/**
* @brief Encode a ap_adc struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param ap_adc C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_ap_adc_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_ap_adc_t* ap_adc)
{
return mavlink_msg_ap_adc_pack(system_id, component_id, msg, ap_adc->adc1, ap_adc->adc2, ap_adc->adc3, ap_adc->adc4, ap_adc->adc5, ap_adc->adc6);
}
 
/**
* @brief Send a ap_adc message
* @param chan MAVLink channel to send the message
*
* @param adc1 ADC output 1
* @param adc2 ADC output 2
* @param adc3 ADC output 3
* @param adc4 ADC output 4
* @param adc5 ADC output 5
* @param adc6 ADC output 6
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_ap_adc_send(mavlink_channel_t chan, uint16_t adc1, uint16_t adc2, uint16_t adc3, uint16_t adc4, uint16_t adc5, uint16_t adc6)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[12];
_mav_put_uint16_t(buf, 0, adc1);
_mav_put_uint16_t(buf, 2, adc2);
_mav_put_uint16_t(buf, 4, adc3);
_mav_put_uint16_t(buf, 6, adc4);
_mav_put_uint16_t(buf, 8, adc5);
_mav_put_uint16_t(buf, 10, adc6);
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AP_ADC, buf, 12);
#else
mavlink_ap_adc_t packet;
packet.adc1 = adc1;
packet.adc2 = adc2;
packet.adc3 = adc3;
packet.adc4 = adc4;
packet.adc5 = adc5;
packet.adc6 = adc6;
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AP_ADC, (const char *)&packet, 12);
#endif
}
 
#endif
 
// MESSAGE AP_ADC UNPACKING
 
 
/**
* @brief Get field adc1 from ap_adc message
*
* @return ADC output 1
*/
static inline uint16_t mavlink_msg_ap_adc_get_adc1(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 0);
}
 
/**
* @brief Get field adc2 from ap_adc message
*
* @return ADC output 2
*/
static inline uint16_t mavlink_msg_ap_adc_get_adc2(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 2);
}
 
/**
* @brief Get field adc3 from ap_adc message
*
* @return ADC output 3
*/
static inline uint16_t mavlink_msg_ap_adc_get_adc3(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 4);
}
 
/**
* @brief Get field adc4 from ap_adc message
*
* @return ADC output 4
*/
static inline uint16_t mavlink_msg_ap_adc_get_adc4(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 6);
}
 
/**
* @brief Get field adc5 from ap_adc message
*
* @return ADC output 5
*/
static inline uint16_t mavlink_msg_ap_adc_get_adc5(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 8);
}
 
/**
* @brief Get field adc6 from ap_adc message
*
* @return ADC output 6
*/
static inline uint16_t mavlink_msg_ap_adc_get_adc6(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 10);
}
 
/**
* @brief Decode a ap_adc message into a struct
*
* @param msg The message to decode
* @param ap_adc C-struct to decode the message contents into
*/
static inline void mavlink_msg_ap_adc_decode(const mavlink_message_t* msg, mavlink_ap_adc_t* ap_adc)
{
#if MAVLINK_NEED_BYTE_SWAP
ap_adc->adc1 = mavlink_msg_ap_adc_get_adc1(msg);
ap_adc->adc2 = mavlink_msg_ap_adc_get_adc2(msg);
ap_adc->adc3 = mavlink_msg_ap_adc_get_adc3(msg);
ap_adc->adc4 = mavlink_msg_ap_adc_get_adc4(msg);
ap_adc->adc5 = mavlink_msg_ap_adc_get_adc5(msg);
ap_adc->adc6 = mavlink_msg_ap_adc_get_adc6(msg);
#else
memcpy(ap_adc, _MAV_PAYLOAD(msg), 12);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v0.9/ardupilotmega/mavlink_msg_digicam_configure.h
0,0 → 1,364
// MESSAGE DIGICAM_CONFIGURE PACKING
 
#define MAVLINK_MSG_ID_DIGICAM_CONFIGURE 154
 
typedef struct __mavlink_digicam_configure_t
{
uint8_t target_system; ///< System ID
uint8_t target_component; ///< Component ID
uint8_t mode; ///< Mode enumeration from 1 to N //P, TV, AV, M, Etc (0 means ignore)
uint16_t shutter_speed; ///< Divisor number //e.g. 1000 means 1/1000 (0 means ignore)
uint8_t aperture; ///< F stop number x 10 //e.g. 28 means 2.8 (0 means ignore)
uint8_t iso; ///< ISO enumeration from 1 to N //e.g. 80, 100, 200, Etc (0 means ignore)
uint8_t exposure_type; ///< Exposure type enumeration from 1 to N (0 means ignore)
uint8_t command_id; ///< Command Identity (incremental loop: 0 to 255)//A command sent multiple times will be executed or pooled just once
uint8_t engine_cut_off; ///< Main engine cut-off time before camera trigger in seconds/10 (0 means no cut-off)
uint8_t extra_param; ///< Extra parameters enumeration (0 means ignore)
float extra_value; ///< Correspondent value to given extra_param
} mavlink_digicam_configure_t;
 
#define MAVLINK_MSG_ID_DIGICAM_CONFIGURE_LEN 15
#define MAVLINK_MSG_ID_154_LEN 15
 
 
 
#define MAVLINK_MESSAGE_INFO_DIGICAM_CONFIGURE { \
"DIGICAM_CONFIGURE", \
11, \
{ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_digicam_configure_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_digicam_configure_t, target_component) }, \
{ "mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_digicam_configure_t, mode) }, \
{ "shutter_speed", NULL, MAVLINK_TYPE_UINT16_T, 0, 3, offsetof(mavlink_digicam_configure_t, shutter_speed) }, \
{ "aperture", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_digicam_configure_t, aperture) }, \
{ "iso", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_digicam_configure_t, iso) }, \
{ "exposure_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 7, offsetof(mavlink_digicam_configure_t, exposure_type) }, \
{ "command_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_digicam_configure_t, command_id) }, \
{ "engine_cut_off", NULL, MAVLINK_TYPE_UINT8_T, 0, 9, offsetof(mavlink_digicam_configure_t, engine_cut_off) }, \
{ "extra_param", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_digicam_configure_t, extra_param) }, \
{ "extra_value", NULL, MAVLINK_TYPE_FLOAT, 0, 11, offsetof(mavlink_digicam_configure_t, extra_value) }, \
} \
}
 
 
/**
* @brief Pack a digicam_configure message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param target_system System ID
* @param target_component Component ID
* @param mode Mode enumeration from 1 to N //P, TV, AV, M, Etc (0 means ignore)
* @param shutter_speed Divisor number //e.g. 1000 means 1/1000 (0 means ignore)
* @param aperture F stop number x 10 //e.g. 28 means 2.8 (0 means ignore)
* @param iso ISO enumeration from 1 to N //e.g. 80, 100, 200, Etc (0 means ignore)
* @param exposure_type Exposure type enumeration from 1 to N (0 means ignore)
* @param command_id Command Identity (incremental loop: 0 to 255)//A command sent multiple times will be executed or pooled just once
* @param engine_cut_off Main engine cut-off time before camera trigger in seconds/10 (0 means no cut-off)
* @param extra_param Extra parameters enumeration (0 means ignore)
* @param extra_value Correspondent value to given extra_param
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_digicam_configure_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t target_system, uint8_t target_component, uint8_t mode, uint16_t shutter_speed, uint8_t aperture, uint8_t iso, uint8_t exposure_type, uint8_t command_id, uint8_t engine_cut_off, uint8_t extra_param, float extra_value)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[15];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
_mav_put_uint8_t(buf, 2, mode);
_mav_put_uint16_t(buf, 3, shutter_speed);
_mav_put_uint8_t(buf, 5, aperture);
_mav_put_uint8_t(buf, 6, iso);
_mav_put_uint8_t(buf, 7, exposure_type);
_mav_put_uint8_t(buf, 8, command_id);
_mav_put_uint8_t(buf, 9, engine_cut_off);
_mav_put_uint8_t(buf, 10, extra_param);
_mav_put_float(buf, 11, extra_value);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 15);
#else
mavlink_digicam_configure_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
packet.mode = mode;
packet.shutter_speed = shutter_speed;
packet.aperture = aperture;
packet.iso = iso;
packet.exposure_type = exposure_type;
packet.command_id = command_id;
packet.engine_cut_off = engine_cut_off;
packet.extra_param = extra_param;
packet.extra_value = extra_value;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 15);
#endif
 
msg->msgid = MAVLINK_MSG_ID_DIGICAM_CONFIGURE;
return mavlink_finalize_message(msg, system_id, component_id, 15);
}
 
/**
* @brief Pack a digicam_configure message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param target_system System ID
* @param target_component Component ID
* @param mode Mode enumeration from 1 to N //P, TV, AV, M, Etc (0 means ignore)
* @param shutter_speed Divisor number //e.g. 1000 means 1/1000 (0 means ignore)
* @param aperture F stop number x 10 //e.g. 28 means 2.8 (0 means ignore)
* @param iso ISO enumeration from 1 to N //e.g. 80, 100, 200, Etc (0 means ignore)
* @param exposure_type Exposure type enumeration from 1 to N (0 means ignore)
* @param command_id Command Identity (incremental loop: 0 to 255)//A command sent multiple times will be executed or pooled just once
* @param engine_cut_off Main engine cut-off time before camera trigger in seconds/10 (0 means no cut-off)
* @param extra_param Extra parameters enumeration (0 means ignore)
* @param extra_value Correspondent value to given extra_param
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_digicam_configure_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 mode,uint16_t shutter_speed,uint8_t aperture,uint8_t iso,uint8_t exposure_type,uint8_t command_id,uint8_t engine_cut_off,uint8_t extra_param,float extra_value)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[15];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
_mav_put_uint8_t(buf, 2, mode);
_mav_put_uint16_t(buf, 3, shutter_speed);
_mav_put_uint8_t(buf, 5, aperture);
_mav_put_uint8_t(buf, 6, iso);
_mav_put_uint8_t(buf, 7, exposure_type);
_mav_put_uint8_t(buf, 8, command_id);
_mav_put_uint8_t(buf, 9, engine_cut_off);
_mav_put_uint8_t(buf, 10, extra_param);
_mav_put_float(buf, 11, extra_value);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 15);
#else
mavlink_digicam_configure_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
packet.mode = mode;
packet.shutter_speed = shutter_speed;
packet.aperture = aperture;
packet.iso = iso;
packet.exposure_type = exposure_type;
packet.command_id = command_id;
packet.engine_cut_off = engine_cut_off;
packet.extra_param = extra_param;
packet.extra_value = extra_value;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 15);
#endif
 
msg->msgid = MAVLINK_MSG_ID_DIGICAM_CONFIGURE;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 15);
}
 
/**
* @brief Encode a digicam_configure struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param digicam_configure C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_digicam_configure_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_digicam_configure_t* digicam_configure)
{
return mavlink_msg_digicam_configure_pack(system_id, component_id, msg, digicam_configure->target_system, digicam_configure->target_component, digicam_configure->mode, digicam_configure->shutter_speed, digicam_configure->aperture, digicam_configure->iso, digicam_configure->exposure_type, digicam_configure->command_id, digicam_configure->engine_cut_off, digicam_configure->extra_param, digicam_configure->extra_value);
}
 
/**
* @brief Send a digicam_configure message
* @param chan MAVLink channel to send the message
*
* @param target_system System ID
* @param target_component Component ID
* @param mode Mode enumeration from 1 to N //P, TV, AV, M, Etc (0 means ignore)
* @param shutter_speed Divisor number //e.g. 1000 means 1/1000 (0 means ignore)
* @param aperture F stop number x 10 //e.g. 28 means 2.8 (0 means ignore)
* @param iso ISO enumeration from 1 to N //e.g. 80, 100, 200, Etc (0 means ignore)
* @param exposure_type Exposure type enumeration from 1 to N (0 means ignore)
* @param command_id Command Identity (incremental loop: 0 to 255)//A command sent multiple times will be executed or pooled just once
* @param engine_cut_off Main engine cut-off time before camera trigger in seconds/10 (0 means no cut-off)
* @param extra_param Extra parameters enumeration (0 means ignore)
* @param extra_value Correspondent value to given extra_param
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_digicam_configure_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t mode, uint16_t shutter_speed, uint8_t aperture, uint8_t iso, uint8_t exposure_type, uint8_t command_id, uint8_t engine_cut_off, uint8_t extra_param, float extra_value)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[15];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
_mav_put_uint8_t(buf, 2, mode);
_mav_put_uint16_t(buf, 3, shutter_speed);
_mav_put_uint8_t(buf, 5, aperture);
_mav_put_uint8_t(buf, 6, iso);
_mav_put_uint8_t(buf, 7, exposure_type);
_mav_put_uint8_t(buf, 8, command_id);
_mav_put_uint8_t(buf, 9, engine_cut_off);
_mav_put_uint8_t(buf, 10, extra_param);
_mav_put_float(buf, 11, extra_value);
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DIGICAM_CONFIGURE, buf, 15);
#else
mavlink_digicam_configure_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
packet.mode = mode;
packet.shutter_speed = shutter_speed;
packet.aperture = aperture;
packet.iso = iso;
packet.exposure_type = exposure_type;
packet.command_id = command_id;
packet.engine_cut_off = engine_cut_off;
packet.extra_param = extra_param;
packet.extra_value = extra_value;
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DIGICAM_CONFIGURE, (const char *)&packet, 15);
#endif
}
 
#endif
 
// MESSAGE DIGICAM_CONFIGURE UNPACKING
 
 
/**
* @brief Get field target_system from digicam_configure message
*
* @return System ID
*/
static inline uint8_t mavlink_msg_digicam_configure_get_target_system(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 0);
}
 
/**
* @brief Get field target_component from digicam_configure message
*
* @return Component ID
*/
static inline uint8_t mavlink_msg_digicam_configure_get_target_component(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 1);
}
 
/**
* @brief Get field mode from digicam_configure message
*
* @return Mode enumeration from 1 to N //P, TV, AV, M, Etc (0 means ignore)
*/
static inline uint8_t mavlink_msg_digicam_configure_get_mode(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 2);
}
 
/**
* @brief Get field shutter_speed from digicam_configure message
*
* @return Divisor number //e.g. 1000 means 1/1000 (0 means ignore)
*/
static inline uint16_t mavlink_msg_digicam_configure_get_shutter_speed(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 3);
}
 
/**
* @brief Get field aperture from digicam_configure message
*
* @return F stop number x 10 //e.g. 28 means 2.8 (0 means ignore)
*/
static inline uint8_t mavlink_msg_digicam_configure_get_aperture(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 5);
}
 
/**
* @brief Get field iso from digicam_configure message
*
* @return ISO enumeration from 1 to N //e.g. 80, 100, 200, Etc (0 means ignore)
*/
static inline uint8_t mavlink_msg_digicam_configure_get_iso(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 6);
}
 
/**
* @brief Get field exposure_type from digicam_configure message
*
* @return Exposure type enumeration from 1 to N (0 means ignore)
*/
static inline uint8_t mavlink_msg_digicam_configure_get_exposure_type(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 7);
}
 
/**
* @brief Get field command_id from digicam_configure message
*
* @return Command Identity (incremental loop: 0 to 255)//A command sent multiple times will be executed or pooled just once
*/
static inline uint8_t mavlink_msg_digicam_configure_get_command_id(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 8);
}
 
/**
* @brief Get field engine_cut_off from digicam_configure message
*
* @return Main engine cut-off time before camera trigger in seconds/10 (0 means no cut-off)
*/
static inline uint8_t mavlink_msg_digicam_configure_get_engine_cut_off(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 9);
}
 
/**
* @brief Get field extra_param from digicam_configure message
*
* @return Extra parameters enumeration (0 means ignore)
*/
static inline uint8_t mavlink_msg_digicam_configure_get_extra_param(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 10);
}
 
/**
* @brief Get field extra_value from digicam_configure message
*
* @return Correspondent value to given extra_param
*/
static inline float mavlink_msg_digicam_configure_get_extra_value(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 11);
}
 
/**
* @brief Decode a digicam_configure message into a struct
*
* @param msg The message to decode
* @param digicam_configure C-struct to decode the message contents into
*/
static inline void mavlink_msg_digicam_configure_decode(const mavlink_message_t* msg, mavlink_digicam_configure_t* digicam_configure)
{
#if MAVLINK_NEED_BYTE_SWAP
digicam_configure->target_system = mavlink_msg_digicam_configure_get_target_system(msg);
digicam_configure->target_component = mavlink_msg_digicam_configure_get_target_component(msg);
digicam_configure->mode = mavlink_msg_digicam_configure_get_mode(msg);
digicam_configure->shutter_speed = mavlink_msg_digicam_configure_get_shutter_speed(msg);
digicam_configure->aperture = mavlink_msg_digicam_configure_get_aperture(msg);
digicam_configure->iso = mavlink_msg_digicam_configure_get_iso(msg);
digicam_configure->exposure_type = mavlink_msg_digicam_configure_get_exposure_type(msg);
digicam_configure->command_id = mavlink_msg_digicam_configure_get_command_id(msg);
digicam_configure->engine_cut_off = mavlink_msg_digicam_configure_get_engine_cut_off(msg);
digicam_configure->extra_param = mavlink_msg_digicam_configure_get_extra_param(msg);
digicam_configure->extra_value = mavlink_msg_digicam_configure_get_extra_value(msg);
#else
memcpy(digicam_configure, _MAV_PAYLOAD(msg), 15);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v0.9/ardupilotmega/mavlink_msg_digicam_control.h
0,0 → 1,342
// MESSAGE DIGICAM_CONTROL PACKING
 
#define MAVLINK_MSG_ID_DIGICAM_CONTROL 155
 
typedef struct __mavlink_digicam_control_t
{
uint8_t target_system; ///< System ID
uint8_t target_component; ///< Component ID
uint8_t session; ///< 0: stop, 1: start or keep it up //Session control e.g. show/hide lens
uint8_t zoom_pos; ///< 1 to N //Zoom's absolute position (0 means ignore)
int8_t zoom_step; ///< -100 to 100 //Zooming step value to offset zoom from the current position
uint8_t focus_lock; ///< 0: unlock focus or keep unlocked, 1: lock focus or keep locked, 3: re-lock focus
uint8_t shot; ///< 0: ignore, 1: shot or start filming
uint8_t command_id; ///< Command Identity (incremental loop: 0 to 255)//A command sent multiple times will be executed or pooled just once
uint8_t extra_param; ///< Extra parameters enumeration (0 means ignore)
float extra_value; ///< Correspondent value to given extra_param
} mavlink_digicam_control_t;
 
#define MAVLINK_MSG_ID_DIGICAM_CONTROL_LEN 13
#define MAVLINK_MSG_ID_155_LEN 13
 
 
 
#define MAVLINK_MESSAGE_INFO_DIGICAM_CONTROL { \
"DIGICAM_CONTROL", \
10, \
{ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_digicam_control_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_digicam_control_t, target_component) }, \
{ "session", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_digicam_control_t, session) }, \
{ "zoom_pos", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_digicam_control_t, zoom_pos) }, \
{ "zoom_step", NULL, MAVLINK_TYPE_INT8_T, 0, 4, offsetof(mavlink_digicam_control_t, zoom_step) }, \
{ "focus_lock", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_digicam_control_t, focus_lock) }, \
{ "shot", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_digicam_control_t, shot) }, \
{ "command_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 7, offsetof(mavlink_digicam_control_t, command_id) }, \
{ "extra_param", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_digicam_control_t, extra_param) }, \
{ "extra_value", NULL, MAVLINK_TYPE_FLOAT, 0, 9, offsetof(mavlink_digicam_control_t, extra_value) }, \
} \
}
 
 
/**
* @brief Pack a digicam_control message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param target_system System ID
* @param target_component Component ID
* @param session 0: stop, 1: start or keep it up //Session control e.g. show/hide lens
* @param zoom_pos 1 to N //Zoom's absolute position (0 means ignore)
* @param zoom_step -100 to 100 //Zooming step value to offset zoom from the current position
* @param focus_lock 0: unlock focus or keep unlocked, 1: lock focus or keep locked, 3: re-lock focus
* @param shot 0: ignore, 1: shot or start filming
* @param command_id Command Identity (incremental loop: 0 to 255)//A command sent multiple times will be executed or pooled just once
* @param extra_param Extra parameters enumeration (0 means ignore)
* @param extra_value Correspondent value to given extra_param
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_digicam_control_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t target_system, uint8_t target_component, uint8_t session, uint8_t zoom_pos, int8_t zoom_step, uint8_t focus_lock, uint8_t shot, uint8_t command_id, uint8_t extra_param, float extra_value)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[13];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
_mav_put_uint8_t(buf, 2, session);
_mav_put_uint8_t(buf, 3, zoom_pos);
_mav_put_int8_t(buf, 4, zoom_step);
_mav_put_uint8_t(buf, 5, focus_lock);
_mav_put_uint8_t(buf, 6, shot);
_mav_put_uint8_t(buf, 7, command_id);
_mav_put_uint8_t(buf, 8, extra_param);
_mav_put_float(buf, 9, extra_value);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 13);
#else
mavlink_digicam_control_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
packet.session = session;
packet.zoom_pos = zoom_pos;
packet.zoom_step = zoom_step;
packet.focus_lock = focus_lock;
packet.shot = shot;
packet.command_id = command_id;
packet.extra_param = extra_param;
packet.extra_value = extra_value;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 13);
#endif
 
msg->msgid = MAVLINK_MSG_ID_DIGICAM_CONTROL;
return mavlink_finalize_message(msg, system_id, component_id, 13);
}
 
/**
* @brief Pack a digicam_control message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param target_system System ID
* @param target_component Component ID
* @param session 0: stop, 1: start or keep it up //Session control e.g. show/hide lens
* @param zoom_pos 1 to N //Zoom's absolute position (0 means ignore)
* @param zoom_step -100 to 100 //Zooming step value to offset zoom from the current position
* @param focus_lock 0: unlock focus or keep unlocked, 1: lock focus or keep locked, 3: re-lock focus
* @param shot 0: ignore, 1: shot or start filming
* @param command_id Command Identity (incremental loop: 0 to 255)//A command sent multiple times will be executed or pooled just once
* @param extra_param Extra parameters enumeration (0 means ignore)
* @param extra_value Correspondent value to given extra_param
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_digicam_control_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 session,uint8_t zoom_pos,int8_t zoom_step,uint8_t focus_lock,uint8_t shot,uint8_t command_id,uint8_t extra_param,float extra_value)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[13];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
_mav_put_uint8_t(buf, 2, session);
_mav_put_uint8_t(buf, 3, zoom_pos);
_mav_put_int8_t(buf, 4, zoom_step);
_mav_put_uint8_t(buf, 5, focus_lock);
_mav_put_uint8_t(buf, 6, shot);
_mav_put_uint8_t(buf, 7, command_id);
_mav_put_uint8_t(buf, 8, extra_param);
_mav_put_float(buf, 9, extra_value);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 13);
#else
mavlink_digicam_control_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
packet.session = session;
packet.zoom_pos = zoom_pos;
packet.zoom_step = zoom_step;
packet.focus_lock = focus_lock;
packet.shot = shot;
packet.command_id = command_id;
packet.extra_param = extra_param;
packet.extra_value = extra_value;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 13);
#endif
 
msg->msgid = MAVLINK_MSG_ID_DIGICAM_CONTROL;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 13);
}
 
/**
* @brief Encode a digicam_control struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param digicam_control C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_digicam_control_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_digicam_control_t* digicam_control)
{
return mavlink_msg_digicam_control_pack(system_id, component_id, msg, digicam_control->target_system, digicam_control->target_component, digicam_control->session, digicam_control->zoom_pos, digicam_control->zoom_step, digicam_control->focus_lock, digicam_control->shot, digicam_control->command_id, digicam_control->extra_param, digicam_control->extra_value);
}
 
/**
* @brief Send a digicam_control message
* @param chan MAVLink channel to send the message
*
* @param target_system System ID
* @param target_component Component ID
* @param session 0: stop, 1: start or keep it up //Session control e.g. show/hide lens
* @param zoom_pos 1 to N //Zoom's absolute position (0 means ignore)
* @param zoom_step -100 to 100 //Zooming step value to offset zoom from the current position
* @param focus_lock 0: unlock focus or keep unlocked, 1: lock focus or keep locked, 3: re-lock focus
* @param shot 0: ignore, 1: shot or start filming
* @param command_id Command Identity (incremental loop: 0 to 255)//A command sent multiple times will be executed or pooled just once
* @param extra_param Extra parameters enumeration (0 means ignore)
* @param extra_value Correspondent value to given extra_param
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_digicam_control_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t session, uint8_t zoom_pos, int8_t zoom_step, uint8_t focus_lock, uint8_t shot, uint8_t command_id, uint8_t extra_param, float extra_value)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[13];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
_mav_put_uint8_t(buf, 2, session);
_mav_put_uint8_t(buf, 3, zoom_pos);
_mav_put_int8_t(buf, 4, zoom_step);
_mav_put_uint8_t(buf, 5, focus_lock);
_mav_put_uint8_t(buf, 6, shot);
_mav_put_uint8_t(buf, 7, command_id);
_mav_put_uint8_t(buf, 8, extra_param);
_mav_put_float(buf, 9, extra_value);
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DIGICAM_CONTROL, buf, 13);
#else
mavlink_digicam_control_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
packet.session = session;
packet.zoom_pos = zoom_pos;
packet.zoom_step = zoom_step;
packet.focus_lock = focus_lock;
packet.shot = shot;
packet.command_id = command_id;
packet.extra_param = extra_param;
packet.extra_value = extra_value;
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DIGICAM_CONTROL, (const char *)&packet, 13);
#endif
}
 
#endif
 
// MESSAGE DIGICAM_CONTROL UNPACKING
 
 
/**
* @brief Get field target_system from digicam_control message
*
* @return System ID
*/
static inline uint8_t mavlink_msg_digicam_control_get_target_system(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 0);
}
 
/**
* @brief Get field target_component from digicam_control message
*
* @return Component ID
*/
static inline uint8_t mavlink_msg_digicam_control_get_target_component(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 1);
}
 
/**
* @brief Get field session from digicam_control message
*
* @return 0: stop, 1: start or keep it up //Session control e.g. show/hide lens
*/
static inline uint8_t mavlink_msg_digicam_control_get_session(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 2);
}
 
/**
* @brief Get field zoom_pos from digicam_control message
*
* @return 1 to N //Zoom's absolute position (0 means ignore)
*/
static inline uint8_t mavlink_msg_digicam_control_get_zoom_pos(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 3);
}
 
/**
* @brief Get field zoom_step from digicam_control message
*
* @return -100 to 100 //Zooming step value to offset zoom from the current position
*/
static inline int8_t mavlink_msg_digicam_control_get_zoom_step(const mavlink_message_t* msg)
{
return _MAV_RETURN_int8_t(msg, 4);
}
 
/**
* @brief Get field focus_lock from digicam_control message
*
* @return 0: unlock focus or keep unlocked, 1: lock focus or keep locked, 3: re-lock focus
*/
static inline uint8_t mavlink_msg_digicam_control_get_focus_lock(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 5);
}
 
/**
* @brief Get field shot from digicam_control message
*
* @return 0: ignore, 1: shot or start filming
*/
static inline uint8_t mavlink_msg_digicam_control_get_shot(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 6);
}
 
/**
* @brief Get field command_id from digicam_control message
*
* @return Command Identity (incremental loop: 0 to 255)//A command sent multiple times will be executed or pooled just once
*/
static inline uint8_t mavlink_msg_digicam_control_get_command_id(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 7);
}
 
/**
* @brief Get field extra_param from digicam_control message
*
* @return Extra parameters enumeration (0 means ignore)
*/
static inline uint8_t mavlink_msg_digicam_control_get_extra_param(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 8);
}
 
/**
* @brief Get field extra_value from digicam_control message
*
* @return Correspondent value to given extra_param
*/
static inline float mavlink_msg_digicam_control_get_extra_value(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 9);
}
 
/**
* @brief Decode a digicam_control message into a struct
*
* @param msg The message to decode
* @param digicam_control C-struct to decode the message contents into
*/
static inline void mavlink_msg_digicam_control_decode(const mavlink_message_t* msg, mavlink_digicam_control_t* digicam_control)
{
#if MAVLINK_NEED_BYTE_SWAP
digicam_control->target_system = mavlink_msg_digicam_control_get_target_system(msg);
digicam_control->target_component = mavlink_msg_digicam_control_get_target_component(msg);
digicam_control->session = mavlink_msg_digicam_control_get_session(msg);
digicam_control->zoom_pos = mavlink_msg_digicam_control_get_zoom_pos(msg);
digicam_control->zoom_step = mavlink_msg_digicam_control_get_zoom_step(msg);
digicam_control->focus_lock = mavlink_msg_digicam_control_get_focus_lock(msg);
digicam_control->shot = mavlink_msg_digicam_control_get_shot(msg);
digicam_control->command_id = mavlink_msg_digicam_control_get_command_id(msg);
digicam_control->extra_param = mavlink_msg_digicam_control_get_extra_param(msg);
digicam_control->extra_value = mavlink_msg_digicam_control_get_extra_value(msg);
#else
memcpy(digicam_control, _MAV_PAYLOAD(msg), 13);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v0.9/ardupilotmega/mavlink_msg_fence_fetch_point.h
0,0 → 1,188
// MESSAGE FENCE_FETCH_POINT PACKING
 
#define MAVLINK_MSG_ID_FENCE_FETCH_POINT 161
 
typedef struct __mavlink_fence_fetch_point_t
{
uint8_t target_system; ///< System ID
uint8_t target_component; ///< Component ID
uint8_t idx; ///< point index (first point is 1, 0 is for return point)
} mavlink_fence_fetch_point_t;
 
#define MAVLINK_MSG_ID_FENCE_FETCH_POINT_LEN 3
#define MAVLINK_MSG_ID_161_LEN 3
 
 
 
#define MAVLINK_MESSAGE_INFO_FENCE_FETCH_POINT { \
"FENCE_FETCH_POINT", \
3, \
{ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_fence_fetch_point_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_fence_fetch_point_t, target_component) }, \
{ "idx", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_fence_fetch_point_t, idx) }, \
} \
}
 
 
/**
* @brief Pack a fence_fetch_point message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param target_system System ID
* @param target_component Component ID
* @param idx point index (first point is 1, 0 is for return point)
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_fence_fetch_point_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t target_system, uint8_t target_component, uint8_t idx)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[3];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
_mav_put_uint8_t(buf, 2, idx);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 3);
#else
mavlink_fence_fetch_point_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
packet.idx = idx;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 3);
#endif
 
msg->msgid = MAVLINK_MSG_ID_FENCE_FETCH_POINT;
return mavlink_finalize_message(msg, system_id, component_id, 3);
}
 
/**
* @brief Pack a fence_fetch_point message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param target_system System ID
* @param target_component Component ID
* @param idx point index (first point is 1, 0 is for return point)
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_fence_fetch_point_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 idx)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[3];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
_mav_put_uint8_t(buf, 2, idx);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 3);
#else
mavlink_fence_fetch_point_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
packet.idx = idx;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 3);
#endif
 
msg->msgid = MAVLINK_MSG_ID_FENCE_FETCH_POINT;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 3);
}
 
/**
* @brief Encode a fence_fetch_point struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param fence_fetch_point C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_fence_fetch_point_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_fence_fetch_point_t* fence_fetch_point)
{
return mavlink_msg_fence_fetch_point_pack(system_id, component_id, msg, fence_fetch_point->target_system, fence_fetch_point->target_component, fence_fetch_point->idx);
}
 
/**
* @brief Send a fence_fetch_point message
* @param chan MAVLink channel to send the message
*
* @param target_system System ID
* @param target_component Component ID
* @param idx point index (first point is 1, 0 is for return point)
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_fence_fetch_point_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t idx)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[3];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
_mav_put_uint8_t(buf, 2, idx);
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FENCE_FETCH_POINT, buf, 3);
#else
mavlink_fence_fetch_point_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
packet.idx = idx;
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FENCE_FETCH_POINT, (const char *)&packet, 3);
#endif
}
 
#endif
 
// MESSAGE FENCE_FETCH_POINT UNPACKING
 
 
/**
* @brief Get field target_system from fence_fetch_point message
*
* @return System ID
*/
static inline uint8_t mavlink_msg_fence_fetch_point_get_target_system(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 0);
}
 
/**
* @brief Get field target_component from fence_fetch_point message
*
* @return Component ID
*/
static inline uint8_t mavlink_msg_fence_fetch_point_get_target_component(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 1);
}
 
/**
* @brief Get field idx from fence_fetch_point message
*
* @return point index (first point is 1, 0 is for return point)
*/
static inline uint8_t mavlink_msg_fence_fetch_point_get_idx(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 2);
}
 
/**
* @brief Decode a fence_fetch_point message into a struct
*
* @param msg The message to decode
* @param fence_fetch_point C-struct to decode the message contents into
*/
static inline void mavlink_msg_fence_fetch_point_decode(const mavlink_message_t* msg, mavlink_fence_fetch_point_t* fence_fetch_point)
{
#if MAVLINK_NEED_BYTE_SWAP
fence_fetch_point->target_system = mavlink_msg_fence_fetch_point_get_target_system(msg);
fence_fetch_point->target_component = mavlink_msg_fence_fetch_point_get_target_component(msg);
fence_fetch_point->idx = mavlink_msg_fence_fetch_point_get_idx(msg);
#else
memcpy(fence_fetch_point, _MAV_PAYLOAD(msg), 3);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v0.9/ardupilotmega/mavlink_msg_fence_point.h
0,0 → 1,254
// MESSAGE FENCE_POINT PACKING
 
#define MAVLINK_MSG_ID_FENCE_POINT 160
 
typedef struct __mavlink_fence_point_t
{
uint8_t target_system; ///< System ID
uint8_t target_component; ///< Component ID
uint8_t idx; ///< point index (first point is 1, 0 is for return point)
uint8_t count; ///< total number of points (for sanity checking)
float lat; ///< Latitude of point
float lng; ///< Longitude of point
} mavlink_fence_point_t;
 
#define MAVLINK_MSG_ID_FENCE_POINT_LEN 12
#define MAVLINK_MSG_ID_160_LEN 12
 
 
 
#define MAVLINK_MESSAGE_INFO_FENCE_POINT { \
"FENCE_POINT", \
6, \
{ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_fence_point_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_fence_point_t, target_component) }, \
{ "idx", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_fence_point_t, idx) }, \
{ "count", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_fence_point_t, count) }, \
{ "lat", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_fence_point_t, lat) }, \
{ "lng", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_fence_point_t, lng) }, \
} \
}
 
 
/**
* @brief Pack a fence_point message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param target_system System ID
* @param target_component Component ID
* @param idx point index (first point is 1, 0 is for return point)
* @param count total number of points (for sanity checking)
* @param lat Latitude of point
* @param lng Longitude of point
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_fence_point_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t target_system, uint8_t target_component, uint8_t idx, uint8_t count, float lat, float lng)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[12];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
_mav_put_uint8_t(buf, 2, idx);
_mav_put_uint8_t(buf, 3, count);
_mav_put_float(buf, 4, lat);
_mav_put_float(buf, 8, lng);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 12);
#else
mavlink_fence_point_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
packet.idx = idx;
packet.count = count;
packet.lat = lat;
packet.lng = lng;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 12);
#endif
 
msg->msgid = MAVLINK_MSG_ID_FENCE_POINT;
return mavlink_finalize_message(msg, system_id, component_id, 12);
}
 
/**
* @brief Pack a fence_point message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param target_system System ID
* @param target_component Component ID
* @param idx point index (first point is 1, 0 is for return point)
* @param count total number of points (for sanity checking)
* @param lat Latitude of point
* @param lng Longitude of point
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_fence_point_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 idx,uint8_t count,float lat,float lng)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[12];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
_mav_put_uint8_t(buf, 2, idx);
_mav_put_uint8_t(buf, 3, count);
_mav_put_float(buf, 4, lat);
_mav_put_float(buf, 8, lng);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 12);
#else
mavlink_fence_point_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
packet.idx = idx;
packet.count = count;
packet.lat = lat;
packet.lng = lng;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 12);
#endif
 
msg->msgid = MAVLINK_MSG_ID_FENCE_POINT;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 12);
}
 
/**
* @brief Encode a fence_point struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param fence_point C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_fence_point_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_fence_point_t* fence_point)
{
return mavlink_msg_fence_point_pack(system_id, component_id, msg, fence_point->target_system, fence_point->target_component, fence_point->idx, fence_point->count, fence_point->lat, fence_point->lng);
}
 
/**
* @brief Send a fence_point message
* @param chan MAVLink channel to send the message
*
* @param target_system System ID
* @param target_component Component ID
* @param idx point index (first point is 1, 0 is for return point)
* @param count total number of points (for sanity checking)
* @param lat Latitude of point
* @param lng Longitude of point
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_fence_point_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t idx, uint8_t count, float lat, float lng)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[12];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
_mav_put_uint8_t(buf, 2, idx);
_mav_put_uint8_t(buf, 3, count);
_mav_put_float(buf, 4, lat);
_mav_put_float(buf, 8, lng);
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FENCE_POINT, buf, 12);
#else
mavlink_fence_point_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
packet.idx = idx;
packet.count = count;
packet.lat = lat;
packet.lng = lng;
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FENCE_POINT, (const char *)&packet, 12);
#endif
}
 
#endif
 
// MESSAGE FENCE_POINT UNPACKING
 
 
/**
* @brief Get field target_system from fence_point message
*
* @return System ID
*/
static inline uint8_t mavlink_msg_fence_point_get_target_system(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 0);
}
 
/**
* @brief Get field target_component from fence_point message
*
* @return Component ID
*/
static inline uint8_t mavlink_msg_fence_point_get_target_component(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 1);
}
 
/**
* @brief Get field idx from fence_point message
*
* @return point index (first point is 1, 0 is for return point)
*/
static inline uint8_t mavlink_msg_fence_point_get_idx(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 2);
}
 
/**
* @brief Get field count from fence_point message
*
* @return total number of points (for sanity checking)
*/
static inline uint8_t mavlink_msg_fence_point_get_count(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 3);
}
 
/**
* @brief Get field lat from fence_point message
*
* @return Latitude of point
*/
static inline float mavlink_msg_fence_point_get_lat(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 4);
}
 
/**
* @brief Get field lng from fence_point message
*
* @return Longitude of point
*/
static inline float mavlink_msg_fence_point_get_lng(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 8);
}
 
/**
* @brief Decode a fence_point message into a struct
*
* @param msg The message to decode
* @param fence_point C-struct to decode the message contents into
*/
static inline void mavlink_msg_fence_point_decode(const mavlink_message_t* msg, mavlink_fence_point_t* fence_point)
{
#if MAVLINK_NEED_BYTE_SWAP
fence_point->target_system = mavlink_msg_fence_point_get_target_system(msg);
fence_point->target_component = mavlink_msg_fence_point_get_target_component(msg);
fence_point->idx = mavlink_msg_fence_point_get_idx(msg);
fence_point->count = mavlink_msg_fence_point_get_count(msg);
fence_point->lat = mavlink_msg_fence_point_get_lat(msg);
fence_point->lng = mavlink_msg_fence_point_get_lng(msg);
#else
memcpy(fence_point, _MAV_PAYLOAD(msg), 12);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v0.9/ardupilotmega/mavlink_msg_fence_status.h
0,0 → 1,210
// MESSAGE FENCE_STATUS PACKING
 
#define MAVLINK_MSG_ID_FENCE_STATUS 162
 
typedef struct __mavlink_fence_status_t
{
uint8_t breach_status; ///< 0 if currently inside fence, 1 if outside
uint16_t breach_count; ///< number of fence breaches
uint8_t breach_type; ///< last breach type (see FENCE_BREACH_* enum)
uint32_t breach_time; ///< time of last breach in milliseconds since boot
} mavlink_fence_status_t;
 
#define MAVLINK_MSG_ID_FENCE_STATUS_LEN 8
#define MAVLINK_MSG_ID_162_LEN 8
 
 
 
#define MAVLINK_MESSAGE_INFO_FENCE_STATUS { \
"FENCE_STATUS", \
4, \
{ { "breach_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_fence_status_t, breach_status) }, \
{ "breach_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 1, offsetof(mavlink_fence_status_t, breach_count) }, \
{ "breach_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_fence_status_t, breach_type) }, \
{ "breach_time", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_fence_status_t, breach_time) }, \
} \
}
 
 
/**
* @brief Pack a fence_status message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param breach_status 0 if currently inside fence, 1 if outside
* @param breach_count number of fence breaches
* @param breach_type last breach type (see FENCE_BREACH_* enum)
* @param breach_time time of last breach in milliseconds since boot
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_fence_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t breach_status, uint16_t breach_count, uint8_t breach_type, uint32_t breach_time)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[8];
_mav_put_uint8_t(buf, 0, breach_status);
_mav_put_uint16_t(buf, 1, breach_count);
_mav_put_uint8_t(buf, 3, breach_type);
_mav_put_uint32_t(buf, 4, breach_time);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 8);
#else
mavlink_fence_status_t packet;
packet.breach_status = breach_status;
packet.breach_count = breach_count;
packet.breach_type = breach_type;
packet.breach_time = breach_time;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 8);
#endif
 
msg->msgid = MAVLINK_MSG_ID_FENCE_STATUS;
return mavlink_finalize_message(msg, system_id, component_id, 8);
}
 
/**
* @brief Pack a fence_status message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param breach_status 0 if currently inside fence, 1 if outside
* @param breach_count number of fence breaches
* @param breach_type last breach type (see FENCE_BREACH_* enum)
* @param breach_time time of last breach in milliseconds since boot
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_fence_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint8_t breach_status,uint16_t breach_count,uint8_t breach_type,uint32_t breach_time)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[8];
_mav_put_uint8_t(buf, 0, breach_status);
_mav_put_uint16_t(buf, 1, breach_count);
_mav_put_uint8_t(buf, 3, breach_type);
_mav_put_uint32_t(buf, 4, breach_time);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 8);
#else
mavlink_fence_status_t packet;
packet.breach_status = breach_status;
packet.breach_count = breach_count;
packet.breach_type = breach_type;
packet.breach_time = breach_time;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 8);
#endif
 
msg->msgid = MAVLINK_MSG_ID_FENCE_STATUS;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 8);
}
 
/**
* @brief Encode a fence_status struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param fence_status C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_fence_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_fence_status_t* fence_status)
{
return mavlink_msg_fence_status_pack(system_id, component_id, msg, fence_status->breach_status, fence_status->breach_count, fence_status->breach_type, fence_status->breach_time);
}
 
/**
* @brief Send a fence_status message
* @param chan MAVLink channel to send the message
*
* @param breach_status 0 if currently inside fence, 1 if outside
* @param breach_count number of fence breaches
* @param breach_type last breach type (see FENCE_BREACH_* enum)
* @param breach_time time of last breach in milliseconds since boot
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_fence_status_send(mavlink_channel_t chan, uint8_t breach_status, uint16_t breach_count, uint8_t breach_type, uint32_t breach_time)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[8];
_mav_put_uint8_t(buf, 0, breach_status);
_mav_put_uint16_t(buf, 1, breach_count);
_mav_put_uint8_t(buf, 3, breach_type);
_mav_put_uint32_t(buf, 4, breach_time);
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FENCE_STATUS, buf, 8);
#else
mavlink_fence_status_t packet;
packet.breach_status = breach_status;
packet.breach_count = breach_count;
packet.breach_type = breach_type;
packet.breach_time = breach_time;
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FENCE_STATUS, (const char *)&packet, 8);
#endif
}
 
#endif
 
// MESSAGE FENCE_STATUS UNPACKING
 
 
/**
* @brief Get field breach_status from fence_status message
*
* @return 0 if currently inside fence, 1 if outside
*/
static inline uint8_t mavlink_msg_fence_status_get_breach_status(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 0);
}
 
/**
* @brief Get field breach_count from fence_status message
*
* @return number of fence breaches
*/
static inline uint16_t mavlink_msg_fence_status_get_breach_count(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 1);
}
 
/**
* @brief Get field breach_type from fence_status message
*
* @return last breach type (see FENCE_BREACH_* enum)
*/
static inline uint8_t mavlink_msg_fence_status_get_breach_type(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 3);
}
 
/**
* @brief Get field breach_time from fence_status message
*
* @return time of last breach in milliseconds since boot
*/
static inline uint32_t mavlink_msg_fence_status_get_breach_time(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint32_t(msg, 4);
}
 
/**
* @brief Decode a fence_status message into a struct
*
* @param msg The message to decode
* @param fence_status C-struct to decode the message contents into
*/
static inline void mavlink_msg_fence_status_decode(const mavlink_message_t* msg, mavlink_fence_status_t* fence_status)
{
#if MAVLINK_NEED_BYTE_SWAP
fence_status->breach_status = mavlink_msg_fence_status_get_breach_status(msg);
fence_status->breach_count = mavlink_msg_fence_status_get_breach_count(msg);
fence_status->breach_type = mavlink_msg_fence_status_get_breach_type(msg);
fence_status->breach_time = mavlink_msg_fence_status_get_breach_time(msg);
#else
memcpy(fence_status, _MAV_PAYLOAD(msg), 8);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v0.9/ardupilotmega/mavlink_msg_hwstatus.h
0,0 → 1,166
// MESSAGE HWSTATUS PACKING
 
#define MAVLINK_MSG_ID_HWSTATUS 165
 
typedef struct __mavlink_hwstatus_t
{
uint16_t Vcc; ///< board voltage (mV)
uint8_t I2Cerr; ///< I2C error count
} mavlink_hwstatus_t;
 
#define MAVLINK_MSG_ID_HWSTATUS_LEN 3
#define MAVLINK_MSG_ID_165_LEN 3
 
 
 
#define MAVLINK_MESSAGE_INFO_HWSTATUS { \
"HWSTATUS", \
2, \
{ { "Vcc", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_hwstatus_t, Vcc) }, \
{ "I2Cerr", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_hwstatus_t, I2Cerr) }, \
} \
}
 
 
/**
* @brief Pack a hwstatus message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param Vcc board voltage (mV)
* @param I2Cerr I2C error count
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_hwstatus_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint16_t Vcc, uint8_t I2Cerr)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[3];
_mav_put_uint16_t(buf, 0, Vcc);
_mav_put_uint8_t(buf, 2, I2Cerr);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 3);
#else
mavlink_hwstatus_t packet;
packet.Vcc = Vcc;
packet.I2Cerr = I2Cerr;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 3);
#endif
 
msg->msgid = MAVLINK_MSG_ID_HWSTATUS;
return mavlink_finalize_message(msg, system_id, component_id, 3);
}
 
/**
* @brief Pack a hwstatus message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param Vcc board voltage (mV)
* @param I2Cerr I2C error count
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_hwstatus_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint16_t Vcc,uint8_t I2Cerr)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[3];
_mav_put_uint16_t(buf, 0, Vcc);
_mav_put_uint8_t(buf, 2, I2Cerr);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 3);
#else
mavlink_hwstatus_t packet;
packet.Vcc = Vcc;
packet.I2Cerr = I2Cerr;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 3);
#endif
 
msg->msgid = MAVLINK_MSG_ID_HWSTATUS;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 3);
}
 
/**
* @brief Encode a hwstatus struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param hwstatus C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_hwstatus_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_hwstatus_t* hwstatus)
{
return mavlink_msg_hwstatus_pack(system_id, component_id, msg, hwstatus->Vcc, hwstatus->I2Cerr);
}
 
/**
* @brief Send a hwstatus message
* @param chan MAVLink channel to send the message
*
* @param Vcc board voltage (mV)
* @param I2Cerr I2C error count
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_hwstatus_send(mavlink_channel_t chan, uint16_t Vcc, uint8_t I2Cerr)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[3];
_mav_put_uint16_t(buf, 0, Vcc);
_mav_put_uint8_t(buf, 2, I2Cerr);
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HWSTATUS, buf, 3);
#else
mavlink_hwstatus_t packet;
packet.Vcc = Vcc;
packet.I2Cerr = I2Cerr;
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HWSTATUS, (const char *)&packet, 3);
#endif
}
 
#endif
 
// MESSAGE HWSTATUS UNPACKING
 
 
/**
* @brief Get field Vcc from hwstatus message
*
* @return board voltage (mV)
*/
static inline uint16_t mavlink_msg_hwstatus_get_Vcc(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 0);
}
 
/**
* @brief Get field I2Cerr from hwstatus message
*
* @return I2C error count
*/
static inline uint8_t mavlink_msg_hwstatus_get_I2Cerr(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 2);
}
 
/**
* @brief Decode a hwstatus message into a struct
*
* @param msg The message to decode
* @param hwstatus C-struct to decode the message contents into
*/
static inline void mavlink_msg_hwstatus_decode(const mavlink_message_t* msg, mavlink_hwstatus_t* hwstatus)
{
#if MAVLINK_NEED_BYTE_SWAP
hwstatus->Vcc = mavlink_msg_hwstatus_get_Vcc(msg);
hwstatus->I2Cerr = mavlink_msg_hwstatus_get_I2Cerr(msg);
#else
memcpy(hwstatus, _MAV_PAYLOAD(msg), 3);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v0.9/ardupilotmega/mavlink_msg_meminfo.h
0,0 → 1,166
// MESSAGE MEMINFO PACKING
 
#define MAVLINK_MSG_ID_MEMINFO 152
 
typedef struct __mavlink_meminfo_t
{
uint16_t brkval; ///< heap top
uint16_t freemem; ///< free memory
} mavlink_meminfo_t;
 
#define MAVLINK_MSG_ID_MEMINFO_LEN 4
#define MAVLINK_MSG_ID_152_LEN 4
 
 
 
#define MAVLINK_MESSAGE_INFO_MEMINFO { \
"MEMINFO", \
2, \
{ { "brkval", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_meminfo_t, brkval) }, \
{ "freemem", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_meminfo_t, freemem) }, \
} \
}
 
 
/**
* @brief Pack a meminfo message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param brkval heap top
* @param freemem free memory
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_meminfo_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint16_t brkval, uint16_t freemem)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[4];
_mav_put_uint16_t(buf, 0, brkval);
_mav_put_uint16_t(buf, 2, freemem);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 4);
#else
mavlink_meminfo_t packet;
packet.brkval = brkval;
packet.freemem = freemem;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 4);
#endif
 
msg->msgid = MAVLINK_MSG_ID_MEMINFO;
return mavlink_finalize_message(msg, system_id, component_id, 4);
}
 
/**
* @brief Pack a meminfo message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param brkval heap top
* @param freemem free memory
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_meminfo_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint16_t brkval,uint16_t freemem)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[4];
_mav_put_uint16_t(buf, 0, brkval);
_mav_put_uint16_t(buf, 2, freemem);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 4);
#else
mavlink_meminfo_t packet;
packet.brkval = brkval;
packet.freemem = freemem;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 4);
#endif
 
msg->msgid = MAVLINK_MSG_ID_MEMINFO;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 4);
}
 
/**
* @brief Encode a meminfo struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param meminfo C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_meminfo_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_meminfo_t* meminfo)
{
return mavlink_msg_meminfo_pack(system_id, component_id, msg, meminfo->brkval, meminfo->freemem);
}
 
/**
* @brief Send a meminfo message
* @param chan MAVLink channel to send the message
*
* @param brkval heap top
* @param freemem free memory
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_meminfo_send(mavlink_channel_t chan, uint16_t brkval, uint16_t freemem)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[4];
_mav_put_uint16_t(buf, 0, brkval);
_mav_put_uint16_t(buf, 2, freemem);
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MEMINFO, buf, 4);
#else
mavlink_meminfo_t packet;
packet.brkval = brkval;
packet.freemem = freemem;
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MEMINFO, (const char *)&packet, 4);
#endif
}
 
#endif
 
// MESSAGE MEMINFO UNPACKING
 
 
/**
* @brief Get field brkval from meminfo message
*
* @return heap top
*/
static inline uint16_t mavlink_msg_meminfo_get_brkval(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 0);
}
 
/**
* @brief Get field freemem from meminfo message
*
* @return free memory
*/
static inline uint16_t mavlink_msg_meminfo_get_freemem(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 2);
}
 
/**
* @brief Decode a meminfo message into a struct
*
* @param msg The message to decode
* @param meminfo C-struct to decode the message contents into
*/
static inline void mavlink_msg_meminfo_decode(const mavlink_message_t* msg, mavlink_meminfo_t* meminfo)
{
#if MAVLINK_NEED_BYTE_SWAP
meminfo->brkval = mavlink_msg_meminfo_get_brkval(msg);
meminfo->freemem = mavlink_msg_meminfo_get_freemem(msg);
#else
memcpy(meminfo, _MAV_PAYLOAD(msg), 4);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v0.9/ardupilotmega/mavlink_msg_mount_configure.h
0,0 → 1,254
// MESSAGE MOUNT_CONFIGURE PACKING
 
#define MAVLINK_MSG_ID_MOUNT_CONFIGURE 156
 
typedef struct __mavlink_mount_configure_t
{
uint8_t target_system; ///< System ID
uint8_t target_component; ///< Component ID
uint8_t mount_mode; ///< mount operating mode (see MAV_MOUNT_MODE enum)
uint8_t stab_roll; ///< (1 = yes, 0 = no)
uint8_t stab_pitch; ///< (1 = yes, 0 = no)
uint8_t stab_yaw; ///< (1 = yes, 0 = no)
} mavlink_mount_configure_t;
 
#define MAVLINK_MSG_ID_MOUNT_CONFIGURE_LEN 6
#define MAVLINK_MSG_ID_156_LEN 6
 
 
 
#define MAVLINK_MESSAGE_INFO_MOUNT_CONFIGURE { \
"MOUNT_CONFIGURE", \
6, \
{ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_mount_configure_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_mount_configure_t, target_component) }, \
{ "mount_mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_mount_configure_t, mount_mode) }, \
{ "stab_roll", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_mount_configure_t, stab_roll) }, \
{ "stab_pitch", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_mount_configure_t, stab_pitch) }, \
{ "stab_yaw", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_mount_configure_t, stab_yaw) }, \
} \
}
 
 
/**
* @brief Pack a mount_configure message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param target_system System ID
* @param target_component Component ID
* @param mount_mode mount operating mode (see MAV_MOUNT_MODE enum)
* @param stab_roll (1 = yes, 0 = no)
* @param stab_pitch (1 = yes, 0 = no)
* @param stab_yaw (1 = yes, 0 = no)
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_mount_configure_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t target_system, uint8_t target_component, uint8_t mount_mode, uint8_t stab_roll, uint8_t stab_pitch, uint8_t stab_yaw)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[6];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
_mav_put_uint8_t(buf, 2, mount_mode);
_mav_put_uint8_t(buf, 3, stab_roll);
_mav_put_uint8_t(buf, 4, stab_pitch);
_mav_put_uint8_t(buf, 5, stab_yaw);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 6);
#else
mavlink_mount_configure_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
packet.mount_mode = mount_mode;
packet.stab_roll = stab_roll;
packet.stab_pitch = stab_pitch;
packet.stab_yaw = stab_yaw;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 6);
#endif
 
msg->msgid = MAVLINK_MSG_ID_MOUNT_CONFIGURE;
return mavlink_finalize_message(msg, system_id, component_id, 6);
}
 
/**
* @brief Pack a mount_configure message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param target_system System ID
* @param target_component Component ID
* @param mount_mode mount operating mode (see MAV_MOUNT_MODE enum)
* @param stab_roll (1 = yes, 0 = no)
* @param stab_pitch (1 = yes, 0 = no)
* @param stab_yaw (1 = yes, 0 = no)
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_mount_configure_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 mount_mode,uint8_t stab_roll,uint8_t stab_pitch,uint8_t stab_yaw)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[6];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
_mav_put_uint8_t(buf, 2, mount_mode);
_mav_put_uint8_t(buf, 3, stab_roll);
_mav_put_uint8_t(buf, 4, stab_pitch);
_mav_put_uint8_t(buf, 5, stab_yaw);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 6);
#else
mavlink_mount_configure_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
packet.mount_mode = mount_mode;
packet.stab_roll = stab_roll;
packet.stab_pitch = stab_pitch;
packet.stab_yaw = stab_yaw;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 6);
#endif
 
msg->msgid = MAVLINK_MSG_ID_MOUNT_CONFIGURE;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 6);
}
 
/**
* @brief Encode a mount_configure struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param mount_configure C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_mount_configure_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mount_configure_t* mount_configure)
{
return mavlink_msg_mount_configure_pack(system_id, component_id, msg, mount_configure->target_system, mount_configure->target_component, mount_configure->mount_mode, mount_configure->stab_roll, mount_configure->stab_pitch, mount_configure->stab_yaw);
}
 
/**
* @brief Send a mount_configure message
* @param chan MAVLink channel to send the message
*
* @param target_system System ID
* @param target_component Component ID
* @param mount_mode mount operating mode (see MAV_MOUNT_MODE enum)
* @param stab_roll (1 = yes, 0 = no)
* @param stab_pitch (1 = yes, 0 = no)
* @param stab_yaw (1 = yes, 0 = no)
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_mount_configure_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t mount_mode, uint8_t stab_roll, uint8_t stab_pitch, uint8_t stab_yaw)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[6];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
_mav_put_uint8_t(buf, 2, mount_mode);
_mav_put_uint8_t(buf, 3, stab_roll);
_mav_put_uint8_t(buf, 4, stab_pitch);
_mav_put_uint8_t(buf, 5, stab_yaw);
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MOUNT_CONFIGURE, buf, 6);
#else
mavlink_mount_configure_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
packet.mount_mode = mount_mode;
packet.stab_roll = stab_roll;
packet.stab_pitch = stab_pitch;
packet.stab_yaw = stab_yaw;
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MOUNT_CONFIGURE, (const char *)&packet, 6);
#endif
}
 
#endif
 
// MESSAGE MOUNT_CONFIGURE UNPACKING
 
 
/**
* @brief Get field target_system from mount_configure message
*
* @return System ID
*/
static inline uint8_t mavlink_msg_mount_configure_get_target_system(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 0);
}
 
/**
* @brief Get field target_component from mount_configure message
*
* @return Component ID
*/
static inline uint8_t mavlink_msg_mount_configure_get_target_component(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 1);
}
 
/**
* @brief Get field mount_mode from mount_configure message
*
* @return mount operating mode (see MAV_MOUNT_MODE enum)
*/
static inline uint8_t mavlink_msg_mount_configure_get_mount_mode(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 2);
}
 
/**
* @brief Get field stab_roll from mount_configure message
*
* @return (1 = yes, 0 = no)
*/
static inline uint8_t mavlink_msg_mount_configure_get_stab_roll(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 3);
}
 
/**
* @brief Get field stab_pitch from mount_configure message
*
* @return (1 = yes, 0 = no)
*/
static inline uint8_t mavlink_msg_mount_configure_get_stab_pitch(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 4);
}
 
/**
* @brief Get field stab_yaw from mount_configure message
*
* @return (1 = yes, 0 = no)
*/
static inline uint8_t mavlink_msg_mount_configure_get_stab_yaw(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 5);
}
 
/**
* @brief Decode a mount_configure message into a struct
*
* @param msg The message to decode
* @param mount_configure C-struct to decode the message contents into
*/
static inline void mavlink_msg_mount_configure_decode(const mavlink_message_t* msg, mavlink_mount_configure_t* mount_configure)
{
#if MAVLINK_NEED_BYTE_SWAP
mount_configure->target_system = mavlink_msg_mount_configure_get_target_system(msg);
mount_configure->target_component = mavlink_msg_mount_configure_get_target_component(msg);
mount_configure->mount_mode = mavlink_msg_mount_configure_get_mount_mode(msg);
mount_configure->stab_roll = mavlink_msg_mount_configure_get_stab_roll(msg);
mount_configure->stab_pitch = mavlink_msg_mount_configure_get_stab_pitch(msg);
mount_configure->stab_yaw = mavlink_msg_mount_configure_get_stab_yaw(msg);
#else
memcpy(mount_configure, _MAV_PAYLOAD(msg), 6);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v0.9/ardupilotmega/mavlink_msg_mount_control.h
0,0 → 1,254
// MESSAGE MOUNT_CONTROL PACKING
 
#define MAVLINK_MSG_ID_MOUNT_CONTROL 157
 
typedef struct __mavlink_mount_control_t
{
uint8_t target_system; ///< System ID
uint8_t target_component; ///< Component ID
int32_t input_a; ///< pitch(deg*100) or lat, depending on mount mode
int32_t input_b; ///< roll(deg*100) or lon depending on mount mode
int32_t input_c; ///< yaw(deg*100) or alt (in cm) depending on mount mode
uint8_t save_position; ///< if "1" it will save current trimmed position on EEPROM (just valid for NEUTRAL and LANDING)
} mavlink_mount_control_t;
 
#define MAVLINK_MSG_ID_MOUNT_CONTROL_LEN 15
#define MAVLINK_MSG_ID_157_LEN 15
 
 
 
#define MAVLINK_MESSAGE_INFO_MOUNT_CONTROL { \
"MOUNT_CONTROL", \
6, \
{ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_mount_control_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_mount_control_t, target_component) }, \
{ "input_a", NULL, MAVLINK_TYPE_INT32_T, 0, 2, offsetof(mavlink_mount_control_t, input_a) }, \
{ "input_b", NULL, MAVLINK_TYPE_INT32_T, 0, 6, offsetof(mavlink_mount_control_t, input_b) }, \
{ "input_c", NULL, MAVLINK_TYPE_INT32_T, 0, 10, offsetof(mavlink_mount_control_t, input_c) }, \
{ "save_position", NULL, MAVLINK_TYPE_UINT8_T, 0, 14, offsetof(mavlink_mount_control_t, save_position) }, \
} \
}
 
 
/**
* @brief Pack a mount_control message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param target_system System ID
* @param target_component Component ID
* @param input_a pitch(deg*100) or lat, depending on mount mode
* @param input_b roll(deg*100) or lon depending on mount mode
* @param input_c yaw(deg*100) or alt (in cm) depending on mount mode
* @param save_position if "1" it will save current trimmed position on EEPROM (just valid for NEUTRAL and LANDING)
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_mount_control_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t target_system, uint8_t target_component, int32_t input_a, int32_t input_b, int32_t input_c, uint8_t save_position)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[15];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
_mav_put_int32_t(buf, 2, input_a);
_mav_put_int32_t(buf, 6, input_b);
_mav_put_int32_t(buf, 10, input_c);
_mav_put_uint8_t(buf, 14, save_position);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 15);
#else
mavlink_mount_control_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
packet.input_a = input_a;
packet.input_b = input_b;
packet.input_c = input_c;
packet.save_position = save_position;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 15);
#endif
 
msg->msgid = MAVLINK_MSG_ID_MOUNT_CONTROL;
return mavlink_finalize_message(msg, system_id, component_id, 15);
}
 
/**
* @brief Pack a mount_control message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param target_system System ID
* @param target_component Component ID
* @param input_a pitch(deg*100) or lat, depending on mount mode
* @param input_b roll(deg*100) or lon depending on mount mode
* @param input_c yaw(deg*100) or alt (in cm) depending on mount mode
* @param save_position if "1" it will save current trimmed position on EEPROM (just valid for NEUTRAL and LANDING)
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_mount_control_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,int32_t input_a,int32_t input_b,int32_t input_c,uint8_t save_position)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[15];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
_mav_put_int32_t(buf, 2, input_a);
_mav_put_int32_t(buf, 6, input_b);
_mav_put_int32_t(buf, 10, input_c);
_mav_put_uint8_t(buf, 14, save_position);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 15);
#else
mavlink_mount_control_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
packet.input_a = input_a;
packet.input_b = input_b;
packet.input_c = input_c;
packet.save_position = save_position;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 15);
#endif
 
msg->msgid = MAVLINK_MSG_ID_MOUNT_CONTROL;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 15);
}
 
/**
* @brief Encode a mount_control struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param mount_control C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_mount_control_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mount_control_t* mount_control)
{
return mavlink_msg_mount_control_pack(system_id, component_id, msg, mount_control->target_system, mount_control->target_component, mount_control->input_a, mount_control->input_b, mount_control->input_c, mount_control->save_position);
}
 
/**
* @brief Send a mount_control message
* @param chan MAVLink channel to send the message
*
* @param target_system System ID
* @param target_component Component ID
* @param input_a pitch(deg*100) or lat, depending on mount mode
* @param input_b roll(deg*100) or lon depending on mount mode
* @param input_c yaw(deg*100) or alt (in cm) depending on mount mode
* @param save_position if "1" it will save current trimmed position on EEPROM (just valid for NEUTRAL and LANDING)
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_mount_control_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, int32_t input_a, int32_t input_b, int32_t input_c, uint8_t save_position)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[15];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
_mav_put_int32_t(buf, 2, input_a);
_mav_put_int32_t(buf, 6, input_b);
_mav_put_int32_t(buf, 10, input_c);
_mav_put_uint8_t(buf, 14, save_position);
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MOUNT_CONTROL, buf, 15);
#else
mavlink_mount_control_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
packet.input_a = input_a;
packet.input_b = input_b;
packet.input_c = input_c;
packet.save_position = save_position;
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MOUNT_CONTROL, (const char *)&packet, 15);
#endif
}
 
#endif
 
// MESSAGE MOUNT_CONTROL UNPACKING
 
 
/**
* @brief Get field target_system from mount_control message
*
* @return System ID
*/
static inline uint8_t mavlink_msg_mount_control_get_target_system(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 0);
}
 
/**
* @brief Get field target_component from mount_control message
*
* @return Component ID
*/
static inline uint8_t mavlink_msg_mount_control_get_target_component(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 1);
}
 
/**
* @brief Get field input_a from mount_control message
*
* @return pitch(deg*100) or lat, depending on mount mode
*/
static inline int32_t mavlink_msg_mount_control_get_input_a(const mavlink_message_t* msg)
{
return _MAV_RETURN_int32_t(msg, 2);
}
 
/**
* @brief Get field input_b from mount_control message
*
* @return roll(deg*100) or lon depending on mount mode
*/
static inline int32_t mavlink_msg_mount_control_get_input_b(const mavlink_message_t* msg)
{
return _MAV_RETURN_int32_t(msg, 6);
}
 
/**
* @brief Get field input_c from mount_control message
*
* @return yaw(deg*100) or alt (in cm) depending on mount mode
*/
static inline int32_t mavlink_msg_mount_control_get_input_c(const mavlink_message_t* msg)
{
return _MAV_RETURN_int32_t(msg, 10);
}
 
/**
* @brief Get field save_position from mount_control message
*
* @return if "1" it will save current trimmed position on EEPROM (just valid for NEUTRAL and LANDING)
*/
static inline uint8_t mavlink_msg_mount_control_get_save_position(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 14);
}
 
/**
* @brief Decode a mount_control message into a struct
*
* @param msg The message to decode
* @param mount_control C-struct to decode the message contents into
*/
static inline void mavlink_msg_mount_control_decode(const mavlink_message_t* msg, mavlink_mount_control_t* mount_control)
{
#if MAVLINK_NEED_BYTE_SWAP
mount_control->target_system = mavlink_msg_mount_control_get_target_system(msg);
mount_control->target_component = mavlink_msg_mount_control_get_target_component(msg);
mount_control->input_a = mavlink_msg_mount_control_get_input_a(msg);
mount_control->input_b = mavlink_msg_mount_control_get_input_b(msg);
mount_control->input_c = mavlink_msg_mount_control_get_input_c(msg);
mount_control->save_position = mavlink_msg_mount_control_get_save_position(msg);
#else
memcpy(mount_control, _MAV_PAYLOAD(msg), 15);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v0.9/ardupilotmega/mavlink_msg_mount_status.h
0,0 → 1,232
// MESSAGE MOUNT_STATUS PACKING
 
#define MAVLINK_MSG_ID_MOUNT_STATUS 158
 
typedef struct __mavlink_mount_status_t
{
uint8_t target_system; ///< System ID
uint8_t target_component; ///< Component ID
int32_t pointing_a; ///< pitch(deg*100) or lat, depending on mount mode
int32_t pointing_b; ///< roll(deg*100) or lon depending on mount mode
int32_t pointing_c; ///< yaw(deg*100) or alt (in cm) depending on mount mode
} mavlink_mount_status_t;
 
#define MAVLINK_MSG_ID_MOUNT_STATUS_LEN 14
#define MAVLINK_MSG_ID_158_LEN 14
 
 
 
#define MAVLINK_MESSAGE_INFO_MOUNT_STATUS { \
"MOUNT_STATUS", \
5, \
{ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_mount_status_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_mount_status_t, target_component) }, \
{ "pointing_a", NULL, MAVLINK_TYPE_INT32_T, 0, 2, offsetof(mavlink_mount_status_t, pointing_a) }, \
{ "pointing_b", NULL, MAVLINK_TYPE_INT32_T, 0, 6, offsetof(mavlink_mount_status_t, pointing_b) }, \
{ "pointing_c", NULL, MAVLINK_TYPE_INT32_T, 0, 10, offsetof(mavlink_mount_status_t, pointing_c) }, \
} \
}
 
 
/**
* @brief Pack a mount_status message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param target_system System ID
* @param target_component Component ID
* @param pointing_a pitch(deg*100) or lat, depending on mount mode
* @param pointing_b roll(deg*100) or lon depending on mount mode
* @param pointing_c yaw(deg*100) or alt (in cm) depending on mount mode
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_mount_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t target_system, uint8_t target_component, int32_t pointing_a, int32_t pointing_b, int32_t pointing_c)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[14];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
_mav_put_int32_t(buf, 2, pointing_a);
_mav_put_int32_t(buf, 6, pointing_b);
_mav_put_int32_t(buf, 10, pointing_c);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 14);
#else
mavlink_mount_status_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
packet.pointing_a = pointing_a;
packet.pointing_b = pointing_b;
packet.pointing_c = pointing_c;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 14);
#endif
 
msg->msgid = MAVLINK_MSG_ID_MOUNT_STATUS;
return mavlink_finalize_message(msg, system_id, component_id, 14);
}
 
/**
* @brief Pack a mount_status message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param target_system System ID
* @param target_component Component ID
* @param pointing_a pitch(deg*100) or lat, depending on mount mode
* @param pointing_b roll(deg*100) or lon depending on mount mode
* @param pointing_c yaw(deg*100) or alt (in cm) depending on mount mode
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_mount_status_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,int32_t pointing_a,int32_t pointing_b,int32_t pointing_c)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[14];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
_mav_put_int32_t(buf, 2, pointing_a);
_mav_put_int32_t(buf, 6, pointing_b);
_mav_put_int32_t(buf, 10, pointing_c);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 14);
#else
mavlink_mount_status_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
packet.pointing_a = pointing_a;
packet.pointing_b = pointing_b;
packet.pointing_c = pointing_c;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 14);
#endif
 
msg->msgid = MAVLINK_MSG_ID_MOUNT_STATUS;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 14);
}
 
/**
* @brief Encode a mount_status struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param mount_status C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_mount_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mount_status_t* mount_status)
{
return mavlink_msg_mount_status_pack(system_id, component_id, msg, mount_status->target_system, mount_status->target_component, mount_status->pointing_a, mount_status->pointing_b, mount_status->pointing_c);
}
 
/**
* @brief Send a mount_status message
* @param chan MAVLink channel to send the message
*
* @param target_system System ID
* @param target_component Component ID
* @param pointing_a pitch(deg*100) or lat, depending on mount mode
* @param pointing_b roll(deg*100) or lon depending on mount mode
* @param pointing_c yaw(deg*100) or alt (in cm) depending on mount mode
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_mount_status_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, int32_t pointing_a, int32_t pointing_b, int32_t pointing_c)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[14];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
_mav_put_int32_t(buf, 2, pointing_a);
_mav_put_int32_t(buf, 6, pointing_b);
_mav_put_int32_t(buf, 10, pointing_c);
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MOUNT_STATUS, buf, 14);
#else
mavlink_mount_status_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
packet.pointing_a = pointing_a;
packet.pointing_b = pointing_b;
packet.pointing_c = pointing_c;
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MOUNT_STATUS, (const char *)&packet, 14);
#endif
}
 
#endif
 
// MESSAGE MOUNT_STATUS UNPACKING
 
 
/**
* @brief Get field target_system from mount_status message
*
* @return System ID
*/
static inline uint8_t mavlink_msg_mount_status_get_target_system(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 0);
}
 
/**
* @brief Get field target_component from mount_status message
*
* @return Component ID
*/
static inline uint8_t mavlink_msg_mount_status_get_target_component(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 1);
}
 
/**
* @brief Get field pointing_a from mount_status message
*
* @return pitch(deg*100) or lat, depending on mount mode
*/
static inline int32_t mavlink_msg_mount_status_get_pointing_a(const mavlink_message_t* msg)
{
return _MAV_RETURN_int32_t(msg, 2);
}
 
/**
* @brief Get field pointing_b from mount_status message
*
* @return roll(deg*100) or lon depending on mount mode
*/
static inline int32_t mavlink_msg_mount_status_get_pointing_b(const mavlink_message_t* msg)
{
return _MAV_RETURN_int32_t(msg, 6);
}
 
/**
* @brief Get field pointing_c from mount_status message
*
* @return yaw(deg*100) or alt (in cm) depending on mount mode
*/
static inline int32_t mavlink_msg_mount_status_get_pointing_c(const mavlink_message_t* msg)
{
return _MAV_RETURN_int32_t(msg, 10);
}
 
/**
* @brief Decode a mount_status message into a struct
*
* @param msg The message to decode
* @param mount_status C-struct to decode the message contents into
*/
static inline void mavlink_msg_mount_status_decode(const mavlink_message_t* msg, mavlink_mount_status_t* mount_status)
{
#if MAVLINK_NEED_BYTE_SWAP
mount_status->target_system = mavlink_msg_mount_status_get_target_system(msg);
mount_status->target_component = mavlink_msg_mount_status_get_target_component(msg);
mount_status->pointing_a = mavlink_msg_mount_status_get_pointing_a(msg);
mount_status->pointing_b = mavlink_msg_mount_status_get_pointing_b(msg);
mount_status->pointing_c = mavlink_msg_mount_status_get_pointing_c(msg);
#else
memcpy(mount_status, _MAV_PAYLOAD(msg), 14);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v0.9/ardupilotmega/mavlink_msg_radio.h
0,0 → 1,276
// MESSAGE RADIO PACKING
 
#define MAVLINK_MSG_ID_RADIO 166
 
typedef struct __mavlink_radio_t
{
uint8_t rssi; ///< local signal strength
uint8_t remrssi; ///< remote signal strength
uint8_t txbuf; ///< how full the tx buffer is as a percentage
uint8_t noise; ///< background noise level
uint8_t remnoise; ///< remote background noise level
uint16_t rxerrors; ///< receive errors
uint16_t fixed; ///< count of error corrected packets
} mavlink_radio_t;
 
#define MAVLINK_MSG_ID_RADIO_LEN 9
#define MAVLINK_MSG_ID_166_LEN 9
 
 
 
#define MAVLINK_MESSAGE_INFO_RADIO { \
"RADIO", \
7, \
{ { "rssi", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_radio_t, rssi) }, \
{ "remrssi", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_radio_t, remrssi) }, \
{ "txbuf", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_radio_t, txbuf) }, \
{ "noise", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_radio_t, noise) }, \
{ "remnoise", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_radio_t, remnoise) }, \
{ "rxerrors", NULL, MAVLINK_TYPE_UINT16_T, 0, 5, offsetof(mavlink_radio_t, rxerrors) }, \
{ "fixed", NULL, MAVLINK_TYPE_UINT16_T, 0, 7, offsetof(mavlink_radio_t, fixed) }, \
} \
}
 
 
/**
* @brief Pack a radio message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param rssi local signal strength
* @param remrssi remote signal strength
* @param txbuf how full the tx buffer is as a percentage
* @param noise background noise level
* @param remnoise remote background noise level
* @param rxerrors receive errors
* @param fixed count of error corrected packets
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_radio_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t rssi, uint8_t remrssi, uint8_t txbuf, uint8_t noise, uint8_t remnoise, uint16_t rxerrors, uint16_t fixed)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[9];
_mav_put_uint8_t(buf, 0, rssi);
_mav_put_uint8_t(buf, 1, remrssi);
_mav_put_uint8_t(buf, 2, txbuf);
_mav_put_uint8_t(buf, 3, noise);
_mav_put_uint8_t(buf, 4, remnoise);
_mav_put_uint16_t(buf, 5, rxerrors);
_mav_put_uint16_t(buf, 7, fixed);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 9);
#else
mavlink_radio_t packet;
packet.rssi = rssi;
packet.remrssi = remrssi;
packet.txbuf = txbuf;
packet.noise = noise;
packet.remnoise = remnoise;
packet.rxerrors = rxerrors;
packet.fixed = fixed;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 9);
#endif
 
msg->msgid = MAVLINK_MSG_ID_RADIO;
return mavlink_finalize_message(msg, system_id, component_id, 9);
}
 
/**
* @brief Pack a radio message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param rssi local signal strength
* @param remrssi remote signal strength
* @param txbuf how full the tx buffer is as a percentage
* @param noise background noise level
* @param remnoise remote background noise level
* @param rxerrors receive errors
* @param fixed count of error corrected packets
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_radio_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint8_t rssi,uint8_t remrssi,uint8_t txbuf,uint8_t noise,uint8_t remnoise,uint16_t rxerrors,uint16_t fixed)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[9];
_mav_put_uint8_t(buf, 0, rssi);
_mav_put_uint8_t(buf, 1, remrssi);
_mav_put_uint8_t(buf, 2, txbuf);
_mav_put_uint8_t(buf, 3, noise);
_mav_put_uint8_t(buf, 4, remnoise);
_mav_put_uint16_t(buf, 5, rxerrors);
_mav_put_uint16_t(buf, 7, fixed);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 9);
#else
mavlink_radio_t packet;
packet.rssi = rssi;
packet.remrssi = remrssi;
packet.txbuf = txbuf;
packet.noise = noise;
packet.remnoise = remnoise;
packet.rxerrors = rxerrors;
packet.fixed = fixed;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 9);
#endif
 
msg->msgid = MAVLINK_MSG_ID_RADIO;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 9);
}
 
/**
* @brief Encode a radio struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param radio C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_radio_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_radio_t* radio)
{
return mavlink_msg_radio_pack(system_id, component_id, msg, radio->rssi, radio->remrssi, radio->txbuf, radio->noise, radio->remnoise, radio->rxerrors, radio->fixed);
}
 
/**
* @brief Send a radio message
* @param chan MAVLink channel to send the message
*
* @param rssi local signal strength
* @param remrssi remote signal strength
* @param txbuf how full the tx buffer is as a percentage
* @param noise background noise level
* @param remnoise remote background noise level
* @param rxerrors receive errors
* @param fixed count of error corrected packets
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_radio_send(mavlink_channel_t chan, uint8_t rssi, uint8_t remrssi, uint8_t txbuf, uint8_t noise, uint8_t remnoise, uint16_t rxerrors, uint16_t fixed)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[9];
_mav_put_uint8_t(buf, 0, rssi);
_mav_put_uint8_t(buf, 1, remrssi);
_mav_put_uint8_t(buf, 2, txbuf);
_mav_put_uint8_t(buf, 3, noise);
_mav_put_uint8_t(buf, 4, remnoise);
_mav_put_uint16_t(buf, 5, rxerrors);
_mav_put_uint16_t(buf, 7, fixed);
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RADIO, buf, 9);
#else
mavlink_radio_t packet;
packet.rssi = rssi;
packet.remrssi = remrssi;
packet.txbuf = txbuf;
packet.noise = noise;
packet.remnoise = remnoise;
packet.rxerrors = rxerrors;
packet.fixed = fixed;
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RADIO, (const char *)&packet, 9);
#endif
}
 
#endif
 
// MESSAGE RADIO UNPACKING
 
 
/**
* @brief Get field rssi from radio message
*
* @return local signal strength
*/
static inline uint8_t mavlink_msg_radio_get_rssi(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 0);
}
 
/**
* @brief Get field remrssi from radio message
*
* @return remote signal strength
*/
static inline uint8_t mavlink_msg_radio_get_remrssi(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 1);
}
 
/**
* @brief Get field txbuf from radio message
*
* @return how full the tx buffer is as a percentage
*/
static inline uint8_t mavlink_msg_radio_get_txbuf(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 2);
}
 
/**
* @brief Get field noise from radio message
*
* @return background noise level
*/
static inline uint8_t mavlink_msg_radio_get_noise(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 3);
}
 
/**
* @brief Get field remnoise from radio message
*
* @return remote background noise level
*/
static inline uint8_t mavlink_msg_radio_get_remnoise(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 4);
}
 
/**
* @brief Get field rxerrors from radio message
*
* @return receive errors
*/
static inline uint16_t mavlink_msg_radio_get_rxerrors(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 5);
}
 
/**
* @brief Get field fixed from radio message
*
* @return count of error corrected packets
*/
static inline uint16_t mavlink_msg_radio_get_fixed(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 7);
}
 
/**
* @brief Decode a radio message into a struct
*
* @param msg The message to decode
* @param radio C-struct to decode the message contents into
*/
static inline void mavlink_msg_radio_decode(const mavlink_message_t* msg, mavlink_radio_t* radio)
{
#if MAVLINK_NEED_BYTE_SWAP
radio->rssi = mavlink_msg_radio_get_rssi(msg);
radio->remrssi = mavlink_msg_radio_get_remrssi(msg);
radio->txbuf = mavlink_msg_radio_get_txbuf(msg);
radio->noise = mavlink_msg_radio_get_noise(msg);
radio->remnoise = mavlink_msg_radio_get_remnoise(msg);
radio->rxerrors = mavlink_msg_radio_get_rxerrors(msg);
radio->fixed = mavlink_msg_radio_get_fixed(msg);
#else
memcpy(radio, _MAV_PAYLOAD(msg), 9);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v0.9/ardupilotmega/mavlink_msg_sensor_offsets.h
0,0 → 1,386
// MESSAGE SENSOR_OFFSETS PACKING
 
#define MAVLINK_MSG_ID_SENSOR_OFFSETS 150
 
typedef struct __mavlink_sensor_offsets_t
{
int16_t mag_ofs_x; ///< magnetometer X offset
int16_t mag_ofs_y; ///< magnetometer Y offset
int16_t mag_ofs_z; ///< magnetometer Z offset
float mag_declination; ///< magnetic declination (radians)
int32_t raw_press; ///< raw pressure from barometer
int32_t raw_temp; ///< raw temperature from barometer
float gyro_cal_x; ///< gyro X calibration
float gyro_cal_y; ///< gyro Y calibration
float gyro_cal_z; ///< gyro Z calibration
float accel_cal_x; ///< accel X calibration
float accel_cal_y; ///< accel Y calibration
float accel_cal_z; ///< accel Z calibration
} mavlink_sensor_offsets_t;
 
#define MAVLINK_MSG_ID_SENSOR_OFFSETS_LEN 42
#define MAVLINK_MSG_ID_150_LEN 42
 
 
 
#define MAVLINK_MESSAGE_INFO_SENSOR_OFFSETS { \
"SENSOR_OFFSETS", \
12, \
{ { "mag_ofs_x", NULL, MAVLINK_TYPE_INT16_T, 0, 0, offsetof(mavlink_sensor_offsets_t, mag_ofs_x) }, \
{ "mag_ofs_y", NULL, MAVLINK_TYPE_INT16_T, 0, 2, offsetof(mavlink_sensor_offsets_t, mag_ofs_y) }, \
{ "mag_ofs_z", NULL, MAVLINK_TYPE_INT16_T, 0, 4, offsetof(mavlink_sensor_offsets_t, mag_ofs_z) }, \
{ "mag_declination", NULL, MAVLINK_TYPE_FLOAT, 0, 6, offsetof(mavlink_sensor_offsets_t, mag_declination) }, \
{ "raw_press", NULL, MAVLINK_TYPE_INT32_T, 0, 10, offsetof(mavlink_sensor_offsets_t, raw_press) }, \
{ "raw_temp", NULL, MAVLINK_TYPE_INT32_T, 0, 14, offsetof(mavlink_sensor_offsets_t, raw_temp) }, \
{ "gyro_cal_x", NULL, MAVLINK_TYPE_FLOAT, 0, 18, offsetof(mavlink_sensor_offsets_t, gyro_cal_x) }, \
{ "gyro_cal_y", NULL, MAVLINK_TYPE_FLOAT, 0, 22, offsetof(mavlink_sensor_offsets_t, gyro_cal_y) }, \
{ "gyro_cal_z", NULL, MAVLINK_TYPE_FLOAT, 0, 26, offsetof(mavlink_sensor_offsets_t, gyro_cal_z) }, \
{ "accel_cal_x", NULL, MAVLINK_TYPE_FLOAT, 0, 30, offsetof(mavlink_sensor_offsets_t, accel_cal_x) }, \
{ "accel_cal_y", NULL, MAVLINK_TYPE_FLOAT, 0, 34, offsetof(mavlink_sensor_offsets_t, accel_cal_y) }, \
{ "accel_cal_z", NULL, MAVLINK_TYPE_FLOAT, 0, 38, offsetof(mavlink_sensor_offsets_t, accel_cal_z) }, \
} \
}
 
 
/**
* @brief Pack a sensor_offsets message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param mag_ofs_x magnetometer X offset
* @param mag_ofs_y magnetometer Y offset
* @param mag_ofs_z magnetometer Z offset
* @param mag_declination magnetic declination (radians)
* @param raw_press raw pressure from barometer
* @param raw_temp raw temperature from barometer
* @param gyro_cal_x gyro X calibration
* @param gyro_cal_y gyro Y calibration
* @param gyro_cal_z gyro Z calibration
* @param accel_cal_x accel X calibration
* @param accel_cal_y accel Y calibration
* @param accel_cal_z accel Z calibration
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_sensor_offsets_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
int16_t mag_ofs_x, int16_t mag_ofs_y, int16_t mag_ofs_z, float mag_declination, int32_t raw_press, int32_t raw_temp, float gyro_cal_x, float gyro_cal_y, float gyro_cal_z, float accel_cal_x, float accel_cal_y, float accel_cal_z)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[42];
_mav_put_int16_t(buf, 0, mag_ofs_x);
_mav_put_int16_t(buf, 2, mag_ofs_y);
_mav_put_int16_t(buf, 4, mag_ofs_z);
_mav_put_float(buf, 6, mag_declination);
_mav_put_int32_t(buf, 10, raw_press);
_mav_put_int32_t(buf, 14, raw_temp);
_mav_put_float(buf, 18, gyro_cal_x);
_mav_put_float(buf, 22, gyro_cal_y);
_mav_put_float(buf, 26, gyro_cal_z);
_mav_put_float(buf, 30, accel_cal_x);
_mav_put_float(buf, 34, accel_cal_y);
_mav_put_float(buf, 38, accel_cal_z);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 42);
#else
mavlink_sensor_offsets_t packet;
packet.mag_ofs_x = mag_ofs_x;
packet.mag_ofs_y = mag_ofs_y;
packet.mag_ofs_z = mag_ofs_z;
packet.mag_declination = mag_declination;
packet.raw_press = raw_press;
packet.raw_temp = raw_temp;
packet.gyro_cal_x = gyro_cal_x;
packet.gyro_cal_y = gyro_cal_y;
packet.gyro_cal_z = gyro_cal_z;
packet.accel_cal_x = accel_cal_x;
packet.accel_cal_y = accel_cal_y;
packet.accel_cal_z = accel_cal_z;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 42);
#endif
 
msg->msgid = MAVLINK_MSG_ID_SENSOR_OFFSETS;
return mavlink_finalize_message(msg, system_id, component_id, 42);
}
 
/**
* @brief Pack a sensor_offsets message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param mag_ofs_x magnetometer X offset
* @param mag_ofs_y magnetometer Y offset
* @param mag_ofs_z magnetometer Z offset
* @param mag_declination magnetic declination (radians)
* @param raw_press raw pressure from barometer
* @param raw_temp raw temperature from barometer
* @param gyro_cal_x gyro X calibration
* @param gyro_cal_y gyro Y calibration
* @param gyro_cal_z gyro Z calibration
* @param accel_cal_x accel X calibration
* @param accel_cal_y accel Y calibration
* @param accel_cal_z accel Z calibration
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_sensor_offsets_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
int16_t mag_ofs_x,int16_t mag_ofs_y,int16_t mag_ofs_z,float mag_declination,int32_t raw_press,int32_t raw_temp,float gyro_cal_x,float gyro_cal_y,float gyro_cal_z,float accel_cal_x,float accel_cal_y,float accel_cal_z)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[42];
_mav_put_int16_t(buf, 0, mag_ofs_x);
_mav_put_int16_t(buf, 2, mag_ofs_y);
_mav_put_int16_t(buf, 4, mag_ofs_z);
_mav_put_float(buf, 6, mag_declination);
_mav_put_int32_t(buf, 10, raw_press);
_mav_put_int32_t(buf, 14, raw_temp);
_mav_put_float(buf, 18, gyro_cal_x);
_mav_put_float(buf, 22, gyro_cal_y);
_mav_put_float(buf, 26, gyro_cal_z);
_mav_put_float(buf, 30, accel_cal_x);
_mav_put_float(buf, 34, accel_cal_y);
_mav_put_float(buf, 38, accel_cal_z);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 42);
#else
mavlink_sensor_offsets_t packet;
packet.mag_ofs_x = mag_ofs_x;
packet.mag_ofs_y = mag_ofs_y;
packet.mag_ofs_z = mag_ofs_z;
packet.mag_declination = mag_declination;
packet.raw_press = raw_press;
packet.raw_temp = raw_temp;
packet.gyro_cal_x = gyro_cal_x;
packet.gyro_cal_y = gyro_cal_y;
packet.gyro_cal_z = gyro_cal_z;
packet.accel_cal_x = accel_cal_x;
packet.accel_cal_y = accel_cal_y;
packet.accel_cal_z = accel_cal_z;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 42);
#endif
 
msg->msgid = MAVLINK_MSG_ID_SENSOR_OFFSETS;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 42);
}
 
/**
* @brief Encode a sensor_offsets struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param sensor_offsets C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_sensor_offsets_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_sensor_offsets_t* sensor_offsets)
{
return mavlink_msg_sensor_offsets_pack(system_id, component_id, msg, sensor_offsets->mag_ofs_x, sensor_offsets->mag_ofs_y, sensor_offsets->mag_ofs_z, sensor_offsets->mag_declination, sensor_offsets->raw_press, sensor_offsets->raw_temp, sensor_offsets->gyro_cal_x, sensor_offsets->gyro_cal_y, sensor_offsets->gyro_cal_z, sensor_offsets->accel_cal_x, sensor_offsets->accel_cal_y, sensor_offsets->accel_cal_z);
}
 
/**
* @brief Send a sensor_offsets message
* @param chan MAVLink channel to send the message
*
* @param mag_ofs_x magnetometer X offset
* @param mag_ofs_y magnetometer Y offset
* @param mag_ofs_z magnetometer Z offset
* @param mag_declination magnetic declination (radians)
* @param raw_press raw pressure from barometer
* @param raw_temp raw temperature from barometer
* @param gyro_cal_x gyro X calibration
* @param gyro_cal_y gyro Y calibration
* @param gyro_cal_z gyro Z calibration
* @param accel_cal_x accel X calibration
* @param accel_cal_y accel Y calibration
* @param accel_cal_z accel Z calibration
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_sensor_offsets_send(mavlink_channel_t chan, int16_t mag_ofs_x, int16_t mag_ofs_y, int16_t mag_ofs_z, float mag_declination, int32_t raw_press, int32_t raw_temp, float gyro_cal_x, float gyro_cal_y, float gyro_cal_z, float accel_cal_x, float accel_cal_y, float accel_cal_z)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[42];
_mav_put_int16_t(buf, 0, mag_ofs_x);
_mav_put_int16_t(buf, 2, mag_ofs_y);
_mav_put_int16_t(buf, 4, mag_ofs_z);
_mav_put_float(buf, 6, mag_declination);
_mav_put_int32_t(buf, 10, raw_press);
_mav_put_int32_t(buf, 14, raw_temp);
_mav_put_float(buf, 18, gyro_cal_x);
_mav_put_float(buf, 22, gyro_cal_y);
_mav_put_float(buf, 26, gyro_cal_z);
_mav_put_float(buf, 30, accel_cal_x);
_mav_put_float(buf, 34, accel_cal_y);
_mav_put_float(buf, 38, accel_cal_z);
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SENSOR_OFFSETS, buf, 42);
#else
mavlink_sensor_offsets_t packet;
packet.mag_ofs_x = mag_ofs_x;
packet.mag_ofs_y = mag_ofs_y;
packet.mag_ofs_z = mag_ofs_z;
packet.mag_declination = mag_declination;
packet.raw_press = raw_press;
packet.raw_temp = raw_temp;
packet.gyro_cal_x = gyro_cal_x;
packet.gyro_cal_y = gyro_cal_y;
packet.gyro_cal_z = gyro_cal_z;
packet.accel_cal_x = accel_cal_x;
packet.accel_cal_y = accel_cal_y;
packet.accel_cal_z = accel_cal_z;
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SENSOR_OFFSETS, (const char *)&packet, 42);
#endif
}
 
#endif
 
// MESSAGE SENSOR_OFFSETS UNPACKING
 
 
/**
* @brief Get field mag_ofs_x from sensor_offsets message
*
* @return magnetometer X offset
*/
static inline int16_t mavlink_msg_sensor_offsets_get_mag_ofs_x(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 0);
}
 
/**
* @brief Get field mag_ofs_y from sensor_offsets message
*
* @return magnetometer Y offset
*/
static inline int16_t mavlink_msg_sensor_offsets_get_mag_ofs_y(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 2);
}
 
/**
* @brief Get field mag_ofs_z from sensor_offsets message
*
* @return magnetometer Z offset
*/
static inline int16_t mavlink_msg_sensor_offsets_get_mag_ofs_z(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 4);
}
 
/**
* @brief Get field mag_declination from sensor_offsets message
*
* @return magnetic declination (radians)
*/
static inline float mavlink_msg_sensor_offsets_get_mag_declination(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 6);
}
 
/**
* @brief Get field raw_press from sensor_offsets message
*
* @return raw pressure from barometer
*/
static inline int32_t mavlink_msg_sensor_offsets_get_raw_press(const mavlink_message_t* msg)
{
return _MAV_RETURN_int32_t(msg, 10);
}
 
/**
* @brief Get field raw_temp from sensor_offsets message
*
* @return raw temperature from barometer
*/
static inline int32_t mavlink_msg_sensor_offsets_get_raw_temp(const mavlink_message_t* msg)
{
return _MAV_RETURN_int32_t(msg, 14);
}
 
/**
* @brief Get field gyro_cal_x from sensor_offsets message
*
* @return gyro X calibration
*/
static inline float mavlink_msg_sensor_offsets_get_gyro_cal_x(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 18);
}
 
/**
* @brief Get field gyro_cal_y from sensor_offsets message
*
* @return gyro Y calibration
*/
static inline float mavlink_msg_sensor_offsets_get_gyro_cal_y(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 22);
}
 
/**
* @brief Get field gyro_cal_z from sensor_offsets message
*
* @return gyro Z calibration
*/
static inline float mavlink_msg_sensor_offsets_get_gyro_cal_z(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 26);
}
 
/**
* @brief Get field accel_cal_x from sensor_offsets message
*
* @return accel X calibration
*/
static inline float mavlink_msg_sensor_offsets_get_accel_cal_x(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 30);
}
 
/**
* @brief Get field accel_cal_y from sensor_offsets message
*
* @return accel Y calibration
*/
static inline float mavlink_msg_sensor_offsets_get_accel_cal_y(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 34);
}
 
/**
* @brief Get field accel_cal_z from sensor_offsets message
*
* @return accel Z calibration
*/
static inline float mavlink_msg_sensor_offsets_get_accel_cal_z(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 38);
}
 
/**
* @brief Decode a sensor_offsets message into a struct
*
* @param msg The message to decode
* @param sensor_offsets C-struct to decode the message contents into
*/
static inline void mavlink_msg_sensor_offsets_decode(const mavlink_message_t* msg, mavlink_sensor_offsets_t* sensor_offsets)
{
#if MAVLINK_NEED_BYTE_SWAP
sensor_offsets->mag_ofs_x = mavlink_msg_sensor_offsets_get_mag_ofs_x(msg);
sensor_offsets->mag_ofs_y = mavlink_msg_sensor_offsets_get_mag_ofs_y(msg);
sensor_offsets->mag_ofs_z = mavlink_msg_sensor_offsets_get_mag_ofs_z(msg);
sensor_offsets->mag_declination = mavlink_msg_sensor_offsets_get_mag_declination(msg);
sensor_offsets->raw_press = mavlink_msg_sensor_offsets_get_raw_press(msg);
sensor_offsets->raw_temp = mavlink_msg_sensor_offsets_get_raw_temp(msg);
sensor_offsets->gyro_cal_x = mavlink_msg_sensor_offsets_get_gyro_cal_x(msg);
sensor_offsets->gyro_cal_y = mavlink_msg_sensor_offsets_get_gyro_cal_y(msg);
sensor_offsets->gyro_cal_z = mavlink_msg_sensor_offsets_get_gyro_cal_z(msg);
sensor_offsets->accel_cal_x = mavlink_msg_sensor_offsets_get_accel_cal_x(msg);
sensor_offsets->accel_cal_y = mavlink_msg_sensor_offsets_get_accel_cal_y(msg);
sensor_offsets->accel_cal_z = mavlink_msg_sensor_offsets_get_accel_cal_z(msg);
#else
memcpy(sensor_offsets, _MAV_PAYLOAD(msg), 42);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v0.9/ardupilotmega/mavlink_msg_set_mag_offsets.h
0,0 → 1,232
// MESSAGE SET_MAG_OFFSETS PACKING
 
#define MAVLINK_MSG_ID_SET_MAG_OFFSETS 151
 
typedef struct __mavlink_set_mag_offsets_t
{
uint8_t target_system; ///< System ID
uint8_t target_component; ///< Component ID
int16_t mag_ofs_x; ///< magnetometer X offset
int16_t mag_ofs_y; ///< magnetometer Y offset
int16_t mag_ofs_z; ///< magnetometer Z offset
} mavlink_set_mag_offsets_t;
 
#define MAVLINK_MSG_ID_SET_MAG_OFFSETS_LEN 8
#define MAVLINK_MSG_ID_151_LEN 8
 
 
 
#define MAVLINK_MESSAGE_INFO_SET_MAG_OFFSETS { \
"SET_MAG_OFFSETS", \
5, \
{ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_set_mag_offsets_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_set_mag_offsets_t, target_component) }, \
{ "mag_ofs_x", NULL, MAVLINK_TYPE_INT16_T, 0, 2, offsetof(mavlink_set_mag_offsets_t, mag_ofs_x) }, \
{ "mag_ofs_y", NULL, MAVLINK_TYPE_INT16_T, 0, 4, offsetof(mavlink_set_mag_offsets_t, mag_ofs_y) }, \
{ "mag_ofs_z", NULL, MAVLINK_TYPE_INT16_T, 0, 6, offsetof(mavlink_set_mag_offsets_t, mag_ofs_z) }, \
} \
}
 
 
/**
* @brief Pack a set_mag_offsets message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param target_system System ID
* @param target_component Component ID
* @param mag_ofs_x magnetometer X offset
* @param mag_ofs_y magnetometer Y offset
* @param mag_ofs_z magnetometer Z offset
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_set_mag_offsets_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t target_system, uint8_t target_component, int16_t mag_ofs_x, int16_t mag_ofs_y, int16_t mag_ofs_z)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[8];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
_mav_put_int16_t(buf, 2, mag_ofs_x);
_mav_put_int16_t(buf, 4, mag_ofs_y);
_mav_put_int16_t(buf, 6, mag_ofs_z);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 8);
#else
mavlink_set_mag_offsets_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
packet.mag_ofs_x = mag_ofs_x;
packet.mag_ofs_y = mag_ofs_y;
packet.mag_ofs_z = mag_ofs_z;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 8);
#endif
 
msg->msgid = MAVLINK_MSG_ID_SET_MAG_OFFSETS;
return mavlink_finalize_message(msg, system_id, component_id, 8);
}
 
/**
* @brief Pack a set_mag_offsets message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param target_system System ID
* @param target_component Component ID
* @param mag_ofs_x magnetometer X offset
* @param mag_ofs_y magnetometer Y offset
* @param mag_ofs_z magnetometer Z offset
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_set_mag_offsets_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,int16_t mag_ofs_x,int16_t mag_ofs_y,int16_t mag_ofs_z)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[8];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
_mav_put_int16_t(buf, 2, mag_ofs_x);
_mav_put_int16_t(buf, 4, mag_ofs_y);
_mav_put_int16_t(buf, 6, mag_ofs_z);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 8);
#else
mavlink_set_mag_offsets_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
packet.mag_ofs_x = mag_ofs_x;
packet.mag_ofs_y = mag_ofs_y;
packet.mag_ofs_z = mag_ofs_z;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 8);
#endif
 
msg->msgid = MAVLINK_MSG_ID_SET_MAG_OFFSETS;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 8);
}
 
/**
* @brief Encode a set_mag_offsets struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param set_mag_offsets C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_set_mag_offsets_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_mag_offsets_t* set_mag_offsets)
{
return mavlink_msg_set_mag_offsets_pack(system_id, component_id, msg, set_mag_offsets->target_system, set_mag_offsets->target_component, set_mag_offsets->mag_ofs_x, set_mag_offsets->mag_ofs_y, set_mag_offsets->mag_ofs_z);
}
 
/**
* @brief Send a set_mag_offsets message
* @param chan MAVLink channel to send the message
*
* @param target_system System ID
* @param target_component Component ID
* @param mag_ofs_x magnetometer X offset
* @param mag_ofs_y magnetometer Y offset
* @param mag_ofs_z magnetometer Z offset
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_set_mag_offsets_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, int16_t mag_ofs_x, int16_t mag_ofs_y, int16_t mag_ofs_z)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[8];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
_mav_put_int16_t(buf, 2, mag_ofs_x);
_mav_put_int16_t(buf, 4, mag_ofs_y);
_mav_put_int16_t(buf, 6, mag_ofs_z);
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_MAG_OFFSETS, buf, 8);
#else
mavlink_set_mag_offsets_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
packet.mag_ofs_x = mag_ofs_x;
packet.mag_ofs_y = mag_ofs_y;
packet.mag_ofs_z = mag_ofs_z;
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_MAG_OFFSETS, (const char *)&packet, 8);
#endif
}
 
#endif
 
// MESSAGE SET_MAG_OFFSETS UNPACKING
 
 
/**
* @brief Get field target_system from set_mag_offsets message
*
* @return System ID
*/
static inline uint8_t mavlink_msg_set_mag_offsets_get_target_system(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 0);
}
 
/**
* @brief Get field target_component from set_mag_offsets message
*
* @return Component ID
*/
static inline uint8_t mavlink_msg_set_mag_offsets_get_target_component(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 1);
}
 
/**
* @brief Get field mag_ofs_x from set_mag_offsets message
*
* @return magnetometer X offset
*/
static inline int16_t mavlink_msg_set_mag_offsets_get_mag_ofs_x(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 2);
}
 
/**
* @brief Get field mag_ofs_y from set_mag_offsets message
*
* @return magnetometer Y offset
*/
static inline int16_t mavlink_msg_set_mag_offsets_get_mag_ofs_y(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 4);
}
 
/**
* @brief Get field mag_ofs_z from set_mag_offsets message
*
* @return magnetometer Z offset
*/
static inline int16_t mavlink_msg_set_mag_offsets_get_mag_ofs_z(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 6);
}
 
/**
* @brief Decode a set_mag_offsets message into a struct
*
* @param msg The message to decode
* @param set_mag_offsets C-struct to decode the message contents into
*/
static inline void mavlink_msg_set_mag_offsets_decode(const mavlink_message_t* msg, mavlink_set_mag_offsets_t* set_mag_offsets)
{
#if MAVLINK_NEED_BYTE_SWAP
set_mag_offsets->target_system = mavlink_msg_set_mag_offsets_get_target_system(msg);
set_mag_offsets->target_component = mavlink_msg_set_mag_offsets_get_target_component(msg);
set_mag_offsets->mag_ofs_x = mavlink_msg_set_mag_offsets_get_mag_ofs_x(msg);
set_mag_offsets->mag_ofs_y = mavlink_msg_set_mag_offsets_get_mag_ofs_y(msg);
set_mag_offsets->mag_ofs_z = mavlink_msg_set_mag_offsets_get_mag_ofs_z(msg);
#else
memcpy(set_mag_offsets, _MAV_PAYLOAD(msg), 8);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v0.9/ardupilotmega/mavlink_msg_simstate.h
0,0 → 1,320
// MESSAGE SIMSTATE PACKING
 
#define MAVLINK_MSG_ID_SIMSTATE 164
 
typedef struct __mavlink_simstate_t
{
float roll; ///< Roll angle (rad)
float pitch; ///< Pitch angle (rad)
float yaw; ///< Yaw angle (rad)
float xacc; ///< X acceleration m/s/s
float yacc; ///< Y acceleration m/s/s
float zacc; ///< Z acceleration m/s/s
float xgyro; ///< Angular speed around X axis rad/s
float ygyro; ///< Angular speed around Y axis rad/s
float zgyro; ///< Angular speed around Z axis rad/s
} mavlink_simstate_t;
 
#define MAVLINK_MSG_ID_SIMSTATE_LEN 36
#define MAVLINK_MSG_ID_164_LEN 36
 
 
 
#define MAVLINK_MESSAGE_INFO_SIMSTATE { \
"SIMSTATE", \
9, \
{ { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_simstate_t, roll) }, \
{ "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_simstate_t, pitch) }, \
{ "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_simstate_t, yaw) }, \
{ "xacc", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_simstate_t, xacc) }, \
{ "yacc", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_simstate_t, yacc) }, \
{ "zacc", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_simstate_t, zacc) }, \
{ "xgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_simstate_t, xgyro) }, \
{ "ygyro", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_simstate_t, ygyro) }, \
{ "zgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_simstate_t, zgyro) }, \
} \
}
 
 
/**
* @brief Pack a simstate message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param roll Roll angle (rad)
* @param pitch Pitch angle (rad)
* @param yaw Yaw angle (rad)
* @param xacc X acceleration m/s/s
* @param yacc Y acceleration m/s/s
* @param zacc Z acceleration m/s/s
* @param xgyro Angular speed around X axis rad/s
* @param ygyro Angular speed around Y axis rad/s
* @param zgyro Angular speed around Z axis rad/s
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_simstate_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
float roll, float pitch, float yaw, float xacc, float yacc, float zacc, float xgyro, float ygyro, float zgyro)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[36];
_mav_put_float(buf, 0, roll);
_mav_put_float(buf, 4, pitch);
_mav_put_float(buf, 8, yaw);
_mav_put_float(buf, 12, xacc);
_mav_put_float(buf, 16, yacc);
_mav_put_float(buf, 20, zacc);
_mav_put_float(buf, 24, xgyro);
_mav_put_float(buf, 28, ygyro);
_mav_put_float(buf, 32, zgyro);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 36);
#else
mavlink_simstate_t packet;
packet.roll = roll;
packet.pitch = pitch;
packet.yaw = yaw;
packet.xacc = xacc;
packet.yacc = yacc;
packet.zacc = zacc;
packet.xgyro = xgyro;
packet.ygyro = ygyro;
packet.zgyro = zgyro;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 36);
#endif
 
msg->msgid = MAVLINK_MSG_ID_SIMSTATE;
return mavlink_finalize_message(msg, system_id, component_id, 36);
}
 
/**
* @brief Pack a simstate message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param roll Roll angle (rad)
* @param pitch Pitch angle (rad)
* @param yaw Yaw angle (rad)
* @param xacc X acceleration m/s/s
* @param yacc Y acceleration m/s/s
* @param zacc Z acceleration m/s/s
* @param xgyro Angular speed around X axis rad/s
* @param ygyro Angular speed around Y axis rad/s
* @param zgyro Angular speed around Z axis rad/s
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_simstate_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
float roll,float pitch,float yaw,float xacc,float yacc,float zacc,float xgyro,float ygyro,float zgyro)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[36];
_mav_put_float(buf, 0, roll);
_mav_put_float(buf, 4, pitch);
_mav_put_float(buf, 8, yaw);
_mav_put_float(buf, 12, xacc);
_mav_put_float(buf, 16, yacc);
_mav_put_float(buf, 20, zacc);
_mav_put_float(buf, 24, xgyro);
_mav_put_float(buf, 28, ygyro);
_mav_put_float(buf, 32, zgyro);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 36);
#else
mavlink_simstate_t packet;
packet.roll = roll;
packet.pitch = pitch;
packet.yaw = yaw;
packet.xacc = xacc;
packet.yacc = yacc;
packet.zacc = zacc;
packet.xgyro = xgyro;
packet.ygyro = ygyro;
packet.zgyro = zgyro;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 36);
#endif
 
msg->msgid = MAVLINK_MSG_ID_SIMSTATE;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 36);
}
 
/**
* @brief Encode a simstate struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param simstate C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_simstate_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_simstate_t* simstate)
{
return mavlink_msg_simstate_pack(system_id, component_id, msg, simstate->roll, simstate->pitch, simstate->yaw, simstate->xacc, simstate->yacc, simstate->zacc, simstate->xgyro, simstate->ygyro, simstate->zgyro);
}
 
/**
* @brief Send a simstate message
* @param chan MAVLink channel to send the message
*
* @param roll Roll angle (rad)
* @param pitch Pitch angle (rad)
* @param yaw Yaw angle (rad)
* @param xacc X acceleration m/s/s
* @param yacc Y acceleration m/s/s
* @param zacc Z acceleration m/s/s
* @param xgyro Angular speed around X axis rad/s
* @param ygyro Angular speed around Y axis rad/s
* @param zgyro Angular speed around Z axis rad/s
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_simstate_send(mavlink_channel_t chan, float roll, float pitch, float yaw, float xacc, float yacc, float zacc, float xgyro, float ygyro, float zgyro)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[36];
_mav_put_float(buf, 0, roll);
_mav_put_float(buf, 4, pitch);
_mav_put_float(buf, 8, yaw);
_mav_put_float(buf, 12, xacc);
_mav_put_float(buf, 16, yacc);
_mav_put_float(buf, 20, zacc);
_mav_put_float(buf, 24, xgyro);
_mav_put_float(buf, 28, ygyro);
_mav_put_float(buf, 32, zgyro);
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SIMSTATE, buf, 36);
#else
mavlink_simstate_t packet;
packet.roll = roll;
packet.pitch = pitch;
packet.yaw = yaw;
packet.xacc = xacc;
packet.yacc = yacc;
packet.zacc = zacc;
packet.xgyro = xgyro;
packet.ygyro = ygyro;
packet.zgyro = zgyro;
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SIMSTATE, (const char *)&packet, 36);
#endif
}
 
#endif
 
// MESSAGE SIMSTATE UNPACKING
 
 
/**
* @brief Get field roll from simstate message
*
* @return Roll angle (rad)
*/
static inline float mavlink_msg_simstate_get_roll(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 0);
}
 
/**
* @brief Get field pitch from simstate message
*
* @return Pitch angle (rad)
*/
static inline float mavlink_msg_simstate_get_pitch(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 4);
}
 
/**
* @brief Get field yaw from simstate message
*
* @return Yaw angle (rad)
*/
static inline float mavlink_msg_simstate_get_yaw(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 8);
}
 
/**
* @brief Get field xacc from simstate message
*
* @return X acceleration m/s/s
*/
static inline float mavlink_msg_simstate_get_xacc(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 12);
}
 
/**
* @brief Get field yacc from simstate message
*
* @return Y acceleration m/s/s
*/
static inline float mavlink_msg_simstate_get_yacc(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 16);
}
 
/**
* @brief Get field zacc from simstate message
*
* @return Z acceleration m/s/s
*/
static inline float mavlink_msg_simstate_get_zacc(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 20);
}
 
/**
* @brief Get field xgyro from simstate message
*
* @return Angular speed around X axis rad/s
*/
static inline float mavlink_msg_simstate_get_xgyro(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 24);
}
 
/**
* @brief Get field ygyro from simstate message
*
* @return Angular speed around Y axis rad/s
*/
static inline float mavlink_msg_simstate_get_ygyro(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 28);
}
 
/**
* @brief Get field zgyro from simstate message
*
* @return Angular speed around Z axis rad/s
*/
static inline float mavlink_msg_simstate_get_zgyro(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 32);
}
 
/**
* @brief Decode a simstate message into a struct
*
* @param msg The message to decode
* @param simstate C-struct to decode the message contents into
*/
static inline void mavlink_msg_simstate_decode(const mavlink_message_t* msg, mavlink_simstate_t* simstate)
{
#if MAVLINK_NEED_BYTE_SWAP
simstate->roll = mavlink_msg_simstate_get_roll(msg);
simstate->pitch = mavlink_msg_simstate_get_pitch(msg);
simstate->yaw = mavlink_msg_simstate_get_yaw(msg);
simstate->xacc = mavlink_msg_simstate_get_xacc(msg);
simstate->yacc = mavlink_msg_simstate_get_yacc(msg);
simstate->zacc = mavlink_msg_simstate_get_zacc(msg);
simstate->xgyro = mavlink_msg_simstate_get_xgyro(msg);
simstate->ygyro = mavlink_msg_simstate_get_ygyro(msg);
simstate->zgyro = mavlink_msg_simstate_get_zgyro(msg);
#else
memcpy(simstate, _MAV_PAYLOAD(msg), 36);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v0.9/ardupilotmega/testsuite.h
0,0 → 1,908
/** @file
* @brief MAVLink comm protocol testsuite generated from ardupilotmega.xml
* @see http://qgroundcontrol.org/mavlink/
*/
#ifndef ARDUPILOTMEGA_TESTSUITE_H
#define ARDUPILOTMEGA_TESTSUITE_H
 
#ifdef __cplusplus
extern "C" {
#endif
 
#ifndef MAVLINK_TEST_ALL
#define MAVLINK_TEST_ALL
static void mavlink_test_common(uint8_t, uint8_t, mavlink_message_t *last_msg);
static void mavlink_test_ardupilotmega(uint8_t, uint8_t, mavlink_message_t *last_msg);
 
static void mavlink_test_all(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_test_common(system_id, component_id, last_msg);
mavlink_test_ardupilotmega(system_id, component_id, last_msg);
}
#endif
 
#include "../common/testsuite.h"
 
 
static void mavlink_test_sensor_offsets(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_sensor_offsets_t packet_in = {
17235,
17339,
17443,
59.0,
963497984,
963498192,
143.0,
171.0,
199.0,
227.0,
255.0,
283.0,
};
mavlink_sensor_offsets_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.mag_ofs_x = packet_in.mag_ofs_x;
packet1.mag_ofs_y = packet_in.mag_ofs_y;
packet1.mag_ofs_z = packet_in.mag_ofs_z;
packet1.mag_declination = packet_in.mag_declination;
packet1.raw_press = packet_in.raw_press;
packet1.raw_temp = packet_in.raw_temp;
packet1.gyro_cal_x = packet_in.gyro_cal_x;
packet1.gyro_cal_y = packet_in.gyro_cal_y;
packet1.gyro_cal_z = packet_in.gyro_cal_z;
packet1.accel_cal_x = packet_in.accel_cal_x;
packet1.accel_cal_y = packet_in.accel_cal_y;
packet1.accel_cal_z = packet_in.accel_cal_z;
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_sensor_offsets_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_sensor_offsets_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_sensor_offsets_pack(system_id, component_id, &msg , packet1.mag_ofs_x , packet1.mag_ofs_y , packet1.mag_ofs_z , packet1.mag_declination , packet1.raw_press , packet1.raw_temp , packet1.gyro_cal_x , packet1.gyro_cal_y , packet1.gyro_cal_z , packet1.accel_cal_x , packet1.accel_cal_y , packet1.accel_cal_z );
mavlink_msg_sensor_offsets_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_sensor_offsets_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.mag_ofs_x , packet1.mag_ofs_y , packet1.mag_ofs_z , packet1.mag_declination , packet1.raw_press , packet1.raw_temp , packet1.gyro_cal_x , packet1.gyro_cal_y , packet1.gyro_cal_z , packet1.accel_cal_x , packet1.accel_cal_y , packet1.accel_cal_z );
mavlink_msg_sensor_offsets_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_sensor_offsets_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_sensor_offsets_send(MAVLINK_COMM_1 , packet1.mag_ofs_x , packet1.mag_ofs_y , packet1.mag_ofs_z , packet1.mag_declination , packet1.raw_press , packet1.raw_temp , packet1.gyro_cal_x , packet1.gyro_cal_y , packet1.gyro_cal_z , packet1.accel_cal_x , packet1.accel_cal_y , packet1.accel_cal_z );
mavlink_msg_sensor_offsets_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_set_mag_offsets(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_set_mag_offsets_t packet_in = {
5,
72,
17339,
17443,
17547,
};
mavlink_set_mag_offsets_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.target_system = packet_in.target_system;
packet1.target_component = packet_in.target_component;
packet1.mag_ofs_x = packet_in.mag_ofs_x;
packet1.mag_ofs_y = packet_in.mag_ofs_y;
packet1.mag_ofs_z = packet_in.mag_ofs_z;
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_set_mag_offsets_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_set_mag_offsets_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_set_mag_offsets_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.mag_ofs_x , packet1.mag_ofs_y , packet1.mag_ofs_z );
mavlink_msg_set_mag_offsets_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_set_mag_offsets_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.mag_ofs_x , packet1.mag_ofs_y , packet1.mag_ofs_z );
mavlink_msg_set_mag_offsets_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_set_mag_offsets_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_set_mag_offsets_send(MAVLINK_COMM_1 , packet1.target_system , packet1.target_component , packet1.mag_ofs_x , packet1.mag_ofs_y , packet1.mag_ofs_z );
mavlink_msg_set_mag_offsets_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_meminfo(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_meminfo_t packet_in = {
17235,
17339,
};
mavlink_meminfo_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.brkval = packet_in.brkval;
packet1.freemem = packet_in.freemem;
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_meminfo_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_meminfo_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_meminfo_pack(system_id, component_id, &msg , packet1.brkval , packet1.freemem );
mavlink_msg_meminfo_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_meminfo_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.brkval , packet1.freemem );
mavlink_msg_meminfo_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_meminfo_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_meminfo_send(MAVLINK_COMM_1 , packet1.brkval , packet1.freemem );
mavlink_msg_meminfo_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_ap_adc(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_ap_adc_t packet_in = {
17235,
17339,
17443,
17547,
17651,
17755,
};
mavlink_ap_adc_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.adc1 = packet_in.adc1;
packet1.adc2 = packet_in.adc2;
packet1.adc3 = packet_in.adc3;
packet1.adc4 = packet_in.adc4;
packet1.adc5 = packet_in.adc5;
packet1.adc6 = packet_in.adc6;
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_ap_adc_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_ap_adc_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_ap_adc_pack(system_id, component_id, &msg , packet1.adc1 , packet1.adc2 , packet1.adc3 , packet1.adc4 , packet1.adc5 , packet1.adc6 );
mavlink_msg_ap_adc_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_ap_adc_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.adc1 , packet1.adc2 , packet1.adc3 , packet1.adc4 , packet1.adc5 , packet1.adc6 );
mavlink_msg_ap_adc_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_ap_adc_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_ap_adc_send(MAVLINK_COMM_1 , packet1.adc1 , packet1.adc2 , packet1.adc3 , packet1.adc4 , packet1.adc5 , packet1.adc6 );
mavlink_msg_ap_adc_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_digicam_configure(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_digicam_configure_t packet_in = {
5,
72,
139,
17391,
84,
151,
218,
29,
96,
163,
94.0,
};
mavlink_digicam_configure_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.target_system = packet_in.target_system;
packet1.target_component = packet_in.target_component;
packet1.mode = packet_in.mode;
packet1.shutter_speed = packet_in.shutter_speed;
packet1.aperture = packet_in.aperture;
packet1.iso = packet_in.iso;
packet1.exposure_type = packet_in.exposure_type;
packet1.command_id = packet_in.command_id;
packet1.engine_cut_off = packet_in.engine_cut_off;
packet1.extra_param = packet_in.extra_param;
packet1.extra_value = packet_in.extra_value;
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_digicam_configure_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_digicam_configure_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_digicam_configure_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.mode , packet1.shutter_speed , packet1.aperture , packet1.iso , packet1.exposure_type , packet1.command_id , packet1.engine_cut_off , packet1.extra_param , packet1.extra_value );
mavlink_msg_digicam_configure_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_digicam_configure_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.mode , packet1.shutter_speed , packet1.aperture , packet1.iso , packet1.exposure_type , packet1.command_id , packet1.engine_cut_off , packet1.extra_param , packet1.extra_value );
mavlink_msg_digicam_configure_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_digicam_configure_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_digicam_configure_send(MAVLINK_COMM_1 , packet1.target_system , packet1.target_component , packet1.mode , packet1.shutter_speed , packet1.aperture , packet1.iso , packet1.exposure_type , packet1.command_id , packet1.engine_cut_off , packet1.extra_param , packet1.extra_value );
mavlink_msg_digicam_configure_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_digicam_control(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_digicam_control_t packet_in = {
5,
72,
139,
206,
17,
84,
151,
218,
29,
80.0,
};
mavlink_digicam_control_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.target_system = packet_in.target_system;
packet1.target_component = packet_in.target_component;
packet1.session = packet_in.session;
packet1.zoom_pos = packet_in.zoom_pos;
packet1.zoom_step = packet_in.zoom_step;
packet1.focus_lock = packet_in.focus_lock;
packet1.shot = packet_in.shot;
packet1.command_id = packet_in.command_id;
packet1.extra_param = packet_in.extra_param;
packet1.extra_value = packet_in.extra_value;
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_digicam_control_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_digicam_control_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_digicam_control_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.session , packet1.zoom_pos , packet1.zoom_step , packet1.focus_lock , packet1.shot , packet1.command_id , packet1.extra_param , packet1.extra_value );
mavlink_msg_digicam_control_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_digicam_control_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.session , packet1.zoom_pos , packet1.zoom_step , packet1.focus_lock , packet1.shot , packet1.command_id , packet1.extra_param , packet1.extra_value );
mavlink_msg_digicam_control_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_digicam_control_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_digicam_control_send(MAVLINK_COMM_1 , packet1.target_system , packet1.target_component , packet1.session , packet1.zoom_pos , packet1.zoom_step , packet1.focus_lock , packet1.shot , packet1.command_id , packet1.extra_param , packet1.extra_value );
mavlink_msg_digicam_control_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_mount_configure(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_mount_configure_t packet_in = {
5,
72,
139,
206,
17,
84,
};
mavlink_mount_configure_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.target_system = packet_in.target_system;
packet1.target_component = packet_in.target_component;
packet1.mount_mode = packet_in.mount_mode;
packet1.stab_roll = packet_in.stab_roll;
packet1.stab_pitch = packet_in.stab_pitch;
packet1.stab_yaw = packet_in.stab_yaw;
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_mount_configure_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_mount_configure_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_mount_configure_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.mount_mode , packet1.stab_roll , packet1.stab_pitch , packet1.stab_yaw );
mavlink_msg_mount_configure_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_mount_configure_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.mount_mode , packet1.stab_roll , packet1.stab_pitch , packet1.stab_yaw );
mavlink_msg_mount_configure_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_mount_configure_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_mount_configure_send(MAVLINK_COMM_1 , packet1.target_system , packet1.target_component , packet1.mount_mode , packet1.stab_roll , packet1.stab_pitch , packet1.stab_yaw );
mavlink_msg_mount_configure_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_mount_control(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_mount_control_t packet_in = {
5,
72,
963497568,
963497776,
963497984,
175,
};
mavlink_mount_control_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.target_system = packet_in.target_system;
packet1.target_component = packet_in.target_component;
packet1.input_a = packet_in.input_a;
packet1.input_b = packet_in.input_b;
packet1.input_c = packet_in.input_c;
packet1.save_position = packet_in.save_position;
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_mount_control_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_mount_control_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_mount_control_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.input_a , packet1.input_b , packet1.input_c , packet1.save_position );
mavlink_msg_mount_control_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_mount_control_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.input_a , packet1.input_b , packet1.input_c , packet1.save_position );
mavlink_msg_mount_control_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_mount_control_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_mount_control_send(MAVLINK_COMM_1 , packet1.target_system , packet1.target_component , packet1.input_a , packet1.input_b , packet1.input_c , packet1.save_position );
mavlink_msg_mount_control_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_mount_status(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_mount_status_t packet_in = {
5,
72,
963497568,
963497776,
963497984,
};
mavlink_mount_status_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.target_system = packet_in.target_system;
packet1.target_component = packet_in.target_component;
packet1.pointing_a = packet_in.pointing_a;
packet1.pointing_b = packet_in.pointing_b;
packet1.pointing_c = packet_in.pointing_c;
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_mount_status_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_mount_status_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_mount_status_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.pointing_a , packet1.pointing_b , packet1.pointing_c );
mavlink_msg_mount_status_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_mount_status_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.pointing_a , packet1.pointing_b , packet1.pointing_c );
mavlink_msg_mount_status_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_mount_status_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_mount_status_send(MAVLINK_COMM_1 , packet1.target_system , packet1.target_component , packet1.pointing_a , packet1.pointing_b , packet1.pointing_c );
mavlink_msg_mount_status_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_fence_point(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_fence_point_t packet_in = {
5,
72,
139,
206,
45.0,
73.0,
};
mavlink_fence_point_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.target_system = packet_in.target_system;
packet1.target_component = packet_in.target_component;
packet1.idx = packet_in.idx;
packet1.count = packet_in.count;
packet1.lat = packet_in.lat;
packet1.lng = packet_in.lng;
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_fence_point_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_fence_point_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_fence_point_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.idx , packet1.count , packet1.lat , packet1.lng );
mavlink_msg_fence_point_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_fence_point_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.idx , packet1.count , packet1.lat , packet1.lng );
mavlink_msg_fence_point_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_fence_point_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_fence_point_send(MAVLINK_COMM_1 , packet1.target_system , packet1.target_component , packet1.idx , packet1.count , packet1.lat , packet1.lng );
mavlink_msg_fence_point_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_fence_fetch_point(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_fence_fetch_point_t packet_in = {
5,
72,
139,
};
mavlink_fence_fetch_point_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.target_system = packet_in.target_system;
packet1.target_component = packet_in.target_component;
packet1.idx = packet_in.idx;
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_fence_fetch_point_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_fence_fetch_point_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_fence_fetch_point_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.idx );
mavlink_msg_fence_fetch_point_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_fence_fetch_point_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.idx );
mavlink_msg_fence_fetch_point_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_fence_fetch_point_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_fence_fetch_point_send(MAVLINK_COMM_1 , packet1.target_system , packet1.target_component , packet1.idx );
mavlink_msg_fence_fetch_point_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_fence_status(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_fence_status_t packet_in = {
5,
17287,
206,
963497672,
};
mavlink_fence_status_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.breach_status = packet_in.breach_status;
packet1.breach_count = packet_in.breach_count;
packet1.breach_type = packet_in.breach_type;
packet1.breach_time = packet_in.breach_time;
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_fence_status_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_fence_status_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_fence_status_pack(system_id, component_id, &msg , packet1.breach_status , packet1.breach_count , packet1.breach_type , packet1.breach_time );
mavlink_msg_fence_status_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_fence_status_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.breach_status , packet1.breach_count , packet1.breach_type , packet1.breach_time );
mavlink_msg_fence_status_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_fence_status_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_fence_status_send(MAVLINK_COMM_1 , packet1.breach_status , packet1.breach_count , packet1.breach_type , packet1.breach_time );
mavlink_msg_fence_status_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_ahrs(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_ahrs_t packet_in = {
17.0,
45.0,
73.0,
101.0,
129.0,
157.0,
185.0,
};
mavlink_ahrs_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.omegaIx = packet_in.omegaIx;
packet1.omegaIy = packet_in.omegaIy;
packet1.omegaIz = packet_in.omegaIz;
packet1.accel_weight = packet_in.accel_weight;
packet1.renorm_val = packet_in.renorm_val;
packet1.error_rp = packet_in.error_rp;
packet1.error_yaw = packet_in.error_yaw;
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_ahrs_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_ahrs_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_ahrs_pack(system_id, component_id, &msg , packet1.omegaIx , packet1.omegaIy , packet1.omegaIz , packet1.accel_weight , packet1.renorm_val , packet1.error_rp , packet1.error_yaw );
mavlink_msg_ahrs_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_ahrs_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.omegaIx , packet1.omegaIy , packet1.omegaIz , packet1.accel_weight , packet1.renorm_val , packet1.error_rp , packet1.error_yaw );
mavlink_msg_ahrs_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_ahrs_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_ahrs_send(MAVLINK_COMM_1 , packet1.omegaIx , packet1.omegaIy , packet1.omegaIz , packet1.accel_weight , packet1.renorm_val , packet1.error_rp , packet1.error_yaw );
mavlink_msg_ahrs_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_simstate(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_simstate_t packet_in = {
17.0,
45.0,
73.0,
101.0,
129.0,
157.0,
185.0,
213.0,
241.0,
};
mavlink_simstate_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.roll = packet_in.roll;
packet1.pitch = packet_in.pitch;
packet1.yaw = packet_in.yaw;
packet1.xacc = packet_in.xacc;
packet1.yacc = packet_in.yacc;
packet1.zacc = packet_in.zacc;
packet1.xgyro = packet_in.xgyro;
packet1.ygyro = packet_in.ygyro;
packet1.zgyro = packet_in.zgyro;
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_simstate_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_simstate_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_simstate_pack(system_id, component_id, &msg , packet1.roll , packet1.pitch , packet1.yaw , packet1.xacc , packet1.yacc , packet1.zacc , packet1.xgyro , packet1.ygyro , packet1.zgyro );
mavlink_msg_simstate_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_simstate_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.roll , packet1.pitch , packet1.yaw , packet1.xacc , packet1.yacc , packet1.zacc , packet1.xgyro , packet1.ygyro , packet1.zgyro );
mavlink_msg_simstate_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_simstate_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_simstate_send(MAVLINK_COMM_1 , packet1.roll , packet1.pitch , packet1.yaw , packet1.xacc , packet1.yacc , packet1.zacc , packet1.xgyro , packet1.ygyro , packet1.zgyro );
mavlink_msg_simstate_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_hwstatus(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_hwstatus_t packet_in = {
17235,
139,
};
mavlink_hwstatus_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.Vcc = packet_in.Vcc;
packet1.I2Cerr = packet_in.I2Cerr;
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_hwstatus_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_hwstatus_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_hwstatus_pack(system_id, component_id, &msg , packet1.Vcc , packet1.I2Cerr );
mavlink_msg_hwstatus_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_hwstatus_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.Vcc , packet1.I2Cerr );
mavlink_msg_hwstatus_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_hwstatus_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_hwstatus_send(MAVLINK_COMM_1 , packet1.Vcc , packet1.I2Cerr );
mavlink_msg_hwstatus_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_radio(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_radio_t packet_in = {
5,
72,
139,
206,
17,
17495,
17599,
};
mavlink_radio_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.rssi = packet_in.rssi;
packet1.remrssi = packet_in.remrssi;
packet1.txbuf = packet_in.txbuf;
packet1.noise = packet_in.noise;
packet1.remnoise = packet_in.remnoise;
packet1.rxerrors = packet_in.rxerrors;
packet1.fixed = packet_in.fixed;
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_radio_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_radio_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_radio_pack(system_id, component_id, &msg , packet1.rssi , packet1.remrssi , packet1.txbuf , packet1.noise , packet1.remnoise , packet1.rxerrors , packet1.fixed );
mavlink_msg_radio_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_radio_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.rssi , packet1.remrssi , packet1.txbuf , packet1.noise , packet1.remnoise , packet1.rxerrors , packet1.fixed );
mavlink_msg_radio_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_radio_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_radio_send(MAVLINK_COMM_1 , packet1.rssi , packet1.remrssi , packet1.txbuf , packet1.noise , packet1.remnoise , packet1.rxerrors , packet1.fixed );
mavlink_msg_radio_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_ardupilotmega(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_test_sensor_offsets(system_id, component_id, last_msg);
mavlink_test_set_mag_offsets(system_id, component_id, last_msg);
mavlink_test_meminfo(system_id, component_id, last_msg);
mavlink_test_ap_adc(system_id, component_id, last_msg);
mavlink_test_digicam_configure(system_id, component_id, last_msg);
mavlink_test_digicam_control(system_id, component_id, last_msg);
mavlink_test_mount_configure(system_id, component_id, last_msg);
mavlink_test_mount_control(system_id, component_id, last_msg);
mavlink_test_mount_status(system_id, component_id, last_msg);
mavlink_test_fence_point(system_id, component_id, last_msg);
mavlink_test_fence_fetch_point(system_id, component_id, last_msg);
mavlink_test_fence_status(system_id, component_id, last_msg);
mavlink_test_ahrs(system_id, component_id, last_msg);
mavlink_test_simstate(system_id, component_id, last_msg);
mavlink_test_hwstatus(system_id, component_id, last_msg);
mavlink_test_radio(system_id, component_id, last_msg);
}
 
#ifdef __cplusplus
}
#endif // __cplusplus
#endif // ARDUPILOTMEGA_TESTSUITE_H
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v0.9/ardupilotmega/version.h
0,0 → 1,12
/** @file
* @brief MAVLink comm protocol built from ardupilotmega.xml
* @see http://pixhawk.ethz.ch/software/mavlink
*/
#ifndef MAVLINK_VERSION_H
#define MAVLINK_VERSION_H
 
#define MAVLINK_BUILD_DATE "Mon Apr 30 11:40:11 2012"
#define MAVLINK_WIRE_PROTOCOL_VERSION "0.9"
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 101
#endif // MAVLINK_VERSION_H
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v0.9/checksum.h
0,0 → 1,89
#ifdef __cplusplus
extern "C" {
#endif
 
#ifndef _CHECKSUM_H_
#define _CHECKSUM_H_
 
 
/**
*
* CALCULATE THE CHECKSUM
*
*/
 
#define X25_INIT_CRC 0xffff
#define X25_VALIDATE_CRC 0xf0b8
 
/**
* @brief Accumulate the X.25 CRC by adding one char at a time.
*
* The checksum function adds the hash of one char at a time to the
* 16 bit checksum (uint16_t).
*
* @param data new char to hash
* @param crcAccum the already accumulated checksum
**/
static inline void crc_accumulate(uint8_t data, uint16_t *crcAccum)
{
/*Accumulate one byte of data into the CRC*/
uint8_t tmp;
 
tmp = data ^ (uint8_t)(*crcAccum &0xff);
tmp ^= (tmp<<4);
*crcAccum = (*crcAccum>>8) ^ (tmp<<8) ^ (tmp <<3) ^ (tmp>>4);
}
 
/**
* @brief Initiliaze the buffer for the X.25 CRC
*
* @param crcAccum the 16 bit X.25 CRC
*/
static inline void crc_init(uint16_t* crcAccum)
{
*crcAccum = X25_INIT_CRC;
}
 
 
/**
* @brief Calculates the X.25 checksum on a byte buffer
*
* @param pBuffer buffer containing the byte array to hash
* @param length length of the byte array
* @return the checksum over the buffer bytes
**/
static inline uint16_t crc_calculate(const uint8_t* pBuffer, uint16_t length)
{
uint16_t crcTmp;
crc_init(&crcTmp);
while (length--) {
crc_accumulate(*pBuffer++, &crcTmp);
}
return crcTmp;
}
 
/**
* @brief Accumulate the X.25 CRC by adding an array of bytes
*
* The checksum function adds the hash of one char at a time to the
* 16 bit checksum (uint16_t).
*
* @param data new bytes to hash
* @param crcAccum the already accumulated checksum
**/
static inline void crc_accumulate_buffer(uint16_t *crcAccum, const char *pBuffer, uint8_t length)
{
const uint8_t *p = (const uint8_t *)pBuffer;
while (length--) {
crc_accumulate(*p++, crcAccum);
}
}
 
 
 
 
#endif /* _CHECKSUM_H_ */
 
#ifdef __cplusplus
}
#endif
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v0.9/common/common.h
0,0 → 1,159
/** @file
* @brief MAVLink comm protocol generated from common.xml
* @see http://qgroundcontrol.org/mavlink/
*/
#ifndef COMMON_H
#define COMMON_H
 
#ifdef __cplusplus
extern "C" {
#endif
 
// MESSAGE LENGTHS AND CRCS
 
#ifndef MAVLINK_MESSAGE_LENGTHS
#define MAVLINK_MESSAGE_LENGTHS {3, 4, 8, 14, 8, 28, 3, 32, 0, 2, 3, 2, 2, 0, 0, 0, 0, 0, 0, 0, 19, 2, 23, 21, 0, 37, 26, 101, 26, 16, 32, 32, 37, 32, 11, 17, 17, 16, 18, 36, 4, 4, 2, 2, 4, 2, 2, 3, 14, 12, 18, 16, 8, 27, 25, 18, 18, 24, 24, 0, 0, 0, 26, 16, 36, 5, 6, 56, 26, 21, 18, 0, 0, 18, 20, 20, 8, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 18, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 36, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 30, 14, 14, 51, 5}
#endif
 
#ifndef MAVLINK_MESSAGE_CRCS
#define MAVLINK_MESSAGE_CRCS {72, 39, 190, 92, 191, 217, 104, 119, 0, 219, 60, 186, 10, 0, 0, 0, 0, 0, 0, 0, 89, 159, 162, 121, 0, 149, 222, 110, 179, 136, 66, 126, 185, 147, 112, 252, 162, 215, 229, 128, 9, 106, 101, 213, 4, 229, 21, 214, 215, 14, 206, 50, 157, 126, 108, 213, 95, 5, 127, 0, 0, 0, 57, 126, 130, 119, 193, 191, 236, 158, 143, 0, 0, 104, 123, 131, 8, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 174, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 155, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 178, 224, 60, 106, 7}
#endif
 
#ifndef MAVLINK_MESSAGE_INFO
#define MAVLINK_MESSAGE_INFO {MAVLINK_MESSAGE_INFO_HEARTBEAT, MAVLINK_MESSAGE_INFO_BOOT, MAVLINK_MESSAGE_INFO_SYSTEM_TIME, MAVLINK_MESSAGE_INFO_PING, MAVLINK_MESSAGE_INFO_SYSTEM_TIME_UTC, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL_ACK, MAVLINK_MESSAGE_INFO_AUTH_KEY, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_ACTION_ACK, MAVLINK_MESSAGE_INFO_ACTION, MAVLINK_MESSAGE_INFO_SET_MODE, MAVLINK_MESSAGE_INFO_SET_NAV_MODE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_READ, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_LIST, MAVLINK_MESSAGE_INFO_PARAM_VALUE, MAVLINK_MESSAGE_INFO_PARAM_SET, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_GPS_RAW_INT, MAVLINK_MESSAGE_INFO_SCALED_IMU, MAVLINK_MESSAGE_INFO_GPS_STATUS, MAVLINK_MESSAGE_INFO_RAW_IMU, MAVLINK_MESSAGE_INFO_RAW_PRESSURE, MAVLINK_MESSAGE_INFO_ATTITUDE, MAVLINK_MESSAGE_INFO_LOCAL_POSITION, MAVLINK_MESSAGE_INFO_GPS_RAW, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION, MAVLINK_MESSAGE_INFO_SYS_STATUS, MAVLINK_MESSAGE_INFO_RC_CHANNELS_RAW, MAVLINK_MESSAGE_INFO_RC_CHANNELS_SCALED, MAVLINK_MESSAGE_INFO_SERVO_OUTPUT_RAW, MAVLINK_MESSAGE_INFO_SCALED_PRESSURE, MAVLINK_MESSAGE_INFO_WAYPOINT, MAVLINK_MESSAGE_INFO_WAYPOINT_REQUEST, MAVLINK_MESSAGE_INFO_WAYPOINT_SET_CURRENT, MAVLINK_MESSAGE_INFO_WAYPOINT_CURRENT, MAVLINK_MESSAGE_INFO_WAYPOINT_REQUEST_LIST, MAVLINK_MESSAGE_INFO_WAYPOINT_COUNT, MAVLINK_MESSAGE_INFO_WAYPOINT_CLEAR_ALL, MAVLINK_MESSAGE_INFO_WAYPOINT_REACHED, MAVLINK_MESSAGE_INFO_WAYPOINT_ACK, MAVLINK_MESSAGE_INFO_GPS_SET_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_GPS_LOCAL_ORIGIN_SET, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_SETPOINT_SET, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_SETPOINT, MAVLINK_MESSAGE_INFO_CONTROL_STATUS, MAVLINK_MESSAGE_INFO_SAFETY_SET_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SAFETY_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SET_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_SET_ROLL_PITCH_YAW_SPEED_THRUST, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_NAV_CONTROLLER_OUTPUT, MAVLINK_MESSAGE_INFO_POSITION_TARGET, MAVLINK_MESSAGE_INFO_STATE_CORRECTION, MAVLINK_MESSAGE_INFO_SET_ALTITUDE, MAVLINK_MESSAGE_INFO_REQUEST_DATA_STREAM, MAVLINK_MESSAGE_INFO_HIL_STATE, MAVLINK_MESSAGE_INFO_HIL_CONTROLS, MAVLINK_MESSAGE_INFO_MANUAL_CONTROL, MAVLINK_MESSAGE_INFO_RC_CHANNELS_OVERRIDE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_INT, MAVLINK_MESSAGE_INFO_VFR_HUD, MAVLINK_MESSAGE_INFO_COMMAND, MAVLINK_MESSAGE_INFO_COMMAND_ACK, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_OPTICAL_FLOW, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_OBJECT_DETECTION_EVENT, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_DEBUG_VECT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_FLOAT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_INT, MAVLINK_MESSAGE_INFO_STATUSTEXT, MAVLINK_MESSAGE_INFO_DEBUG}
#endif
 
#include "../protocol.h"
 
#define MAVLINK_ENABLED_COMMON
 
// ENUM DEFINITIONS
 
 
/** @brief Data stream IDs. A data stream is not a fixed set of messages, but rather a
recommendation to the autopilot software. Individual autopilots may or may not obey
the recommended messages.
*/
#ifndef HAVE_ENUM_MAV_DATA_STREAM
#define HAVE_ENUM_MAV_DATA_STREAM
enum MAV_DATA_STREAM
{
MAV_DATA_STREAM_ALL=0, /* Enable all data streams | */
MAV_DATA_STREAM_RAW_SENSORS=1, /* Enable IMU_RAW, GPS_RAW, GPS_STATUS packets. | */
MAV_DATA_STREAM_EXTENDED_STATUS=2, /* Enable GPS_STATUS, CONTROL_STATUS, AUX_STATUS | */
MAV_DATA_STREAM_RC_CHANNELS=3, /* Enable RC_CHANNELS_SCALED, RC_CHANNELS_RAW, SERVO_OUTPUT_RAW | */
MAV_DATA_STREAM_RAW_CONTROLLER=4, /* Enable ATTITUDE_CONTROLLER_OUTPUT, POSITION_CONTROLLER_OUTPUT, NAV_CONTROLLER_OUTPUT. | */
MAV_DATA_STREAM_POSITION=6, /* Enable LOCAL_POSITION, GLOBAL_POSITION/GLOBAL_POSITION_INT messages. | */
MAV_DATA_STREAM_EXTRA1=10, /* Dependent on the autopilot | */
MAV_DATA_STREAM_EXTRA2=11, /* Dependent on the autopilot | */
MAV_DATA_STREAM_EXTRA3=12, /* Dependent on the autopilot | */
MAV_DATA_STREAM_ENUM_END=13, /* | */
};
#endif
 
/** @brief The ROI (region of interest) for the vehicle. This can be
be used by the vehicle for camera/vehicle attitude alignment (see
MAV_CMD_NAV_ROI).
*/
#ifndef HAVE_ENUM_MAV_ROI
#define HAVE_ENUM_MAV_ROI
enum MAV_ROI
{
MAV_ROI_NONE=0, /* No region of interest. | */
MAV_ROI_WPNEXT=1, /* Point toward next waypoint. | */
MAV_ROI_WPINDEX=2, /* Point toward given waypoint. | */
MAV_ROI_LOCATION=3, /* Point toward fixed location. | */
MAV_ROI_TARGET=4, /* Point toward of given id. | */
MAV_ROI_ENUM_END=5, /* | */
};
#endif
 
 
 
// MAVLINK VERSION
 
#ifndef MAVLINK_VERSION
#define MAVLINK_VERSION 2
#endif
 
#if (MAVLINK_VERSION == 0)
#undef MAVLINK_VERSION
#define MAVLINK_VERSION 2
#endif
 
// MESSAGE DEFINITIONS
#include "./mavlink_msg_heartbeat.h"
#include "./mavlink_msg_boot.h"
#include "./mavlink_msg_system_time.h"
#include "./mavlink_msg_ping.h"
#include "./mavlink_msg_system_time_utc.h"
#include "./mavlink_msg_change_operator_control.h"
#include "./mavlink_msg_change_operator_control_ack.h"
#include "./mavlink_msg_auth_key.h"
#include "./mavlink_msg_action_ack.h"
#include "./mavlink_msg_action.h"
#include "./mavlink_msg_set_mode.h"
#include "./mavlink_msg_set_nav_mode.h"
#include "./mavlink_msg_param_request_read.h"
#include "./mavlink_msg_param_request_list.h"
#include "./mavlink_msg_param_value.h"
#include "./mavlink_msg_param_set.h"
#include "./mavlink_msg_gps_raw_int.h"
#include "./mavlink_msg_scaled_imu.h"
#include "./mavlink_msg_gps_status.h"
#include "./mavlink_msg_raw_imu.h"
#include "./mavlink_msg_raw_pressure.h"
#include "./mavlink_msg_scaled_pressure.h"
#include "./mavlink_msg_attitude.h"
#include "./mavlink_msg_local_position.h"
#include "./mavlink_msg_global_position.h"
#include "./mavlink_msg_gps_raw.h"
#include "./mavlink_msg_sys_status.h"
#include "./mavlink_msg_rc_channels_raw.h"
#include "./mavlink_msg_rc_channels_scaled.h"
#include "./mavlink_msg_servo_output_raw.h"
#include "./mavlink_msg_waypoint.h"
#include "./mavlink_msg_waypoint_request.h"
#include "./mavlink_msg_waypoint_set_current.h"
#include "./mavlink_msg_waypoint_current.h"
#include "./mavlink_msg_waypoint_request_list.h"
#include "./mavlink_msg_waypoint_count.h"
#include "./mavlink_msg_waypoint_clear_all.h"
#include "./mavlink_msg_waypoint_reached.h"
#include "./mavlink_msg_waypoint_ack.h"
#include "./mavlink_msg_gps_set_global_origin.h"
#include "./mavlink_msg_gps_local_origin_set.h"
#include "./mavlink_msg_local_position_setpoint_set.h"
#include "./mavlink_msg_local_position_setpoint.h"
#include "./mavlink_msg_control_status.h"
#include "./mavlink_msg_safety_set_allowed_area.h"
#include "./mavlink_msg_safety_allowed_area.h"
#include "./mavlink_msg_set_roll_pitch_yaw_thrust.h"
#include "./mavlink_msg_set_roll_pitch_yaw_speed_thrust.h"
#include "./mavlink_msg_roll_pitch_yaw_thrust_setpoint.h"
#include "./mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint.h"
#include "./mavlink_msg_nav_controller_output.h"
#include "./mavlink_msg_position_target.h"
#include "./mavlink_msg_state_correction.h"
#include "./mavlink_msg_set_altitude.h"
#include "./mavlink_msg_request_data_stream.h"
#include "./mavlink_msg_hil_state.h"
#include "./mavlink_msg_hil_controls.h"
#include "./mavlink_msg_manual_control.h"
#include "./mavlink_msg_rc_channels_override.h"
#include "./mavlink_msg_global_position_int.h"
#include "./mavlink_msg_vfr_hud.h"
#include "./mavlink_msg_command.h"
#include "./mavlink_msg_command_ack.h"
#include "./mavlink_msg_optical_flow.h"
#include "./mavlink_msg_object_detection_event.h"
#include "./mavlink_msg_debug_vect.h"
#include "./mavlink_msg_named_value_float.h"
#include "./mavlink_msg_named_value_int.h"
#include "./mavlink_msg_statustext.h"
#include "./mavlink_msg_debug.h"
 
#ifdef __cplusplus
}
#endif // __cplusplus
#endif // COMMON_H
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v0.9/common/mavlink.h
0,0 → 1,27
/** @file
* @brief MAVLink comm protocol built from common.xml
* @see http://pixhawk.ethz.ch/software/mavlink
*/
#ifndef MAVLINK_H
#define MAVLINK_H
 
#ifndef MAVLINK_STX
#define MAVLINK_STX 85
#endif
 
#ifndef MAVLINK_ENDIAN
#define MAVLINK_ENDIAN MAVLINK_BIG_ENDIAN
#endif
 
#ifndef MAVLINK_ALIGNED_FIELDS
#define MAVLINK_ALIGNED_FIELDS 0
#endif
 
#ifndef MAVLINK_CRC_EXTRA
#define MAVLINK_CRC_EXTRA 0
#endif
 
#include "version.h"
#include "common.h"
 
#endif // MAVLINK_H
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v0.9/common/mavlink_msg_action.h
0,0 → 1,188
// MESSAGE ACTION PACKING
 
#define MAVLINK_MSG_ID_ACTION 10
 
typedef struct __mavlink_action_t
{
uint8_t target; ///< The system executing the action
uint8_t target_component; ///< The component executing the action
uint8_t action; ///< The action id
} mavlink_action_t;
 
#define MAVLINK_MSG_ID_ACTION_LEN 3
#define MAVLINK_MSG_ID_10_LEN 3
 
 
 
#define MAVLINK_MESSAGE_INFO_ACTION { \
"ACTION", \
3, \
{ { "target", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_action_t, target) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_action_t, target_component) }, \
{ "action", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_action_t, action) }, \
} \
}
 
 
/**
* @brief Pack a action message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param target The system executing the action
* @param target_component The component executing the action
* @param action The action id
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_action_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t target, uint8_t target_component, uint8_t action)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[3];
_mav_put_uint8_t(buf, 0, target);
_mav_put_uint8_t(buf, 1, target_component);
_mav_put_uint8_t(buf, 2, action);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 3);
#else
mavlink_action_t packet;
packet.target = target;
packet.target_component = target_component;
packet.action = action;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 3);
#endif
 
msg->msgid = MAVLINK_MSG_ID_ACTION;
return mavlink_finalize_message(msg, system_id, component_id, 3);
}
 
/**
* @brief Pack a action message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param target The system executing the action
* @param target_component The component executing the action
* @param action The action id
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_action_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint8_t target,uint8_t target_component,uint8_t action)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[3];
_mav_put_uint8_t(buf, 0, target);
_mav_put_uint8_t(buf, 1, target_component);
_mav_put_uint8_t(buf, 2, action);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 3);
#else
mavlink_action_t packet;
packet.target = target;
packet.target_component = target_component;
packet.action = action;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 3);
#endif
 
msg->msgid = MAVLINK_MSG_ID_ACTION;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 3);
}
 
/**
* @brief Encode a action struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param action C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_action_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_action_t* action)
{
return mavlink_msg_action_pack(system_id, component_id, msg, action->target, action->target_component, action->action);
}
 
/**
* @brief Send a action message
* @param chan MAVLink channel to send the message
*
* @param target The system executing the action
* @param target_component The component executing the action
* @param action The action id
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_action_send(mavlink_channel_t chan, uint8_t target, uint8_t target_component, uint8_t action)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[3];
_mav_put_uint8_t(buf, 0, target);
_mav_put_uint8_t(buf, 1, target_component);
_mav_put_uint8_t(buf, 2, action);
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ACTION, buf, 3);
#else
mavlink_action_t packet;
packet.target = target;
packet.target_component = target_component;
packet.action = action;
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ACTION, (const char *)&packet, 3);
#endif
}
 
#endif
 
// MESSAGE ACTION UNPACKING
 
 
/**
* @brief Get field target from action message
*
* @return The system executing the action
*/
static inline uint8_t mavlink_msg_action_get_target(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 0);
}
 
/**
* @brief Get field target_component from action message
*
* @return The component executing the action
*/
static inline uint8_t mavlink_msg_action_get_target_component(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 1);
}
 
/**
* @brief Get field action from action message
*
* @return The action id
*/
static inline uint8_t mavlink_msg_action_get_action(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 2);
}
 
/**
* @brief Decode a action message into a struct
*
* @param msg The message to decode
* @param action C-struct to decode the message contents into
*/
static inline void mavlink_msg_action_decode(const mavlink_message_t* msg, mavlink_action_t* action)
{
#if MAVLINK_NEED_BYTE_SWAP
action->target = mavlink_msg_action_get_target(msg);
action->target_component = mavlink_msg_action_get_target_component(msg);
action->action = mavlink_msg_action_get_action(msg);
#else
memcpy(action, _MAV_PAYLOAD(msg), 3);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v0.9/common/mavlink_msg_action_ack.h
0,0 → 1,166
// MESSAGE ACTION_ACK PACKING
 
#define MAVLINK_MSG_ID_ACTION_ACK 9
 
typedef struct __mavlink_action_ack_t
{
uint8_t action; ///< The action id
uint8_t result; ///< 0: Action DENIED, 1: Action executed
} mavlink_action_ack_t;
 
#define MAVLINK_MSG_ID_ACTION_ACK_LEN 2
#define MAVLINK_MSG_ID_9_LEN 2
 
 
 
#define MAVLINK_MESSAGE_INFO_ACTION_ACK { \
"ACTION_ACK", \
2, \
{ { "action", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_action_ack_t, action) }, \
{ "result", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_action_ack_t, result) }, \
} \
}
 
 
/**
* @brief Pack a action_ack message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param action The action id
* @param result 0: Action DENIED, 1: Action executed
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_action_ack_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t action, uint8_t result)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[2];
_mav_put_uint8_t(buf, 0, action);
_mav_put_uint8_t(buf, 1, result);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 2);
#else
mavlink_action_ack_t packet;
packet.action = action;
packet.result = result;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 2);
#endif
 
msg->msgid = MAVLINK_MSG_ID_ACTION_ACK;
return mavlink_finalize_message(msg, system_id, component_id, 2);
}
 
/**
* @brief Pack a action_ack message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param action The action id
* @param result 0: Action DENIED, 1: Action executed
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_action_ack_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint8_t action,uint8_t result)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[2];
_mav_put_uint8_t(buf, 0, action);
_mav_put_uint8_t(buf, 1, result);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 2);
#else
mavlink_action_ack_t packet;
packet.action = action;
packet.result = result;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 2);
#endif
 
msg->msgid = MAVLINK_MSG_ID_ACTION_ACK;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 2);
}
 
/**
* @brief Encode a action_ack struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param action_ack C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_action_ack_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_action_ack_t* action_ack)
{
return mavlink_msg_action_ack_pack(system_id, component_id, msg, action_ack->action, action_ack->result);
}
 
/**
* @brief Send a action_ack message
* @param chan MAVLink channel to send the message
*
* @param action The action id
* @param result 0: Action DENIED, 1: Action executed
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_action_ack_send(mavlink_channel_t chan, uint8_t action, uint8_t result)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[2];
_mav_put_uint8_t(buf, 0, action);
_mav_put_uint8_t(buf, 1, result);
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ACTION_ACK, buf, 2);
#else
mavlink_action_ack_t packet;
packet.action = action;
packet.result = result;
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ACTION_ACK, (const char *)&packet, 2);
#endif
}
 
#endif
 
// MESSAGE ACTION_ACK UNPACKING
 
 
/**
* @brief Get field action from action_ack message
*
* @return The action id
*/
static inline uint8_t mavlink_msg_action_ack_get_action(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 0);
}
 
/**
* @brief Get field result from action_ack message
*
* @return 0: Action DENIED, 1: Action executed
*/
static inline uint8_t mavlink_msg_action_ack_get_result(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 1);
}
 
/**
* @brief Decode a action_ack message into a struct
*
* @param msg The message to decode
* @param action_ack C-struct to decode the message contents into
*/
static inline void mavlink_msg_action_ack_decode(const mavlink_message_t* msg, mavlink_action_ack_t* action_ack)
{
#if MAVLINK_NEED_BYTE_SWAP
action_ack->action = mavlink_msg_action_ack_get_action(msg);
action_ack->result = mavlink_msg_action_ack_get_result(msg);
#else
memcpy(action_ack, _MAV_PAYLOAD(msg), 2);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v0.9/common/mavlink_msg_attitude.h
0,0 → 1,276
// MESSAGE ATTITUDE PACKING
 
#define MAVLINK_MSG_ID_ATTITUDE 30
 
typedef struct __mavlink_attitude_t
{
uint64_t usec; ///< Timestamp (microseconds since UNIX epoch or microseconds since system boot)
float roll; ///< Roll angle (rad)
float pitch; ///< Pitch angle (rad)
float yaw; ///< Yaw angle (rad)
float rollspeed; ///< Roll angular speed (rad/s)
float pitchspeed; ///< Pitch angular speed (rad/s)
float yawspeed; ///< Yaw angular speed (rad/s)
} mavlink_attitude_t;
 
#define MAVLINK_MSG_ID_ATTITUDE_LEN 32
#define MAVLINK_MSG_ID_30_LEN 32
 
 
 
#define MAVLINK_MESSAGE_INFO_ATTITUDE { \
"ATTITUDE", \
7, \
{ { "usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_attitude_t, usec) }, \
{ "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_attitude_t, roll) }, \
{ "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_attitude_t, pitch) }, \
{ "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_attitude_t, yaw) }, \
{ "rollspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_attitude_t, rollspeed) }, \
{ "pitchspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_attitude_t, pitchspeed) }, \
{ "yawspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_attitude_t, yawspeed) }, \
} \
}
 
 
/**
* @brief Pack a attitude message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
* @param roll Roll angle (rad)
* @param pitch Pitch angle (rad)
* @param yaw Yaw angle (rad)
* @param rollspeed Roll angular speed (rad/s)
* @param pitchspeed Pitch angular speed (rad/s)
* @param yawspeed Yaw angular speed (rad/s)
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_attitude_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint64_t usec, float roll, float pitch, float yaw, float rollspeed, float pitchspeed, float yawspeed)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[32];
_mav_put_uint64_t(buf, 0, usec);
_mav_put_float(buf, 8, roll);
_mav_put_float(buf, 12, pitch);
_mav_put_float(buf, 16, yaw);
_mav_put_float(buf, 20, rollspeed);
_mav_put_float(buf, 24, pitchspeed);
_mav_put_float(buf, 28, yawspeed);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 32);
#else
mavlink_attitude_t packet;
packet.usec = usec;
packet.roll = roll;
packet.pitch = pitch;
packet.yaw = yaw;
packet.rollspeed = rollspeed;
packet.pitchspeed = pitchspeed;
packet.yawspeed = yawspeed;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 32);
#endif
 
msg->msgid = MAVLINK_MSG_ID_ATTITUDE;
return mavlink_finalize_message(msg, system_id, component_id, 32);
}
 
/**
* @brief Pack a attitude message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
* @param roll Roll angle (rad)
* @param pitch Pitch angle (rad)
* @param yaw Yaw angle (rad)
* @param rollspeed Roll angular speed (rad/s)
* @param pitchspeed Pitch angular speed (rad/s)
* @param yawspeed Yaw angular speed (rad/s)
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_attitude_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint64_t usec,float roll,float pitch,float yaw,float rollspeed,float pitchspeed,float yawspeed)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[32];
_mav_put_uint64_t(buf, 0, usec);
_mav_put_float(buf, 8, roll);
_mav_put_float(buf, 12, pitch);
_mav_put_float(buf, 16, yaw);
_mav_put_float(buf, 20, rollspeed);
_mav_put_float(buf, 24, pitchspeed);
_mav_put_float(buf, 28, yawspeed);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 32);
#else
mavlink_attitude_t packet;
packet.usec = usec;
packet.roll = roll;
packet.pitch = pitch;
packet.yaw = yaw;
packet.rollspeed = rollspeed;
packet.pitchspeed = pitchspeed;
packet.yawspeed = yawspeed;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 32);
#endif
 
msg->msgid = MAVLINK_MSG_ID_ATTITUDE;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 32);
}
 
/**
* @brief Encode a attitude struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param attitude C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_attitude_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_attitude_t* attitude)
{
return mavlink_msg_attitude_pack(system_id, component_id, msg, attitude->usec, attitude->roll, attitude->pitch, attitude->yaw, attitude->rollspeed, attitude->pitchspeed, attitude->yawspeed);
}
 
/**
* @brief Send a attitude message
* @param chan MAVLink channel to send the message
*
* @param usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
* @param roll Roll angle (rad)
* @param pitch Pitch angle (rad)
* @param yaw Yaw angle (rad)
* @param rollspeed Roll angular speed (rad/s)
* @param pitchspeed Pitch angular speed (rad/s)
* @param yawspeed Yaw angular speed (rad/s)
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_attitude_send(mavlink_channel_t chan, uint64_t usec, float roll, float pitch, float yaw, float rollspeed, float pitchspeed, float yawspeed)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[32];
_mav_put_uint64_t(buf, 0, usec);
_mav_put_float(buf, 8, roll);
_mav_put_float(buf, 12, pitch);
_mav_put_float(buf, 16, yaw);
_mav_put_float(buf, 20, rollspeed);
_mav_put_float(buf, 24, pitchspeed);
_mav_put_float(buf, 28, yawspeed);
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE, buf, 32);
#else
mavlink_attitude_t packet;
packet.usec = usec;
packet.roll = roll;
packet.pitch = pitch;
packet.yaw = yaw;
packet.rollspeed = rollspeed;
packet.pitchspeed = pitchspeed;
packet.yawspeed = yawspeed;
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE, (const char *)&packet, 32);
#endif
}
 
#endif
 
// MESSAGE ATTITUDE UNPACKING
 
 
/**
* @brief Get field usec from attitude message
*
* @return Timestamp (microseconds since UNIX epoch or microseconds since system boot)
*/
static inline uint64_t mavlink_msg_attitude_get_usec(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint64_t(msg, 0);
}
 
/**
* @brief Get field roll from attitude message
*
* @return Roll angle (rad)
*/
static inline float mavlink_msg_attitude_get_roll(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 8);
}
 
/**
* @brief Get field pitch from attitude message
*
* @return Pitch angle (rad)
*/
static inline float mavlink_msg_attitude_get_pitch(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 12);
}
 
/**
* @brief Get field yaw from attitude message
*
* @return Yaw angle (rad)
*/
static inline float mavlink_msg_attitude_get_yaw(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 16);
}
 
/**
* @brief Get field rollspeed from attitude message
*
* @return Roll angular speed (rad/s)
*/
static inline float mavlink_msg_attitude_get_rollspeed(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 20);
}
 
/**
* @brief Get field pitchspeed from attitude message
*
* @return Pitch angular speed (rad/s)
*/
static inline float mavlink_msg_attitude_get_pitchspeed(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 24);
}
 
/**
* @brief Get field yawspeed from attitude message
*
* @return Yaw angular speed (rad/s)
*/
static inline float mavlink_msg_attitude_get_yawspeed(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 28);
}
 
/**
* @brief Decode a attitude message into a struct
*
* @param msg The message to decode
* @param attitude C-struct to decode the message contents into
*/
static inline void mavlink_msg_attitude_decode(const mavlink_message_t* msg, mavlink_attitude_t* attitude)
{
#if MAVLINK_NEED_BYTE_SWAP
attitude->usec = mavlink_msg_attitude_get_usec(msg);
attitude->roll = mavlink_msg_attitude_get_roll(msg);
attitude->pitch = mavlink_msg_attitude_get_pitch(msg);
attitude->yaw = mavlink_msg_attitude_get_yaw(msg);
attitude->rollspeed = mavlink_msg_attitude_get_rollspeed(msg);
attitude->pitchspeed = mavlink_msg_attitude_get_pitchspeed(msg);
attitude->yawspeed = mavlink_msg_attitude_get_yawspeed(msg);
#else
memcpy(attitude, _MAV_PAYLOAD(msg), 32);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v0.9/common/mavlink_msg_auth_key.h
0,0 → 1,144
// MESSAGE AUTH_KEY PACKING
 
#define MAVLINK_MSG_ID_AUTH_KEY 7
 
typedef struct __mavlink_auth_key_t
{
char key[32]; ///< key
} mavlink_auth_key_t;
 
#define MAVLINK_MSG_ID_AUTH_KEY_LEN 32
#define MAVLINK_MSG_ID_7_LEN 32
 
#define MAVLINK_MSG_AUTH_KEY_FIELD_KEY_LEN 32
 
#define MAVLINK_MESSAGE_INFO_AUTH_KEY { \
"AUTH_KEY", \
1, \
{ { "key", NULL, MAVLINK_TYPE_CHAR, 32, 0, offsetof(mavlink_auth_key_t, key) }, \
} \
}
 
 
/**
* @brief Pack a auth_key message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param key key
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_auth_key_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
const char *key)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[32];
 
_mav_put_char_array(buf, 0, key, 32);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 32);
#else
mavlink_auth_key_t packet;
 
mav_array_memcpy(packet.key, key, sizeof(char)*32);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 32);
#endif
 
msg->msgid = MAVLINK_MSG_ID_AUTH_KEY;
return mavlink_finalize_message(msg, system_id, component_id, 32);
}
 
/**
* @brief Pack a auth_key message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param key key
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_auth_key_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
const char *key)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[32];
 
_mav_put_char_array(buf, 0, key, 32);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 32);
#else
mavlink_auth_key_t packet;
 
mav_array_memcpy(packet.key, key, sizeof(char)*32);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 32);
#endif
 
msg->msgid = MAVLINK_MSG_ID_AUTH_KEY;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 32);
}
 
/**
* @brief Encode a auth_key struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param auth_key C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_auth_key_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_auth_key_t* auth_key)
{
return mavlink_msg_auth_key_pack(system_id, component_id, msg, auth_key->key);
}
 
/**
* @brief Send a auth_key message
* @param chan MAVLink channel to send the message
*
* @param key key
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_auth_key_send(mavlink_channel_t chan, const char *key)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[32];
 
_mav_put_char_array(buf, 0, key, 32);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTH_KEY, buf, 32);
#else
mavlink_auth_key_t packet;
 
mav_array_memcpy(packet.key, key, sizeof(char)*32);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTH_KEY, (const char *)&packet, 32);
#endif
}
 
#endif
 
// MESSAGE AUTH_KEY UNPACKING
 
 
/**
* @brief Get field key from auth_key message
*
* @return key
*/
static inline uint16_t mavlink_msg_auth_key_get_key(const mavlink_message_t* msg, char *key)
{
return _MAV_RETURN_char_array(msg, key, 32, 0);
}
 
/**
* @brief Decode a auth_key message into a struct
*
* @param msg The message to decode
* @param auth_key C-struct to decode the message contents into
*/
static inline void mavlink_msg_auth_key_decode(const mavlink_message_t* msg, mavlink_auth_key_t* auth_key)
{
#if MAVLINK_NEED_BYTE_SWAP
mavlink_msg_auth_key_get_key(msg, auth_key->key);
#else
memcpy(auth_key, _MAV_PAYLOAD(msg), 32);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v0.9/common/mavlink_msg_boot.h
0,0 → 1,144
// MESSAGE BOOT PACKING
 
#define MAVLINK_MSG_ID_BOOT 1
 
typedef struct __mavlink_boot_t
{
uint32_t version; ///< The onboard software version
} mavlink_boot_t;
 
#define MAVLINK_MSG_ID_BOOT_LEN 4
#define MAVLINK_MSG_ID_1_LEN 4
 
 
 
#define MAVLINK_MESSAGE_INFO_BOOT { \
"BOOT", \
1, \
{ { "version", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_boot_t, version) }, \
} \
}
 
 
/**
* @brief Pack a boot message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param version The onboard software version
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_boot_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint32_t version)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[4];
_mav_put_uint32_t(buf, 0, version);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 4);
#else
mavlink_boot_t packet;
packet.version = version;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 4);
#endif
 
msg->msgid = MAVLINK_MSG_ID_BOOT;
return mavlink_finalize_message(msg, system_id, component_id, 4);
}
 
/**
* @brief Pack a boot message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param version The onboard software version
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_boot_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint32_t version)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[4];
_mav_put_uint32_t(buf, 0, version);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 4);
#else
mavlink_boot_t packet;
packet.version = version;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 4);
#endif
 
msg->msgid = MAVLINK_MSG_ID_BOOT;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 4);
}
 
/**
* @brief Encode a boot struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param boot C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_boot_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_boot_t* boot)
{
return mavlink_msg_boot_pack(system_id, component_id, msg, boot->version);
}
 
/**
* @brief Send a boot message
* @param chan MAVLink channel to send the message
*
* @param version The onboard software version
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_boot_send(mavlink_channel_t chan, uint32_t version)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[4];
_mav_put_uint32_t(buf, 0, version);
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_BOOT, buf, 4);
#else
mavlink_boot_t packet;
packet.version = version;
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_BOOT, (const char *)&packet, 4);
#endif
}
 
#endif
 
// MESSAGE BOOT UNPACKING
 
 
/**
* @brief Get field version from boot message
*
* @return The onboard software version
*/
static inline uint32_t mavlink_msg_boot_get_version(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint32_t(msg, 0);
}
 
/**
* @brief Decode a boot message into a struct
*
* @param msg The message to decode
* @param boot C-struct to decode the message contents into
*/
static inline void mavlink_msg_boot_decode(const mavlink_message_t* msg, mavlink_boot_t* boot)
{
#if MAVLINK_NEED_BYTE_SWAP
boot->version = mavlink_msg_boot_get_version(msg);
#else
memcpy(boot, _MAV_PAYLOAD(msg), 4);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v0.9/common/mavlink_msg_change_operator_control.h
0,0 → 1,204
// MESSAGE CHANGE_OPERATOR_CONTROL PACKING
 
#define MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL 5
 
typedef struct __mavlink_change_operator_control_t
{
uint8_t target_system; ///< System the GCS requests control for
uint8_t control_request; ///< 0: request control of this MAV, 1: Release control of this MAV
uint8_t version; ///< 0: key as plaintext, 1-255: future, different hashing/encryption variants. The GCS should in general use the safest mode possible initially and then gradually move down the encryption level if it gets a NACK message indicating an encryption mismatch.
char passkey[25]; ///< Password / Key, depending on version plaintext or encrypted. 25 or less characters, NULL terminated. The characters may involve A-Z, a-z, 0-9, and "!?,.-"
} mavlink_change_operator_control_t;
 
#define MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN 28
#define MAVLINK_MSG_ID_5_LEN 28
 
#define MAVLINK_MSG_CHANGE_OPERATOR_CONTROL_FIELD_PASSKEY_LEN 25
 
#define MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL { \
"CHANGE_OPERATOR_CONTROL", \
4, \
{ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_change_operator_control_t, target_system) }, \
{ "control_request", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_change_operator_control_t, control_request) }, \
{ "version", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_change_operator_control_t, version) }, \
{ "passkey", NULL, MAVLINK_TYPE_CHAR, 25, 3, offsetof(mavlink_change_operator_control_t, passkey) }, \
} \
}
 
 
/**
* @brief Pack a change_operator_control message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param target_system System the GCS requests control for
* @param control_request 0: request control of this MAV, 1: Release control of this MAV
* @param version 0: key as plaintext, 1-255: future, different hashing/encryption variants. The GCS should in general use the safest mode possible initially and then gradually move down the encryption level if it gets a NACK message indicating an encryption mismatch.
* @param passkey Password / Key, depending on version plaintext or encrypted. 25 or less characters, NULL terminated. The characters may involve A-Z, a-z, 0-9, and "!?,.-"
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_change_operator_control_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t target_system, uint8_t control_request, uint8_t version, const char *passkey)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[28];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, control_request);
_mav_put_uint8_t(buf, 2, version);
_mav_put_char_array(buf, 3, passkey, 25);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 28);
#else
mavlink_change_operator_control_t packet;
packet.target_system = target_system;
packet.control_request = control_request;
packet.version = version;
mav_array_memcpy(packet.passkey, passkey, sizeof(char)*25);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 28);
#endif
 
msg->msgid = MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL;
return mavlink_finalize_message(msg, system_id, component_id, 28);
}
 
/**
* @brief Pack a change_operator_control message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param target_system System the GCS requests control for
* @param control_request 0: request control of this MAV, 1: Release control of this MAV
* @param version 0: key as plaintext, 1-255: future, different hashing/encryption variants. The GCS should in general use the safest mode possible initially and then gradually move down the encryption level if it gets a NACK message indicating an encryption mismatch.
* @param passkey Password / Key, depending on version plaintext or encrypted. 25 or less characters, NULL terminated. The characters may involve A-Z, a-z, 0-9, and "!?,.-"
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_change_operator_control_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint8_t target_system,uint8_t control_request,uint8_t version,const char *passkey)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[28];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, control_request);
_mav_put_uint8_t(buf, 2, version);
_mav_put_char_array(buf, 3, passkey, 25);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 28);
#else
mavlink_change_operator_control_t packet;
packet.target_system = target_system;
packet.control_request = control_request;
packet.version = version;
mav_array_memcpy(packet.passkey, passkey, sizeof(char)*25);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 28);
#endif
 
msg->msgid = MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 28);
}
 
/**
* @brief Encode a change_operator_control struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param change_operator_control C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_change_operator_control_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_change_operator_control_t* change_operator_control)
{
return mavlink_msg_change_operator_control_pack(system_id, component_id, msg, change_operator_control->target_system, change_operator_control->control_request, change_operator_control->version, change_operator_control->passkey);
}
 
/**
* @brief Send a change_operator_control message
* @param chan MAVLink channel to send the message
*
* @param target_system System the GCS requests control for
* @param control_request 0: request control of this MAV, 1: Release control of this MAV
* @param version 0: key as plaintext, 1-255: future, different hashing/encryption variants. The GCS should in general use the safest mode possible initially and then gradually move down the encryption level if it gets a NACK message indicating an encryption mismatch.
* @param passkey Password / Key, depending on version plaintext or encrypted. 25 or less characters, NULL terminated. The characters may involve A-Z, a-z, 0-9, and "!?,.-"
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_change_operator_control_send(mavlink_channel_t chan, uint8_t target_system, uint8_t control_request, uint8_t version, const char *passkey)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[28];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, control_request);
_mav_put_uint8_t(buf, 2, version);
_mav_put_char_array(buf, 3, passkey, 25);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL, buf, 28);
#else
mavlink_change_operator_control_t packet;
packet.target_system = target_system;
packet.control_request = control_request;
packet.version = version;
mav_array_memcpy(packet.passkey, passkey, sizeof(char)*25);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL, (const char *)&packet, 28);
#endif
}
 
#endif
 
// MESSAGE CHANGE_OPERATOR_CONTROL UNPACKING
 
 
/**
* @brief Get field target_system from change_operator_control message
*
* @return System the GCS requests control for
*/
static inline uint8_t mavlink_msg_change_operator_control_get_target_system(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 0);
}
 
/**
* @brief Get field control_request from change_operator_control message
*
* @return 0: request control of this MAV, 1: Release control of this MAV
*/
static inline uint8_t mavlink_msg_change_operator_control_get_control_request(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 1);
}
 
/**
* @brief Get field version from change_operator_control message
*
* @return 0: key as plaintext, 1-255: future, different hashing/encryption variants. The GCS should in general use the safest mode possible initially and then gradually move down the encryption level if it gets a NACK message indicating an encryption mismatch.
*/
static inline uint8_t mavlink_msg_change_operator_control_get_version(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 2);
}
 
/**
* @brief Get field passkey from change_operator_control message
*
* @return Password / Key, depending on version plaintext or encrypted. 25 or less characters, NULL terminated. The characters may involve A-Z, a-z, 0-9, and "!?,.-"
*/
static inline uint16_t mavlink_msg_change_operator_control_get_passkey(const mavlink_message_t* msg, char *passkey)
{
return _MAV_RETURN_char_array(msg, passkey, 25, 3);
}
 
/**
* @brief Decode a change_operator_control message into a struct
*
* @param msg The message to decode
* @param change_operator_control C-struct to decode the message contents into
*/
static inline void mavlink_msg_change_operator_control_decode(const mavlink_message_t* msg, mavlink_change_operator_control_t* change_operator_control)
{
#if MAVLINK_NEED_BYTE_SWAP
change_operator_control->target_system = mavlink_msg_change_operator_control_get_target_system(msg);
change_operator_control->control_request = mavlink_msg_change_operator_control_get_control_request(msg);
change_operator_control->version = mavlink_msg_change_operator_control_get_version(msg);
mavlink_msg_change_operator_control_get_passkey(msg, change_operator_control->passkey);
#else
memcpy(change_operator_control, _MAV_PAYLOAD(msg), 28);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v0.9/common/mavlink_msg_change_operator_control_ack.h
0,0 → 1,188
// MESSAGE CHANGE_OPERATOR_CONTROL_ACK PACKING
 
#define MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK 6
 
typedef struct __mavlink_change_operator_control_ack_t
{
uint8_t gcs_system_id; ///< ID of the GCS this message
uint8_t control_request; ///< 0: request control of this MAV, 1: Release control of this MAV
uint8_t ack; ///< 0: ACK, 1: NACK: Wrong passkey, 2: NACK: Unsupported passkey encryption method, 3: NACK: Already under control
} mavlink_change_operator_control_ack_t;
 
#define MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN 3
#define MAVLINK_MSG_ID_6_LEN 3
 
 
 
#define MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL_ACK { \
"CHANGE_OPERATOR_CONTROL_ACK", \
3, \
{ { "gcs_system_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_change_operator_control_ack_t, gcs_system_id) }, \
{ "control_request", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_change_operator_control_ack_t, control_request) }, \
{ "ack", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_change_operator_control_ack_t, ack) }, \
} \
}
 
 
/**
* @brief Pack a change_operator_control_ack message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param gcs_system_id ID of the GCS this message
* @param control_request 0: request control of this MAV, 1: Release control of this MAV
* @param ack 0: ACK, 1: NACK: Wrong passkey, 2: NACK: Unsupported passkey encryption method, 3: NACK: Already under control
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_change_operator_control_ack_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t gcs_system_id, uint8_t control_request, uint8_t ack)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[3];
_mav_put_uint8_t(buf, 0, gcs_system_id);
_mav_put_uint8_t(buf, 1, control_request);
_mav_put_uint8_t(buf, 2, ack);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 3);
#else
mavlink_change_operator_control_ack_t packet;
packet.gcs_system_id = gcs_system_id;
packet.control_request = control_request;
packet.ack = ack;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 3);
#endif
 
msg->msgid = MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK;
return mavlink_finalize_message(msg, system_id, component_id, 3);
}
 
/**
* @brief Pack a change_operator_control_ack message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param gcs_system_id ID of the GCS this message
* @param control_request 0: request control of this MAV, 1: Release control of this MAV
* @param ack 0: ACK, 1: NACK: Wrong passkey, 2: NACK: Unsupported passkey encryption method, 3: NACK: Already under control
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_change_operator_control_ack_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint8_t gcs_system_id,uint8_t control_request,uint8_t ack)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[3];
_mav_put_uint8_t(buf, 0, gcs_system_id);
_mav_put_uint8_t(buf, 1, control_request);
_mav_put_uint8_t(buf, 2, ack);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 3);
#else
mavlink_change_operator_control_ack_t packet;
packet.gcs_system_id = gcs_system_id;
packet.control_request = control_request;
packet.ack = ack;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 3);
#endif
 
msg->msgid = MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 3);
}
 
/**
* @brief Encode a change_operator_control_ack struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param change_operator_control_ack C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_change_operator_control_ack_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_change_operator_control_ack_t* change_operator_control_ack)
{
return mavlink_msg_change_operator_control_ack_pack(system_id, component_id, msg, change_operator_control_ack->gcs_system_id, change_operator_control_ack->control_request, change_operator_control_ack->ack);
}
 
/**
* @brief Send a change_operator_control_ack message
* @param chan MAVLink channel to send the message
*
* @param gcs_system_id ID of the GCS this message
* @param control_request 0: request control of this MAV, 1: Release control of this MAV
* @param ack 0: ACK, 1: NACK: Wrong passkey, 2: NACK: Unsupported passkey encryption method, 3: NACK: Already under control
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_change_operator_control_ack_send(mavlink_channel_t chan, uint8_t gcs_system_id, uint8_t control_request, uint8_t ack)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[3];
_mav_put_uint8_t(buf, 0, gcs_system_id);
_mav_put_uint8_t(buf, 1, control_request);
_mav_put_uint8_t(buf, 2, ack);
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK, buf, 3);
#else
mavlink_change_operator_control_ack_t packet;
packet.gcs_system_id = gcs_system_id;
packet.control_request = control_request;
packet.ack = ack;
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK, (const char *)&packet, 3);
#endif
}
 
#endif
 
// MESSAGE CHANGE_OPERATOR_CONTROL_ACK UNPACKING
 
 
/**
* @brief Get field gcs_system_id from change_operator_control_ack message
*
* @return ID of the GCS this message
*/
static inline uint8_t mavlink_msg_change_operator_control_ack_get_gcs_system_id(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 0);
}
 
/**
* @brief Get field control_request from change_operator_control_ack message
*
* @return 0: request control of this MAV, 1: Release control of this MAV
*/
static inline uint8_t mavlink_msg_change_operator_control_ack_get_control_request(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 1);
}
 
/**
* @brief Get field ack from change_operator_control_ack message
*
* @return 0: ACK, 1: NACK: Wrong passkey, 2: NACK: Unsupported passkey encryption method, 3: NACK: Already under control
*/
static inline uint8_t mavlink_msg_change_operator_control_ack_get_ack(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 2);
}
 
/**
* @brief Decode a change_operator_control_ack message into a struct
*
* @param msg The message to decode
* @param change_operator_control_ack C-struct to decode the message contents into
*/
static inline void mavlink_msg_change_operator_control_ack_decode(const mavlink_message_t* msg, mavlink_change_operator_control_ack_t* change_operator_control_ack)
{
#if MAVLINK_NEED_BYTE_SWAP
change_operator_control_ack->gcs_system_id = mavlink_msg_change_operator_control_ack_get_gcs_system_id(msg);
change_operator_control_ack->control_request = mavlink_msg_change_operator_control_ack_get_control_request(msg);
change_operator_control_ack->ack = mavlink_msg_change_operator_control_ack_get_ack(msg);
#else
memcpy(change_operator_control_ack, _MAV_PAYLOAD(msg), 3);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v0.9/common/mavlink_msg_command.h
0,0 → 1,298
// MESSAGE COMMAND PACKING
 
#define MAVLINK_MSG_ID_COMMAND 75
 
typedef struct __mavlink_command_t
{
uint8_t target_system; ///< System which should execute the command
uint8_t target_component; ///< Component which should execute the command, 0 for all components
uint8_t command; ///< Command ID, as defined by MAV_CMD enum.
uint8_t confirmation; ///< 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command)
float param1; ///< Parameter 1, as defined by MAV_CMD enum.
float param2; ///< Parameter 2, as defined by MAV_CMD enum.
float param3; ///< Parameter 3, as defined by MAV_CMD enum.
float param4; ///< Parameter 4, as defined by MAV_CMD enum.
} mavlink_command_t;
 
#define MAVLINK_MSG_ID_COMMAND_LEN 20
#define MAVLINK_MSG_ID_75_LEN 20
 
 
 
#define MAVLINK_MESSAGE_INFO_COMMAND { \
"COMMAND", \
8, \
{ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_command_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_command_t, target_component) }, \
{ "command", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_command_t, command) }, \
{ "confirmation", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_command_t, confirmation) }, \
{ "param1", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_command_t, param1) }, \
{ "param2", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_command_t, param2) }, \
{ "param3", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_command_t, param3) }, \
{ "param4", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_command_t, param4) }, \
} \
}
 
 
/**
* @brief Pack a command message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param target_system System which should execute the command
* @param target_component Component which should execute the command, 0 for all components
* @param command Command ID, as defined by MAV_CMD enum.
* @param confirmation 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command)
* @param param1 Parameter 1, as defined by MAV_CMD enum.
* @param param2 Parameter 2, as defined by MAV_CMD enum.
* @param param3 Parameter 3, as defined by MAV_CMD enum.
* @param param4 Parameter 4, as defined by MAV_CMD enum.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_command_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t target_system, uint8_t target_component, uint8_t command, uint8_t confirmation, float param1, float param2, float param3, float param4)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[20];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
_mav_put_uint8_t(buf, 2, command);
_mav_put_uint8_t(buf, 3, confirmation);
_mav_put_float(buf, 4, param1);
_mav_put_float(buf, 8, param2);
_mav_put_float(buf, 12, param3);
_mav_put_float(buf, 16, param4);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 20);
#else
mavlink_command_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
packet.command = command;
packet.confirmation = confirmation;
packet.param1 = param1;
packet.param2 = param2;
packet.param3 = param3;
packet.param4 = param4;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 20);
#endif
 
msg->msgid = MAVLINK_MSG_ID_COMMAND;
return mavlink_finalize_message(msg, system_id, component_id, 20);
}
 
/**
* @brief Pack a command message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param target_system System which should execute the command
* @param target_component Component which should execute the command, 0 for all components
* @param command Command ID, as defined by MAV_CMD enum.
* @param confirmation 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command)
* @param param1 Parameter 1, as defined by MAV_CMD enum.
* @param param2 Parameter 2, as defined by MAV_CMD enum.
* @param param3 Parameter 3, as defined by MAV_CMD enum.
* @param param4 Parameter 4, as defined by MAV_CMD enum.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_command_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 command,uint8_t confirmation,float param1,float param2,float param3,float param4)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[20];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
_mav_put_uint8_t(buf, 2, command);
_mav_put_uint8_t(buf, 3, confirmation);
_mav_put_float(buf, 4, param1);
_mav_put_float(buf, 8, param2);
_mav_put_float(buf, 12, param3);
_mav_put_float(buf, 16, param4);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 20);
#else
mavlink_command_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
packet.command = command;
packet.confirmation = confirmation;
packet.param1 = param1;
packet.param2 = param2;
packet.param3 = param3;
packet.param4 = param4;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 20);
#endif
 
msg->msgid = MAVLINK_MSG_ID_COMMAND;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 20);
}
 
/**
* @brief Encode a command struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param command C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_command_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_command_t* command)
{
return mavlink_msg_command_pack(system_id, component_id, msg, command->target_system, command->target_component, command->command, command->confirmation, command->param1, command->param2, command->param3, command->param4);
}
 
/**
* @brief Send a command message
* @param chan MAVLink channel to send the message
*
* @param target_system System which should execute the command
* @param target_component Component which should execute the command, 0 for all components
* @param command Command ID, as defined by MAV_CMD enum.
* @param confirmation 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command)
* @param param1 Parameter 1, as defined by MAV_CMD enum.
* @param param2 Parameter 2, as defined by MAV_CMD enum.
* @param param3 Parameter 3, as defined by MAV_CMD enum.
* @param param4 Parameter 4, as defined by MAV_CMD enum.
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_command_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t command, uint8_t confirmation, float param1, float param2, float param3, float param4)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[20];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
_mav_put_uint8_t(buf, 2, command);
_mav_put_uint8_t(buf, 3, confirmation);
_mav_put_float(buf, 4, param1);
_mav_put_float(buf, 8, param2);
_mav_put_float(buf, 12, param3);
_mav_put_float(buf, 16, param4);
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND, buf, 20);
#else
mavlink_command_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
packet.command = command;
packet.confirmation = confirmation;
packet.param1 = param1;
packet.param2 = param2;
packet.param3 = param3;
packet.param4 = param4;
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND, (const char *)&packet, 20);
#endif
}
 
#endif
 
// MESSAGE COMMAND UNPACKING
 
 
/**
* @brief Get field target_system from command message
*
* @return System which should execute the command
*/
static inline uint8_t mavlink_msg_command_get_target_system(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 0);
}
 
/**
* @brief Get field target_component from command message
*
* @return Component which should execute the command, 0 for all components
*/
static inline uint8_t mavlink_msg_command_get_target_component(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 1);
}
 
/**
* @brief Get field command from command message
*
* @return Command ID, as defined by MAV_CMD enum.
*/
static inline uint8_t mavlink_msg_command_get_command(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 2);
}
 
/**
* @brief Get field confirmation from command message
*
* @return 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command)
*/
static inline uint8_t mavlink_msg_command_get_confirmation(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 3);
}
 
/**
* @brief Get field param1 from command message
*
* @return Parameter 1, as defined by MAV_CMD enum.
*/
static inline float mavlink_msg_command_get_param1(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 4);
}
 
/**
* @brief Get field param2 from command message
*
* @return Parameter 2, as defined by MAV_CMD enum.
*/
static inline float mavlink_msg_command_get_param2(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 8);
}
 
/**
* @brief Get field param3 from command message
*
* @return Parameter 3, as defined by MAV_CMD enum.
*/
static inline float mavlink_msg_command_get_param3(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 12);
}
 
/**
* @brief Get field param4 from command message
*
* @return Parameter 4, as defined by MAV_CMD enum.
*/
static inline float mavlink_msg_command_get_param4(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 16);
}
 
/**
* @brief Decode a command message into a struct
*
* @param msg The message to decode
* @param command C-struct to decode the message contents into
*/
static inline void mavlink_msg_command_decode(const mavlink_message_t* msg, mavlink_command_t* command)
{
#if MAVLINK_NEED_BYTE_SWAP
command->target_system = mavlink_msg_command_get_target_system(msg);
command->target_component = mavlink_msg_command_get_target_component(msg);
command->command = mavlink_msg_command_get_command(msg);
command->confirmation = mavlink_msg_command_get_confirmation(msg);
command->param1 = mavlink_msg_command_get_param1(msg);
command->param2 = mavlink_msg_command_get_param2(msg);
command->param3 = mavlink_msg_command_get_param3(msg);
command->param4 = mavlink_msg_command_get_param4(msg);
#else
memcpy(command, _MAV_PAYLOAD(msg), 20);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v0.9/common/mavlink_msg_command_ack.h
0,0 → 1,166
// MESSAGE COMMAND_ACK PACKING
 
#define MAVLINK_MSG_ID_COMMAND_ACK 76
 
typedef struct __mavlink_command_ack_t
{
float command; ///< Current airspeed in m/s
float result; ///< 1: Action ACCEPTED and EXECUTED, 1: Action TEMPORARY REJECTED/DENIED, 2: Action PERMANENTLY DENIED, 3: Action UNKNOWN/UNSUPPORTED, 4: Requesting CONFIRMATION
} mavlink_command_ack_t;
 
#define MAVLINK_MSG_ID_COMMAND_ACK_LEN 8
#define MAVLINK_MSG_ID_76_LEN 8
 
 
 
#define MAVLINK_MESSAGE_INFO_COMMAND_ACK { \
"COMMAND_ACK", \
2, \
{ { "command", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_command_ack_t, command) }, \
{ "result", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_command_ack_t, result) }, \
} \
}
 
 
/**
* @brief Pack a command_ack message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param command Current airspeed in m/s
* @param result 1: Action ACCEPTED and EXECUTED, 1: Action TEMPORARY REJECTED/DENIED, 2: Action PERMANENTLY DENIED, 3: Action UNKNOWN/UNSUPPORTED, 4: Requesting CONFIRMATION
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_command_ack_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
float command, float result)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[8];
_mav_put_float(buf, 0, command);
_mav_put_float(buf, 4, result);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 8);
#else
mavlink_command_ack_t packet;
packet.command = command;
packet.result = result;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 8);
#endif
 
msg->msgid = MAVLINK_MSG_ID_COMMAND_ACK;
return mavlink_finalize_message(msg, system_id, component_id, 8);
}
 
/**
* @brief Pack a command_ack message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param command Current airspeed in m/s
* @param result 1: Action ACCEPTED and EXECUTED, 1: Action TEMPORARY REJECTED/DENIED, 2: Action PERMANENTLY DENIED, 3: Action UNKNOWN/UNSUPPORTED, 4: Requesting CONFIRMATION
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_command_ack_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
float command,float result)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[8];
_mav_put_float(buf, 0, command);
_mav_put_float(buf, 4, result);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 8);
#else
mavlink_command_ack_t packet;
packet.command = command;
packet.result = result;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 8);
#endif
 
msg->msgid = MAVLINK_MSG_ID_COMMAND_ACK;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 8);
}
 
/**
* @brief Encode a command_ack struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param command_ack C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_command_ack_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_command_ack_t* command_ack)
{
return mavlink_msg_command_ack_pack(system_id, component_id, msg, command_ack->command, command_ack->result);
}
 
/**
* @brief Send a command_ack message
* @param chan MAVLink channel to send the message
*
* @param command Current airspeed in m/s
* @param result 1: Action ACCEPTED and EXECUTED, 1: Action TEMPORARY REJECTED/DENIED, 2: Action PERMANENTLY DENIED, 3: Action UNKNOWN/UNSUPPORTED, 4: Requesting CONFIRMATION
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_command_ack_send(mavlink_channel_t chan, float command, float result)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[8];
_mav_put_float(buf, 0, command);
_mav_put_float(buf, 4, result);
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_ACK, buf, 8);
#else
mavlink_command_ack_t packet;
packet.command = command;
packet.result = result;
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_ACK, (const char *)&packet, 8);
#endif
}
 
#endif
 
// MESSAGE COMMAND_ACK UNPACKING
 
 
/**
* @brief Get field command from command_ack message
*
* @return Current airspeed in m/s
*/
static inline float mavlink_msg_command_ack_get_command(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 0);
}
 
/**
* @brief Get field result from command_ack message
*
* @return 1: Action ACCEPTED and EXECUTED, 1: Action TEMPORARY REJECTED/DENIED, 2: Action PERMANENTLY DENIED, 3: Action UNKNOWN/UNSUPPORTED, 4: Requesting CONFIRMATION
*/
static inline float mavlink_msg_command_ack_get_result(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 4);
}
 
/**
* @brief Decode a command_ack message into a struct
*
* @param msg The message to decode
* @param command_ack C-struct to decode the message contents into
*/
static inline void mavlink_msg_command_ack_decode(const mavlink_message_t* msg, mavlink_command_ack_t* command_ack)
{
#if MAVLINK_NEED_BYTE_SWAP
command_ack->command = mavlink_msg_command_ack_get_command(msg);
command_ack->result = mavlink_msg_command_ack_get_result(msg);
#else
memcpy(command_ack, _MAV_PAYLOAD(msg), 8);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v0.9/common/mavlink_msg_control_status.h
0,0 → 1,298
// MESSAGE CONTROL_STATUS PACKING
 
#define MAVLINK_MSG_ID_CONTROL_STATUS 52
 
typedef struct __mavlink_control_status_t
{
uint8_t position_fix; ///< Position fix: 0: lost, 2: 2D position fix, 3: 3D position fix
uint8_t vision_fix; ///< Vision position fix: 0: lost, 1: 2D local position hold, 2: 2D global position fix, 3: 3D global position fix
uint8_t gps_fix; ///< GPS position fix: 0: no reception, 1: Minimum 1 satellite, but no position fix, 2: 2D position fix, 3: 3D position fix
uint8_t ahrs_health; ///< Attitude estimation health: 0: poor, 255: excellent
uint8_t control_att; ///< 0: Attitude control disabled, 1: enabled
uint8_t control_pos_xy; ///< 0: X, Y position control disabled, 1: enabled
uint8_t control_pos_z; ///< 0: Z position control disabled, 1: enabled
uint8_t control_pos_yaw; ///< 0: Yaw angle control disabled, 1: enabled
} mavlink_control_status_t;
 
#define MAVLINK_MSG_ID_CONTROL_STATUS_LEN 8
#define MAVLINK_MSG_ID_52_LEN 8
 
 
 
#define MAVLINK_MESSAGE_INFO_CONTROL_STATUS { \
"CONTROL_STATUS", \
8, \
{ { "position_fix", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_control_status_t, position_fix) }, \
{ "vision_fix", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_control_status_t, vision_fix) }, \
{ "gps_fix", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_control_status_t, gps_fix) }, \
{ "ahrs_health", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_control_status_t, ahrs_health) }, \
{ "control_att", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_control_status_t, control_att) }, \
{ "control_pos_xy", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_control_status_t, control_pos_xy) }, \
{ "control_pos_z", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_control_status_t, control_pos_z) }, \
{ "control_pos_yaw", NULL, MAVLINK_TYPE_UINT8_T, 0, 7, offsetof(mavlink_control_status_t, control_pos_yaw) }, \
} \
}
 
 
/**
* @brief Pack a control_status message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param position_fix Position fix: 0: lost, 2: 2D position fix, 3: 3D position fix
* @param vision_fix Vision position fix: 0: lost, 1: 2D local position hold, 2: 2D global position fix, 3: 3D global position fix
* @param gps_fix GPS position fix: 0: no reception, 1: Minimum 1 satellite, but no position fix, 2: 2D position fix, 3: 3D position fix
* @param ahrs_health Attitude estimation health: 0: poor, 255: excellent
* @param control_att 0: Attitude control disabled, 1: enabled
* @param control_pos_xy 0: X, Y position control disabled, 1: enabled
* @param control_pos_z 0: Z position control disabled, 1: enabled
* @param control_pos_yaw 0: Yaw angle control disabled, 1: enabled
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_control_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t position_fix, uint8_t vision_fix, uint8_t gps_fix, uint8_t ahrs_health, uint8_t control_att, uint8_t control_pos_xy, uint8_t control_pos_z, uint8_t control_pos_yaw)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[8];
_mav_put_uint8_t(buf, 0, position_fix);
_mav_put_uint8_t(buf, 1, vision_fix);
_mav_put_uint8_t(buf, 2, gps_fix);
_mav_put_uint8_t(buf, 3, ahrs_health);
_mav_put_uint8_t(buf, 4, control_att);
_mav_put_uint8_t(buf, 5, control_pos_xy);
_mav_put_uint8_t(buf, 6, control_pos_z);
_mav_put_uint8_t(buf, 7, control_pos_yaw);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 8);
#else
mavlink_control_status_t packet;
packet.position_fix = position_fix;
packet.vision_fix = vision_fix;
packet.gps_fix = gps_fix;
packet.ahrs_health = ahrs_health;
packet.control_att = control_att;
packet.control_pos_xy = control_pos_xy;
packet.control_pos_z = control_pos_z;
packet.control_pos_yaw = control_pos_yaw;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 8);
#endif
 
msg->msgid = MAVLINK_MSG_ID_CONTROL_STATUS;
return mavlink_finalize_message(msg, system_id, component_id, 8);
}
 
/**
* @brief Pack a control_status message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param position_fix Position fix: 0: lost, 2: 2D position fix, 3: 3D position fix
* @param vision_fix Vision position fix: 0: lost, 1: 2D local position hold, 2: 2D global position fix, 3: 3D global position fix
* @param gps_fix GPS position fix: 0: no reception, 1: Minimum 1 satellite, but no position fix, 2: 2D position fix, 3: 3D position fix
* @param ahrs_health Attitude estimation health: 0: poor, 255: excellent
* @param control_att 0: Attitude control disabled, 1: enabled
* @param control_pos_xy 0: X, Y position control disabled, 1: enabled
* @param control_pos_z 0: Z position control disabled, 1: enabled
* @param control_pos_yaw 0: Yaw angle control disabled, 1: enabled
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_control_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint8_t position_fix,uint8_t vision_fix,uint8_t gps_fix,uint8_t ahrs_health,uint8_t control_att,uint8_t control_pos_xy,uint8_t control_pos_z,uint8_t control_pos_yaw)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[8];
_mav_put_uint8_t(buf, 0, position_fix);
_mav_put_uint8_t(buf, 1, vision_fix);
_mav_put_uint8_t(buf, 2, gps_fix);
_mav_put_uint8_t(buf, 3, ahrs_health);
_mav_put_uint8_t(buf, 4, control_att);
_mav_put_uint8_t(buf, 5, control_pos_xy);
_mav_put_uint8_t(buf, 6, control_pos_z);
_mav_put_uint8_t(buf, 7, control_pos_yaw);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 8);
#else
mavlink_control_status_t packet;
packet.position_fix = position_fix;
packet.vision_fix = vision_fix;
packet.gps_fix = gps_fix;
packet.ahrs_health = ahrs_health;
packet.control_att = control_att;
packet.control_pos_xy = control_pos_xy;
packet.control_pos_z = control_pos_z;
packet.control_pos_yaw = control_pos_yaw;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 8);
#endif
 
msg->msgid = MAVLINK_MSG_ID_CONTROL_STATUS;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 8);
}
 
/**
* @brief Encode a control_status struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param control_status C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_control_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_control_status_t* control_status)
{
return mavlink_msg_control_status_pack(system_id, component_id, msg, control_status->position_fix, control_status->vision_fix, control_status->gps_fix, control_status->ahrs_health, control_status->control_att, control_status->control_pos_xy, control_status->control_pos_z, control_status->control_pos_yaw);
}
 
/**
* @brief Send a control_status message
* @param chan MAVLink channel to send the message
*
* @param position_fix Position fix: 0: lost, 2: 2D position fix, 3: 3D position fix
* @param vision_fix Vision position fix: 0: lost, 1: 2D local position hold, 2: 2D global position fix, 3: 3D global position fix
* @param gps_fix GPS position fix: 0: no reception, 1: Minimum 1 satellite, but no position fix, 2: 2D position fix, 3: 3D position fix
* @param ahrs_health Attitude estimation health: 0: poor, 255: excellent
* @param control_att 0: Attitude control disabled, 1: enabled
* @param control_pos_xy 0: X, Y position control disabled, 1: enabled
* @param control_pos_z 0: Z position control disabled, 1: enabled
* @param control_pos_yaw 0: Yaw angle control disabled, 1: enabled
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_control_status_send(mavlink_channel_t chan, uint8_t position_fix, uint8_t vision_fix, uint8_t gps_fix, uint8_t ahrs_health, uint8_t control_att, uint8_t control_pos_xy, uint8_t control_pos_z, uint8_t control_pos_yaw)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[8];
_mav_put_uint8_t(buf, 0, position_fix);
_mav_put_uint8_t(buf, 1, vision_fix);
_mav_put_uint8_t(buf, 2, gps_fix);
_mav_put_uint8_t(buf, 3, ahrs_health);
_mav_put_uint8_t(buf, 4, control_att);
_mav_put_uint8_t(buf, 5, control_pos_xy);
_mav_put_uint8_t(buf, 6, control_pos_z);
_mav_put_uint8_t(buf, 7, control_pos_yaw);
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CONTROL_STATUS, buf, 8);
#else
mavlink_control_status_t packet;
packet.position_fix = position_fix;
packet.vision_fix = vision_fix;
packet.gps_fix = gps_fix;
packet.ahrs_health = ahrs_health;
packet.control_att = control_att;
packet.control_pos_xy = control_pos_xy;
packet.control_pos_z = control_pos_z;
packet.control_pos_yaw = control_pos_yaw;
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CONTROL_STATUS, (const char *)&packet, 8);
#endif
}
 
#endif
 
// MESSAGE CONTROL_STATUS UNPACKING
 
 
/**
* @brief Get field position_fix from control_status message
*
* @return Position fix: 0: lost, 2: 2D position fix, 3: 3D position fix
*/
static inline uint8_t mavlink_msg_control_status_get_position_fix(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 0);
}
 
/**
* @brief Get field vision_fix from control_status message
*
* @return Vision position fix: 0: lost, 1: 2D local position hold, 2: 2D global position fix, 3: 3D global position fix
*/
static inline uint8_t mavlink_msg_control_status_get_vision_fix(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 1);
}
 
/**
* @brief Get field gps_fix from control_status message
*
* @return GPS position fix: 0: no reception, 1: Minimum 1 satellite, but no position fix, 2: 2D position fix, 3: 3D position fix
*/
static inline uint8_t mavlink_msg_control_status_get_gps_fix(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 2);
}
 
/**
* @brief Get field ahrs_health from control_status message
*
* @return Attitude estimation health: 0: poor, 255: excellent
*/
static inline uint8_t mavlink_msg_control_status_get_ahrs_health(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 3);
}
 
/**
* @brief Get field control_att from control_status message
*
* @return 0: Attitude control disabled, 1: enabled
*/
static inline uint8_t mavlink_msg_control_status_get_control_att(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 4);
}
 
/**
* @brief Get field control_pos_xy from control_status message
*
* @return 0: X, Y position control disabled, 1: enabled
*/
static inline uint8_t mavlink_msg_control_status_get_control_pos_xy(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 5);
}
 
/**
* @brief Get field control_pos_z from control_status message
*
* @return 0: Z position control disabled, 1: enabled
*/
static inline uint8_t mavlink_msg_control_status_get_control_pos_z(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 6);
}
 
/**
* @brief Get field control_pos_yaw from control_status message
*
* @return 0: Yaw angle control disabled, 1: enabled
*/
static inline uint8_t mavlink_msg_control_status_get_control_pos_yaw(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 7);
}
 
/**
* @brief Decode a control_status message into a struct
*
* @param msg The message to decode
* @param control_status C-struct to decode the message contents into
*/
static inline void mavlink_msg_control_status_decode(const mavlink_message_t* msg, mavlink_control_status_t* control_status)
{
#if MAVLINK_NEED_BYTE_SWAP
control_status->position_fix = mavlink_msg_control_status_get_position_fix(msg);
control_status->vision_fix = mavlink_msg_control_status_get_vision_fix(msg);
control_status->gps_fix = mavlink_msg_control_status_get_gps_fix(msg);
control_status->ahrs_health = mavlink_msg_control_status_get_ahrs_health(msg);
control_status->control_att = mavlink_msg_control_status_get_control_att(msg);
control_status->control_pos_xy = mavlink_msg_control_status_get_control_pos_xy(msg);
control_status->control_pos_z = mavlink_msg_control_status_get_control_pos_z(msg);
control_status->control_pos_yaw = mavlink_msg_control_status_get_control_pos_yaw(msg);
#else
memcpy(control_status, _MAV_PAYLOAD(msg), 8);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v0.9/common/mavlink_msg_debug.h
0,0 → 1,166
// MESSAGE DEBUG PACKING
 
#define MAVLINK_MSG_ID_DEBUG 255
 
typedef struct __mavlink_debug_t
{
uint8_t ind; ///< index of debug variable
float value; ///< DEBUG value
} mavlink_debug_t;
 
#define MAVLINK_MSG_ID_DEBUG_LEN 5
#define MAVLINK_MSG_ID_255_LEN 5
 
 
 
#define MAVLINK_MESSAGE_INFO_DEBUG { \
"DEBUG", \
2, \
{ { "ind", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_debug_t, ind) }, \
{ "value", NULL, MAVLINK_TYPE_FLOAT, 0, 1, offsetof(mavlink_debug_t, value) }, \
} \
}
 
 
/**
* @brief Pack a debug message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param ind index of debug variable
* @param value DEBUG value
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_debug_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t ind, float value)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[5];
_mav_put_uint8_t(buf, 0, ind);
_mav_put_float(buf, 1, value);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 5);
#else
mavlink_debug_t packet;
packet.ind = ind;
packet.value = value;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 5);
#endif
 
msg->msgid = MAVLINK_MSG_ID_DEBUG;
return mavlink_finalize_message(msg, system_id, component_id, 5);
}
 
/**
* @brief Pack a debug message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param ind index of debug variable
* @param value DEBUG value
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_debug_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint8_t ind,float value)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[5];
_mav_put_uint8_t(buf, 0, ind);
_mav_put_float(buf, 1, value);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 5);
#else
mavlink_debug_t packet;
packet.ind = ind;
packet.value = value;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 5);
#endif
 
msg->msgid = MAVLINK_MSG_ID_DEBUG;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 5);
}
 
/**
* @brief Encode a debug struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param debug C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_debug_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_debug_t* debug)
{
return mavlink_msg_debug_pack(system_id, component_id, msg, debug->ind, debug->value);
}
 
/**
* @brief Send a debug message
* @param chan MAVLink channel to send the message
*
* @param ind index of debug variable
* @param value DEBUG value
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_debug_send(mavlink_channel_t chan, uint8_t ind, float value)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[5];
_mav_put_uint8_t(buf, 0, ind);
_mav_put_float(buf, 1, value);
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG, buf, 5);
#else
mavlink_debug_t packet;
packet.ind = ind;
packet.value = value;
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG, (const char *)&packet, 5);
#endif
}
 
#endif
 
// MESSAGE DEBUG UNPACKING
 
 
/**
* @brief Get field ind from debug message
*
* @return index of debug variable
*/
static inline uint8_t mavlink_msg_debug_get_ind(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 0);
}
 
/**
* @brief Get field value from debug message
*
* @return DEBUG value
*/
static inline float mavlink_msg_debug_get_value(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 1);
}
 
/**
* @brief Decode a debug message into a struct
*
* @param msg The message to decode
* @param debug C-struct to decode the message contents into
*/
static inline void mavlink_msg_debug_decode(const mavlink_message_t* msg, mavlink_debug_t* debug)
{
#if MAVLINK_NEED_BYTE_SWAP
debug->ind = mavlink_msg_debug_get_ind(msg);
debug->value = mavlink_msg_debug_get_value(msg);
#else
memcpy(debug, _MAV_PAYLOAD(msg), 5);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v0.9/common/mavlink_msg_debug_vect.h
0,0 → 1,226
// MESSAGE DEBUG_VECT PACKING
 
#define MAVLINK_MSG_ID_DEBUG_VECT 251
 
typedef struct __mavlink_debug_vect_t
{
char name[10]; ///< Name
uint64_t usec; ///< Timestamp
float x; ///< x
float y; ///< y
float z; ///< z
} mavlink_debug_vect_t;
 
#define MAVLINK_MSG_ID_DEBUG_VECT_LEN 30
#define MAVLINK_MSG_ID_251_LEN 30
 
#define MAVLINK_MSG_DEBUG_VECT_FIELD_NAME_LEN 10
 
#define MAVLINK_MESSAGE_INFO_DEBUG_VECT { \
"DEBUG_VECT", \
5, \
{ { "name", NULL, MAVLINK_TYPE_CHAR, 10, 0, offsetof(mavlink_debug_vect_t, name) }, \
{ "usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 10, offsetof(mavlink_debug_vect_t, usec) }, \
{ "x", NULL, MAVLINK_TYPE_FLOAT, 0, 18, offsetof(mavlink_debug_vect_t, x) }, \
{ "y", NULL, MAVLINK_TYPE_FLOAT, 0, 22, offsetof(mavlink_debug_vect_t, y) }, \
{ "z", NULL, MAVLINK_TYPE_FLOAT, 0, 26, offsetof(mavlink_debug_vect_t, z) }, \
} \
}
 
 
/**
* @brief Pack a debug_vect message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param name Name
* @param usec Timestamp
* @param x x
* @param y y
* @param z z
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_debug_vect_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
const char *name, uint64_t usec, float x, float y, float z)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[30];
_mav_put_uint64_t(buf, 10, usec);
_mav_put_float(buf, 18, x);
_mav_put_float(buf, 22, y);
_mav_put_float(buf, 26, z);
_mav_put_char_array(buf, 0, name, 10);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 30);
#else
mavlink_debug_vect_t packet;
packet.usec = usec;
packet.x = x;
packet.y = y;
packet.z = z;
mav_array_memcpy(packet.name, name, sizeof(char)*10);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 30);
#endif
 
msg->msgid = MAVLINK_MSG_ID_DEBUG_VECT;
return mavlink_finalize_message(msg, system_id, component_id, 30);
}
 
/**
* @brief Pack a debug_vect message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param name Name
* @param usec Timestamp
* @param x x
* @param y y
* @param z z
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_debug_vect_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
const char *name,uint64_t usec,float x,float y,float z)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[30];
_mav_put_uint64_t(buf, 10, usec);
_mav_put_float(buf, 18, x);
_mav_put_float(buf, 22, y);
_mav_put_float(buf, 26, z);
_mav_put_char_array(buf, 0, name, 10);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 30);
#else
mavlink_debug_vect_t packet;
packet.usec = usec;
packet.x = x;
packet.y = y;
packet.z = z;
mav_array_memcpy(packet.name, name, sizeof(char)*10);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 30);
#endif
 
msg->msgid = MAVLINK_MSG_ID_DEBUG_VECT;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 30);
}
 
/**
* @brief Encode a debug_vect struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param debug_vect C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_debug_vect_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_debug_vect_t* debug_vect)
{
return mavlink_msg_debug_vect_pack(system_id, component_id, msg, debug_vect->name, debug_vect->usec, debug_vect->x, debug_vect->y, debug_vect->z);
}
 
/**
* @brief Send a debug_vect message
* @param chan MAVLink channel to send the message
*
* @param name Name
* @param usec Timestamp
* @param x x
* @param y y
* @param z z
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_debug_vect_send(mavlink_channel_t chan, const char *name, uint64_t usec, float x, float y, float z)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[30];
_mav_put_uint64_t(buf, 10, usec);
_mav_put_float(buf, 18, x);
_mav_put_float(buf, 22, y);
_mav_put_float(buf, 26, z);
_mav_put_char_array(buf, 0, name, 10);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG_VECT, buf, 30);
#else
mavlink_debug_vect_t packet;
packet.usec = usec;
packet.x = x;
packet.y = y;
packet.z = z;
mav_array_memcpy(packet.name, name, sizeof(char)*10);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG_VECT, (const char *)&packet, 30);
#endif
}
 
#endif
 
// MESSAGE DEBUG_VECT UNPACKING
 
 
/**
* @brief Get field name from debug_vect message
*
* @return Name
*/
static inline uint16_t mavlink_msg_debug_vect_get_name(const mavlink_message_t* msg, char *name)
{
return _MAV_RETURN_char_array(msg, name, 10, 0);
}
 
/**
* @brief Get field usec from debug_vect message
*
* @return Timestamp
*/
static inline uint64_t mavlink_msg_debug_vect_get_usec(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint64_t(msg, 10);
}
 
/**
* @brief Get field x from debug_vect message
*
* @return x
*/
static inline float mavlink_msg_debug_vect_get_x(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 18);
}
 
/**
* @brief Get field y from debug_vect message
*
* @return y
*/
static inline float mavlink_msg_debug_vect_get_y(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 22);
}
 
/**
* @brief Get field z from debug_vect message
*
* @return z
*/
static inline float mavlink_msg_debug_vect_get_z(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 26);
}
 
/**
* @brief Decode a debug_vect message into a struct
*
* @param msg The message to decode
* @param debug_vect C-struct to decode the message contents into
*/
static inline void mavlink_msg_debug_vect_decode(const mavlink_message_t* msg, mavlink_debug_vect_t* debug_vect)
{
#if MAVLINK_NEED_BYTE_SWAP
mavlink_msg_debug_vect_get_name(msg, debug_vect->name);
debug_vect->usec = mavlink_msg_debug_vect_get_usec(msg);
debug_vect->x = mavlink_msg_debug_vect_get_x(msg);
debug_vect->y = mavlink_msg_debug_vect_get_y(msg);
debug_vect->z = mavlink_msg_debug_vect_get_z(msg);
#else
memcpy(debug_vect, _MAV_PAYLOAD(msg), 30);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v0.9/common/mavlink_msg_global_position.h
0,0 → 1,276
// MESSAGE GLOBAL_POSITION PACKING
 
#define MAVLINK_MSG_ID_GLOBAL_POSITION 33
 
typedef struct __mavlink_global_position_t
{
uint64_t usec; ///< Timestamp (microseconds since unix epoch)
float lat; ///< Latitude, in degrees
float lon; ///< Longitude, in degrees
float alt; ///< Absolute altitude, in meters
float vx; ///< X Speed (in Latitude direction, positive: going north)
float vy; ///< Y Speed (in Longitude direction, positive: going east)
float vz; ///< Z Speed (in Altitude direction, positive: going up)
} mavlink_global_position_t;
 
#define MAVLINK_MSG_ID_GLOBAL_POSITION_LEN 32
#define MAVLINK_MSG_ID_33_LEN 32
 
 
 
#define MAVLINK_MESSAGE_INFO_GLOBAL_POSITION { \
"GLOBAL_POSITION", \
7, \
{ { "usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_global_position_t, usec) }, \
{ "lat", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_global_position_t, lat) }, \
{ "lon", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_global_position_t, lon) }, \
{ "alt", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_global_position_t, alt) }, \
{ "vx", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_global_position_t, vx) }, \
{ "vy", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_global_position_t, vy) }, \
{ "vz", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_global_position_t, vz) }, \
} \
}
 
 
/**
* @brief Pack a global_position message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param usec Timestamp (microseconds since unix epoch)
* @param lat Latitude, in degrees
* @param lon Longitude, in degrees
* @param alt Absolute altitude, in meters
* @param vx X Speed (in Latitude direction, positive: going north)
* @param vy Y Speed (in Longitude direction, positive: going east)
* @param vz Z Speed (in Altitude direction, positive: going up)
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_global_position_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint64_t usec, float lat, float lon, float alt, float vx, float vy, float vz)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[32];
_mav_put_uint64_t(buf, 0, usec);
_mav_put_float(buf, 8, lat);
_mav_put_float(buf, 12, lon);
_mav_put_float(buf, 16, alt);
_mav_put_float(buf, 20, vx);
_mav_put_float(buf, 24, vy);
_mav_put_float(buf, 28, vz);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 32);
#else
mavlink_global_position_t packet;
packet.usec = usec;
packet.lat = lat;
packet.lon = lon;
packet.alt = alt;
packet.vx = vx;
packet.vy = vy;
packet.vz = vz;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 32);
#endif
 
msg->msgid = MAVLINK_MSG_ID_GLOBAL_POSITION;
return mavlink_finalize_message(msg, system_id, component_id, 32);
}
 
/**
* @brief Pack a global_position message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param usec Timestamp (microseconds since unix epoch)
* @param lat Latitude, in degrees
* @param lon Longitude, in degrees
* @param alt Absolute altitude, in meters
* @param vx X Speed (in Latitude direction, positive: going north)
* @param vy Y Speed (in Longitude direction, positive: going east)
* @param vz Z Speed (in Altitude direction, positive: going up)
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_global_position_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint64_t usec,float lat,float lon,float alt,float vx,float vy,float vz)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[32];
_mav_put_uint64_t(buf, 0, usec);
_mav_put_float(buf, 8, lat);
_mav_put_float(buf, 12, lon);
_mav_put_float(buf, 16, alt);
_mav_put_float(buf, 20, vx);
_mav_put_float(buf, 24, vy);
_mav_put_float(buf, 28, vz);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 32);
#else
mavlink_global_position_t packet;
packet.usec = usec;
packet.lat = lat;
packet.lon = lon;
packet.alt = alt;
packet.vx = vx;
packet.vy = vy;
packet.vz = vz;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 32);
#endif
 
msg->msgid = MAVLINK_MSG_ID_GLOBAL_POSITION;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 32);
}
 
/**
* @brief Encode a global_position struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param global_position C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_global_position_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_global_position_t* global_position)
{
return mavlink_msg_global_position_pack(system_id, component_id, msg, global_position->usec, global_position->lat, global_position->lon, global_position->alt, global_position->vx, global_position->vy, global_position->vz);
}
 
/**
* @brief Send a global_position message
* @param chan MAVLink channel to send the message
*
* @param usec Timestamp (microseconds since unix epoch)
* @param lat Latitude, in degrees
* @param lon Longitude, in degrees
* @param alt Absolute altitude, in meters
* @param vx X Speed (in Latitude direction, positive: going north)
* @param vy Y Speed (in Longitude direction, positive: going east)
* @param vz Z Speed (in Altitude direction, positive: going up)
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_global_position_send(mavlink_channel_t chan, uint64_t usec, float lat, float lon, float alt, float vx, float vy, float vz)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[32];
_mav_put_uint64_t(buf, 0, usec);
_mav_put_float(buf, 8, lat);
_mav_put_float(buf, 12, lon);
_mav_put_float(buf, 16, alt);
_mav_put_float(buf, 20, vx);
_mav_put_float(buf, 24, vy);
_mav_put_float(buf, 28, vz);
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION, buf, 32);
#else
mavlink_global_position_t packet;
packet.usec = usec;
packet.lat = lat;
packet.lon = lon;
packet.alt = alt;
packet.vx = vx;
packet.vy = vy;
packet.vz = vz;
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION, (const char *)&packet, 32);
#endif
}
 
#endif
 
// MESSAGE GLOBAL_POSITION UNPACKING
 
 
/**
* @brief Get field usec from global_position message
*
* @return Timestamp (microseconds since unix epoch)
*/
static inline uint64_t mavlink_msg_global_position_get_usec(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint64_t(msg, 0);
}
 
/**
* @brief Get field lat from global_position message
*
* @return Latitude, in degrees
*/
static inline float mavlink_msg_global_position_get_lat(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 8);
}
 
/**
* @brief Get field lon from global_position message
*
* @return Longitude, in degrees
*/
static inline float mavlink_msg_global_position_get_lon(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 12);
}
 
/**
* @brief Get field alt from global_position message
*
* @return Absolute altitude, in meters
*/
static inline float mavlink_msg_global_position_get_alt(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 16);
}
 
/**
* @brief Get field vx from global_position message
*
* @return X Speed (in Latitude direction, positive: going north)
*/
static inline float mavlink_msg_global_position_get_vx(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 20);
}
 
/**
* @brief Get field vy from global_position message
*
* @return Y Speed (in Longitude direction, positive: going east)
*/
static inline float mavlink_msg_global_position_get_vy(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 24);
}
 
/**
* @brief Get field vz from global_position message
*
* @return Z Speed (in Altitude direction, positive: going up)
*/
static inline float mavlink_msg_global_position_get_vz(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 28);
}
 
/**
* @brief Decode a global_position message into a struct
*
* @param msg The message to decode
* @param global_position C-struct to decode the message contents into
*/
static inline void mavlink_msg_global_position_decode(const mavlink_message_t* msg, mavlink_global_position_t* global_position)
{
#if MAVLINK_NEED_BYTE_SWAP
global_position->usec = mavlink_msg_global_position_get_usec(msg);
global_position->lat = mavlink_msg_global_position_get_lat(msg);
global_position->lon = mavlink_msg_global_position_get_lon(msg);
global_position->alt = mavlink_msg_global_position_get_alt(msg);
global_position->vx = mavlink_msg_global_position_get_vx(msg);
global_position->vy = mavlink_msg_global_position_get_vy(msg);
global_position->vz = mavlink_msg_global_position_get_vz(msg);
#else
memcpy(global_position, _MAV_PAYLOAD(msg), 32);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v0.9/common/mavlink_msg_global_position_int.h
0,0 → 1,254
// MESSAGE GLOBAL_POSITION_INT PACKING
 
#define MAVLINK_MSG_ID_GLOBAL_POSITION_INT 73
 
typedef struct __mavlink_global_position_int_t
{
int32_t lat; ///< Latitude, expressed as * 1E7
int32_t lon; ///< Longitude, expressed as * 1E7
int32_t alt; ///< Altitude in meters, expressed as * 1000 (millimeters)
int16_t vx; ///< Ground X Speed (Latitude), expressed as m/s * 100
int16_t vy; ///< Ground Y Speed (Longitude), expressed as m/s * 100
int16_t vz; ///< Ground Z Speed (Altitude), expressed as m/s * 100
} mavlink_global_position_int_t;
 
#define MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN 18
#define MAVLINK_MSG_ID_73_LEN 18
 
 
 
#define MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_INT { \
"GLOBAL_POSITION_INT", \
6, \
{ { "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_global_position_int_t, lat) }, \
{ "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_global_position_int_t, lon) }, \
{ "alt", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_global_position_int_t, alt) }, \
{ "vx", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_global_position_int_t, vx) }, \
{ "vy", NULL, MAVLINK_TYPE_INT16_T, 0, 14, offsetof(mavlink_global_position_int_t, vy) }, \
{ "vz", NULL, MAVLINK_TYPE_INT16_T, 0, 16, offsetof(mavlink_global_position_int_t, vz) }, \
} \
}
 
 
/**
* @brief Pack a global_position_int message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param lat Latitude, expressed as * 1E7
* @param lon Longitude, expressed as * 1E7
* @param alt Altitude in meters, expressed as * 1000 (millimeters)
* @param vx Ground X Speed (Latitude), expressed as m/s * 100
* @param vy Ground Y Speed (Longitude), expressed as m/s * 100
* @param vz Ground Z Speed (Altitude), expressed as m/s * 100
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_global_position_int_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
int32_t lat, int32_t lon, int32_t alt, int16_t vx, int16_t vy, int16_t vz)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[18];
_mav_put_int32_t(buf, 0, lat);
_mav_put_int32_t(buf, 4, lon);
_mav_put_int32_t(buf, 8, alt);
_mav_put_int16_t(buf, 12, vx);
_mav_put_int16_t(buf, 14, vy);
_mav_put_int16_t(buf, 16, vz);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 18);
#else
mavlink_global_position_int_t packet;
packet.lat = lat;
packet.lon = lon;
packet.alt = alt;
packet.vx = vx;
packet.vy = vy;
packet.vz = vz;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 18);
#endif
 
msg->msgid = MAVLINK_MSG_ID_GLOBAL_POSITION_INT;
return mavlink_finalize_message(msg, system_id, component_id, 18);
}
 
/**
* @brief Pack a global_position_int message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param lat Latitude, expressed as * 1E7
* @param lon Longitude, expressed as * 1E7
* @param alt Altitude in meters, expressed as * 1000 (millimeters)
* @param vx Ground X Speed (Latitude), expressed as m/s * 100
* @param vy Ground Y Speed (Longitude), expressed as m/s * 100
* @param vz Ground Z Speed (Altitude), expressed as m/s * 100
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_global_position_int_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
int32_t lat,int32_t lon,int32_t alt,int16_t vx,int16_t vy,int16_t vz)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[18];
_mav_put_int32_t(buf, 0, lat);
_mav_put_int32_t(buf, 4, lon);
_mav_put_int32_t(buf, 8, alt);
_mav_put_int16_t(buf, 12, vx);
_mav_put_int16_t(buf, 14, vy);
_mav_put_int16_t(buf, 16, vz);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 18);
#else
mavlink_global_position_int_t packet;
packet.lat = lat;
packet.lon = lon;
packet.alt = alt;
packet.vx = vx;
packet.vy = vy;
packet.vz = vz;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 18);
#endif
 
msg->msgid = MAVLINK_MSG_ID_GLOBAL_POSITION_INT;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 18);
}
 
/**
* @brief Encode a global_position_int struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param global_position_int C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_global_position_int_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_global_position_int_t* global_position_int)
{
return mavlink_msg_global_position_int_pack(system_id, component_id, msg, global_position_int->lat, global_position_int->lon, global_position_int->alt, global_position_int->vx, global_position_int->vy, global_position_int->vz);
}
 
/**
* @brief Send a global_position_int message
* @param chan MAVLink channel to send the message
*
* @param lat Latitude, expressed as * 1E7
* @param lon Longitude, expressed as * 1E7
* @param alt Altitude in meters, expressed as * 1000 (millimeters)
* @param vx Ground X Speed (Latitude), expressed as m/s * 100
* @param vy Ground Y Speed (Longitude), expressed as m/s * 100
* @param vz Ground Z Speed (Altitude), expressed as m/s * 100
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_global_position_int_send(mavlink_channel_t chan, int32_t lat, int32_t lon, int32_t alt, int16_t vx, int16_t vy, int16_t vz)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[18];
_mav_put_int32_t(buf, 0, lat);
_mav_put_int32_t(buf, 4, lon);
_mav_put_int32_t(buf, 8, alt);
_mav_put_int16_t(buf, 12, vx);
_mav_put_int16_t(buf, 14, vy);
_mav_put_int16_t(buf, 16, vz);
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT, buf, 18);
#else
mavlink_global_position_int_t packet;
packet.lat = lat;
packet.lon = lon;
packet.alt = alt;
packet.vx = vx;
packet.vy = vy;
packet.vz = vz;
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT, (const char *)&packet, 18);
#endif
}
 
#endif
 
// MESSAGE GLOBAL_POSITION_INT UNPACKING
 
 
/**
* @brief Get field lat from global_position_int message
*
* @return Latitude, expressed as * 1E7
*/
static inline int32_t mavlink_msg_global_position_int_get_lat(const mavlink_message_t* msg)
{
return _MAV_RETURN_int32_t(msg, 0);
}
 
/**
* @brief Get field lon from global_position_int message
*
* @return Longitude, expressed as * 1E7
*/
static inline int32_t mavlink_msg_global_position_int_get_lon(const mavlink_message_t* msg)
{
return _MAV_RETURN_int32_t(msg, 4);
}
 
/**
* @brief Get field alt from global_position_int message
*
* @return Altitude in meters, expressed as * 1000 (millimeters)
*/
static inline int32_t mavlink_msg_global_position_int_get_alt(const mavlink_message_t* msg)
{
return _MAV_RETURN_int32_t(msg, 8);
}
 
/**
* @brief Get field vx from global_position_int message
*
* @return Ground X Speed (Latitude), expressed as m/s * 100
*/
static inline int16_t mavlink_msg_global_position_int_get_vx(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 12);
}
 
/**
* @brief Get field vy from global_position_int message
*
* @return Ground Y Speed (Longitude), expressed as m/s * 100
*/
static inline int16_t mavlink_msg_global_position_int_get_vy(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 14);
}
 
/**
* @brief Get field vz from global_position_int message
*
* @return Ground Z Speed (Altitude), expressed as m/s * 100
*/
static inline int16_t mavlink_msg_global_position_int_get_vz(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 16);
}
 
/**
* @brief Decode a global_position_int message into a struct
*
* @param msg The message to decode
* @param global_position_int C-struct to decode the message contents into
*/
static inline void mavlink_msg_global_position_int_decode(const mavlink_message_t* msg, mavlink_global_position_int_t* global_position_int)
{
#if MAVLINK_NEED_BYTE_SWAP
global_position_int->lat = mavlink_msg_global_position_int_get_lat(msg);
global_position_int->lon = mavlink_msg_global_position_int_get_lon(msg);
global_position_int->alt = mavlink_msg_global_position_int_get_alt(msg);
global_position_int->vx = mavlink_msg_global_position_int_get_vx(msg);
global_position_int->vy = mavlink_msg_global_position_int_get_vy(msg);
global_position_int->vz = mavlink_msg_global_position_int_get_vz(msg);
#else
memcpy(global_position_int, _MAV_PAYLOAD(msg), 18);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v0.9/common/mavlink_msg_gps_local_origin_set.h
0,0 → 1,188
// MESSAGE GPS_LOCAL_ORIGIN_SET PACKING
 
#define MAVLINK_MSG_ID_GPS_LOCAL_ORIGIN_SET 49
 
typedef struct __mavlink_gps_local_origin_set_t
{
int32_t latitude; ///< Latitude (WGS84), expressed as * 1E7
int32_t longitude; ///< Longitude (WGS84), expressed as * 1E7
int32_t altitude; ///< Altitude(WGS84), expressed as * 1000
} mavlink_gps_local_origin_set_t;
 
#define MAVLINK_MSG_ID_GPS_LOCAL_ORIGIN_SET_LEN 12
#define MAVLINK_MSG_ID_49_LEN 12
 
 
 
#define MAVLINK_MESSAGE_INFO_GPS_LOCAL_ORIGIN_SET { \
"GPS_LOCAL_ORIGIN_SET", \
3, \
{ { "latitude", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_gps_local_origin_set_t, latitude) }, \
{ "longitude", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_gps_local_origin_set_t, longitude) }, \
{ "altitude", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_gps_local_origin_set_t, altitude) }, \
} \
}
 
 
/**
* @brief Pack a gps_local_origin_set message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param latitude Latitude (WGS84), expressed as * 1E7
* @param longitude Longitude (WGS84), expressed as * 1E7
* @param altitude Altitude(WGS84), expressed as * 1000
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_gps_local_origin_set_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
int32_t latitude, int32_t longitude, int32_t altitude)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[12];
_mav_put_int32_t(buf, 0, latitude);
_mav_put_int32_t(buf, 4, longitude);
_mav_put_int32_t(buf, 8, altitude);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 12);
#else
mavlink_gps_local_origin_set_t packet;
packet.latitude = latitude;
packet.longitude = longitude;
packet.altitude = altitude;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 12);
#endif
 
msg->msgid = MAVLINK_MSG_ID_GPS_LOCAL_ORIGIN_SET;
return mavlink_finalize_message(msg, system_id, component_id, 12);
}
 
/**
* @brief Pack a gps_local_origin_set message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param latitude Latitude (WGS84), expressed as * 1E7
* @param longitude Longitude (WGS84), expressed as * 1E7
* @param altitude Altitude(WGS84), expressed as * 1000
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_gps_local_origin_set_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
int32_t latitude,int32_t longitude,int32_t altitude)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[12];
_mav_put_int32_t(buf, 0, latitude);
_mav_put_int32_t(buf, 4, longitude);
_mav_put_int32_t(buf, 8, altitude);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 12);
#else
mavlink_gps_local_origin_set_t packet;
packet.latitude = latitude;
packet.longitude = longitude;
packet.altitude = altitude;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 12);
#endif
 
msg->msgid = MAVLINK_MSG_ID_GPS_LOCAL_ORIGIN_SET;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 12);
}
 
/**
* @brief Encode a gps_local_origin_set struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param gps_local_origin_set C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_gps_local_origin_set_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gps_local_origin_set_t* gps_local_origin_set)
{
return mavlink_msg_gps_local_origin_set_pack(system_id, component_id, msg, gps_local_origin_set->latitude, gps_local_origin_set->longitude, gps_local_origin_set->altitude);
}
 
/**
* @brief Send a gps_local_origin_set message
* @param chan MAVLink channel to send the message
*
* @param latitude Latitude (WGS84), expressed as * 1E7
* @param longitude Longitude (WGS84), expressed as * 1E7
* @param altitude Altitude(WGS84), expressed as * 1000
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_gps_local_origin_set_send(mavlink_channel_t chan, int32_t latitude, int32_t longitude, int32_t altitude)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[12];
_mav_put_int32_t(buf, 0, latitude);
_mav_put_int32_t(buf, 4, longitude);
_mav_put_int32_t(buf, 8, altitude);
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_LOCAL_ORIGIN_SET, buf, 12);
#else
mavlink_gps_local_origin_set_t packet;
packet.latitude = latitude;
packet.longitude = longitude;
packet.altitude = altitude;
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_LOCAL_ORIGIN_SET, (const char *)&packet, 12);
#endif
}
 
#endif
 
// MESSAGE GPS_LOCAL_ORIGIN_SET UNPACKING
 
 
/**
* @brief Get field latitude from gps_local_origin_set message
*
* @return Latitude (WGS84), expressed as * 1E7
*/
static inline int32_t mavlink_msg_gps_local_origin_set_get_latitude(const mavlink_message_t* msg)
{
return _MAV_RETURN_int32_t(msg, 0);
}
 
/**
* @brief Get field longitude from gps_local_origin_set message
*
* @return Longitude (WGS84), expressed as * 1E7
*/
static inline int32_t mavlink_msg_gps_local_origin_set_get_longitude(const mavlink_message_t* msg)
{
return _MAV_RETURN_int32_t(msg, 4);
}
 
/**
* @brief Get field altitude from gps_local_origin_set message
*
* @return Altitude(WGS84), expressed as * 1000
*/
static inline int32_t mavlink_msg_gps_local_origin_set_get_altitude(const mavlink_message_t* msg)
{
return _MAV_RETURN_int32_t(msg, 8);
}
 
/**
* @brief Decode a gps_local_origin_set message into a struct
*
* @param msg The message to decode
* @param gps_local_origin_set C-struct to decode the message contents into
*/
static inline void mavlink_msg_gps_local_origin_set_decode(const mavlink_message_t* msg, mavlink_gps_local_origin_set_t* gps_local_origin_set)
{
#if MAVLINK_NEED_BYTE_SWAP
gps_local_origin_set->latitude = mavlink_msg_gps_local_origin_set_get_latitude(msg);
gps_local_origin_set->longitude = mavlink_msg_gps_local_origin_set_get_longitude(msg);
gps_local_origin_set->altitude = mavlink_msg_gps_local_origin_set_get_altitude(msg);
#else
memcpy(gps_local_origin_set, _MAV_PAYLOAD(msg), 12);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v0.9/common/mavlink_msg_gps_raw.h
0,0 → 1,320
// MESSAGE GPS_RAW PACKING
 
#define MAVLINK_MSG_ID_GPS_RAW 32
 
typedef struct __mavlink_gps_raw_t
{
uint64_t usec; ///< Timestamp (microseconds since UNIX epoch or microseconds since system boot)
uint8_t fix_type; ///< 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix.
float lat; ///< Latitude in degrees
float lon; ///< Longitude in degrees
float alt; ///< Altitude in meters
float eph; ///< GPS HDOP
float epv; ///< GPS VDOP
float v; ///< GPS ground speed
float hdg; ///< Compass heading in degrees, 0..360 degrees
} mavlink_gps_raw_t;
 
#define MAVLINK_MSG_ID_GPS_RAW_LEN 37
#define MAVLINK_MSG_ID_32_LEN 37
 
 
 
#define MAVLINK_MESSAGE_INFO_GPS_RAW { \
"GPS_RAW", \
9, \
{ { "usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_gps_raw_t, usec) }, \
{ "fix_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_gps_raw_t, fix_type) }, \
{ "lat", NULL, MAVLINK_TYPE_FLOAT, 0, 9, offsetof(mavlink_gps_raw_t, lat) }, \
{ "lon", NULL, MAVLINK_TYPE_FLOAT, 0, 13, offsetof(mavlink_gps_raw_t, lon) }, \
{ "alt", NULL, MAVLINK_TYPE_FLOAT, 0, 17, offsetof(mavlink_gps_raw_t, alt) }, \
{ "eph", NULL, MAVLINK_TYPE_FLOAT, 0, 21, offsetof(mavlink_gps_raw_t, eph) }, \
{ "epv", NULL, MAVLINK_TYPE_FLOAT, 0, 25, offsetof(mavlink_gps_raw_t, epv) }, \
{ "v", NULL, MAVLINK_TYPE_FLOAT, 0, 29, offsetof(mavlink_gps_raw_t, v) }, \
{ "hdg", NULL, MAVLINK_TYPE_FLOAT, 0, 33, offsetof(mavlink_gps_raw_t, hdg) }, \
} \
}
 
 
/**
* @brief Pack a gps_raw message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
* @param fix_type 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix.
* @param lat Latitude in degrees
* @param lon Longitude in degrees
* @param alt Altitude in meters
* @param eph GPS HDOP
* @param epv GPS VDOP
* @param v GPS ground speed
* @param hdg Compass heading in degrees, 0..360 degrees
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_gps_raw_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint64_t usec, uint8_t fix_type, float lat, float lon, float alt, float eph, float epv, float v, float hdg)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[37];
_mav_put_uint64_t(buf, 0, usec);
_mav_put_uint8_t(buf, 8, fix_type);
_mav_put_float(buf, 9, lat);
_mav_put_float(buf, 13, lon);
_mav_put_float(buf, 17, alt);
_mav_put_float(buf, 21, eph);
_mav_put_float(buf, 25, epv);
_mav_put_float(buf, 29, v);
_mav_put_float(buf, 33, hdg);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 37);
#else
mavlink_gps_raw_t packet;
packet.usec = usec;
packet.fix_type = fix_type;
packet.lat = lat;
packet.lon = lon;
packet.alt = alt;
packet.eph = eph;
packet.epv = epv;
packet.v = v;
packet.hdg = hdg;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 37);
#endif
 
msg->msgid = MAVLINK_MSG_ID_GPS_RAW;
return mavlink_finalize_message(msg, system_id, component_id, 37);
}
 
/**
* @brief Pack a gps_raw message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
* @param fix_type 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix.
* @param lat Latitude in degrees
* @param lon Longitude in degrees
* @param alt Altitude in meters
* @param eph GPS HDOP
* @param epv GPS VDOP
* @param v GPS ground speed
* @param hdg Compass heading in degrees, 0..360 degrees
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_gps_raw_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint64_t usec,uint8_t fix_type,float lat,float lon,float alt,float eph,float epv,float v,float hdg)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[37];
_mav_put_uint64_t(buf, 0, usec);
_mav_put_uint8_t(buf, 8, fix_type);
_mav_put_float(buf, 9, lat);
_mav_put_float(buf, 13, lon);
_mav_put_float(buf, 17, alt);
_mav_put_float(buf, 21, eph);
_mav_put_float(buf, 25, epv);
_mav_put_float(buf, 29, v);
_mav_put_float(buf, 33, hdg);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 37);
#else
mavlink_gps_raw_t packet;
packet.usec = usec;
packet.fix_type = fix_type;
packet.lat = lat;
packet.lon = lon;
packet.alt = alt;
packet.eph = eph;
packet.epv = epv;
packet.v = v;
packet.hdg = hdg;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 37);
#endif
 
msg->msgid = MAVLINK_MSG_ID_GPS_RAW;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 37);
}
 
/**
* @brief Encode a gps_raw struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param gps_raw C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_gps_raw_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gps_raw_t* gps_raw)
{
return mavlink_msg_gps_raw_pack(system_id, component_id, msg, gps_raw->usec, gps_raw->fix_type, gps_raw->lat, gps_raw->lon, gps_raw->alt, gps_raw->eph, gps_raw->epv, gps_raw->v, gps_raw->hdg);
}
 
/**
* @brief Send a gps_raw message
* @param chan MAVLink channel to send the message
*
* @param usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
* @param fix_type 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix.
* @param lat Latitude in degrees
* @param lon Longitude in degrees
* @param alt Altitude in meters
* @param eph GPS HDOP
* @param epv GPS VDOP
* @param v GPS ground speed
* @param hdg Compass heading in degrees, 0..360 degrees
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_gps_raw_send(mavlink_channel_t chan, uint64_t usec, uint8_t fix_type, float lat, float lon, float alt, float eph, float epv, float v, float hdg)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[37];
_mav_put_uint64_t(buf, 0, usec);
_mav_put_uint8_t(buf, 8, fix_type);
_mav_put_float(buf, 9, lat);
_mav_put_float(buf, 13, lon);
_mav_put_float(buf, 17, alt);
_mav_put_float(buf, 21, eph);
_mav_put_float(buf, 25, epv);
_mav_put_float(buf, 29, v);
_mav_put_float(buf, 33, hdg);
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RAW, buf, 37);
#else
mavlink_gps_raw_t packet;
packet.usec = usec;
packet.fix_type = fix_type;
packet.lat = lat;
packet.lon = lon;
packet.alt = alt;
packet.eph = eph;
packet.epv = epv;
packet.v = v;
packet.hdg = hdg;
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RAW, (const char *)&packet, 37);
#endif
}
 
#endif
 
// MESSAGE GPS_RAW UNPACKING
 
 
/**
* @brief Get field usec from gps_raw message
*
* @return Timestamp (microseconds since UNIX epoch or microseconds since system boot)
*/
static inline uint64_t mavlink_msg_gps_raw_get_usec(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint64_t(msg, 0);
}
 
/**
* @brief Get field fix_type from gps_raw message
*
* @return 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix.
*/
static inline uint8_t mavlink_msg_gps_raw_get_fix_type(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 8);
}
 
/**
* @brief Get field lat from gps_raw message
*
* @return Latitude in degrees
*/
static inline float mavlink_msg_gps_raw_get_lat(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 9);
}
 
/**
* @brief Get field lon from gps_raw message
*
* @return Longitude in degrees
*/
static inline float mavlink_msg_gps_raw_get_lon(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 13);
}
 
/**
* @brief Get field alt from gps_raw message
*
* @return Altitude in meters
*/
static inline float mavlink_msg_gps_raw_get_alt(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 17);
}
 
/**
* @brief Get field eph from gps_raw message
*
* @return GPS HDOP
*/
static inline float mavlink_msg_gps_raw_get_eph(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 21);
}
 
/**
* @brief Get field epv from gps_raw message
*
* @return GPS VDOP
*/
static inline float mavlink_msg_gps_raw_get_epv(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 25);
}
 
/**
* @brief Get field v from gps_raw message
*
* @return GPS ground speed
*/
static inline float mavlink_msg_gps_raw_get_v(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 29);
}
 
/**
* @brief Get field hdg from gps_raw message
*
* @return Compass heading in degrees, 0..360 degrees
*/
static inline float mavlink_msg_gps_raw_get_hdg(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 33);
}
 
/**
* @brief Decode a gps_raw message into a struct
*
* @param msg The message to decode
* @param gps_raw C-struct to decode the message contents into
*/
static inline void mavlink_msg_gps_raw_decode(const mavlink_message_t* msg, mavlink_gps_raw_t* gps_raw)
{
#if MAVLINK_NEED_BYTE_SWAP
gps_raw->usec = mavlink_msg_gps_raw_get_usec(msg);
gps_raw->fix_type = mavlink_msg_gps_raw_get_fix_type(msg);
gps_raw->lat = mavlink_msg_gps_raw_get_lat(msg);
gps_raw->lon = mavlink_msg_gps_raw_get_lon(msg);
gps_raw->alt = mavlink_msg_gps_raw_get_alt(msg);
gps_raw->eph = mavlink_msg_gps_raw_get_eph(msg);
gps_raw->epv = mavlink_msg_gps_raw_get_epv(msg);
gps_raw->v = mavlink_msg_gps_raw_get_v(msg);
gps_raw->hdg = mavlink_msg_gps_raw_get_hdg(msg);
#else
memcpy(gps_raw, _MAV_PAYLOAD(msg), 37);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v0.9/common/mavlink_msg_gps_raw_int.h
0,0 → 1,320
// MESSAGE GPS_RAW_INT PACKING
 
#define MAVLINK_MSG_ID_GPS_RAW_INT 25
 
typedef struct __mavlink_gps_raw_int_t
{
uint64_t usec; ///< Timestamp (microseconds since UNIX epoch or microseconds since system boot)
uint8_t fix_type; ///< 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix.
int32_t lat; ///< Latitude in 1E7 degrees
int32_t lon; ///< Longitude in 1E7 degrees
int32_t alt; ///< Altitude in 1E3 meters (millimeters)
float eph; ///< GPS HDOP
float epv; ///< GPS VDOP
float v; ///< GPS ground speed (m/s)
float hdg; ///< Compass heading in degrees, 0..360 degrees
} mavlink_gps_raw_int_t;
 
#define MAVLINK_MSG_ID_GPS_RAW_INT_LEN 37
#define MAVLINK_MSG_ID_25_LEN 37
 
 
 
#define MAVLINK_MESSAGE_INFO_GPS_RAW_INT { \
"GPS_RAW_INT", \
9, \
{ { "usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_gps_raw_int_t, usec) }, \
{ "fix_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_gps_raw_int_t, fix_type) }, \
{ "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 9, offsetof(mavlink_gps_raw_int_t, lat) }, \
{ "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 13, offsetof(mavlink_gps_raw_int_t, lon) }, \
{ "alt", NULL, MAVLINK_TYPE_INT32_T, 0, 17, offsetof(mavlink_gps_raw_int_t, alt) }, \
{ "eph", NULL, MAVLINK_TYPE_FLOAT, 0, 21, offsetof(mavlink_gps_raw_int_t, eph) }, \
{ "epv", NULL, MAVLINK_TYPE_FLOAT, 0, 25, offsetof(mavlink_gps_raw_int_t, epv) }, \
{ "v", NULL, MAVLINK_TYPE_FLOAT, 0, 29, offsetof(mavlink_gps_raw_int_t, v) }, \
{ "hdg", NULL, MAVLINK_TYPE_FLOAT, 0, 33, offsetof(mavlink_gps_raw_int_t, hdg) }, \
} \
}
 
 
/**
* @brief Pack a gps_raw_int message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
* @param fix_type 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix.
* @param lat Latitude in 1E7 degrees
* @param lon Longitude in 1E7 degrees
* @param alt Altitude in 1E3 meters (millimeters)
* @param eph GPS HDOP
* @param epv GPS VDOP
* @param v GPS ground speed (m/s)
* @param hdg Compass heading in degrees, 0..360 degrees
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_gps_raw_int_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint64_t usec, uint8_t fix_type, int32_t lat, int32_t lon, int32_t alt, float eph, float epv, float v, float hdg)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[37];
_mav_put_uint64_t(buf, 0, usec);
_mav_put_uint8_t(buf, 8, fix_type);
_mav_put_int32_t(buf, 9, lat);
_mav_put_int32_t(buf, 13, lon);
_mav_put_int32_t(buf, 17, alt);
_mav_put_float(buf, 21, eph);
_mav_put_float(buf, 25, epv);
_mav_put_float(buf, 29, v);
_mav_put_float(buf, 33, hdg);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 37);
#else
mavlink_gps_raw_int_t packet;
packet.usec = usec;
packet.fix_type = fix_type;
packet.lat = lat;
packet.lon = lon;
packet.alt = alt;
packet.eph = eph;
packet.epv = epv;
packet.v = v;
packet.hdg = hdg;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 37);
#endif
 
msg->msgid = MAVLINK_MSG_ID_GPS_RAW_INT;
return mavlink_finalize_message(msg, system_id, component_id, 37);
}
 
/**
* @brief Pack a gps_raw_int message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
* @param fix_type 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix.
* @param lat Latitude in 1E7 degrees
* @param lon Longitude in 1E7 degrees
* @param alt Altitude in 1E3 meters (millimeters)
* @param eph GPS HDOP
* @param epv GPS VDOP
* @param v GPS ground speed (m/s)
* @param hdg Compass heading in degrees, 0..360 degrees
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_gps_raw_int_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint64_t usec,uint8_t fix_type,int32_t lat,int32_t lon,int32_t alt,float eph,float epv,float v,float hdg)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[37];
_mav_put_uint64_t(buf, 0, usec);
_mav_put_uint8_t(buf, 8, fix_type);
_mav_put_int32_t(buf, 9, lat);
_mav_put_int32_t(buf, 13, lon);
_mav_put_int32_t(buf, 17, alt);
_mav_put_float(buf, 21, eph);
_mav_put_float(buf, 25, epv);
_mav_put_float(buf, 29, v);
_mav_put_float(buf, 33, hdg);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 37);
#else
mavlink_gps_raw_int_t packet;
packet.usec = usec;
packet.fix_type = fix_type;
packet.lat = lat;
packet.lon = lon;
packet.alt = alt;
packet.eph = eph;
packet.epv = epv;
packet.v = v;
packet.hdg = hdg;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 37);
#endif
 
msg->msgid = MAVLINK_MSG_ID_GPS_RAW_INT;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 37);
}
 
/**
* @brief Encode a gps_raw_int struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param gps_raw_int C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_gps_raw_int_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gps_raw_int_t* gps_raw_int)
{
return mavlink_msg_gps_raw_int_pack(system_id, component_id, msg, gps_raw_int->usec, gps_raw_int->fix_type, gps_raw_int->lat, gps_raw_int->lon, gps_raw_int->alt, gps_raw_int->eph, gps_raw_int->epv, gps_raw_int->v, gps_raw_int->hdg);
}
 
/**
* @brief Send a gps_raw_int message
* @param chan MAVLink channel to send the message
*
* @param usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
* @param fix_type 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix.
* @param lat Latitude in 1E7 degrees
* @param lon Longitude in 1E7 degrees
* @param alt Altitude in 1E3 meters (millimeters)
* @param eph GPS HDOP
* @param epv GPS VDOP
* @param v GPS ground speed (m/s)
* @param hdg Compass heading in degrees, 0..360 degrees
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_gps_raw_int_send(mavlink_channel_t chan, uint64_t usec, uint8_t fix_type, int32_t lat, int32_t lon, int32_t alt, float eph, float epv, float v, float hdg)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[37];
_mav_put_uint64_t(buf, 0, usec);
_mav_put_uint8_t(buf, 8, fix_type);
_mav_put_int32_t(buf, 9, lat);
_mav_put_int32_t(buf, 13, lon);
_mav_put_int32_t(buf, 17, alt);
_mav_put_float(buf, 21, eph);
_mav_put_float(buf, 25, epv);
_mav_put_float(buf, 29, v);
_mav_put_float(buf, 33, hdg);
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RAW_INT, buf, 37);
#else
mavlink_gps_raw_int_t packet;
packet.usec = usec;
packet.fix_type = fix_type;
packet.lat = lat;
packet.lon = lon;
packet.alt = alt;
packet.eph = eph;
packet.epv = epv;
packet.v = v;
packet.hdg = hdg;
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RAW_INT, (const char *)&packet, 37);
#endif
}
 
#endif
 
// MESSAGE GPS_RAW_INT UNPACKING
 
 
/**
* @brief Get field usec from gps_raw_int message
*
* @return Timestamp (microseconds since UNIX epoch or microseconds since system boot)
*/
static inline uint64_t mavlink_msg_gps_raw_int_get_usec(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint64_t(msg, 0);
}
 
/**
* @brief Get field fix_type from gps_raw_int message
*
* @return 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix.
*/
static inline uint8_t mavlink_msg_gps_raw_int_get_fix_type(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 8);
}
 
/**
* @brief Get field lat from gps_raw_int message
*
* @return Latitude in 1E7 degrees
*/
static inline int32_t mavlink_msg_gps_raw_int_get_lat(const mavlink_message_t* msg)
{
return _MAV_RETURN_int32_t(msg, 9);
}
 
/**
* @brief Get field lon from gps_raw_int message
*
* @return Longitude in 1E7 degrees
*/
static inline int32_t mavlink_msg_gps_raw_int_get_lon(const mavlink_message_t* msg)
{
return _MAV_RETURN_int32_t(msg, 13);
}
 
/**
* @brief Get field alt from gps_raw_int message
*
* @return Altitude in 1E3 meters (millimeters)
*/
static inline int32_t mavlink_msg_gps_raw_int_get_alt(const mavlink_message_t* msg)
{
return _MAV_RETURN_int32_t(msg, 17);
}
 
/**
* @brief Get field eph from gps_raw_int message
*
* @return GPS HDOP
*/
static inline float mavlink_msg_gps_raw_int_get_eph(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 21);
}
 
/**
* @brief Get field epv from gps_raw_int message
*
* @return GPS VDOP
*/
static inline float mavlink_msg_gps_raw_int_get_epv(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 25);
}
 
/**
* @brief Get field v from gps_raw_int message
*
* @return GPS ground speed (m/s)
*/
static inline float mavlink_msg_gps_raw_int_get_v(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 29);
}
 
/**
* @brief Get field hdg from gps_raw_int message
*
* @return Compass heading in degrees, 0..360 degrees
*/
static inline float mavlink_msg_gps_raw_int_get_hdg(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 33);
}
 
/**
* @brief Decode a gps_raw_int message into a struct
*
* @param msg The message to decode
* @param gps_raw_int C-struct to decode the message contents into
*/
static inline void mavlink_msg_gps_raw_int_decode(const mavlink_message_t* msg, mavlink_gps_raw_int_t* gps_raw_int)
{
#if MAVLINK_NEED_BYTE_SWAP
gps_raw_int->usec = mavlink_msg_gps_raw_int_get_usec(msg);
gps_raw_int->fix_type = mavlink_msg_gps_raw_int_get_fix_type(msg);
gps_raw_int->lat = mavlink_msg_gps_raw_int_get_lat(msg);
gps_raw_int->lon = mavlink_msg_gps_raw_int_get_lon(msg);
gps_raw_int->alt = mavlink_msg_gps_raw_int_get_alt(msg);
gps_raw_int->eph = mavlink_msg_gps_raw_int_get_eph(msg);
gps_raw_int->epv = mavlink_msg_gps_raw_int_get_epv(msg);
gps_raw_int->v = mavlink_msg_gps_raw_int_get_v(msg);
gps_raw_int->hdg = mavlink_msg_gps_raw_int_get_hdg(msg);
#else
memcpy(gps_raw_int, _MAV_PAYLOAD(msg), 37);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v0.9/common/mavlink_msg_gps_set_global_origin.h
0,0 → 1,232
// MESSAGE GPS_SET_GLOBAL_ORIGIN PACKING
 
#define MAVLINK_MSG_ID_GPS_SET_GLOBAL_ORIGIN 48
 
typedef struct __mavlink_gps_set_global_origin_t
{
uint8_t target_system; ///< System ID
uint8_t target_component; ///< Component ID
int32_t latitude; ///< global position * 1E7
int32_t longitude; ///< global position * 1E7
int32_t altitude; ///< global position * 1000
} mavlink_gps_set_global_origin_t;
 
#define MAVLINK_MSG_ID_GPS_SET_GLOBAL_ORIGIN_LEN 14
#define MAVLINK_MSG_ID_48_LEN 14
 
 
 
#define MAVLINK_MESSAGE_INFO_GPS_SET_GLOBAL_ORIGIN { \
"GPS_SET_GLOBAL_ORIGIN", \
5, \
{ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_gps_set_global_origin_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_gps_set_global_origin_t, target_component) }, \
{ "latitude", NULL, MAVLINK_TYPE_INT32_T, 0, 2, offsetof(mavlink_gps_set_global_origin_t, latitude) }, \
{ "longitude", NULL, MAVLINK_TYPE_INT32_T, 0, 6, offsetof(mavlink_gps_set_global_origin_t, longitude) }, \
{ "altitude", NULL, MAVLINK_TYPE_INT32_T, 0, 10, offsetof(mavlink_gps_set_global_origin_t, altitude) }, \
} \
}
 
 
/**
* @brief Pack a gps_set_global_origin message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param target_system System ID
* @param target_component Component ID
* @param latitude global position * 1E7
* @param longitude global position * 1E7
* @param altitude global position * 1000
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_gps_set_global_origin_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t target_system, uint8_t target_component, int32_t latitude, int32_t longitude, int32_t altitude)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[14];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
_mav_put_int32_t(buf, 2, latitude);
_mav_put_int32_t(buf, 6, longitude);
_mav_put_int32_t(buf, 10, altitude);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 14);
#else
mavlink_gps_set_global_origin_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
packet.latitude = latitude;
packet.longitude = longitude;
packet.altitude = altitude;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 14);
#endif
 
msg->msgid = MAVLINK_MSG_ID_GPS_SET_GLOBAL_ORIGIN;
return mavlink_finalize_message(msg, system_id, component_id, 14);
}
 
/**
* @brief Pack a gps_set_global_origin message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param target_system System ID
* @param target_component Component ID
* @param latitude global position * 1E7
* @param longitude global position * 1E7
* @param altitude global position * 1000
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_gps_set_global_origin_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,int32_t latitude,int32_t longitude,int32_t altitude)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[14];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
_mav_put_int32_t(buf, 2, latitude);
_mav_put_int32_t(buf, 6, longitude);
_mav_put_int32_t(buf, 10, altitude);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 14);
#else
mavlink_gps_set_global_origin_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
packet.latitude = latitude;
packet.longitude = longitude;
packet.altitude = altitude;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 14);
#endif
 
msg->msgid = MAVLINK_MSG_ID_GPS_SET_GLOBAL_ORIGIN;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 14);
}
 
/**
* @brief Encode a gps_set_global_origin struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param gps_set_global_origin C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_gps_set_global_origin_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gps_set_global_origin_t* gps_set_global_origin)
{
return mavlink_msg_gps_set_global_origin_pack(system_id, component_id, msg, gps_set_global_origin->target_system, gps_set_global_origin->target_component, gps_set_global_origin->latitude, gps_set_global_origin->longitude, gps_set_global_origin->altitude);
}
 
/**
* @brief Send a gps_set_global_origin message
* @param chan MAVLink channel to send the message
*
* @param target_system System ID
* @param target_component Component ID
* @param latitude global position * 1E7
* @param longitude global position * 1E7
* @param altitude global position * 1000
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_gps_set_global_origin_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, int32_t latitude, int32_t longitude, int32_t altitude)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[14];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
_mav_put_int32_t(buf, 2, latitude);
_mav_put_int32_t(buf, 6, longitude);
_mav_put_int32_t(buf, 10, altitude);
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_SET_GLOBAL_ORIGIN, buf, 14);
#else
mavlink_gps_set_global_origin_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
packet.latitude = latitude;
packet.longitude = longitude;
packet.altitude = altitude;
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_SET_GLOBAL_ORIGIN, (const char *)&packet, 14);
#endif
}
 
#endif
 
// MESSAGE GPS_SET_GLOBAL_ORIGIN UNPACKING
 
 
/**
* @brief Get field target_system from gps_set_global_origin message
*
* @return System ID
*/
static inline uint8_t mavlink_msg_gps_set_global_origin_get_target_system(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 0);
}
 
/**
* @brief Get field target_component from gps_set_global_origin message
*
* @return Component ID
*/
static inline uint8_t mavlink_msg_gps_set_global_origin_get_target_component(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 1);
}
 
/**
* @brief Get field latitude from gps_set_global_origin message
*
* @return global position * 1E7
*/
static inline int32_t mavlink_msg_gps_set_global_origin_get_latitude(const mavlink_message_t* msg)
{
return _MAV_RETURN_int32_t(msg, 2);
}
 
/**
* @brief Get field longitude from gps_set_global_origin message
*
* @return global position * 1E7
*/
static inline int32_t mavlink_msg_gps_set_global_origin_get_longitude(const mavlink_message_t* msg)
{
return _MAV_RETURN_int32_t(msg, 6);
}
 
/**
* @brief Get field altitude from gps_set_global_origin message
*
* @return global position * 1000
*/
static inline int32_t mavlink_msg_gps_set_global_origin_get_altitude(const mavlink_message_t* msg)
{
return _MAV_RETURN_int32_t(msg, 10);
}
 
/**
* @brief Decode a gps_set_global_origin message into a struct
*
* @param msg The message to decode
* @param gps_set_global_origin C-struct to decode the message contents into
*/
static inline void mavlink_msg_gps_set_global_origin_decode(const mavlink_message_t* msg, mavlink_gps_set_global_origin_t* gps_set_global_origin)
{
#if MAVLINK_NEED_BYTE_SWAP
gps_set_global_origin->target_system = mavlink_msg_gps_set_global_origin_get_target_system(msg);
gps_set_global_origin->target_component = mavlink_msg_gps_set_global_origin_get_target_component(msg);
gps_set_global_origin->latitude = mavlink_msg_gps_set_global_origin_get_latitude(msg);
gps_set_global_origin->longitude = mavlink_msg_gps_set_global_origin_get_longitude(msg);
gps_set_global_origin->altitude = mavlink_msg_gps_set_global_origin_get_altitude(msg);
#else
memcpy(gps_set_global_origin, _MAV_PAYLOAD(msg), 14);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v0.9/common/mavlink_msg_gps_status.h
0,0 → 1,252
// MESSAGE GPS_STATUS PACKING
 
#define MAVLINK_MSG_ID_GPS_STATUS 27
 
typedef struct __mavlink_gps_status_t
{
uint8_t satellites_visible; ///< Number of satellites visible
int8_t satellite_prn[20]; ///< Global satellite ID
int8_t satellite_used[20]; ///< 0: Satellite not used, 1: used for localization
int8_t satellite_elevation[20]; ///< Elevation (0: right on top of receiver, 90: on the horizon) of satellite
int8_t satellite_azimuth[20]; ///< Direction of satellite, 0: 0 deg, 255: 360 deg.
int8_t satellite_snr[20]; ///< Signal to noise ratio of satellite
} mavlink_gps_status_t;
 
#define MAVLINK_MSG_ID_GPS_STATUS_LEN 101
#define MAVLINK_MSG_ID_27_LEN 101
 
#define MAVLINK_MSG_GPS_STATUS_FIELD_SATELLITE_PRN_LEN 20
#define MAVLINK_MSG_GPS_STATUS_FIELD_SATELLITE_USED_LEN 20
#define MAVLINK_MSG_GPS_STATUS_FIELD_SATELLITE_ELEVATION_LEN 20
#define MAVLINK_MSG_GPS_STATUS_FIELD_SATELLITE_AZIMUTH_LEN 20
#define MAVLINK_MSG_GPS_STATUS_FIELD_SATELLITE_SNR_LEN 20
 
#define MAVLINK_MESSAGE_INFO_GPS_STATUS { \
"GPS_STATUS", \
6, \
{ { "satellites_visible", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_gps_status_t, satellites_visible) }, \
{ "satellite_prn", NULL, MAVLINK_TYPE_INT8_T, 20, 1, offsetof(mavlink_gps_status_t, satellite_prn) }, \
{ "satellite_used", NULL, MAVLINK_TYPE_INT8_T, 20, 21, offsetof(mavlink_gps_status_t, satellite_used) }, \
{ "satellite_elevation", NULL, MAVLINK_TYPE_INT8_T, 20, 41, offsetof(mavlink_gps_status_t, satellite_elevation) }, \
{ "satellite_azimuth", NULL, MAVLINK_TYPE_INT8_T, 20, 61, offsetof(mavlink_gps_status_t, satellite_azimuth) }, \
{ "satellite_snr", NULL, MAVLINK_TYPE_INT8_T, 20, 81, offsetof(mavlink_gps_status_t, satellite_snr) }, \
} \
}
 
 
/**
* @brief Pack a gps_status message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param satellites_visible Number of satellites visible
* @param satellite_prn Global satellite ID
* @param satellite_used 0: Satellite not used, 1: used for localization
* @param satellite_elevation Elevation (0: right on top of receiver, 90: on the horizon) of satellite
* @param satellite_azimuth Direction of satellite, 0: 0 deg, 255: 360 deg.
* @param satellite_snr Signal to noise ratio of satellite
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_gps_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t satellites_visible, const int8_t *satellite_prn, const int8_t *satellite_used, const int8_t *satellite_elevation, const int8_t *satellite_azimuth, const int8_t *satellite_snr)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[101];
_mav_put_uint8_t(buf, 0, satellites_visible);
_mav_put_int8_t_array(buf, 1, satellite_prn, 20);
_mav_put_int8_t_array(buf, 21, satellite_used, 20);
_mav_put_int8_t_array(buf, 41, satellite_elevation, 20);
_mav_put_int8_t_array(buf, 61, satellite_azimuth, 20);
_mav_put_int8_t_array(buf, 81, satellite_snr, 20);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 101);
#else
mavlink_gps_status_t packet;
packet.satellites_visible = satellites_visible;
mav_array_memcpy(packet.satellite_prn, satellite_prn, sizeof(int8_t)*20);
mav_array_memcpy(packet.satellite_used, satellite_used, sizeof(int8_t)*20);
mav_array_memcpy(packet.satellite_elevation, satellite_elevation, sizeof(int8_t)*20);
mav_array_memcpy(packet.satellite_azimuth, satellite_azimuth, sizeof(int8_t)*20);
mav_array_memcpy(packet.satellite_snr, satellite_snr, sizeof(int8_t)*20);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 101);
#endif
 
msg->msgid = MAVLINK_MSG_ID_GPS_STATUS;
return mavlink_finalize_message(msg, system_id, component_id, 101);
}
 
/**
* @brief Pack a gps_status message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param satellites_visible Number of satellites visible
* @param satellite_prn Global satellite ID
* @param satellite_used 0: Satellite not used, 1: used for localization
* @param satellite_elevation Elevation (0: right on top of receiver, 90: on the horizon) of satellite
* @param satellite_azimuth Direction of satellite, 0: 0 deg, 255: 360 deg.
* @param satellite_snr Signal to noise ratio of satellite
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_gps_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint8_t satellites_visible,const int8_t *satellite_prn,const int8_t *satellite_used,const int8_t *satellite_elevation,const int8_t *satellite_azimuth,const int8_t *satellite_snr)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[101];
_mav_put_uint8_t(buf, 0, satellites_visible);
_mav_put_int8_t_array(buf, 1, satellite_prn, 20);
_mav_put_int8_t_array(buf, 21, satellite_used, 20);
_mav_put_int8_t_array(buf, 41, satellite_elevation, 20);
_mav_put_int8_t_array(buf, 61, satellite_azimuth, 20);
_mav_put_int8_t_array(buf, 81, satellite_snr, 20);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 101);
#else
mavlink_gps_status_t packet;
packet.satellites_visible = satellites_visible;
mav_array_memcpy(packet.satellite_prn, satellite_prn, sizeof(int8_t)*20);
mav_array_memcpy(packet.satellite_used, satellite_used, sizeof(int8_t)*20);
mav_array_memcpy(packet.satellite_elevation, satellite_elevation, sizeof(int8_t)*20);
mav_array_memcpy(packet.satellite_azimuth, satellite_azimuth, sizeof(int8_t)*20);
mav_array_memcpy(packet.satellite_snr, satellite_snr, sizeof(int8_t)*20);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 101);
#endif
 
msg->msgid = MAVLINK_MSG_ID_GPS_STATUS;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 101);
}
 
/**
* @brief Encode a gps_status struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param gps_status C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_gps_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gps_status_t* gps_status)
{
return mavlink_msg_gps_status_pack(system_id, component_id, msg, gps_status->satellites_visible, gps_status->satellite_prn, gps_status->satellite_used, gps_status->satellite_elevation, gps_status->satellite_azimuth, gps_status->satellite_snr);
}
 
/**
* @brief Send a gps_status message
* @param chan MAVLink channel to send the message
*
* @param satellites_visible Number of satellites visible
* @param satellite_prn Global satellite ID
* @param satellite_used 0: Satellite not used, 1: used for localization
* @param satellite_elevation Elevation (0: right on top of receiver, 90: on the horizon) of satellite
* @param satellite_azimuth Direction of satellite, 0: 0 deg, 255: 360 deg.
* @param satellite_snr Signal to noise ratio of satellite
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_gps_status_send(mavlink_channel_t chan, uint8_t satellites_visible, const int8_t *satellite_prn, const int8_t *satellite_used, const int8_t *satellite_elevation, const int8_t *satellite_azimuth, const int8_t *satellite_snr)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[101];
_mav_put_uint8_t(buf, 0, satellites_visible);
_mav_put_int8_t_array(buf, 1, satellite_prn, 20);
_mav_put_int8_t_array(buf, 21, satellite_used, 20);
_mav_put_int8_t_array(buf, 41, satellite_elevation, 20);
_mav_put_int8_t_array(buf, 61, satellite_azimuth, 20);
_mav_put_int8_t_array(buf, 81, satellite_snr, 20);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_STATUS, buf, 101);
#else
mavlink_gps_status_t packet;
packet.satellites_visible = satellites_visible;
mav_array_memcpy(packet.satellite_prn, satellite_prn, sizeof(int8_t)*20);
mav_array_memcpy(packet.satellite_used, satellite_used, sizeof(int8_t)*20);
mav_array_memcpy(packet.satellite_elevation, satellite_elevation, sizeof(int8_t)*20);
mav_array_memcpy(packet.satellite_azimuth, satellite_azimuth, sizeof(int8_t)*20);
mav_array_memcpy(packet.satellite_snr, satellite_snr, sizeof(int8_t)*20);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_STATUS, (const char *)&packet, 101);
#endif
}
 
#endif
 
// MESSAGE GPS_STATUS UNPACKING
 
 
/**
* @brief Get field satellites_visible from gps_status message
*
* @return Number of satellites visible
*/
static inline uint8_t mavlink_msg_gps_status_get_satellites_visible(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 0);
}
 
/**
* @brief Get field satellite_prn from gps_status message
*
* @return Global satellite ID
*/
static inline uint16_t mavlink_msg_gps_status_get_satellite_prn(const mavlink_message_t* msg, int8_t *satellite_prn)
{
return _MAV_RETURN_int8_t_array(msg, satellite_prn, 20, 1);
}
 
/**
* @brief Get field satellite_used from gps_status message
*
* @return 0: Satellite not used, 1: used for localization
*/
static inline uint16_t mavlink_msg_gps_status_get_satellite_used(const mavlink_message_t* msg, int8_t *satellite_used)
{
return _MAV_RETURN_int8_t_array(msg, satellite_used, 20, 21);
}
 
/**
* @brief Get field satellite_elevation from gps_status message
*
* @return Elevation (0: right on top of receiver, 90: on the horizon) of satellite
*/
static inline uint16_t mavlink_msg_gps_status_get_satellite_elevation(const mavlink_message_t* msg, int8_t *satellite_elevation)
{
return _MAV_RETURN_int8_t_array(msg, satellite_elevation, 20, 41);
}
 
/**
* @brief Get field satellite_azimuth from gps_status message
*
* @return Direction of satellite, 0: 0 deg, 255: 360 deg.
*/
static inline uint16_t mavlink_msg_gps_status_get_satellite_azimuth(const mavlink_message_t* msg, int8_t *satellite_azimuth)
{
return _MAV_RETURN_int8_t_array(msg, satellite_azimuth, 20, 61);
}
 
/**
* @brief Get field satellite_snr from gps_status message
*
* @return Signal to noise ratio of satellite
*/
static inline uint16_t mavlink_msg_gps_status_get_satellite_snr(const mavlink_message_t* msg, int8_t *satellite_snr)
{
return _MAV_RETURN_int8_t_array(msg, satellite_snr, 20, 81);
}
 
/**
* @brief Decode a gps_status message into a struct
*
* @param msg The message to decode
* @param gps_status C-struct to decode the message contents into
*/
static inline void mavlink_msg_gps_status_decode(const mavlink_message_t* msg, mavlink_gps_status_t* gps_status)
{
#if MAVLINK_NEED_BYTE_SWAP
gps_status->satellites_visible = mavlink_msg_gps_status_get_satellites_visible(msg);
mavlink_msg_gps_status_get_satellite_prn(msg, gps_status->satellite_prn);
mavlink_msg_gps_status_get_satellite_used(msg, gps_status->satellite_used);
mavlink_msg_gps_status_get_satellite_elevation(msg, gps_status->satellite_elevation);
mavlink_msg_gps_status_get_satellite_azimuth(msg, gps_status->satellite_azimuth);
mavlink_msg_gps_status_get_satellite_snr(msg, gps_status->satellite_snr);
#else
memcpy(gps_status, _MAV_PAYLOAD(msg), 101);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v0.9/common/mavlink_msg_heartbeat.h
0,0 → 1,185
// MESSAGE HEARTBEAT PACKING
 
#define MAVLINK_MSG_ID_HEARTBEAT 0
 
typedef struct __mavlink_heartbeat_t
{
uint8_t type; ///< Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM)
uint8_t autopilot; ///< Type of the Autopilot: 0: Generic, 1: PIXHAWK, 2: SLUGS, 3: Ardupilot (up to 15 types), defined in MAV_AUTOPILOT_TYPE ENUM
uint8_t mavlink_version; ///< MAVLink version
} mavlink_heartbeat_t;
 
#define MAVLINK_MSG_ID_HEARTBEAT_LEN 3
#define MAVLINK_MSG_ID_0_LEN 3
 
 
 
#define MAVLINK_MESSAGE_INFO_HEARTBEAT { \
"HEARTBEAT", \
3, \
{ { "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_heartbeat_t, type) }, \
{ "autopilot", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_heartbeat_t, autopilot) }, \
{ "mavlink_version", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_heartbeat_t, mavlink_version) }, \
} \
}
 
 
/**
* @brief Pack a heartbeat message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param type Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM)
* @param autopilot Type of the Autopilot: 0: Generic, 1: PIXHAWK, 2: SLUGS, 3: Ardupilot (up to 15 types), defined in MAV_AUTOPILOT_TYPE ENUM
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_heartbeat_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t type, uint8_t autopilot)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[3];
_mav_put_uint8_t(buf, 0, type);
_mav_put_uint8_t(buf, 1, autopilot);
_mav_put_uint8_t(buf, 2, 2);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 3);
#else
mavlink_heartbeat_t packet;
packet.type = type;
packet.autopilot = autopilot;
packet.mavlink_version = 2;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 3);
#endif
 
msg->msgid = MAVLINK_MSG_ID_HEARTBEAT;
return mavlink_finalize_message(msg, system_id, component_id, 3);
}
 
/**
* @brief Pack a heartbeat message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param type Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM)
* @param autopilot Type of the Autopilot: 0: Generic, 1: PIXHAWK, 2: SLUGS, 3: Ardupilot (up to 15 types), defined in MAV_AUTOPILOT_TYPE ENUM
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_heartbeat_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint8_t type,uint8_t autopilot)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[3];
_mav_put_uint8_t(buf, 0, type);
_mav_put_uint8_t(buf, 1, autopilot);
_mav_put_uint8_t(buf, 2, 2);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 3);
#else
mavlink_heartbeat_t packet;
packet.type = type;
packet.autopilot = autopilot;
packet.mavlink_version = 2;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 3);
#endif
 
msg->msgid = MAVLINK_MSG_ID_HEARTBEAT;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 3);
}
 
/**
* @brief Encode a heartbeat struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param heartbeat C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_heartbeat_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_heartbeat_t* heartbeat)
{
return mavlink_msg_heartbeat_pack(system_id, component_id, msg, heartbeat->type, heartbeat->autopilot);
}
 
/**
* @brief Send a heartbeat message
* @param chan MAVLink channel to send the message
*
* @param type Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM)
* @param autopilot Type of the Autopilot: 0: Generic, 1: PIXHAWK, 2: SLUGS, 3: Ardupilot (up to 15 types), defined in MAV_AUTOPILOT_TYPE ENUM
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_heartbeat_send(mavlink_channel_t chan, uint8_t type, uint8_t autopilot)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[3];
_mav_put_uint8_t(buf, 0, type);
_mav_put_uint8_t(buf, 1, autopilot);
_mav_put_uint8_t(buf, 2, 2);
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HEARTBEAT, buf, 3);
#else
mavlink_heartbeat_t packet;
packet.type = type;
packet.autopilot = autopilot;
packet.mavlink_version = 2;
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HEARTBEAT, (const char *)&packet, 3);
#endif
}
 
#endif
 
// MESSAGE HEARTBEAT UNPACKING
 
 
/**
* @brief Get field type from heartbeat message
*
* @return Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM)
*/
static inline uint8_t mavlink_msg_heartbeat_get_type(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 0);
}
 
/**
* @brief Get field autopilot from heartbeat message
*
* @return Type of the Autopilot: 0: Generic, 1: PIXHAWK, 2: SLUGS, 3: Ardupilot (up to 15 types), defined in MAV_AUTOPILOT_TYPE ENUM
*/
static inline uint8_t mavlink_msg_heartbeat_get_autopilot(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 1);
}
 
/**
* @brief Get field mavlink_version from heartbeat message
*
* @return MAVLink version
*/
static inline uint8_t mavlink_msg_heartbeat_get_mavlink_version(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 2);
}
 
/**
* @brief Decode a heartbeat message into a struct
*
* @param msg The message to decode
* @param heartbeat C-struct to decode the message contents into
*/
static inline void mavlink_msg_heartbeat_decode(const mavlink_message_t* msg, mavlink_heartbeat_t* heartbeat)
{
#if MAVLINK_NEED_BYTE_SWAP
heartbeat->type = mavlink_msg_heartbeat_get_type(msg);
heartbeat->autopilot = mavlink_msg_heartbeat_get_autopilot(msg);
heartbeat->mavlink_version = mavlink_msg_heartbeat_get_mavlink_version(msg);
#else
memcpy(heartbeat, _MAV_PAYLOAD(msg), 3);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v0.9/common/mavlink_msg_hil_controls.h
0,0 → 1,276
// MESSAGE HIL_CONTROLS PACKING
 
#define MAVLINK_MSG_ID_HIL_CONTROLS 68
 
typedef struct __mavlink_hil_controls_t
{
uint64_t time_us; ///< Timestamp (microseconds since UNIX epoch or microseconds since system boot)
float roll_ailerons; ///< Control output -3 .. 1
float pitch_elevator; ///< Control output -1 .. 1
float yaw_rudder; ///< Control output -1 .. 1
float throttle; ///< Throttle 0 .. 1
uint8_t mode; ///< System mode (MAV_MODE)
uint8_t nav_mode; ///< Navigation mode (MAV_NAV_MODE)
} mavlink_hil_controls_t;
 
#define MAVLINK_MSG_ID_HIL_CONTROLS_LEN 26
#define MAVLINK_MSG_ID_68_LEN 26
 
 
 
#define MAVLINK_MESSAGE_INFO_HIL_CONTROLS { \
"HIL_CONTROLS", \
7, \
{ { "time_us", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_hil_controls_t, time_us) }, \
{ "roll_ailerons", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_hil_controls_t, roll_ailerons) }, \
{ "pitch_elevator", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_hil_controls_t, pitch_elevator) }, \
{ "yaw_rudder", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_hil_controls_t, yaw_rudder) }, \
{ "throttle", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_hil_controls_t, throttle) }, \
{ "mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 24, offsetof(mavlink_hil_controls_t, mode) }, \
{ "nav_mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 25, offsetof(mavlink_hil_controls_t, nav_mode) }, \
} \
}
 
 
/**
* @brief Pack a hil_controls message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param time_us Timestamp (microseconds since UNIX epoch or microseconds since system boot)
* @param roll_ailerons Control output -3 .. 1
* @param pitch_elevator Control output -1 .. 1
* @param yaw_rudder Control output -1 .. 1
* @param throttle Throttle 0 .. 1
* @param mode System mode (MAV_MODE)
* @param nav_mode Navigation mode (MAV_NAV_MODE)
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_hil_controls_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint64_t time_us, float roll_ailerons, float pitch_elevator, float yaw_rudder, float throttle, uint8_t mode, uint8_t nav_mode)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[26];
_mav_put_uint64_t(buf, 0, time_us);
_mav_put_float(buf, 8, roll_ailerons);
_mav_put_float(buf, 12, pitch_elevator);
_mav_put_float(buf, 16, yaw_rudder);
_mav_put_float(buf, 20, throttle);
_mav_put_uint8_t(buf, 24, mode);
_mav_put_uint8_t(buf, 25, nav_mode);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 26);
#else
mavlink_hil_controls_t packet;
packet.time_us = time_us;
packet.roll_ailerons = roll_ailerons;
packet.pitch_elevator = pitch_elevator;
packet.yaw_rudder = yaw_rudder;
packet.throttle = throttle;
packet.mode = mode;
packet.nav_mode = nav_mode;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 26);
#endif
 
msg->msgid = MAVLINK_MSG_ID_HIL_CONTROLS;
return mavlink_finalize_message(msg, system_id, component_id, 26);
}
 
/**
* @brief Pack a hil_controls message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param time_us Timestamp (microseconds since UNIX epoch or microseconds since system boot)
* @param roll_ailerons Control output -3 .. 1
* @param pitch_elevator Control output -1 .. 1
* @param yaw_rudder Control output -1 .. 1
* @param throttle Throttle 0 .. 1
* @param mode System mode (MAV_MODE)
* @param nav_mode Navigation mode (MAV_NAV_MODE)
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_hil_controls_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint64_t time_us,float roll_ailerons,float pitch_elevator,float yaw_rudder,float throttle,uint8_t mode,uint8_t nav_mode)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[26];
_mav_put_uint64_t(buf, 0, time_us);
_mav_put_float(buf, 8, roll_ailerons);
_mav_put_float(buf, 12, pitch_elevator);
_mav_put_float(buf, 16, yaw_rudder);
_mav_put_float(buf, 20, throttle);
_mav_put_uint8_t(buf, 24, mode);
_mav_put_uint8_t(buf, 25, nav_mode);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 26);
#else
mavlink_hil_controls_t packet;
packet.time_us = time_us;
packet.roll_ailerons = roll_ailerons;
packet.pitch_elevator = pitch_elevator;
packet.yaw_rudder = yaw_rudder;
packet.throttle = throttle;
packet.mode = mode;
packet.nav_mode = nav_mode;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 26);
#endif
 
msg->msgid = MAVLINK_MSG_ID_HIL_CONTROLS;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 26);
}
 
/**
* @brief Encode a hil_controls struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param hil_controls C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_hil_controls_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_hil_controls_t* hil_controls)
{
return mavlink_msg_hil_controls_pack(system_id, component_id, msg, hil_controls->time_us, hil_controls->roll_ailerons, hil_controls->pitch_elevator, hil_controls->yaw_rudder, hil_controls->throttle, hil_controls->mode, hil_controls->nav_mode);
}
 
/**
* @brief Send a hil_controls message
* @param chan MAVLink channel to send the message
*
* @param time_us Timestamp (microseconds since UNIX epoch or microseconds since system boot)
* @param roll_ailerons Control output -3 .. 1
* @param pitch_elevator Control output -1 .. 1
* @param yaw_rudder Control output -1 .. 1
* @param throttle Throttle 0 .. 1
* @param mode System mode (MAV_MODE)
* @param nav_mode Navigation mode (MAV_NAV_MODE)
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_hil_controls_send(mavlink_channel_t chan, uint64_t time_us, float roll_ailerons, float pitch_elevator, float yaw_rudder, float throttle, uint8_t mode, uint8_t nav_mode)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[26];
_mav_put_uint64_t(buf, 0, time_us);
_mav_put_float(buf, 8, roll_ailerons);
_mav_put_float(buf, 12, pitch_elevator);
_mav_put_float(buf, 16, yaw_rudder);
_mav_put_float(buf, 20, throttle);
_mav_put_uint8_t(buf, 24, mode);
_mav_put_uint8_t(buf, 25, nav_mode);
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_CONTROLS, buf, 26);
#else
mavlink_hil_controls_t packet;
packet.time_us = time_us;
packet.roll_ailerons = roll_ailerons;
packet.pitch_elevator = pitch_elevator;
packet.yaw_rudder = yaw_rudder;
packet.throttle = throttle;
packet.mode = mode;
packet.nav_mode = nav_mode;
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_CONTROLS, (const char *)&packet, 26);
#endif
}
 
#endif
 
// MESSAGE HIL_CONTROLS UNPACKING
 
 
/**
* @brief Get field time_us from hil_controls message
*
* @return Timestamp (microseconds since UNIX epoch or microseconds since system boot)
*/
static inline uint64_t mavlink_msg_hil_controls_get_time_us(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint64_t(msg, 0);
}
 
/**
* @brief Get field roll_ailerons from hil_controls message
*
* @return Control output -3 .. 1
*/
static inline float mavlink_msg_hil_controls_get_roll_ailerons(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 8);
}
 
/**
* @brief Get field pitch_elevator from hil_controls message
*
* @return Control output -1 .. 1
*/
static inline float mavlink_msg_hil_controls_get_pitch_elevator(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 12);
}
 
/**
* @brief Get field yaw_rudder from hil_controls message
*
* @return Control output -1 .. 1
*/
static inline float mavlink_msg_hil_controls_get_yaw_rudder(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 16);
}
 
/**
* @brief Get field throttle from hil_controls message
*
* @return Throttle 0 .. 1
*/
static inline float mavlink_msg_hil_controls_get_throttle(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 20);
}
 
/**
* @brief Get field mode from hil_controls message
*
* @return System mode (MAV_MODE)
*/
static inline uint8_t mavlink_msg_hil_controls_get_mode(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 24);
}
 
/**
* @brief Get field nav_mode from hil_controls message
*
* @return Navigation mode (MAV_NAV_MODE)
*/
static inline uint8_t mavlink_msg_hil_controls_get_nav_mode(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 25);
}
 
/**
* @brief Decode a hil_controls message into a struct
*
* @param msg The message to decode
* @param hil_controls C-struct to decode the message contents into
*/
static inline void mavlink_msg_hil_controls_decode(const mavlink_message_t* msg, mavlink_hil_controls_t* hil_controls)
{
#if MAVLINK_NEED_BYTE_SWAP
hil_controls->time_us = mavlink_msg_hil_controls_get_time_us(msg);
hil_controls->roll_ailerons = mavlink_msg_hil_controls_get_roll_ailerons(msg);
hil_controls->pitch_elevator = mavlink_msg_hil_controls_get_pitch_elevator(msg);
hil_controls->yaw_rudder = mavlink_msg_hil_controls_get_yaw_rudder(msg);
hil_controls->throttle = mavlink_msg_hil_controls_get_throttle(msg);
hil_controls->mode = mavlink_msg_hil_controls_get_mode(msg);
hil_controls->nav_mode = mavlink_msg_hil_controls_get_nav_mode(msg);
#else
memcpy(hil_controls, _MAV_PAYLOAD(msg), 26);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v0.9/common/mavlink_msg_hil_state.h
0,0 → 1,474
// MESSAGE HIL_STATE PACKING
 
#define MAVLINK_MSG_ID_HIL_STATE 67
 
typedef struct __mavlink_hil_state_t
{
uint64_t usec; ///< Timestamp (microseconds since UNIX epoch or microseconds since system boot)
float roll; ///< Roll angle (rad)
float pitch; ///< Pitch angle (rad)
float yaw; ///< Yaw angle (rad)
float rollspeed; ///< Roll angular speed (rad/s)
float pitchspeed; ///< Pitch angular speed (rad/s)
float yawspeed; ///< Yaw angular speed (rad/s)
int32_t lat; ///< Latitude, expressed as * 1E7
int32_t lon; ///< Longitude, expressed as * 1E7
int32_t alt; ///< Altitude in meters, expressed as * 1000 (millimeters)
int16_t vx; ///< Ground X Speed (Latitude), expressed as m/s * 100
int16_t vy; ///< Ground Y Speed (Longitude), expressed as m/s * 100
int16_t vz; ///< Ground Z Speed (Altitude), expressed as m/s * 100
int16_t xacc; ///< X acceleration (mg)
int16_t yacc; ///< Y acceleration (mg)
int16_t zacc; ///< Z acceleration (mg)
} mavlink_hil_state_t;
 
#define MAVLINK_MSG_ID_HIL_STATE_LEN 56
#define MAVLINK_MSG_ID_67_LEN 56
 
 
 
#define MAVLINK_MESSAGE_INFO_HIL_STATE { \
"HIL_STATE", \
16, \
{ { "usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_hil_state_t, usec) }, \
{ "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_hil_state_t, roll) }, \
{ "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_hil_state_t, pitch) }, \
{ "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_hil_state_t, yaw) }, \
{ "rollspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_hil_state_t, rollspeed) }, \
{ "pitchspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_hil_state_t, pitchspeed) }, \
{ "yawspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_hil_state_t, yawspeed) }, \
{ "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 32, offsetof(mavlink_hil_state_t, lat) }, \
{ "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 36, offsetof(mavlink_hil_state_t, lon) }, \
{ "alt", NULL, MAVLINK_TYPE_INT32_T, 0, 40, offsetof(mavlink_hil_state_t, alt) }, \
{ "vx", NULL, MAVLINK_TYPE_INT16_T, 0, 44, offsetof(mavlink_hil_state_t, vx) }, \
{ "vy", NULL, MAVLINK_TYPE_INT16_T, 0, 46, offsetof(mavlink_hil_state_t, vy) }, \
{ "vz", NULL, MAVLINK_TYPE_INT16_T, 0, 48, offsetof(mavlink_hil_state_t, vz) }, \
{ "xacc", NULL, MAVLINK_TYPE_INT16_T, 0, 50, offsetof(mavlink_hil_state_t, xacc) }, \
{ "yacc", NULL, MAVLINK_TYPE_INT16_T, 0, 52, offsetof(mavlink_hil_state_t, yacc) }, \
{ "zacc", NULL, MAVLINK_TYPE_INT16_T, 0, 54, offsetof(mavlink_hil_state_t, zacc) }, \
} \
}
 
 
/**
* @brief Pack a hil_state message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
* @param roll Roll angle (rad)
* @param pitch Pitch angle (rad)
* @param yaw Yaw angle (rad)
* @param rollspeed Roll angular speed (rad/s)
* @param pitchspeed Pitch angular speed (rad/s)
* @param yawspeed Yaw angular speed (rad/s)
* @param lat Latitude, expressed as * 1E7
* @param lon Longitude, expressed as * 1E7
* @param alt Altitude in meters, expressed as * 1000 (millimeters)
* @param vx Ground X Speed (Latitude), expressed as m/s * 100
* @param vy Ground Y Speed (Longitude), expressed as m/s * 100
* @param vz Ground Z Speed (Altitude), expressed as m/s * 100
* @param xacc X acceleration (mg)
* @param yacc Y acceleration (mg)
* @param zacc Z acceleration (mg)
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_hil_state_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint64_t usec, float roll, float pitch, float yaw, float rollspeed, float pitchspeed, float yawspeed, int32_t lat, int32_t lon, int32_t alt, int16_t vx, int16_t vy, int16_t vz, int16_t xacc, int16_t yacc, int16_t zacc)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[56];
_mav_put_uint64_t(buf, 0, usec);
_mav_put_float(buf, 8, roll);
_mav_put_float(buf, 12, pitch);
_mav_put_float(buf, 16, yaw);
_mav_put_float(buf, 20, rollspeed);
_mav_put_float(buf, 24, pitchspeed);
_mav_put_float(buf, 28, yawspeed);
_mav_put_int32_t(buf, 32, lat);
_mav_put_int32_t(buf, 36, lon);
_mav_put_int32_t(buf, 40, alt);
_mav_put_int16_t(buf, 44, vx);
_mav_put_int16_t(buf, 46, vy);
_mav_put_int16_t(buf, 48, vz);
_mav_put_int16_t(buf, 50, xacc);
_mav_put_int16_t(buf, 52, yacc);
_mav_put_int16_t(buf, 54, zacc);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 56);
#else
mavlink_hil_state_t packet;
packet.usec = usec;
packet.roll = roll;
packet.pitch = pitch;
packet.yaw = yaw;
packet.rollspeed = rollspeed;
packet.pitchspeed = pitchspeed;
packet.yawspeed = yawspeed;
packet.lat = lat;
packet.lon = lon;
packet.alt = alt;
packet.vx = vx;
packet.vy = vy;
packet.vz = vz;
packet.xacc = xacc;
packet.yacc = yacc;
packet.zacc = zacc;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 56);
#endif
 
msg->msgid = MAVLINK_MSG_ID_HIL_STATE;
return mavlink_finalize_message(msg, system_id, component_id, 56);
}
 
/**
* @brief Pack a hil_state message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
* @param roll Roll angle (rad)
* @param pitch Pitch angle (rad)
* @param yaw Yaw angle (rad)
* @param rollspeed Roll angular speed (rad/s)
* @param pitchspeed Pitch angular speed (rad/s)
* @param yawspeed Yaw angular speed (rad/s)
* @param lat Latitude, expressed as * 1E7
* @param lon Longitude, expressed as * 1E7
* @param alt Altitude in meters, expressed as * 1000 (millimeters)
* @param vx Ground X Speed (Latitude), expressed as m/s * 100
* @param vy Ground Y Speed (Longitude), expressed as m/s * 100
* @param vz Ground Z Speed (Altitude), expressed as m/s * 100
* @param xacc X acceleration (mg)
* @param yacc Y acceleration (mg)
* @param zacc Z acceleration (mg)
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_hil_state_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint64_t usec,float roll,float pitch,float yaw,float rollspeed,float pitchspeed,float yawspeed,int32_t lat,int32_t lon,int32_t alt,int16_t vx,int16_t vy,int16_t vz,int16_t xacc,int16_t yacc,int16_t zacc)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[56];
_mav_put_uint64_t(buf, 0, usec);
_mav_put_float(buf, 8, roll);
_mav_put_float(buf, 12, pitch);
_mav_put_float(buf, 16, yaw);
_mav_put_float(buf, 20, rollspeed);
_mav_put_float(buf, 24, pitchspeed);
_mav_put_float(buf, 28, yawspeed);
_mav_put_int32_t(buf, 32, lat);
_mav_put_int32_t(buf, 36, lon);
_mav_put_int32_t(buf, 40, alt);
_mav_put_int16_t(buf, 44, vx);
_mav_put_int16_t(buf, 46, vy);
_mav_put_int16_t(buf, 48, vz);
_mav_put_int16_t(buf, 50, xacc);
_mav_put_int16_t(buf, 52, yacc);
_mav_put_int16_t(buf, 54, zacc);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 56);
#else
mavlink_hil_state_t packet;
packet.usec = usec;
packet.roll = roll;
packet.pitch = pitch;
packet.yaw = yaw;
packet.rollspeed = rollspeed;
packet.pitchspeed = pitchspeed;
packet.yawspeed = yawspeed;
packet.lat = lat;
packet.lon = lon;
packet.alt = alt;
packet.vx = vx;
packet.vy = vy;
packet.vz = vz;
packet.xacc = xacc;
packet.yacc = yacc;
packet.zacc = zacc;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 56);
#endif
 
msg->msgid = MAVLINK_MSG_ID_HIL_STATE;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 56);
}
 
/**
* @brief Encode a hil_state struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param hil_state C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_hil_state_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_hil_state_t* hil_state)
{
return mavlink_msg_hil_state_pack(system_id, component_id, msg, hil_state->usec, hil_state->roll, hil_state->pitch, hil_state->yaw, hil_state->rollspeed, hil_state->pitchspeed, hil_state->yawspeed, hil_state->lat, hil_state->lon, hil_state->alt, hil_state->vx, hil_state->vy, hil_state->vz, hil_state->xacc, hil_state->yacc, hil_state->zacc);
}
 
/**
* @brief Send a hil_state message
* @param chan MAVLink channel to send the message
*
* @param usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
* @param roll Roll angle (rad)
* @param pitch Pitch angle (rad)
* @param yaw Yaw angle (rad)
* @param rollspeed Roll angular speed (rad/s)
* @param pitchspeed Pitch angular speed (rad/s)
* @param yawspeed Yaw angular speed (rad/s)
* @param lat Latitude, expressed as * 1E7
* @param lon Longitude, expressed as * 1E7
* @param alt Altitude in meters, expressed as * 1000 (millimeters)
* @param vx Ground X Speed (Latitude), expressed as m/s * 100
* @param vy Ground Y Speed (Longitude), expressed as m/s * 100
* @param vz Ground Z Speed (Altitude), expressed as m/s * 100
* @param xacc X acceleration (mg)
* @param yacc Y acceleration (mg)
* @param zacc Z acceleration (mg)
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_hil_state_send(mavlink_channel_t chan, uint64_t usec, float roll, float pitch, float yaw, float rollspeed, float pitchspeed, float yawspeed, int32_t lat, int32_t lon, int32_t alt, int16_t vx, int16_t vy, int16_t vz, int16_t xacc, int16_t yacc, int16_t zacc)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[56];
_mav_put_uint64_t(buf, 0, usec);
_mav_put_float(buf, 8, roll);
_mav_put_float(buf, 12, pitch);
_mav_put_float(buf, 16, yaw);
_mav_put_float(buf, 20, rollspeed);
_mav_put_float(buf, 24, pitchspeed);
_mav_put_float(buf, 28, yawspeed);
_mav_put_int32_t(buf, 32, lat);
_mav_put_int32_t(buf, 36, lon);
_mav_put_int32_t(buf, 40, alt);
_mav_put_int16_t(buf, 44, vx);
_mav_put_int16_t(buf, 46, vy);
_mav_put_int16_t(buf, 48, vz);
_mav_put_int16_t(buf, 50, xacc);
_mav_put_int16_t(buf, 52, yacc);
_mav_put_int16_t(buf, 54, zacc);
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_STATE, buf, 56);
#else
mavlink_hil_state_t packet;
packet.usec = usec;
packet.roll = roll;
packet.pitch = pitch;
packet.yaw = yaw;
packet.rollspeed = rollspeed;
packet.pitchspeed = pitchspeed;
packet.yawspeed = yawspeed;
packet.lat = lat;
packet.lon = lon;
packet.alt = alt;
packet.vx = vx;
packet.vy = vy;
packet.vz = vz;
packet.xacc = xacc;
packet.yacc = yacc;
packet.zacc = zacc;
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_STATE, (const char *)&packet, 56);
#endif
}
 
#endif
 
// MESSAGE HIL_STATE UNPACKING
 
 
/**
* @brief Get field usec from hil_state message
*
* @return Timestamp (microseconds since UNIX epoch or microseconds since system boot)
*/
static inline uint64_t mavlink_msg_hil_state_get_usec(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint64_t(msg, 0);
}
 
/**
* @brief Get field roll from hil_state message
*
* @return Roll angle (rad)
*/
static inline float mavlink_msg_hil_state_get_roll(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 8);
}
 
/**
* @brief Get field pitch from hil_state message
*
* @return Pitch angle (rad)
*/
static inline float mavlink_msg_hil_state_get_pitch(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 12);
}
 
/**
* @brief Get field yaw from hil_state message
*
* @return Yaw angle (rad)
*/
static inline float mavlink_msg_hil_state_get_yaw(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 16);
}
 
/**
* @brief Get field rollspeed from hil_state message
*
* @return Roll angular speed (rad/s)
*/
static inline float mavlink_msg_hil_state_get_rollspeed(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 20);
}
 
/**
* @brief Get field pitchspeed from hil_state message
*
* @return Pitch angular speed (rad/s)
*/
static inline float mavlink_msg_hil_state_get_pitchspeed(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 24);
}
 
/**
* @brief Get field yawspeed from hil_state message
*
* @return Yaw angular speed (rad/s)
*/
static inline float mavlink_msg_hil_state_get_yawspeed(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 28);
}
 
/**
* @brief Get field lat from hil_state message
*
* @return Latitude, expressed as * 1E7
*/
static inline int32_t mavlink_msg_hil_state_get_lat(const mavlink_message_t* msg)
{
return _MAV_RETURN_int32_t(msg, 32);
}
 
/**
* @brief Get field lon from hil_state message
*
* @return Longitude, expressed as * 1E7
*/
static inline int32_t mavlink_msg_hil_state_get_lon(const mavlink_message_t* msg)
{
return _MAV_RETURN_int32_t(msg, 36);
}
 
/**
* @brief Get field alt from hil_state message
*
* @return Altitude in meters, expressed as * 1000 (millimeters)
*/
static inline int32_t mavlink_msg_hil_state_get_alt(const mavlink_message_t* msg)
{
return _MAV_RETURN_int32_t(msg, 40);
}
 
/**
* @brief Get field vx from hil_state message
*
* @return Ground X Speed (Latitude), expressed as m/s * 100
*/
static inline int16_t mavlink_msg_hil_state_get_vx(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 44);
}
 
/**
* @brief Get field vy from hil_state message
*
* @return Ground Y Speed (Longitude), expressed as m/s * 100
*/
static inline int16_t mavlink_msg_hil_state_get_vy(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 46);
}
 
/**
* @brief Get field vz from hil_state message
*
* @return Ground Z Speed (Altitude), expressed as m/s * 100
*/
static inline int16_t mavlink_msg_hil_state_get_vz(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 48);
}
 
/**
* @brief Get field xacc from hil_state message
*
* @return X acceleration (mg)
*/
static inline int16_t mavlink_msg_hil_state_get_xacc(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 50);
}
 
/**
* @brief Get field yacc from hil_state message
*
* @return Y acceleration (mg)
*/
static inline int16_t mavlink_msg_hil_state_get_yacc(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 52);
}
 
/**
* @brief Get field zacc from hil_state message
*
* @return Z acceleration (mg)
*/
static inline int16_t mavlink_msg_hil_state_get_zacc(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 54);
}
 
/**
* @brief Decode a hil_state message into a struct
*
* @param msg The message to decode
* @param hil_state C-struct to decode the message contents into
*/
static inline void mavlink_msg_hil_state_decode(const mavlink_message_t* msg, mavlink_hil_state_t* hil_state)
{
#if MAVLINK_NEED_BYTE_SWAP
hil_state->usec = mavlink_msg_hil_state_get_usec(msg);
hil_state->roll = mavlink_msg_hil_state_get_roll(msg);
hil_state->pitch = mavlink_msg_hil_state_get_pitch(msg);
hil_state->yaw = mavlink_msg_hil_state_get_yaw(msg);
hil_state->rollspeed = mavlink_msg_hil_state_get_rollspeed(msg);
hil_state->pitchspeed = mavlink_msg_hil_state_get_pitchspeed(msg);
hil_state->yawspeed = mavlink_msg_hil_state_get_yawspeed(msg);
hil_state->lat = mavlink_msg_hil_state_get_lat(msg);
hil_state->lon = mavlink_msg_hil_state_get_lon(msg);
hil_state->alt = mavlink_msg_hil_state_get_alt(msg);
hil_state->vx = mavlink_msg_hil_state_get_vx(msg);
hil_state->vy = mavlink_msg_hil_state_get_vy(msg);
hil_state->vz = mavlink_msg_hil_state_get_vz(msg);
hil_state->xacc = mavlink_msg_hil_state_get_xacc(msg);
hil_state->yacc = mavlink_msg_hil_state_get_yacc(msg);
hil_state->zacc = mavlink_msg_hil_state_get_zacc(msg);
#else
memcpy(hil_state, _MAV_PAYLOAD(msg), 56);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v0.9/common/mavlink_msg_local_position.h
0,0 → 1,276
// MESSAGE LOCAL_POSITION PACKING
 
#define MAVLINK_MSG_ID_LOCAL_POSITION 31
 
typedef struct __mavlink_local_position_t
{
uint64_t usec; ///< Timestamp (microseconds since UNIX epoch or microseconds since system boot)
float x; ///< X Position
float y; ///< Y Position
float z; ///< Z Position
float vx; ///< X Speed
float vy; ///< Y Speed
float vz; ///< Z Speed
} mavlink_local_position_t;
 
#define MAVLINK_MSG_ID_LOCAL_POSITION_LEN 32
#define MAVLINK_MSG_ID_31_LEN 32
 
 
 
#define MAVLINK_MESSAGE_INFO_LOCAL_POSITION { \
"LOCAL_POSITION", \
7, \
{ { "usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_local_position_t, usec) }, \
{ "x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_local_position_t, x) }, \
{ "y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_local_position_t, y) }, \
{ "z", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_local_position_t, z) }, \
{ "vx", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_local_position_t, vx) }, \
{ "vy", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_local_position_t, vy) }, \
{ "vz", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_local_position_t, vz) }, \
} \
}
 
 
/**
* @brief Pack a local_position message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
* @param x X Position
* @param y Y Position
* @param z Z Position
* @param vx X Speed
* @param vy Y Speed
* @param vz Z Speed
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_local_position_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint64_t usec, float x, float y, float z, float vx, float vy, float vz)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[32];
_mav_put_uint64_t(buf, 0, usec);
_mav_put_float(buf, 8, x);
_mav_put_float(buf, 12, y);
_mav_put_float(buf, 16, z);
_mav_put_float(buf, 20, vx);
_mav_put_float(buf, 24, vy);
_mav_put_float(buf, 28, vz);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 32);
#else
mavlink_local_position_t packet;
packet.usec = usec;
packet.x = x;
packet.y = y;
packet.z = z;
packet.vx = vx;
packet.vy = vy;
packet.vz = vz;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 32);
#endif
 
msg->msgid = MAVLINK_MSG_ID_LOCAL_POSITION;
return mavlink_finalize_message(msg, system_id, component_id, 32);
}
 
/**
* @brief Pack a local_position message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
* @param x X Position
* @param y Y Position
* @param z Z Position
* @param vx X Speed
* @param vy Y Speed
* @param vz Z Speed
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_local_position_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint64_t usec,float x,float y,float z,float vx,float vy,float vz)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[32];
_mav_put_uint64_t(buf, 0, usec);
_mav_put_float(buf, 8, x);
_mav_put_float(buf, 12, y);
_mav_put_float(buf, 16, z);
_mav_put_float(buf, 20, vx);
_mav_put_float(buf, 24, vy);
_mav_put_float(buf, 28, vz);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 32);
#else
mavlink_local_position_t packet;
packet.usec = usec;
packet.x = x;
packet.y = y;
packet.z = z;
packet.vx = vx;
packet.vy = vy;
packet.vz = vz;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 32);
#endif
 
msg->msgid = MAVLINK_MSG_ID_LOCAL_POSITION;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 32);
}
 
/**
* @brief Encode a local_position struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param local_position C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_local_position_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_local_position_t* local_position)
{
return mavlink_msg_local_position_pack(system_id, component_id, msg, local_position->usec, local_position->x, local_position->y, local_position->z, local_position->vx, local_position->vy, local_position->vz);
}
 
/**
* @brief Send a local_position message
* @param chan MAVLink channel to send the message
*
* @param usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
* @param x X Position
* @param y Y Position
* @param z Z Position
* @param vx X Speed
* @param vy Y Speed
* @param vz Z Speed
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_local_position_send(mavlink_channel_t chan, uint64_t usec, float x, float y, float z, float vx, float vy, float vz)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[32];
_mav_put_uint64_t(buf, 0, usec);
_mav_put_float(buf, 8, x);
_mav_put_float(buf, 12, y);
_mav_put_float(buf, 16, z);
_mav_put_float(buf, 20, vx);
_mav_put_float(buf, 24, vy);
_mav_put_float(buf, 28, vz);
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION, buf, 32);
#else
mavlink_local_position_t packet;
packet.usec = usec;
packet.x = x;
packet.y = y;
packet.z = z;
packet.vx = vx;
packet.vy = vy;
packet.vz = vz;
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION, (const char *)&packet, 32);
#endif
}
 
#endif
 
// MESSAGE LOCAL_POSITION UNPACKING
 
 
/**
* @brief Get field usec from local_position message
*
* @return Timestamp (microseconds since UNIX epoch or microseconds since system boot)
*/
static inline uint64_t mavlink_msg_local_position_get_usec(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint64_t(msg, 0);
}
 
/**
* @brief Get field x from local_position message
*
* @return X Position
*/
static inline float mavlink_msg_local_position_get_x(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 8);
}
 
/**
* @brief Get field y from local_position message
*
* @return Y Position
*/
static inline float mavlink_msg_local_position_get_y(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 12);
}
 
/**
* @brief Get field z from local_position message
*
* @return Z Position
*/
static inline float mavlink_msg_local_position_get_z(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 16);
}
 
/**
* @brief Get field vx from local_position message
*
* @return X Speed
*/
static inline float mavlink_msg_local_position_get_vx(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 20);
}
 
/**
* @brief Get field vy from local_position message
*
* @return Y Speed
*/
static inline float mavlink_msg_local_position_get_vy(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 24);
}
 
/**
* @brief Get field vz from local_position message
*
* @return Z Speed
*/
static inline float mavlink_msg_local_position_get_vz(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 28);
}
 
/**
* @brief Decode a local_position message into a struct
*
* @param msg The message to decode
* @param local_position C-struct to decode the message contents into
*/
static inline void mavlink_msg_local_position_decode(const mavlink_message_t* msg, mavlink_local_position_t* local_position)
{
#if MAVLINK_NEED_BYTE_SWAP
local_position->usec = mavlink_msg_local_position_get_usec(msg);
local_position->x = mavlink_msg_local_position_get_x(msg);
local_position->y = mavlink_msg_local_position_get_y(msg);
local_position->z = mavlink_msg_local_position_get_z(msg);
local_position->vx = mavlink_msg_local_position_get_vx(msg);
local_position->vy = mavlink_msg_local_position_get_vy(msg);
local_position->vz = mavlink_msg_local_position_get_vz(msg);
#else
memcpy(local_position, _MAV_PAYLOAD(msg), 32);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v0.9/common/mavlink_msg_local_position_setpoint.h
0,0 → 1,210
// MESSAGE LOCAL_POSITION_SETPOINT PACKING
 
#define MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT 51
 
typedef struct __mavlink_local_position_setpoint_t
{
float x; ///< x position
float y; ///< y position
float z; ///< z position
float yaw; ///< Desired yaw angle
} mavlink_local_position_setpoint_t;
 
#define MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT_LEN 16
#define MAVLINK_MSG_ID_51_LEN 16
 
 
 
#define MAVLINK_MESSAGE_INFO_LOCAL_POSITION_SETPOINT { \
"LOCAL_POSITION_SETPOINT", \
4, \
{ { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_local_position_setpoint_t, x) }, \
{ "y", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_local_position_setpoint_t, y) }, \
{ "z", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_local_position_setpoint_t, z) }, \
{ "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_local_position_setpoint_t, yaw) }, \
} \
}
 
 
/**
* @brief Pack a local_position_setpoint message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param x x position
* @param y y position
* @param z z position
* @param yaw Desired yaw angle
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_local_position_setpoint_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
float x, float y, float z, float yaw)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[16];
_mav_put_float(buf, 0, x);
_mav_put_float(buf, 4, y);
_mav_put_float(buf, 8, z);
_mav_put_float(buf, 12, yaw);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 16);
#else
mavlink_local_position_setpoint_t packet;
packet.x = x;
packet.y = y;
packet.z = z;
packet.yaw = yaw;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 16);
#endif
 
msg->msgid = MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT;
return mavlink_finalize_message(msg, system_id, component_id, 16);
}
 
/**
* @brief Pack a local_position_setpoint message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param x x position
* @param y y position
* @param z z position
* @param yaw Desired yaw angle
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_local_position_setpoint_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
float x,float y,float z,float yaw)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[16];
_mav_put_float(buf, 0, x);
_mav_put_float(buf, 4, y);
_mav_put_float(buf, 8, z);
_mav_put_float(buf, 12, yaw);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 16);
#else
mavlink_local_position_setpoint_t packet;
packet.x = x;
packet.y = y;
packet.z = z;
packet.yaw = yaw;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 16);
#endif
 
msg->msgid = MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 16);
}
 
/**
* @brief Encode a local_position_setpoint struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param local_position_setpoint C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_local_position_setpoint_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_local_position_setpoint_t* local_position_setpoint)
{
return mavlink_msg_local_position_setpoint_pack(system_id, component_id, msg, local_position_setpoint->x, local_position_setpoint->y, local_position_setpoint->z, local_position_setpoint->yaw);
}
 
/**
* @brief Send a local_position_setpoint message
* @param chan MAVLink channel to send the message
*
* @param x x position
* @param y y position
* @param z z position
* @param yaw Desired yaw angle
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_local_position_setpoint_send(mavlink_channel_t chan, float x, float y, float z, float yaw)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[16];
_mav_put_float(buf, 0, x);
_mav_put_float(buf, 4, y);
_mav_put_float(buf, 8, z);
_mav_put_float(buf, 12, yaw);
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT, buf, 16);
#else
mavlink_local_position_setpoint_t packet;
packet.x = x;
packet.y = y;
packet.z = z;
packet.yaw = yaw;
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT, (const char *)&packet, 16);
#endif
}
 
#endif
 
// MESSAGE LOCAL_POSITION_SETPOINT UNPACKING
 
 
/**
* @brief Get field x from local_position_setpoint message
*
* @return x position
*/
static inline float mavlink_msg_local_position_setpoint_get_x(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 0);
}
 
/**
* @brief Get field y from local_position_setpoint message
*
* @return y position
*/
static inline float mavlink_msg_local_position_setpoint_get_y(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 4);
}
 
/**
* @brief Get field z from local_position_setpoint message
*
* @return z position
*/
static inline float mavlink_msg_local_position_setpoint_get_z(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 8);
}
 
/**
* @brief Get field yaw from local_position_setpoint message
*
* @return Desired yaw angle
*/
static inline float mavlink_msg_local_position_setpoint_get_yaw(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 12);
}
 
/**
* @brief Decode a local_position_setpoint message into a struct
*
* @param msg The message to decode
* @param local_position_setpoint C-struct to decode the message contents into
*/
static inline void mavlink_msg_local_position_setpoint_decode(const mavlink_message_t* msg, mavlink_local_position_setpoint_t* local_position_setpoint)
{
#if MAVLINK_NEED_BYTE_SWAP
local_position_setpoint->x = mavlink_msg_local_position_setpoint_get_x(msg);
local_position_setpoint->y = mavlink_msg_local_position_setpoint_get_y(msg);
local_position_setpoint->z = mavlink_msg_local_position_setpoint_get_z(msg);
local_position_setpoint->yaw = mavlink_msg_local_position_setpoint_get_yaw(msg);
#else
memcpy(local_position_setpoint, _MAV_PAYLOAD(msg), 16);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v0.9/common/mavlink_msg_local_position_setpoint_set.h
0,0 → 1,254
// MESSAGE LOCAL_POSITION_SETPOINT_SET PACKING
 
#define MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT_SET 50
 
typedef struct __mavlink_local_position_setpoint_set_t
{
uint8_t target_system; ///< System ID
uint8_t target_component; ///< Component ID
float x; ///< x position
float y; ///< y position
float z; ///< z position
float yaw; ///< Desired yaw angle
} mavlink_local_position_setpoint_set_t;
 
#define MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT_SET_LEN 18
#define MAVLINK_MSG_ID_50_LEN 18
 
 
 
#define MAVLINK_MESSAGE_INFO_LOCAL_POSITION_SETPOINT_SET { \
"LOCAL_POSITION_SETPOINT_SET", \
6, \
{ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_local_position_setpoint_set_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_local_position_setpoint_set_t, target_component) }, \
{ "x", NULL, MAVLINK_TYPE_FLOAT, 0, 2, offsetof(mavlink_local_position_setpoint_set_t, x) }, \
{ "y", NULL, MAVLINK_TYPE_FLOAT, 0, 6, offsetof(mavlink_local_position_setpoint_set_t, y) }, \
{ "z", NULL, MAVLINK_TYPE_FLOAT, 0, 10, offsetof(mavlink_local_position_setpoint_set_t, z) }, \
{ "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 14, offsetof(mavlink_local_position_setpoint_set_t, yaw) }, \
} \
}
 
 
/**
* @brief Pack a local_position_setpoint_set message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param target_system System ID
* @param target_component Component ID
* @param x x position
* @param y y position
* @param z z position
* @param yaw Desired yaw angle
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_local_position_setpoint_set_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t target_system, uint8_t target_component, float x, float y, float z, float yaw)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[18];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
_mav_put_float(buf, 2, x);
_mav_put_float(buf, 6, y);
_mav_put_float(buf, 10, z);
_mav_put_float(buf, 14, yaw);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 18);
#else
mavlink_local_position_setpoint_set_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
packet.x = x;
packet.y = y;
packet.z = z;
packet.yaw = yaw;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 18);
#endif
 
msg->msgid = MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT_SET;
return mavlink_finalize_message(msg, system_id, component_id, 18);
}
 
/**
* @brief Pack a local_position_setpoint_set message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param target_system System ID
* @param target_component Component ID
* @param x x position
* @param y y position
* @param z z position
* @param yaw Desired yaw angle
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_local_position_setpoint_set_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,float x,float y,float z,float yaw)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[18];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
_mav_put_float(buf, 2, x);
_mav_put_float(buf, 6, y);
_mav_put_float(buf, 10, z);
_mav_put_float(buf, 14, yaw);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 18);
#else
mavlink_local_position_setpoint_set_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
packet.x = x;
packet.y = y;
packet.z = z;
packet.yaw = yaw;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 18);
#endif
 
msg->msgid = MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT_SET;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 18);
}
 
/**
* @brief Encode a local_position_setpoint_set struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param local_position_setpoint_set C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_local_position_setpoint_set_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_local_position_setpoint_set_t* local_position_setpoint_set)
{
return mavlink_msg_local_position_setpoint_set_pack(system_id, component_id, msg, local_position_setpoint_set->target_system, local_position_setpoint_set->target_component, local_position_setpoint_set->x, local_position_setpoint_set->y, local_position_setpoint_set->z, local_position_setpoint_set->yaw);
}
 
/**
* @brief Send a local_position_setpoint_set message
* @param chan MAVLink channel to send the message
*
* @param target_system System ID
* @param target_component Component ID
* @param x x position
* @param y y position
* @param z z position
* @param yaw Desired yaw angle
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_local_position_setpoint_set_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, float x, float y, float z, float yaw)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[18];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
_mav_put_float(buf, 2, x);
_mav_put_float(buf, 6, y);
_mav_put_float(buf, 10, z);
_mav_put_float(buf, 14, yaw);
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT_SET, buf, 18);
#else
mavlink_local_position_setpoint_set_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
packet.x = x;
packet.y = y;
packet.z = z;
packet.yaw = yaw;
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT_SET, (const char *)&packet, 18);
#endif
}
 
#endif
 
// MESSAGE LOCAL_POSITION_SETPOINT_SET UNPACKING
 
 
/**
* @brief Get field target_system from local_position_setpoint_set message
*
* @return System ID
*/
static inline uint8_t mavlink_msg_local_position_setpoint_set_get_target_system(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 0);
}
 
/**
* @brief Get field target_component from local_position_setpoint_set message
*
* @return Component ID
*/
static inline uint8_t mavlink_msg_local_position_setpoint_set_get_target_component(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 1);
}
 
/**
* @brief Get field x from local_position_setpoint_set message
*
* @return x position
*/
static inline float mavlink_msg_local_position_setpoint_set_get_x(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 2);
}
 
/**
* @brief Get field y from local_position_setpoint_set message
*
* @return y position
*/
static inline float mavlink_msg_local_position_setpoint_set_get_y(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 6);
}
 
/**
* @brief Get field z from local_position_setpoint_set message
*
* @return z position
*/
static inline float mavlink_msg_local_position_setpoint_set_get_z(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 10);
}
 
/**
* @brief Get field yaw from local_position_setpoint_set message
*
* @return Desired yaw angle
*/
static inline float mavlink_msg_local_position_setpoint_set_get_yaw(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 14);
}
 
/**
* @brief Decode a local_position_setpoint_set message into a struct
*
* @param msg The message to decode
* @param local_position_setpoint_set C-struct to decode the message contents into
*/
static inline void mavlink_msg_local_position_setpoint_set_decode(const mavlink_message_t* msg, mavlink_local_position_setpoint_set_t* local_position_setpoint_set)
{
#if MAVLINK_NEED_BYTE_SWAP
local_position_setpoint_set->target_system = mavlink_msg_local_position_setpoint_set_get_target_system(msg);
local_position_setpoint_set->target_component = mavlink_msg_local_position_setpoint_set_get_target_component(msg);
local_position_setpoint_set->x = mavlink_msg_local_position_setpoint_set_get_x(msg);
local_position_setpoint_set->y = mavlink_msg_local_position_setpoint_set_get_y(msg);
local_position_setpoint_set->z = mavlink_msg_local_position_setpoint_set_get_z(msg);
local_position_setpoint_set->yaw = mavlink_msg_local_position_setpoint_set_get_yaw(msg);
#else
memcpy(local_position_setpoint_set, _MAV_PAYLOAD(msg), 18);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v0.9/common/mavlink_msg_manual_control.h
0,0 → 1,320
// MESSAGE MANUAL_CONTROL PACKING
 
#define MAVLINK_MSG_ID_MANUAL_CONTROL 69
 
typedef struct __mavlink_manual_control_t
{
uint8_t target; ///< The system to be controlled
float roll; ///< roll
float pitch; ///< pitch
float yaw; ///< yaw
float thrust; ///< thrust
uint8_t roll_manual; ///< roll control enabled auto:0, manual:1
uint8_t pitch_manual; ///< pitch auto:0, manual:1
uint8_t yaw_manual; ///< yaw auto:0, manual:1
uint8_t thrust_manual; ///< thrust auto:0, manual:1
} mavlink_manual_control_t;
 
#define MAVLINK_MSG_ID_MANUAL_CONTROL_LEN 21
#define MAVLINK_MSG_ID_69_LEN 21
 
 
 
#define MAVLINK_MESSAGE_INFO_MANUAL_CONTROL { \
"MANUAL_CONTROL", \
9, \
{ { "target", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_manual_control_t, target) }, \
{ "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 1, offsetof(mavlink_manual_control_t, roll) }, \
{ "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 5, offsetof(mavlink_manual_control_t, pitch) }, \
{ "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 9, offsetof(mavlink_manual_control_t, yaw) }, \
{ "thrust", NULL, MAVLINK_TYPE_FLOAT, 0, 13, offsetof(mavlink_manual_control_t, thrust) }, \
{ "roll_manual", NULL, MAVLINK_TYPE_UINT8_T, 0, 17, offsetof(mavlink_manual_control_t, roll_manual) }, \
{ "pitch_manual", NULL, MAVLINK_TYPE_UINT8_T, 0, 18, offsetof(mavlink_manual_control_t, pitch_manual) }, \
{ "yaw_manual", NULL, MAVLINK_TYPE_UINT8_T, 0, 19, offsetof(mavlink_manual_control_t, yaw_manual) }, \
{ "thrust_manual", NULL, MAVLINK_TYPE_UINT8_T, 0, 20, offsetof(mavlink_manual_control_t, thrust_manual) }, \
} \
}
 
 
/**
* @brief Pack a manual_control message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param target The system to be controlled
* @param roll roll
* @param pitch pitch
* @param yaw yaw
* @param thrust thrust
* @param roll_manual roll control enabled auto:0, manual:1
* @param pitch_manual pitch auto:0, manual:1
* @param yaw_manual yaw auto:0, manual:1
* @param thrust_manual thrust auto:0, manual:1
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_manual_control_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t target, float roll, float pitch, float yaw, float thrust, uint8_t roll_manual, uint8_t pitch_manual, uint8_t yaw_manual, uint8_t thrust_manual)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[21];
_mav_put_uint8_t(buf, 0, target);
_mav_put_float(buf, 1, roll);
_mav_put_float(buf, 5, pitch);
_mav_put_float(buf, 9, yaw);
_mav_put_float(buf, 13, thrust);
_mav_put_uint8_t(buf, 17, roll_manual);
_mav_put_uint8_t(buf, 18, pitch_manual);
_mav_put_uint8_t(buf, 19, yaw_manual);
_mav_put_uint8_t(buf, 20, thrust_manual);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 21);
#else
mavlink_manual_control_t packet;
packet.target = target;
packet.roll = roll;
packet.pitch = pitch;
packet.yaw = yaw;
packet.thrust = thrust;
packet.roll_manual = roll_manual;
packet.pitch_manual = pitch_manual;
packet.yaw_manual = yaw_manual;
packet.thrust_manual = thrust_manual;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 21);
#endif
 
msg->msgid = MAVLINK_MSG_ID_MANUAL_CONTROL;
return mavlink_finalize_message(msg, system_id, component_id, 21);
}
 
/**
* @brief Pack a manual_control message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param target The system to be controlled
* @param roll roll
* @param pitch pitch
* @param yaw yaw
* @param thrust thrust
* @param roll_manual roll control enabled auto:0, manual:1
* @param pitch_manual pitch auto:0, manual:1
* @param yaw_manual yaw auto:0, manual:1
* @param thrust_manual thrust auto:0, manual:1
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_manual_control_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint8_t target,float roll,float pitch,float yaw,float thrust,uint8_t roll_manual,uint8_t pitch_manual,uint8_t yaw_manual,uint8_t thrust_manual)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[21];
_mav_put_uint8_t(buf, 0, target);
_mav_put_float(buf, 1, roll);
_mav_put_float(buf, 5, pitch);
_mav_put_float(buf, 9, yaw);
_mav_put_float(buf, 13, thrust);
_mav_put_uint8_t(buf, 17, roll_manual);
_mav_put_uint8_t(buf, 18, pitch_manual);
_mav_put_uint8_t(buf, 19, yaw_manual);
_mav_put_uint8_t(buf, 20, thrust_manual);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 21);
#else
mavlink_manual_control_t packet;
packet.target = target;
packet.roll = roll;
packet.pitch = pitch;
packet.yaw = yaw;
packet.thrust = thrust;
packet.roll_manual = roll_manual;
packet.pitch_manual = pitch_manual;
packet.yaw_manual = yaw_manual;
packet.thrust_manual = thrust_manual;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 21);
#endif
 
msg->msgid = MAVLINK_MSG_ID_MANUAL_CONTROL;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 21);
}
 
/**
* @brief Encode a manual_control struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param manual_control C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_manual_control_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_manual_control_t* manual_control)
{
return mavlink_msg_manual_control_pack(system_id, component_id, msg, manual_control->target, manual_control->roll, manual_control->pitch, manual_control->yaw, manual_control->thrust, manual_control->roll_manual, manual_control->pitch_manual, manual_control->yaw_manual, manual_control->thrust_manual);
}
 
/**
* @brief Send a manual_control message
* @param chan MAVLink channel to send the message
*
* @param target The system to be controlled
* @param roll roll
* @param pitch pitch
* @param yaw yaw
* @param thrust thrust
* @param roll_manual roll control enabled auto:0, manual:1
* @param pitch_manual pitch auto:0, manual:1
* @param yaw_manual yaw auto:0, manual:1
* @param thrust_manual thrust auto:0, manual:1
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_manual_control_send(mavlink_channel_t chan, uint8_t target, float roll, float pitch, float yaw, float thrust, uint8_t roll_manual, uint8_t pitch_manual, uint8_t yaw_manual, uint8_t thrust_manual)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[21];
_mav_put_uint8_t(buf, 0, target);
_mav_put_float(buf, 1, roll);
_mav_put_float(buf, 5, pitch);
_mav_put_float(buf, 9, yaw);
_mav_put_float(buf, 13, thrust);
_mav_put_uint8_t(buf, 17, roll_manual);
_mav_put_uint8_t(buf, 18, pitch_manual);
_mav_put_uint8_t(buf, 19, yaw_manual);
_mav_put_uint8_t(buf, 20, thrust_manual);
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MANUAL_CONTROL, buf, 21);
#else
mavlink_manual_control_t packet;
packet.target = target;
packet.roll = roll;
packet.pitch = pitch;
packet.yaw = yaw;
packet.thrust = thrust;
packet.roll_manual = roll_manual;
packet.pitch_manual = pitch_manual;
packet.yaw_manual = yaw_manual;
packet.thrust_manual = thrust_manual;
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MANUAL_CONTROL, (const char *)&packet, 21);
#endif
}
 
#endif
 
// MESSAGE MANUAL_CONTROL UNPACKING
 
 
/**
* @brief Get field target from manual_control message
*
* @return The system to be controlled
*/
static inline uint8_t mavlink_msg_manual_control_get_target(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 0);
}
 
/**
* @brief Get field roll from manual_control message
*
* @return roll
*/
static inline float mavlink_msg_manual_control_get_roll(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 1);
}
 
/**
* @brief Get field pitch from manual_control message
*
* @return pitch
*/
static inline float mavlink_msg_manual_control_get_pitch(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 5);
}
 
/**
* @brief Get field yaw from manual_control message
*
* @return yaw
*/
static inline float mavlink_msg_manual_control_get_yaw(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 9);
}
 
/**
* @brief Get field thrust from manual_control message
*
* @return thrust
*/
static inline float mavlink_msg_manual_control_get_thrust(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 13);
}
 
/**
* @brief Get field roll_manual from manual_control message
*
* @return roll control enabled auto:0, manual:1
*/
static inline uint8_t mavlink_msg_manual_control_get_roll_manual(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 17);
}
 
/**
* @brief Get field pitch_manual from manual_control message
*
* @return pitch auto:0, manual:1
*/
static inline uint8_t mavlink_msg_manual_control_get_pitch_manual(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 18);
}
 
/**
* @brief Get field yaw_manual from manual_control message
*
* @return yaw auto:0, manual:1
*/
static inline uint8_t mavlink_msg_manual_control_get_yaw_manual(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 19);
}
 
/**
* @brief Get field thrust_manual from manual_control message
*
* @return thrust auto:0, manual:1
*/
static inline uint8_t mavlink_msg_manual_control_get_thrust_manual(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 20);
}
 
/**
* @brief Decode a manual_control message into a struct
*
* @param msg The message to decode
* @param manual_control C-struct to decode the message contents into
*/
static inline void mavlink_msg_manual_control_decode(const mavlink_message_t* msg, mavlink_manual_control_t* manual_control)
{
#if MAVLINK_NEED_BYTE_SWAP
manual_control->target = mavlink_msg_manual_control_get_target(msg);
manual_control->roll = mavlink_msg_manual_control_get_roll(msg);
manual_control->pitch = mavlink_msg_manual_control_get_pitch(msg);
manual_control->yaw = mavlink_msg_manual_control_get_yaw(msg);
manual_control->thrust = mavlink_msg_manual_control_get_thrust(msg);
manual_control->roll_manual = mavlink_msg_manual_control_get_roll_manual(msg);
manual_control->pitch_manual = mavlink_msg_manual_control_get_pitch_manual(msg);
manual_control->yaw_manual = mavlink_msg_manual_control_get_yaw_manual(msg);
manual_control->thrust_manual = mavlink_msg_manual_control_get_thrust_manual(msg);
#else
memcpy(manual_control, _MAV_PAYLOAD(msg), 21);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v0.9/common/mavlink_msg_named_value_float.h
0,0 → 1,160
// MESSAGE NAMED_VALUE_FLOAT PACKING
 
#define MAVLINK_MSG_ID_NAMED_VALUE_FLOAT 252
 
typedef struct __mavlink_named_value_float_t
{
char name[10]; ///< Name of the debug variable
float value; ///< Floating point value
} mavlink_named_value_float_t;
 
#define MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN 14
#define MAVLINK_MSG_ID_252_LEN 14
 
#define MAVLINK_MSG_NAMED_VALUE_FLOAT_FIELD_NAME_LEN 10
 
#define MAVLINK_MESSAGE_INFO_NAMED_VALUE_FLOAT { \
"NAMED_VALUE_FLOAT", \
2, \
{ { "name", NULL, MAVLINK_TYPE_CHAR, 10, 0, offsetof(mavlink_named_value_float_t, name) }, \
{ "value", NULL, MAVLINK_TYPE_FLOAT, 0, 10, offsetof(mavlink_named_value_float_t, value) }, \
} \
}
 
 
/**
* @brief Pack a named_value_float message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param name Name of the debug variable
* @param value Floating point value
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_named_value_float_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
const char *name, float value)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[14];
_mav_put_float(buf, 10, value);
_mav_put_char_array(buf, 0, name, 10);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 14);
#else
mavlink_named_value_float_t packet;
packet.value = value;
mav_array_memcpy(packet.name, name, sizeof(char)*10);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 14);
#endif
 
msg->msgid = MAVLINK_MSG_ID_NAMED_VALUE_FLOAT;
return mavlink_finalize_message(msg, system_id, component_id, 14);
}
 
/**
* @brief Pack a named_value_float message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param name Name of the debug variable
* @param value Floating point value
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_named_value_float_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
const char *name,float value)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[14];
_mav_put_float(buf, 10, value);
_mav_put_char_array(buf, 0, name, 10);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 14);
#else
mavlink_named_value_float_t packet;
packet.value = value;
mav_array_memcpy(packet.name, name, sizeof(char)*10);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 14);
#endif
 
msg->msgid = MAVLINK_MSG_ID_NAMED_VALUE_FLOAT;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 14);
}
 
/**
* @brief Encode a named_value_float struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param named_value_float C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_named_value_float_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_named_value_float_t* named_value_float)
{
return mavlink_msg_named_value_float_pack(system_id, component_id, msg, named_value_float->name, named_value_float->value);
}
 
/**
* @brief Send a named_value_float message
* @param chan MAVLink channel to send the message
*
* @param name Name of the debug variable
* @param value Floating point value
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_named_value_float_send(mavlink_channel_t chan, const char *name, float value)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[14];
_mav_put_float(buf, 10, value);
_mav_put_char_array(buf, 0, name, 10);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT, buf, 14);
#else
mavlink_named_value_float_t packet;
packet.value = value;
mav_array_memcpy(packet.name, name, sizeof(char)*10);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT, (const char *)&packet, 14);
#endif
}
 
#endif
 
// MESSAGE NAMED_VALUE_FLOAT UNPACKING
 
 
/**
* @brief Get field name from named_value_float message
*
* @return Name of the debug variable
*/
static inline uint16_t mavlink_msg_named_value_float_get_name(const mavlink_message_t* msg, char *name)
{
return _MAV_RETURN_char_array(msg, name, 10, 0);
}
 
/**
* @brief Get field value from named_value_float message
*
* @return Floating point value
*/
static inline float mavlink_msg_named_value_float_get_value(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 10);
}
 
/**
* @brief Decode a named_value_float message into a struct
*
* @param msg The message to decode
* @param named_value_float C-struct to decode the message contents into
*/
static inline void mavlink_msg_named_value_float_decode(const mavlink_message_t* msg, mavlink_named_value_float_t* named_value_float)
{
#if MAVLINK_NEED_BYTE_SWAP
mavlink_msg_named_value_float_get_name(msg, named_value_float->name);
named_value_float->value = mavlink_msg_named_value_float_get_value(msg);
#else
memcpy(named_value_float, _MAV_PAYLOAD(msg), 14);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v0.9/common/mavlink_msg_named_value_int.h
0,0 → 1,160
// MESSAGE NAMED_VALUE_INT PACKING
 
#define MAVLINK_MSG_ID_NAMED_VALUE_INT 253
 
typedef struct __mavlink_named_value_int_t
{
char name[10]; ///< Name of the debug variable
int32_t value; ///< Signed integer value
} mavlink_named_value_int_t;
 
#define MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN 14
#define MAVLINK_MSG_ID_253_LEN 14
 
#define MAVLINK_MSG_NAMED_VALUE_INT_FIELD_NAME_LEN 10
 
#define MAVLINK_MESSAGE_INFO_NAMED_VALUE_INT { \
"NAMED_VALUE_INT", \
2, \
{ { "name", NULL, MAVLINK_TYPE_CHAR, 10, 0, offsetof(mavlink_named_value_int_t, name) }, \
{ "value", NULL, MAVLINK_TYPE_INT32_T, 0, 10, offsetof(mavlink_named_value_int_t, value) }, \
} \
}
 
 
/**
* @brief Pack a named_value_int message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param name Name of the debug variable
* @param value Signed integer value
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_named_value_int_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
const char *name, int32_t value)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[14];
_mav_put_int32_t(buf, 10, value);
_mav_put_char_array(buf, 0, name, 10);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 14);
#else
mavlink_named_value_int_t packet;
packet.value = value;
mav_array_memcpy(packet.name, name, sizeof(char)*10);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 14);
#endif
 
msg->msgid = MAVLINK_MSG_ID_NAMED_VALUE_INT;
return mavlink_finalize_message(msg, system_id, component_id, 14);
}
 
/**
* @brief Pack a named_value_int message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param name Name of the debug variable
* @param value Signed integer value
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_named_value_int_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
const char *name,int32_t value)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[14];
_mav_put_int32_t(buf, 10, value);
_mav_put_char_array(buf, 0, name, 10);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 14);
#else
mavlink_named_value_int_t packet;
packet.value = value;
mav_array_memcpy(packet.name, name, sizeof(char)*10);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 14);
#endif
 
msg->msgid = MAVLINK_MSG_ID_NAMED_VALUE_INT;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 14);
}
 
/**
* @brief Encode a named_value_int struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param named_value_int C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_named_value_int_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_named_value_int_t* named_value_int)
{
return mavlink_msg_named_value_int_pack(system_id, component_id, msg, named_value_int->name, named_value_int->value);
}
 
/**
* @brief Send a named_value_int message
* @param chan MAVLink channel to send the message
*
* @param name Name of the debug variable
* @param value Signed integer value
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_named_value_int_send(mavlink_channel_t chan, const char *name, int32_t value)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[14];
_mav_put_int32_t(buf, 10, value);
_mav_put_char_array(buf, 0, name, 10);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAMED_VALUE_INT, buf, 14);
#else
mavlink_named_value_int_t packet;
packet.value = value;
mav_array_memcpy(packet.name, name, sizeof(char)*10);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAMED_VALUE_INT, (const char *)&packet, 14);
#endif
}
 
#endif
 
// MESSAGE NAMED_VALUE_INT UNPACKING
 
 
/**
* @brief Get field name from named_value_int message
*
* @return Name of the debug variable
*/
static inline uint16_t mavlink_msg_named_value_int_get_name(const mavlink_message_t* msg, char *name)
{
return _MAV_RETURN_char_array(msg, name, 10, 0);
}
 
/**
* @brief Get field value from named_value_int message
*
* @return Signed integer value
*/
static inline int32_t mavlink_msg_named_value_int_get_value(const mavlink_message_t* msg)
{
return _MAV_RETURN_int32_t(msg, 10);
}
 
/**
* @brief Decode a named_value_int message into a struct
*
* @param msg The message to decode
* @param named_value_int C-struct to decode the message contents into
*/
static inline void mavlink_msg_named_value_int_decode(const mavlink_message_t* msg, mavlink_named_value_int_t* named_value_int)
{
#if MAVLINK_NEED_BYTE_SWAP
mavlink_msg_named_value_int_get_name(msg, named_value_int->name);
named_value_int->value = mavlink_msg_named_value_int_get_value(msg);
#else
memcpy(named_value_int, _MAV_PAYLOAD(msg), 14);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v0.9/common/mavlink_msg_nav_controller_output.h
0,0 → 1,298
// MESSAGE NAV_CONTROLLER_OUTPUT PACKING
 
#define MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT 62
 
typedef struct __mavlink_nav_controller_output_t
{
float nav_roll; ///< Current desired roll in degrees
float nav_pitch; ///< Current desired pitch in degrees
int16_t nav_bearing; ///< Current desired heading in degrees
int16_t target_bearing; ///< Bearing to current waypoint/target in degrees
uint16_t wp_dist; ///< Distance to active waypoint in meters
float alt_error; ///< Current altitude error in meters
float aspd_error; ///< Current airspeed error in meters/second
float xtrack_error; ///< Current crosstrack error on x-y plane in meters
} mavlink_nav_controller_output_t;
 
#define MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN 26
#define MAVLINK_MSG_ID_62_LEN 26
 
 
 
#define MAVLINK_MESSAGE_INFO_NAV_CONTROLLER_OUTPUT { \
"NAV_CONTROLLER_OUTPUT", \
8, \
{ { "nav_roll", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_nav_controller_output_t, nav_roll) }, \
{ "nav_pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_nav_controller_output_t, nav_pitch) }, \
{ "nav_bearing", NULL, MAVLINK_TYPE_INT16_T, 0, 8, offsetof(mavlink_nav_controller_output_t, nav_bearing) }, \
{ "target_bearing", NULL, MAVLINK_TYPE_INT16_T, 0, 10, offsetof(mavlink_nav_controller_output_t, target_bearing) }, \
{ "wp_dist", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_nav_controller_output_t, wp_dist) }, \
{ "alt_error", NULL, MAVLINK_TYPE_FLOAT, 0, 14, offsetof(mavlink_nav_controller_output_t, alt_error) }, \
{ "aspd_error", NULL, MAVLINK_TYPE_FLOAT, 0, 18, offsetof(mavlink_nav_controller_output_t, aspd_error) }, \
{ "xtrack_error", NULL, MAVLINK_TYPE_FLOAT, 0, 22, offsetof(mavlink_nav_controller_output_t, xtrack_error) }, \
} \
}
 
 
/**
* @brief Pack a nav_controller_output message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param nav_roll Current desired roll in degrees
* @param nav_pitch Current desired pitch in degrees
* @param nav_bearing Current desired heading in degrees
* @param target_bearing Bearing to current waypoint/target in degrees
* @param wp_dist Distance to active waypoint in meters
* @param alt_error Current altitude error in meters
* @param aspd_error Current airspeed error in meters/second
* @param xtrack_error Current crosstrack error on x-y plane in meters
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_nav_controller_output_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
float nav_roll, float nav_pitch, int16_t nav_bearing, int16_t target_bearing, uint16_t wp_dist, float alt_error, float aspd_error, float xtrack_error)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[26];
_mav_put_float(buf, 0, nav_roll);
_mav_put_float(buf, 4, nav_pitch);
_mav_put_int16_t(buf, 8, nav_bearing);
_mav_put_int16_t(buf, 10, target_bearing);
_mav_put_uint16_t(buf, 12, wp_dist);
_mav_put_float(buf, 14, alt_error);
_mav_put_float(buf, 18, aspd_error);
_mav_put_float(buf, 22, xtrack_error);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 26);
#else
mavlink_nav_controller_output_t packet;
packet.nav_roll = nav_roll;
packet.nav_pitch = nav_pitch;
packet.nav_bearing = nav_bearing;
packet.target_bearing = target_bearing;
packet.wp_dist = wp_dist;
packet.alt_error = alt_error;
packet.aspd_error = aspd_error;
packet.xtrack_error = xtrack_error;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 26);
#endif
 
msg->msgid = MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT;
return mavlink_finalize_message(msg, system_id, component_id, 26);
}
 
/**
* @brief Pack a nav_controller_output message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param nav_roll Current desired roll in degrees
* @param nav_pitch Current desired pitch in degrees
* @param nav_bearing Current desired heading in degrees
* @param target_bearing Bearing to current waypoint/target in degrees
* @param wp_dist Distance to active waypoint in meters
* @param alt_error Current altitude error in meters
* @param aspd_error Current airspeed error in meters/second
* @param xtrack_error Current crosstrack error on x-y plane in meters
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_nav_controller_output_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
float nav_roll,float nav_pitch,int16_t nav_bearing,int16_t target_bearing,uint16_t wp_dist,float alt_error,float aspd_error,float xtrack_error)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[26];
_mav_put_float(buf, 0, nav_roll);
_mav_put_float(buf, 4, nav_pitch);
_mav_put_int16_t(buf, 8, nav_bearing);
_mav_put_int16_t(buf, 10, target_bearing);
_mav_put_uint16_t(buf, 12, wp_dist);
_mav_put_float(buf, 14, alt_error);
_mav_put_float(buf, 18, aspd_error);
_mav_put_float(buf, 22, xtrack_error);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 26);
#else
mavlink_nav_controller_output_t packet;
packet.nav_roll = nav_roll;
packet.nav_pitch = nav_pitch;
packet.nav_bearing = nav_bearing;
packet.target_bearing = target_bearing;
packet.wp_dist = wp_dist;
packet.alt_error = alt_error;
packet.aspd_error = aspd_error;
packet.xtrack_error = xtrack_error;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 26);
#endif
 
msg->msgid = MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 26);
}
 
/**
* @brief Encode a nav_controller_output struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param nav_controller_output C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_nav_controller_output_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_nav_controller_output_t* nav_controller_output)
{
return mavlink_msg_nav_controller_output_pack(system_id, component_id, msg, nav_controller_output->nav_roll, nav_controller_output->nav_pitch, nav_controller_output->nav_bearing, nav_controller_output->target_bearing, nav_controller_output->wp_dist, nav_controller_output->alt_error, nav_controller_output->aspd_error, nav_controller_output->xtrack_error);
}
 
/**
* @brief Send a nav_controller_output message
* @param chan MAVLink channel to send the message
*
* @param nav_roll Current desired roll in degrees
* @param nav_pitch Current desired pitch in degrees
* @param nav_bearing Current desired heading in degrees
* @param target_bearing Bearing to current waypoint/target in degrees
* @param wp_dist Distance to active waypoint in meters
* @param alt_error Current altitude error in meters
* @param aspd_error Current airspeed error in meters/second
* @param xtrack_error Current crosstrack error on x-y plane in meters
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_nav_controller_output_send(mavlink_channel_t chan, float nav_roll, float nav_pitch, int16_t nav_bearing, int16_t target_bearing, uint16_t wp_dist, float alt_error, float aspd_error, float xtrack_error)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[26];
_mav_put_float(buf, 0, nav_roll);
_mav_put_float(buf, 4, nav_pitch);
_mav_put_int16_t(buf, 8, nav_bearing);
_mav_put_int16_t(buf, 10, target_bearing);
_mav_put_uint16_t(buf, 12, wp_dist);
_mav_put_float(buf, 14, alt_error);
_mav_put_float(buf, 18, aspd_error);
_mav_put_float(buf, 22, xtrack_error);
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT, buf, 26);
#else
mavlink_nav_controller_output_t packet;
packet.nav_roll = nav_roll;
packet.nav_pitch = nav_pitch;
packet.nav_bearing = nav_bearing;
packet.target_bearing = target_bearing;
packet.wp_dist = wp_dist;
packet.alt_error = alt_error;
packet.aspd_error = aspd_error;
packet.xtrack_error = xtrack_error;
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT, (const char *)&packet, 26);
#endif
}
 
#endif
 
// MESSAGE NAV_CONTROLLER_OUTPUT UNPACKING
 
 
/**
* @brief Get field nav_roll from nav_controller_output message
*
* @return Current desired roll in degrees
*/
static inline float mavlink_msg_nav_controller_output_get_nav_roll(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 0);
}
 
/**
* @brief Get field nav_pitch from nav_controller_output message
*
* @return Current desired pitch in degrees
*/
static inline float mavlink_msg_nav_controller_output_get_nav_pitch(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 4);
}
 
/**
* @brief Get field nav_bearing from nav_controller_output message
*
* @return Current desired heading in degrees
*/
static inline int16_t mavlink_msg_nav_controller_output_get_nav_bearing(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 8);
}
 
/**
* @brief Get field target_bearing from nav_controller_output message
*
* @return Bearing to current waypoint/target in degrees
*/
static inline int16_t mavlink_msg_nav_controller_output_get_target_bearing(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 10);
}
 
/**
* @brief Get field wp_dist from nav_controller_output message
*
* @return Distance to active waypoint in meters
*/
static inline uint16_t mavlink_msg_nav_controller_output_get_wp_dist(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 12);
}
 
/**
* @brief Get field alt_error from nav_controller_output message
*
* @return Current altitude error in meters
*/
static inline float mavlink_msg_nav_controller_output_get_alt_error(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 14);
}
 
/**
* @brief Get field aspd_error from nav_controller_output message
*
* @return Current airspeed error in meters/second
*/
static inline float mavlink_msg_nav_controller_output_get_aspd_error(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 18);
}
 
/**
* @brief Get field xtrack_error from nav_controller_output message
*
* @return Current crosstrack error on x-y plane in meters
*/
static inline float mavlink_msg_nav_controller_output_get_xtrack_error(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 22);
}
 
/**
* @brief Decode a nav_controller_output message into a struct
*
* @param msg The message to decode
* @param nav_controller_output C-struct to decode the message contents into
*/
static inline void mavlink_msg_nav_controller_output_decode(const mavlink_message_t* msg, mavlink_nav_controller_output_t* nav_controller_output)
{
#if MAVLINK_NEED_BYTE_SWAP
nav_controller_output->nav_roll = mavlink_msg_nav_controller_output_get_nav_roll(msg);
nav_controller_output->nav_pitch = mavlink_msg_nav_controller_output_get_nav_pitch(msg);
nav_controller_output->nav_bearing = mavlink_msg_nav_controller_output_get_nav_bearing(msg);
nav_controller_output->target_bearing = mavlink_msg_nav_controller_output_get_target_bearing(msg);
nav_controller_output->wp_dist = mavlink_msg_nav_controller_output_get_wp_dist(msg);
nav_controller_output->alt_error = mavlink_msg_nav_controller_output_get_alt_error(msg);
nav_controller_output->aspd_error = mavlink_msg_nav_controller_output_get_aspd_error(msg);
nav_controller_output->xtrack_error = mavlink_msg_nav_controller_output_get_xtrack_error(msg);
#else
memcpy(nav_controller_output, _MAV_PAYLOAD(msg), 26);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v0.9/common/mavlink_msg_object_detection_event.h
0,0 → 1,270
// MESSAGE OBJECT_DETECTION_EVENT PACKING
 
#define MAVLINK_MSG_ID_OBJECT_DETECTION_EVENT 140
 
typedef struct __mavlink_object_detection_event_t
{
uint32_t time; ///< Timestamp in milliseconds since system boot
uint16_t object_id; ///< Object ID
uint8_t type; ///< Object type: 0: image, 1: letter, 2: ground vehicle, 3: air vehicle, 4: surface vehicle, 5: sub-surface vehicle, 6: human, 7: animal
char name[20]; ///< Name of the object as defined by the detector
uint8_t quality; ///< Detection quality / confidence. 0: bad, 255: maximum confidence
float bearing; ///< Angle of the object with respect to the body frame in NED coordinates in radians. 0: front
float distance; ///< Ground distance in meters
} mavlink_object_detection_event_t;
 
#define MAVLINK_MSG_ID_OBJECT_DETECTION_EVENT_LEN 36
#define MAVLINK_MSG_ID_140_LEN 36
 
#define MAVLINK_MSG_OBJECT_DETECTION_EVENT_FIELD_NAME_LEN 20
 
#define MAVLINK_MESSAGE_INFO_OBJECT_DETECTION_EVENT { \
"OBJECT_DETECTION_EVENT", \
7, \
{ { "time", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_object_detection_event_t, time) }, \
{ "object_id", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_object_detection_event_t, object_id) }, \
{ "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_object_detection_event_t, type) }, \
{ "name", NULL, MAVLINK_TYPE_CHAR, 20, 7, offsetof(mavlink_object_detection_event_t, name) }, \
{ "quality", NULL, MAVLINK_TYPE_UINT8_T, 0, 27, offsetof(mavlink_object_detection_event_t, quality) }, \
{ "bearing", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_object_detection_event_t, bearing) }, \
{ "distance", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_object_detection_event_t, distance) }, \
} \
}
 
 
/**
* @brief Pack a object_detection_event message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param time Timestamp in milliseconds since system boot
* @param object_id Object ID
* @param type Object type: 0: image, 1: letter, 2: ground vehicle, 3: air vehicle, 4: surface vehicle, 5: sub-surface vehicle, 6: human, 7: animal
* @param name Name of the object as defined by the detector
* @param quality Detection quality / confidence. 0: bad, 255: maximum confidence
* @param bearing Angle of the object with respect to the body frame in NED coordinates in radians. 0: front
* @param distance Ground distance in meters
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_object_detection_event_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint32_t time, uint16_t object_id, uint8_t type, const char *name, uint8_t quality, float bearing, float distance)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[36];
_mav_put_uint32_t(buf, 0, time);
_mav_put_uint16_t(buf, 4, object_id);
_mav_put_uint8_t(buf, 6, type);
_mav_put_uint8_t(buf, 27, quality);
_mav_put_float(buf, 28, bearing);
_mav_put_float(buf, 32, distance);
_mav_put_char_array(buf, 7, name, 20);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 36);
#else
mavlink_object_detection_event_t packet;
packet.time = time;
packet.object_id = object_id;
packet.type = type;
packet.quality = quality;
packet.bearing = bearing;
packet.distance = distance;
mav_array_memcpy(packet.name, name, sizeof(char)*20);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 36);
#endif
 
msg->msgid = MAVLINK_MSG_ID_OBJECT_DETECTION_EVENT;
return mavlink_finalize_message(msg, system_id, component_id, 36);
}
 
/**
* @brief Pack a object_detection_event message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param time Timestamp in milliseconds since system boot
* @param object_id Object ID
* @param type Object type: 0: image, 1: letter, 2: ground vehicle, 3: air vehicle, 4: surface vehicle, 5: sub-surface vehicle, 6: human, 7: animal
* @param name Name of the object as defined by the detector
* @param quality Detection quality / confidence. 0: bad, 255: maximum confidence
* @param bearing Angle of the object with respect to the body frame in NED coordinates in radians. 0: front
* @param distance Ground distance in meters
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_object_detection_event_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint32_t time,uint16_t object_id,uint8_t type,const char *name,uint8_t quality,float bearing,float distance)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[36];
_mav_put_uint32_t(buf, 0, time);
_mav_put_uint16_t(buf, 4, object_id);
_mav_put_uint8_t(buf, 6, type);
_mav_put_uint8_t(buf, 27, quality);
_mav_put_float(buf, 28, bearing);
_mav_put_float(buf, 32, distance);
_mav_put_char_array(buf, 7, name, 20);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 36);
#else
mavlink_object_detection_event_t packet;
packet.time = time;
packet.object_id = object_id;
packet.type = type;
packet.quality = quality;
packet.bearing = bearing;
packet.distance = distance;
mav_array_memcpy(packet.name, name, sizeof(char)*20);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 36);
#endif
 
msg->msgid = MAVLINK_MSG_ID_OBJECT_DETECTION_EVENT;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 36);
}
 
/**
* @brief Encode a object_detection_event struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param object_detection_event C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_object_detection_event_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_object_detection_event_t* object_detection_event)
{
return mavlink_msg_object_detection_event_pack(system_id, component_id, msg, object_detection_event->time, object_detection_event->object_id, object_detection_event->type, object_detection_event->name, object_detection_event->quality, object_detection_event->bearing, object_detection_event->distance);
}
 
/**
* @brief Send a object_detection_event message
* @param chan MAVLink channel to send the message
*
* @param time Timestamp in milliseconds since system boot
* @param object_id Object ID
* @param type Object type: 0: image, 1: letter, 2: ground vehicle, 3: air vehicle, 4: surface vehicle, 5: sub-surface vehicle, 6: human, 7: animal
* @param name Name of the object as defined by the detector
* @param quality Detection quality / confidence. 0: bad, 255: maximum confidence
* @param bearing Angle of the object with respect to the body frame in NED coordinates in radians. 0: front
* @param distance Ground distance in meters
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_object_detection_event_send(mavlink_channel_t chan, uint32_t time, uint16_t object_id, uint8_t type, const char *name, uint8_t quality, float bearing, float distance)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[36];
_mav_put_uint32_t(buf, 0, time);
_mav_put_uint16_t(buf, 4, object_id);
_mav_put_uint8_t(buf, 6, type);
_mav_put_uint8_t(buf, 27, quality);
_mav_put_float(buf, 28, bearing);
_mav_put_float(buf, 32, distance);
_mav_put_char_array(buf, 7, name, 20);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBJECT_DETECTION_EVENT, buf, 36);
#else
mavlink_object_detection_event_t packet;
packet.time = time;
packet.object_id = object_id;
packet.type = type;
packet.quality = quality;
packet.bearing = bearing;
packet.distance = distance;
mav_array_memcpy(packet.name, name, sizeof(char)*20);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBJECT_DETECTION_EVENT, (const char *)&packet, 36);
#endif
}
 
#endif
 
// MESSAGE OBJECT_DETECTION_EVENT UNPACKING
 
 
/**
* @brief Get field time from object_detection_event message
*
* @return Timestamp in milliseconds since system boot
*/
static inline uint32_t mavlink_msg_object_detection_event_get_time(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint32_t(msg, 0);
}
 
/**
* @brief Get field object_id from object_detection_event message
*
* @return Object ID
*/
static inline uint16_t mavlink_msg_object_detection_event_get_object_id(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 4);
}
 
/**
* @brief Get field type from object_detection_event message
*
* @return Object type: 0: image, 1: letter, 2: ground vehicle, 3: air vehicle, 4: surface vehicle, 5: sub-surface vehicle, 6: human, 7: animal
*/
static inline uint8_t mavlink_msg_object_detection_event_get_type(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 6);
}
 
/**
* @brief Get field name from object_detection_event message
*
* @return Name of the object as defined by the detector
*/
static inline uint16_t mavlink_msg_object_detection_event_get_name(const mavlink_message_t* msg, char *name)
{
return _MAV_RETURN_char_array(msg, name, 20, 7);
}
 
/**
* @brief Get field quality from object_detection_event message
*
* @return Detection quality / confidence. 0: bad, 255: maximum confidence
*/
static inline uint8_t mavlink_msg_object_detection_event_get_quality(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 27);
}
 
/**
* @brief Get field bearing from object_detection_event message
*
* @return Angle of the object with respect to the body frame in NED coordinates in radians. 0: front
*/
static inline float mavlink_msg_object_detection_event_get_bearing(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 28);
}
 
/**
* @brief Get field distance from object_detection_event message
*
* @return Ground distance in meters
*/
static inline float mavlink_msg_object_detection_event_get_distance(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 32);
}
 
/**
* @brief Decode a object_detection_event message into a struct
*
* @param msg The message to decode
* @param object_detection_event C-struct to decode the message contents into
*/
static inline void mavlink_msg_object_detection_event_decode(const mavlink_message_t* msg, mavlink_object_detection_event_t* object_detection_event)
{
#if MAVLINK_NEED_BYTE_SWAP
object_detection_event->time = mavlink_msg_object_detection_event_get_time(msg);
object_detection_event->object_id = mavlink_msg_object_detection_event_get_object_id(msg);
object_detection_event->type = mavlink_msg_object_detection_event_get_type(msg);
mavlink_msg_object_detection_event_get_name(msg, object_detection_event->name);
object_detection_event->quality = mavlink_msg_object_detection_event_get_quality(msg);
object_detection_event->bearing = mavlink_msg_object_detection_event_get_bearing(msg);
object_detection_event->distance = mavlink_msg_object_detection_event_get_distance(msg);
#else
memcpy(object_detection_event, _MAV_PAYLOAD(msg), 36);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v0.9/common/mavlink_msg_optical_flow.h
0,0 → 1,254
// MESSAGE OPTICAL_FLOW PACKING
 
#define MAVLINK_MSG_ID_OPTICAL_FLOW 100
 
typedef struct __mavlink_optical_flow_t
{
uint64_t time; ///< Timestamp (UNIX)
uint8_t sensor_id; ///< Sensor ID
int16_t flow_x; ///< Flow in pixels in x-sensor direction
int16_t flow_y; ///< Flow in pixels in y-sensor direction
uint8_t quality; ///< Optical flow quality / confidence. 0: bad, 255: maximum quality
float ground_distance; ///< Ground distance in meters
} mavlink_optical_flow_t;
 
#define MAVLINK_MSG_ID_OPTICAL_FLOW_LEN 18
#define MAVLINK_MSG_ID_100_LEN 18
 
 
 
#define MAVLINK_MESSAGE_INFO_OPTICAL_FLOW { \
"OPTICAL_FLOW", \
6, \
{ { "time", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_optical_flow_t, time) }, \
{ "sensor_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_optical_flow_t, sensor_id) }, \
{ "flow_x", NULL, MAVLINK_TYPE_INT16_T, 0, 9, offsetof(mavlink_optical_flow_t, flow_x) }, \
{ "flow_y", NULL, MAVLINK_TYPE_INT16_T, 0, 11, offsetof(mavlink_optical_flow_t, flow_y) }, \
{ "quality", NULL, MAVLINK_TYPE_UINT8_T, 0, 13, offsetof(mavlink_optical_flow_t, quality) }, \
{ "ground_distance", NULL, MAVLINK_TYPE_FLOAT, 0, 14, offsetof(mavlink_optical_flow_t, ground_distance) }, \
} \
}
 
 
/**
* @brief Pack a optical_flow message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param time Timestamp (UNIX)
* @param sensor_id Sensor ID
* @param flow_x Flow in pixels in x-sensor direction
* @param flow_y Flow in pixels in y-sensor direction
* @param quality Optical flow quality / confidence. 0: bad, 255: maximum quality
* @param ground_distance Ground distance in meters
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_optical_flow_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint64_t time, uint8_t sensor_id, int16_t flow_x, int16_t flow_y, uint8_t quality, float ground_distance)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[18];
_mav_put_uint64_t(buf, 0, time);
_mav_put_uint8_t(buf, 8, sensor_id);
_mav_put_int16_t(buf, 9, flow_x);
_mav_put_int16_t(buf, 11, flow_y);
_mav_put_uint8_t(buf, 13, quality);
_mav_put_float(buf, 14, ground_distance);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 18);
#else
mavlink_optical_flow_t packet;
packet.time = time;
packet.sensor_id = sensor_id;
packet.flow_x = flow_x;
packet.flow_y = flow_y;
packet.quality = quality;
packet.ground_distance = ground_distance;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 18);
#endif
 
msg->msgid = MAVLINK_MSG_ID_OPTICAL_FLOW;
return mavlink_finalize_message(msg, system_id, component_id, 18);
}
 
/**
* @brief Pack a optical_flow message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param time Timestamp (UNIX)
* @param sensor_id Sensor ID
* @param flow_x Flow in pixels in x-sensor direction
* @param flow_y Flow in pixels in y-sensor direction
* @param quality Optical flow quality / confidence. 0: bad, 255: maximum quality
* @param ground_distance Ground distance in meters
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_optical_flow_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint64_t time,uint8_t sensor_id,int16_t flow_x,int16_t flow_y,uint8_t quality,float ground_distance)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[18];
_mav_put_uint64_t(buf, 0, time);
_mav_put_uint8_t(buf, 8, sensor_id);
_mav_put_int16_t(buf, 9, flow_x);
_mav_put_int16_t(buf, 11, flow_y);
_mav_put_uint8_t(buf, 13, quality);
_mav_put_float(buf, 14, ground_distance);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 18);
#else
mavlink_optical_flow_t packet;
packet.time = time;
packet.sensor_id = sensor_id;
packet.flow_x = flow_x;
packet.flow_y = flow_y;
packet.quality = quality;
packet.ground_distance = ground_distance;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 18);
#endif
 
msg->msgid = MAVLINK_MSG_ID_OPTICAL_FLOW;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 18);
}
 
/**
* @brief Encode a optical_flow struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param optical_flow C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_optical_flow_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_optical_flow_t* optical_flow)
{
return mavlink_msg_optical_flow_pack(system_id, component_id, msg, optical_flow->time, optical_flow->sensor_id, optical_flow->flow_x, optical_flow->flow_y, optical_flow->quality, optical_flow->ground_distance);
}
 
/**
* @brief Send a optical_flow message
* @param chan MAVLink channel to send the message
*
* @param time Timestamp (UNIX)
* @param sensor_id Sensor ID
* @param flow_x Flow in pixels in x-sensor direction
* @param flow_y Flow in pixels in y-sensor direction
* @param quality Optical flow quality / confidence. 0: bad, 255: maximum quality
* @param ground_distance Ground distance in meters
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_optical_flow_send(mavlink_channel_t chan, uint64_t time, uint8_t sensor_id, int16_t flow_x, int16_t flow_y, uint8_t quality, float ground_distance)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[18];
_mav_put_uint64_t(buf, 0, time);
_mav_put_uint8_t(buf, 8, sensor_id);
_mav_put_int16_t(buf, 9, flow_x);
_mav_put_int16_t(buf, 11, flow_y);
_mav_put_uint8_t(buf, 13, quality);
_mav_put_float(buf, 14, ground_distance);
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPTICAL_FLOW, buf, 18);
#else
mavlink_optical_flow_t packet;
packet.time = time;
packet.sensor_id = sensor_id;
packet.flow_x = flow_x;
packet.flow_y = flow_y;
packet.quality = quality;
packet.ground_distance = ground_distance;
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPTICAL_FLOW, (const char *)&packet, 18);
#endif
}
 
#endif
 
// MESSAGE OPTICAL_FLOW UNPACKING
 
 
/**
* @brief Get field time from optical_flow message
*
* @return Timestamp (UNIX)
*/
static inline uint64_t mavlink_msg_optical_flow_get_time(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint64_t(msg, 0);
}
 
/**
* @brief Get field sensor_id from optical_flow message
*
* @return Sensor ID
*/
static inline uint8_t mavlink_msg_optical_flow_get_sensor_id(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 8);
}
 
/**
* @brief Get field flow_x from optical_flow message
*
* @return Flow in pixels in x-sensor direction
*/
static inline int16_t mavlink_msg_optical_flow_get_flow_x(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 9);
}
 
/**
* @brief Get field flow_y from optical_flow message
*
* @return Flow in pixels in y-sensor direction
*/
static inline int16_t mavlink_msg_optical_flow_get_flow_y(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 11);
}
 
/**
* @brief Get field quality from optical_flow message
*
* @return Optical flow quality / confidence. 0: bad, 255: maximum quality
*/
static inline uint8_t mavlink_msg_optical_flow_get_quality(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 13);
}
 
/**
* @brief Get field ground_distance from optical_flow message
*
* @return Ground distance in meters
*/
static inline float mavlink_msg_optical_flow_get_ground_distance(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 14);
}
 
/**
* @brief Decode a optical_flow message into a struct
*
* @param msg The message to decode
* @param optical_flow C-struct to decode the message contents into
*/
static inline void mavlink_msg_optical_flow_decode(const mavlink_message_t* msg, mavlink_optical_flow_t* optical_flow)
{
#if MAVLINK_NEED_BYTE_SWAP
optical_flow->time = mavlink_msg_optical_flow_get_time(msg);
optical_flow->sensor_id = mavlink_msg_optical_flow_get_sensor_id(msg);
optical_flow->flow_x = mavlink_msg_optical_flow_get_flow_x(msg);
optical_flow->flow_y = mavlink_msg_optical_flow_get_flow_y(msg);
optical_flow->quality = mavlink_msg_optical_flow_get_quality(msg);
optical_flow->ground_distance = mavlink_msg_optical_flow_get_ground_distance(msg);
#else
memcpy(optical_flow, _MAV_PAYLOAD(msg), 18);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v0.9/common/mavlink_msg_param_request_list.h
0,0 → 1,166
// MESSAGE PARAM_REQUEST_LIST PACKING
 
#define MAVLINK_MSG_ID_PARAM_REQUEST_LIST 21
 
typedef struct __mavlink_param_request_list_t
{
uint8_t target_system; ///< System ID
uint8_t target_component; ///< Component ID
} mavlink_param_request_list_t;
 
#define MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN 2
#define MAVLINK_MSG_ID_21_LEN 2
 
 
 
#define MAVLINK_MESSAGE_INFO_PARAM_REQUEST_LIST { \
"PARAM_REQUEST_LIST", \
2, \
{ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_param_request_list_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_param_request_list_t, target_component) }, \
} \
}
 
 
/**
* @brief Pack a param_request_list message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param target_system System ID
* @param target_component Component ID
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_param_request_list_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t target_system, uint8_t target_component)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[2];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 2);
#else
mavlink_param_request_list_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 2);
#endif
 
msg->msgid = MAVLINK_MSG_ID_PARAM_REQUEST_LIST;
return mavlink_finalize_message(msg, system_id, component_id, 2);
}
 
/**
* @brief Pack a param_request_list message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param target_system System ID
* @param target_component Component ID
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_param_request_list_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)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[2];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 2);
#else
mavlink_param_request_list_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 2);
#endif
 
msg->msgid = MAVLINK_MSG_ID_PARAM_REQUEST_LIST;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 2);
}
 
/**
* @brief Encode a param_request_list struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param param_request_list C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_param_request_list_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_param_request_list_t* param_request_list)
{
return mavlink_msg_param_request_list_pack(system_id, component_id, msg, param_request_list->target_system, param_request_list->target_component);
}
 
/**
* @brief Send a param_request_list message
* @param chan MAVLink channel to send the message
*
* @param target_system System ID
* @param target_component Component ID
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_param_request_list_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[2];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_REQUEST_LIST, buf, 2);
#else
mavlink_param_request_list_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_REQUEST_LIST, (const char *)&packet, 2);
#endif
}
 
#endif
 
// MESSAGE PARAM_REQUEST_LIST UNPACKING
 
 
/**
* @brief Get field target_system from param_request_list message
*
* @return System ID
*/
static inline uint8_t mavlink_msg_param_request_list_get_target_system(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 0);
}
 
/**
* @brief Get field target_component from param_request_list message
*
* @return Component ID
*/
static inline uint8_t mavlink_msg_param_request_list_get_target_component(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 1);
}
 
/**
* @brief Decode a param_request_list message into a struct
*
* @param msg The message to decode
* @param param_request_list C-struct to decode the message contents into
*/
static inline void mavlink_msg_param_request_list_decode(const mavlink_message_t* msg, mavlink_param_request_list_t* param_request_list)
{
#if MAVLINK_NEED_BYTE_SWAP
param_request_list->target_system = mavlink_msg_param_request_list_get_target_system(msg);
param_request_list->target_component = mavlink_msg_param_request_list_get_target_component(msg);
#else
memcpy(param_request_list, _MAV_PAYLOAD(msg), 2);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v0.9/common/mavlink_msg_param_request_read.h
0,0 → 1,204
// MESSAGE PARAM_REQUEST_READ PACKING
 
#define MAVLINK_MSG_ID_PARAM_REQUEST_READ 20
 
typedef struct __mavlink_param_request_read_t
{
uint8_t target_system; ///< System ID
uint8_t target_component; ///< Component ID
int8_t param_id[15]; ///< Onboard parameter id
int16_t param_index; ///< Parameter index. Send -1 to use the param ID field as identifier
} mavlink_param_request_read_t;
 
#define MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN 19
#define MAVLINK_MSG_ID_20_LEN 19
 
#define MAVLINK_MSG_PARAM_REQUEST_READ_FIELD_PARAM_ID_LEN 15
 
#define MAVLINK_MESSAGE_INFO_PARAM_REQUEST_READ { \
"PARAM_REQUEST_READ", \
4, \
{ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_param_request_read_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_param_request_read_t, target_component) }, \
{ "param_id", NULL, MAVLINK_TYPE_INT8_T, 15, 2, offsetof(mavlink_param_request_read_t, param_id) }, \
{ "param_index", NULL, MAVLINK_TYPE_INT16_T, 0, 17, offsetof(mavlink_param_request_read_t, param_index) }, \
} \
}
 
 
/**
* @brief Pack a param_request_read message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param target_system System ID
* @param target_component Component ID
* @param param_id Onboard parameter id
* @param param_index Parameter index. Send -1 to use the param ID field as identifier
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_param_request_read_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t target_system, uint8_t target_component, const int8_t *param_id, int16_t param_index)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[19];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
_mav_put_int16_t(buf, 17, param_index);
_mav_put_int8_t_array(buf, 2, param_id, 15);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 19);
#else
mavlink_param_request_read_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
packet.param_index = param_index;
mav_array_memcpy(packet.param_id, param_id, sizeof(int8_t)*15);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 19);
#endif
 
msg->msgid = MAVLINK_MSG_ID_PARAM_REQUEST_READ;
return mavlink_finalize_message(msg, system_id, component_id, 19);
}
 
/**
* @brief Pack a param_request_read message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param target_system System ID
* @param target_component Component ID
* @param param_id Onboard parameter id
* @param param_index Parameter index. Send -1 to use the param ID field as identifier
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_param_request_read_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,const int8_t *param_id,int16_t param_index)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[19];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
_mav_put_int16_t(buf, 17, param_index);
_mav_put_int8_t_array(buf, 2, param_id, 15);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 19);
#else
mavlink_param_request_read_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
packet.param_index = param_index;
mav_array_memcpy(packet.param_id, param_id, sizeof(int8_t)*15);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 19);
#endif
 
msg->msgid = MAVLINK_MSG_ID_PARAM_REQUEST_READ;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 19);
}
 
/**
* @brief Encode a param_request_read struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param param_request_read C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_param_request_read_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_param_request_read_t* param_request_read)
{
return mavlink_msg_param_request_read_pack(system_id, component_id, msg, param_request_read->target_system, param_request_read->target_component, param_request_read->param_id, param_request_read->param_index);
}
 
/**
* @brief Send a param_request_read message
* @param chan MAVLink channel to send the message
*
* @param target_system System ID
* @param target_component Component ID
* @param param_id Onboard parameter id
* @param param_index Parameter index. Send -1 to use the param ID field as identifier
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_param_request_read_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, const int8_t *param_id, int16_t param_index)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[19];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
_mav_put_int16_t(buf, 17, param_index);
_mav_put_int8_t_array(buf, 2, param_id, 15);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_REQUEST_READ, buf, 19);
#else
mavlink_param_request_read_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
packet.param_index = param_index;
mav_array_memcpy(packet.param_id, param_id, sizeof(int8_t)*15);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_REQUEST_READ, (const char *)&packet, 19);
#endif
}
 
#endif
 
// MESSAGE PARAM_REQUEST_READ UNPACKING
 
 
/**
* @brief Get field target_system from param_request_read message
*
* @return System ID
*/
static inline uint8_t mavlink_msg_param_request_read_get_target_system(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 0);
}
 
/**
* @brief Get field target_component from param_request_read message
*
* @return Component ID
*/
static inline uint8_t mavlink_msg_param_request_read_get_target_component(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 1);
}
 
/**
* @brief Get field param_id from param_request_read message
*
* @return Onboard parameter id
*/
static inline uint16_t mavlink_msg_param_request_read_get_param_id(const mavlink_message_t* msg, int8_t *param_id)
{
return _MAV_RETURN_int8_t_array(msg, param_id, 15, 2);
}
 
/**
* @brief Get field param_index from param_request_read message
*
* @return Parameter index. Send -1 to use the param ID field as identifier
*/
static inline int16_t mavlink_msg_param_request_read_get_param_index(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 17);
}
 
/**
* @brief Decode a param_request_read message into a struct
*
* @param msg The message to decode
* @param param_request_read C-struct to decode the message contents into
*/
static inline void mavlink_msg_param_request_read_decode(const mavlink_message_t* msg, mavlink_param_request_read_t* param_request_read)
{
#if MAVLINK_NEED_BYTE_SWAP
param_request_read->target_system = mavlink_msg_param_request_read_get_target_system(msg);
param_request_read->target_component = mavlink_msg_param_request_read_get_target_component(msg);
mavlink_msg_param_request_read_get_param_id(msg, param_request_read->param_id);
param_request_read->param_index = mavlink_msg_param_request_read_get_param_index(msg);
#else
memcpy(param_request_read, _MAV_PAYLOAD(msg), 19);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v0.9/common/mavlink_msg_param_set.h
0,0 → 1,204
// MESSAGE PARAM_SET PACKING
 
#define MAVLINK_MSG_ID_PARAM_SET 23
 
typedef struct __mavlink_param_set_t
{
uint8_t target_system; ///< System ID
uint8_t target_component; ///< Component ID
int8_t param_id[15]; ///< Onboard parameter id
float param_value; ///< Onboard parameter value
} mavlink_param_set_t;
 
#define MAVLINK_MSG_ID_PARAM_SET_LEN 21
#define MAVLINK_MSG_ID_23_LEN 21
 
#define MAVLINK_MSG_PARAM_SET_FIELD_PARAM_ID_LEN 15
 
#define MAVLINK_MESSAGE_INFO_PARAM_SET { \
"PARAM_SET", \
4, \
{ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_param_set_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_param_set_t, target_component) }, \
{ "param_id", NULL, MAVLINK_TYPE_INT8_T, 15, 2, offsetof(mavlink_param_set_t, param_id) }, \
{ "param_value", NULL, MAVLINK_TYPE_FLOAT, 0, 17, offsetof(mavlink_param_set_t, param_value) }, \
} \
}
 
 
/**
* @brief Pack a param_set message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param target_system System ID
* @param target_component Component ID
* @param param_id Onboard parameter id
* @param param_value Onboard parameter value
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_param_set_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t target_system, uint8_t target_component, const int8_t *param_id, float param_value)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[21];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
_mav_put_float(buf, 17, param_value);
_mav_put_int8_t_array(buf, 2, param_id, 15);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 21);
#else
mavlink_param_set_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
packet.param_value = param_value;
mav_array_memcpy(packet.param_id, param_id, sizeof(int8_t)*15);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 21);
#endif
 
msg->msgid = MAVLINK_MSG_ID_PARAM_SET;
return mavlink_finalize_message(msg, system_id, component_id, 21);
}
 
/**
* @brief Pack a param_set message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param target_system System ID
* @param target_component Component ID
* @param param_id Onboard parameter id
* @param param_value Onboard parameter value
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_param_set_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,const int8_t *param_id,float param_value)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[21];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
_mav_put_float(buf, 17, param_value);
_mav_put_int8_t_array(buf, 2, param_id, 15);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 21);
#else
mavlink_param_set_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
packet.param_value = param_value;
mav_array_memcpy(packet.param_id, param_id, sizeof(int8_t)*15);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 21);
#endif
 
msg->msgid = MAVLINK_MSG_ID_PARAM_SET;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 21);
}
 
/**
* @brief Encode a param_set struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param param_set C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_param_set_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_param_set_t* param_set)
{
return mavlink_msg_param_set_pack(system_id, component_id, msg, param_set->target_system, param_set->target_component, param_set->param_id, param_set->param_value);
}
 
/**
* @brief Send a param_set message
* @param chan MAVLink channel to send the message
*
* @param target_system System ID
* @param target_component Component ID
* @param param_id Onboard parameter id
* @param param_value Onboard parameter value
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_param_set_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, const int8_t *param_id, float param_value)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[21];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
_mav_put_float(buf, 17, param_value);
_mav_put_int8_t_array(buf, 2, param_id, 15);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_SET, buf, 21);
#else
mavlink_param_set_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
packet.param_value = param_value;
mav_array_memcpy(packet.param_id, param_id, sizeof(int8_t)*15);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_SET, (const char *)&packet, 21);
#endif
}
 
#endif
 
// MESSAGE PARAM_SET UNPACKING
 
 
/**
* @brief Get field target_system from param_set message
*
* @return System ID
*/
static inline uint8_t mavlink_msg_param_set_get_target_system(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 0);
}
 
/**
* @brief Get field target_component from param_set message
*
* @return Component ID
*/
static inline uint8_t mavlink_msg_param_set_get_target_component(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 1);
}
 
/**
* @brief Get field param_id from param_set message
*
* @return Onboard parameter id
*/
static inline uint16_t mavlink_msg_param_set_get_param_id(const mavlink_message_t* msg, int8_t *param_id)
{
return _MAV_RETURN_int8_t_array(msg, param_id, 15, 2);
}
 
/**
* @brief Get field param_value from param_set message
*
* @return Onboard parameter value
*/
static inline float mavlink_msg_param_set_get_param_value(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 17);
}
 
/**
* @brief Decode a param_set message into a struct
*
* @param msg The message to decode
* @param param_set C-struct to decode the message contents into
*/
static inline void mavlink_msg_param_set_decode(const mavlink_message_t* msg, mavlink_param_set_t* param_set)
{
#if MAVLINK_NEED_BYTE_SWAP
param_set->target_system = mavlink_msg_param_set_get_target_system(msg);
param_set->target_component = mavlink_msg_param_set_get_target_component(msg);
mavlink_msg_param_set_get_param_id(msg, param_set->param_id);
param_set->param_value = mavlink_msg_param_set_get_param_value(msg);
#else
memcpy(param_set, _MAV_PAYLOAD(msg), 21);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v0.9/common/mavlink_msg_param_value.h
0,0 → 1,204
// MESSAGE PARAM_VALUE PACKING
 
#define MAVLINK_MSG_ID_PARAM_VALUE 22
 
typedef struct __mavlink_param_value_t
{
int8_t param_id[15]; ///< Onboard parameter id
float param_value; ///< Onboard parameter value
uint16_t param_count; ///< Total number of onboard parameters
uint16_t param_index; ///< Index of this onboard parameter
} mavlink_param_value_t;
 
#define MAVLINK_MSG_ID_PARAM_VALUE_LEN 23
#define MAVLINK_MSG_ID_22_LEN 23
 
#define MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN 15
 
#define MAVLINK_MESSAGE_INFO_PARAM_VALUE { \
"PARAM_VALUE", \
4, \
{ { "param_id", NULL, MAVLINK_TYPE_INT8_T, 15, 0, offsetof(mavlink_param_value_t, param_id) }, \
{ "param_value", NULL, MAVLINK_TYPE_FLOAT, 0, 15, offsetof(mavlink_param_value_t, param_value) }, \
{ "param_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 19, offsetof(mavlink_param_value_t, param_count) }, \
{ "param_index", NULL, MAVLINK_TYPE_UINT16_T, 0, 21, offsetof(mavlink_param_value_t, param_index) }, \
} \
}
 
 
/**
* @brief Pack a param_value message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param param_id Onboard parameter id
* @param param_value Onboard parameter value
* @param param_count Total number of onboard parameters
* @param param_index Index of this onboard parameter
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_param_value_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
const int8_t *param_id, float param_value, uint16_t param_count, uint16_t param_index)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[23];
_mav_put_float(buf, 15, param_value);
_mav_put_uint16_t(buf, 19, param_count);
_mav_put_uint16_t(buf, 21, param_index);
_mav_put_int8_t_array(buf, 0, param_id, 15);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 23);
#else
mavlink_param_value_t packet;
packet.param_value = param_value;
packet.param_count = param_count;
packet.param_index = param_index;
mav_array_memcpy(packet.param_id, param_id, sizeof(int8_t)*15);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 23);
#endif
 
msg->msgid = MAVLINK_MSG_ID_PARAM_VALUE;
return mavlink_finalize_message(msg, system_id, component_id, 23);
}
 
/**
* @brief Pack a param_value message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param param_id Onboard parameter id
* @param param_value Onboard parameter value
* @param param_count Total number of onboard parameters
* @param param_index Index of this onboard parameter
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_param_value_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
const int8_t *param_id,float param_value,uint16_t param_count,uint16_t param_index)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[23];
_mav_put_float(buf, 15, param_value);
_mav_put_uint16_t(buf, 19, param_count);
_mav_put_uint16_t(buf, 21, param_index);
_mav_put_int8_t_array(buf, 0, param_id, 15);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 23);
#else
mavlink_param_value_t packet;
packet.param_value = param_value;
packet.param_count = param_count;
packet.param_index = param_index;
mav_array_memcpy(packet.param_id, param_id, sizeof(int8_t)*15);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 23);
#endif
 
msg->msgid = MAVLINK_MSG_ID_PARAM_VALUE;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 23);
}
 
/**
* @brief Encode a param_value struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param param_value C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_param_value_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_param_value_t* param_value)
{
return mavlink_msg_param_value_pack(system_id, component_id, msg, param_value->param_id, param_value->param_value, param_value->param_count, param_value->param_index);
}
 
/**
* @brief Send a param_value message
* @param chan MAVLink channel to send the message
*
* @param param_id Onboard parameter id
* @param param_value Onboard parameter value
* @param param_count Total number of onboard parameters
* @param param_index Index of this onboard parameter
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_param_value_send(mavlink_channel_t chan, const int8_t *param_id, float param_value, uint16_t param_count, uint16_t param_index)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[23];
_mav_put_float(buf, 15, param_value);
_mav_put_uint16_t(buf, 19, param_count);
_mav_put_uint16_t(buf, 21, param_index);
_mav_put_int8_t_array(buf, 0, param_id, 15);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_VALUE, buf, 23);
#else
mavlink_param_value_t packet;
packet.param_value = param_value;
packet.param_count = param_count;
packet.param_index = param_index;
mav_array_memcpy(packet.param_id, param_id, sizeof(int8_t)*15);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_VALUE, (const char *)&packet, 23);
#endif
}
 
#endif
 
// MESSAGE PARAM_VALUE UNPACKING
 
 
/**
* @brief Get field param_id from param_value message
*
* @return Onboard parameter id
*/
static inline uint16_t mavlink_msg_param_value_get_param_id(const mavlink_message_t* msg, int8_t *param_id)
{
return _MAV_RETURN_int8_t_array(msg, param_id, 15, 0);
}
 
/**
* @brief Get field param_value from param_value message
*
* @return Onboard parameter value
*/
static inline float mavlink_msg_param_value_get_param_value(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 15);
}
 
/**
* @brief Get field param_count from param_value message
*
* @return Total number of onboard parameters
*/
static inline uint16_t mavlink_msg_param_value_get_param_count(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 19);
}
 
/**
* @brief Get field param_index from param_value message
*
* @return Index of this onboard parameter
*/
static inline uint16_t mavlink_msg_param_value_get_param_index(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 21);
}
 
/**
* @brief Decode a param_value message into a struct
*
* @param msg The message to decode
* @param param_value C-struct to decode the message contents into
*/
static inline void mavlink_msg_param_value_decode(const mavlink_message_t* msg, mavlink_param_value_t* param_value)
{
#if MAVLINK_NEED_BYTE_SWAP
mavlink_msg_param_value_get_param_id(msg, param_value->param_id);
param_value->param_value = mavlink_msg_param_value_get_param_value(msg);
param_value->param_count = mavlink_msg_param_value_get_param_count(msg);
param_value->param_index = mavlink_msg_param_value_get_param_index(msg);
#else
memcpy(param_value, _MAV_PAYLOAD(msg), 23);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v0.9/common/mavlink_msg_ping.h
0,0 → 1,210
// MESSAGE PING PACKING
 
#define MAVLINK_MSG_ID_PING 3
 
typedef struct __mavlink_ping_t
{
uint32_t seq; ///< PING sequence
uint8_t target_system; ///< 0: request ping from all receiving systems, if greater than 0: message is a ping response and number is the system id of the requesting system
uint8_t target_component; ///< 0: request ping from all receiving components, if greater than 0: message is a ping response and number is the system id of the requesting system
uint64_t time; ///< Unix timestamp in microseconds
} mavlink_ping_t;
 
#define MAVLINK_MSG_ID_PING_LEN 14
#define MAVLINK_MSG_ID_3_LEN 14
 
 
 
#define MAVLINK_MESSAGE_INFO_PING { \
"PING", \
4, \
{ { "seq", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_ping_t, seq) }, \
{ "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_ping_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_ping_t, target_component) }, \
{ "time", NULL, MAVLINK_TYPE_UINT64_T, 0, 6, offsetof(mavlink_ping_t, time) }, \
} \
}
 
 
/**
* @brief Pack a ping message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param seq PING sequence
* @param target_system 0: request ping from all receiving systems, if greater than 0: message is a ping response and number is the system id of the requesting system
* @param target_component 0: request ping from all receiving components, if greater than 0: message is a ping response and number is the system id of the requesting system
* @param time Unix timestamp in microseconds
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_ping_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint32_t seq, uint8_t target_system, uint8_t target_component, uint64_t time)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[14];
_mav_put_uint32_t(buf, 0, seq);
_mav_put_uint8_t(buf, 4, target_system);
_mav_put_uint8_t(buf, 5, target_component);
_mav_put_uint64_t(buf, 6, time);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 14);
#else
mavlink_ping_t packet;
packet.seq = seq;
packet.target_system = target_system;
packet.target_component = target_component;
packet.time = time;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 14);
#endif
 
msg->msgid = MAVLINK_MSG_ID_PING;
return mavlink_finalize_message(msg, system_id, component_id, 14);
}
 
/**
* @brief Pack a ping message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param seq PING sequence
* @param target_system 0: request ping from all receiving systems, if greater than 0: message is a ping response and number is the system id of the requesting system
* @param target_component 0: request ping from all receiving components, if greater than 0: message is a ping response and number is the system id of the requesting system
* @param time Unix timestamp in microseconds
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_ping_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint32_t seq,uint8_t target_system,uint8_t target_component,uint64_t time)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[14];
_mav_put_uint32_t(buf, 0, seq);
_mav_put_uint8_t(buf, 4, target_system);
_mav_put_uint8_t(buf, 5, target_component);
_mav_put_uint64_t(buf, 6, time);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 14);
#else
mavlink_ping_t packet;
packet.seq = seq;
packet.target_system = target_system;
packet.target_component = target_component;
packet.time = time;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 14);
#endif
 
msg->msgid = MAVLINK_MSG_ID_PING;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 14);
}
 
/**
* @brief Encode a ping struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param ping C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_ping_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_ping_t* ping)
{
return mavlink_msg_ping_pack(system_id, component_id, msg, ping->seq, ping->target_system, ping->target_component, ping->time);
}
 
/**
* @brief Send a ping message
* @param chan MAVLink channel to send the message
*
* @param seq PING sequence
* @param target_system 0: request ping from all receiving systems, if greater than 0: message is a ping response and number is the system id of the requesting system
* @param target_component 0: request ping from all receiving components, if greater than 0: message is a ping response and number is the system id of the requesting system
* @param time Unix timestamp in microseconds
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_ping_send(mavlink_channel_t chan, uint32_t seq, uint8_t target_system, uint8_t target_component, uint64_t time)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[14];
_mav_put_uint32_t(buf, 0, seq);
_mav_put_uint8_t(buf, 4, target_system);
_mav_put_uint8_t(buf, 5, target_component);
_mav_put_uint64_t(buf, 6, time);
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PING, buf, 14);
#else
mavlink_ping_t packet;
packet.seq = seq;
packet.target_system = target_system;
packet.target_component = target_component;
packet.time = time;
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PING, (const char *)&packet, 14);
#endif
}
 
#endif
 
// MESSAGE PING UNPACKING
 
 
/**
* @brief Get field seq from ping message
*
* @return PING sequence
*/
static inline uint32_t mavlink_msg_ping_get_seq(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint32_t(msg, 0);
}
 
/**
* @brief Get field target_system from ping message
*
* @return 0: request ping from all receiving systems, if greater than 0: message is a ping response and number is the system id of the requesting system
*/
static inline uint8_t mavlink_msg_ping_get_target_system(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 4);
}
 
/**
* @brief Get field target_component from ping message
*
* @return 0: request ping from all receiving components, if greater than 0: message is a ping response and number is the system id of the requesting system
*/
static inline uint8_t mavlink_msg_ping_get_target_component(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 5);
}
 
/**
* @brief Get field time from ping message
*
* @return Unix timestamp in microseconds
*/
static inline uint64_t mavlink_msg_ping_get_time(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint64_t(msg, 6);
}
 
/**
* @brief Decode a ping message into a struct
*
* @param msg The message to decode
* @param ping C-struct to decode the message contents into
*/
static inline void mavlink_msg_ping_decode(const mavlink_message_t* msg, mavlink_ping_t* ping)
{
#if MAVLINK_NEED_BYTE_SWAP
ping->seq = mavlink_msg_ping_get_seq(msg);
ping->target_system = mavlink_msg_ping_get_target_system(msg);
ping->target_component = mavlink_msg_ping_get_target_component(msg);
ping->time = mavlink_msg_ping_get_time(msg);
#else
memcpy(ping, _MAV_PAYLOAD(msg), 14);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v0.9/common/mavlink_msg_position_target.h
0,0 → 1,210
// MESSAGE POSITION_TARGET PACKING
 
#define MAVLINK_MSG_ID_POSITION_TARGET 63
 
typedef struct __mavlink_position_target_t
{
float x; ///< x position
float y; ///< y position
float z; ///< z position
float yaw; ///< yaw orientation in radians, 0 = NORTH
} mavlink_position_target_t;
 
#define MAVLINK_MSG_ID_POSITION_TARGET_LEN 16
#define MAVLINK_MSG_ID_63_LEN 16
 
 
 
#define MAVLINK_MESSAGE_INFO_POSITION_TARGET { \
"POSITION_TARGET", \
4, \
{ { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_position_target_t, x) }, \
{ "y", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_position_target_t, y) }, \
{ "z", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_position_target_t, z) }, \
{ "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_position_target_t, yaw) }, \
} \
}
 
 
/**
* @brief Pack a position_target message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param x x position
* @param y y position
* @param z z position
* @param yaw yaw orientation in radians, 0 = NORTH
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_position_target_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
float x, float y, float z, float yaw)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[16];
_mav_put_float(buf, 0, x);
_mav_put_float(buf, 4, y);
_mav_put_float(buf, 8, z);
_mav_put_float(buf, 12, yaw);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 16);
#else
mavlink_position_target_t packet;
packet.x = x;
packet.y = y;
packet.z = z;
packet.yaw = yaw;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 16);
#endif
 
msg->msgid = MAVLINK_MSG_ID_POSITION_TARGET;
return mavlink_finalize_message(msg, system_id, component_id, 16);
}
 
/**
* @brief Pack a position_target message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param x x position
* @param y y position
* @param z z position
* @param yaw yaw orientation in radians, 0 = NORTH
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_position_target_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
float x,float y,float z,float yaw)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[16];
_mav_put_float(buf, 0, x);
_mav_put_float(buf, 4, y);
_mav_put_float(buf, 8, z);
_mav_put_float(buf, 12, yaw);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 16);
#else
mavlink_position_target_t packet;
packet.x = x;
packet.y = y;
packet.z = z;
packet.yaw = yaw;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 16);
#endif
 
msg->msgid = MAVLINK_MSG_ID_POSITION_TARGET;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 16);
}
 
/**
* @brief Encode a position_target struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param position_target C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_position_target_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_position_target_t* position_target)
{
return mavlink_msg_position_target_pack(system_id, component_id, msg, position_target->x, position_target->y, position_target->z, position_target->yaw);
}
 
/**
* @brief Send a position_target message
* @param chan MAVLink channel to send the message
*
* @param x x position
* @param y y position
* @param z z position
* @param yaw yaw orientation in radians, 0 = NORTH
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_position_target_send(mavlink_channel_t chan, float x, float y, float z, float yaw)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[16];
_mav_put_float(buf, 0, x);
_mav_put_float(buf, 4, y);
_mav_put_float(buf, 8, z);
_mav_put_float(buf, 12, yaw);
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POSITION_TARGET, buf, 16);
#else
mavlink_position_target_t packet;
packet.x = x;
packet.y = y;
packet.z = z;
packet.yaw = yaw;
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POSITION_TARGET, (const char *)&packet, 16);
#endif
}
 
#endif
 
// MESSAGE POSITION_TARGET UNPACKING
 
 
/**
* @brief Get field x from position_target message
*
* @return x position
*/
static inline float mavlink_msg_position_target_get_x(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 0);
}
 
/**
* @brief Get field y from position_target message
*
* @return y position
*/
static inline float mavlink_msg_position_target_get_y(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 4);
}
 
/**
* @brief Get field z from position_target message
*
* @return z position
*/
static inline float mavlink_msg_position_target_get_z(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 8);
}
 
/**
* @brief Get field yaw from position_target message
*
* @return yaw orientation in radians, 0 = NORTH
*/
static inline float mavlink_msg_position_target_get_yaw(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 12);
}
 
/**
* @brief Decode a position_target message into a struct
*
* @param msg The message to decode
* @param position_target C-struct to decode the message contents into
*/
static inline void mavlink_msg_position_target_decode(const mavlink_message_t* msg, mavlink_position_target_t* position_target)
{
#if MAVLINK_NEED_BYTE_SWAP
position_target->x = mavlink_msg_position_target_get_x(msg);
position_target->y = mavlink_msg_position_target_get_y(msg);
position_target->z = mavlink_msg_position_target_get_z(msg);
position_target->yaw = mavlink_msg_position_target_get_yaw(msg);
#else
memcpy(position_target, _MAV_PAYLOAD(msg), 16);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v0.9/common/mavlink_msg_raw_imu.h
0,0 → 1,342
// MESSAGE RAW_IMU PACKING
 
#define MAVLINK_MSG_ID_RAW_IMU 28
 
typedef struct __mavlink_raw_imu_t
{
uint64_t usec; ///< Timestamp (microseconds since UNIX epoch or microseconds since system boot)
int16_t xacc; ///< X acceleration (raw)
int16_t yacc; ///< Y acceleration (raw)
int16_t zacc; ///< Z acceleration (raw)
int16_t xgyro; ///< Angular speed around X axis (raw)
int16_t ygyro; ///< Angular speed around Y axis (raw)
int16_t zgyro; ///< Angular speed around Z axis (raw)
int16_t xmag; ///< X Magnetic field (raw)
int16_t ymag; ///< Y Magnetic field (raw)
int16_t zmag; ///< Z Magnetic field (raw)
} mavlink_raw_imu_t;
 
#define MAVLINK_MSG_ID_RAW_IMU_LEN 26
#define MAVLINK_MSG_ID_28_LEN 26
 
 
 
#define MAVLINK_MESSAGE_INFO_RAW_IMU { \
"RAW_IMU", \
10, \
{ { "usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_raw_imu_t, usec) }, \
{ "xacc", NULL, MAVLINK_TYPE_INT16_T, 0, 8, offsetof(mavlink_raw_imu_t, xacc) }, \
{ "yacc", NULL, MAVLINK_TYPE_INT16_T, 0, 10, offsetof(mavlink_raw_imu_t, yacc) }, \
{ "zacc", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_raw_imu_t, zacc) }, \
{ "xgyro", NULL, MAVLINK_TYPE_INT16_T, 0, 14, offsetof(mavlink_raw_imu_t, xgyro) }, \
{ "ygyro", NULL, MAVLINK_TYPE_INT16_T, 0, 16, offsetof(mavlink_raw_imu_t, ygyro) }, \
{ "zgyro", NULL, MAVLINK_TYPE_INT16_T, 0, 18, offsetof(mavlink_raw_imu_t, zgyro) }, \
{ "xmag", NULL, MAVLINK_TYPE_INT16_T, 0, 20, offsetof(mavlink_raw_imu_t, xmag) }, \
{ "ymag", NULL, MAVLINK_TYPE_INT16_T, 0, 22, offsetof(mavlink_raw_imu_t, ymag) }, \
{ "zmag", NULL, MAVLINK_TYPE_INT16_T, 0, 24, offsetof(mavlink_raw_imu_t, zmag) }, \
} \
}
 
 
/**
* @brief Pack a raw_imu message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
* @param xacc X acceleration (raw)
* @param yacc Y acceleration (raw)
* @param zacc Z acceleration (raw)
* @param xgyro Angular speed around X axis (raw)
* @param ygyro Angular speed around Y axis (raw)
* @param zgyro Angular speed around Z axis (raw)
* @param xmag X Magnetic field (raw)
* @param ymag Y Magnetic field (raw)
* @param zmag Z Magnetic field (raw)
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_raw_imu_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint64_t usec, int16_t xacc, int16_t yacc, int16_t zacc, int16_t xgyro, int16_t ygyro, int16_t zgyro, int16_t xmag, int16_t ymag, int16_t zmag)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[26];
_mav_put_uint64_t(buf, 0, usec);
_mav_put_int16_t(buf, 8, xacc);
_mav_put_int16_t(buf, 10, yacc);
_mav_put_int16_t(buf, 12, zacc);
_mav_put_int16_t(buf, 14, xgyro);
_mav_put_int16_t(buf, 16, ygyro);
_mav_put_int16_t(buf, 18, zgyro);
_mav_put_int16_t(buf, 20, xmag);
_mav_put_int16_t(buf, 22, ymag);
_mav_put_int16_t(buf, 24, zmag);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 26);
#else
mavlink_raw_imu_t packet;
packet.usec = usec;
packet.xacc = xacc;
packet.yacc = yacc;
packet.zacc = zacc;
packet.xgyro = xgyro;
packet.ygyro = ygyro;
packet.zgyro = zgyro;
packet.xmag = xmag;
packet.ymag = ymag;
packet.zmag = zmag;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 26);
#endif
 
msg->msgid = MAVLINK_MSG_ID_RAW_IMU;
return mavlink_finalize_message(msg, system_id, component_id, 26);
}
 
/**
* @brief Pack a raw_imu message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
* @param xacc X acceleration (raw)
* @param yacc Y acceleration (raw)
* @param zacc Z acceleration (raw)
* @param xgyro Angular speed around X axis (raw)
* @param ygyro Angular speed around Y axis (raw)
* @param zgyro Angular speed around Z axis (raw)
* @param xmag X Magnetic field (raw)
* @param ymag Y Magnetic field (raw)
* @param zmag Z Magnetic field (raw)
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_raw_imu_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint64_t usec,int16_t xacc,int16_t yacc,int16_t zacc,int16_t xgyro,int16_t ygyro,int16_t zgyro,int16_t xmag,int16_t ymag,int16_t zmag)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[26];
_mav_put_uint64_t(buf, 0, usec);
_mav_put_int16_t(buf, 8, xacc);
_mav_put_int16_t(buf, 10, yacc);
_mav_put_int16_t(buf, 12, zacc);
_mav_put_int16_t(buf, 14, xgyro);
_mav_put_int16_t(buf, 16, ygyro);
_mav_put_int16_t(buf, 18, zgyro);
_mav_put_int16_t(buf, 20, xmag);
_mav_put_int16_t(buf, 22, ymag);
_mav_put_int16_t(buf, 24, zmag);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 26);
#else
mavlink_raw_imu_t packet;
packet.usec = usec;
packet.xacc = xacc;
packet.yacc = yacc;
packet.zacc = zacc;
packet.xgyro = xgyro;
packet.ygyro = ygyro;
packet.zgyro = zgyro;
packet.xmag = xmag;
packet.ymag = ymag;
packet.zmag = zmag;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 26);
#endif
 
msg->msgid = MAVLINK_MSG_ID_RAW_IMU;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 26);
}
 
/**
* @brief Encode a raw_imu struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param raw_imu C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_raw_imu_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_raw_imu_t* raw_imu)
{
return mavlink_msg_raw_imu_pack(system_id, component_id, msg, raw_imu->usec, raw_imu->xacc, raw_imu->yacc, raw_imu->zacc, raw_imu->xgyro, raw_imu->ygyro, raw_imu->zgyro, raw_imu->xmag, raw_imu->ymag, raw_imu->zmag);
}
 
/**
* @brief Send a raw_imu message
* @param chan MAVLink channel to send the message
*
* @param usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
* @param xacc X acceleration (raw)
* @param yacc Y acceleration (raw)
* @param zacc Z acceleration (raw)
* @param xgyro Angular speed around X axis (raw)
* @param ygyro Angular speed around Y axis (raw)
* @param zgyro Angular speed around Z axis (raw)
* @param xmag X Magnetic field (raw)
* @param ymag Y Magnetic field (raw)
* @param zmag Z Magnetic field (raw)
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_raw_imu_send(mavlink_channel_t chan, uint64_t usec, int16_t xacc, int16_t yacc, int16_t zacc, int16_t xgyro, int16_t ygyro, int16_t zgyro, int16_t xmag, int16_t ymag, int16_t zmag)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[26];
_mav_put_uint64_t(buf, 0, usec);
_mav_put_int16_t(buf, 8, xacc);
_mav_put_int16_t(buf, 10, yacc);
_mav_put_int16_t(buf, 12, zacc);
_mav_put_int16_t(buf, 14, xgyro);
_mav_put_int16_t(buf, 16, ygyro);
_mav_put_int16_t(buf, 18, zgyro);
_mav_put_int16_t(buf, 20, xmag);
_mav_put_int16_t(buf, 22, ymag);
_mav_put_int16_t(buf, 24, zmag);
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_IMU, buf, 26);
#else
mavlink_raw_imu_t packet;
packet.usec = usec;
packet.xacc = xacc;
packet.yacc = yacc;
packet.zacc = zacc;
packet.xgyro = xgyro;
packet.ygyro = ygyro;
packet.zgyro = zgyro;
packet.xmag = xmag;
packet.ymag = ymag;
packet.zmag = zmag;
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_IMU, (const char *)&packet, 26);
#endif
}
 
#endif
 
// MESSAGE RAW_IMU UNPACKING
 
 
/**
* @brief Get field usec from raw_imu message
*
* @return Timestamp (microseconds since UNIX epoch or microseconds since system boot)
*/
static inline uint64_t mavlink_msg_raw_imu_get_usec(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint64_t(msg, 0);
}
 
/**
* @brief Get field xacc from raw_imu message
*
* @return X acceleration (raw)
*/
static inline int16_t mavlink_msg_raw_imu_get_xacc(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 8);
}
 
/**
* @brief Get field yacc from raw_imu message
*
* @return Y acceleration (raw)
*/
static inline int16_t mavlink_msg_raw_imu_get_yacc(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 10);
}
 
/**
* @brief Get field zacc from raw_imu message
*
* @return Z acceleration (raw)
*/
static inline int16_t mavlink_msg_raw_imu_get_zacc(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 12);
}
 
/**
* @brief Get field xgyro from raw_imu message
*
* @return Angular speed around X axis (raw)
*/
static inline int16_t mavlink_msg_raw_imu_get_xgyro(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 14);
}
 
/**
* @brief Get field ygyro from raw_imu message
*
* @return Angular speed around Y axis (raw)
*/
static inline int16_t mavlink_msg_raw_imu_get_ygyro(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 16);
}
 
/**
* @brief Get field zgyro from raw_imu message
*
* @return Angular speed around Z axis (raw)
*/
static inline int16_t mavlink_msg_raw_imu_get_zgyro(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 18);
}
 
/**
* @brief Get field xmag from raw_imu message
*
* @return X Magnetic field (raw)
*/
static inline int16_t mavlink_msg_raw_imu_get_xmag(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 20);
}
 
/**
* @brief Get field ymag from raw_imu message
*
* @return Y Magnetic field (raw)
*/
static inline int16_t mavlink_msg_raw_imu_get_ymag(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 22);
}
 
/**
* @brief Get field zmag from raw_imu message
*
* @return Z Magnetic field (raw)
*/
static inline int16_t mavlink_msg_raw_imu_get_zmag(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 24);
}
 
/**
* @brief Decode a raw_imu message into a struct
*
* @param msg The message to decode
* @param raw_imu C-struct to decode the message contents into
*/
static inline void mavlink_msg_raw_imu_decode(const mavlink_message_t* msg, mavlink_raw_imu_t* raw_imu)
{
#if MAVLINK_NEED_BYTE_SWAP
raw_imu->usec = mavlink_msg_raw_imu_get_usec(msg);
raw_imu->xacc = mavlink_msg_raw_imu_get_xacc(msg);
raw_imu->yacc = mavlink_msg_raw_imu_get_yacc(msg);
raw_imu->zacc = mavlink_msg_raw_imu_get_zacc(msg);
raw_imu->xgyro = mavlink_msg_raw_imu_get_xgyro(msg);
raw_imu->ygyro = mavlink_msg_raw_imu_get_ygyro(msg);
raw_imu->zgyro = mavlink_msg_raw_imu_get_zgyro(msg);
raw_imu->xmag = mavlink_msg_raw_imu_get_xmag(msg);
raw_imu->ymag = mavlink_msg_raw_imu_get_ymag(msg);
raw_imu->zmag = mavlink_msg_raw_imu_get_zmag(msg);
#else
memcpy(raw_imu, _MAV_PAYLOAD(msg), 26);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v0.9/common/mavlink_msg_raw_pressure.h
0,0 → 1,232
// MESSAGE RAW_PRESSURE PACKING
 
#define MAVLINK_MSG_ID_RAW_PRESSURE 29
 
typedef struct __mavlink_raw_pressure_t
{
uint64_t usec; ///< Timestamp (microseconds since UNIX epoch or microseconds since system boot)
int16_t press_abs; ///< Absolute pressure (raw)
int16_t press_diff1; ///< Differential pressure 1 (raw)
int16_t press_diff2; ///< Differential pressure 2 (raw)
int16_t temperature; ///< Raw Temperature measurement (raw)
} mavlink_raw_pressure_t;
 
#define MAVLINK_MSG_ID_RAW_PRESSURE_LEN 16
#define MAVLINK_MSG_ID_29_LEN 16
 
 
 
#define MAVLINK_MESSAGE_INFO_RAW_PRESSURE { \
"RAW_PRESSURE", \
5, \
{ { "usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_raw_pressure_t, usec) }, \
{ "press_abs", NULL, MAVLINK_TYPE_INT16_T, 0, 8, offsetof(mavlink_raw_pressure_t, press_abs) }, \
{ "press_diff1", NULL, MAVLINK_TYPE_INT16_T, 0, 10, offsetof(mavlink_raw_pressure_t, press_diff1) }, \
{ "press_diff2", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_raw_pressure_t, press_diff2) }, \
{ "temperature", NULL, MAVLINK_TYPE_INT16_T, 0, 14, offsetof(mavlink_raw_pressure_t, temperature) }, \
} \
}
 
 
/**
* @brief Pack a raw_pressure message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
* @param press_abs Absolute pressure (raw)
* @param press_diff1 Differential pressure 1 (raw)
* @param press_diff2 Differential pressure 2 (raw)
* @param temperature Raw Temperature measurement (raw)
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_raw_pressure_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint64_t usec, int16_t press_abs, int16_t press_diff1, int16_t press_diff2, int16_t temperature)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[16];
_mav_put_uint64_t(buf, 0, usec);
_mav_put_int16_t(buf, 8, press_abs);
_mav_put_int16_t(buf, 10, press_diff1);
_mav_put_int16_t(buf, 12, press_diff2);
_mav_put_int16_t(buf, 14, temperature);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 16);
#else
mavlink_raw_pressure_t packet;
packet.usec = usec;
packet.press_abs = press_abs;
packet.press_diff1 = press_diff1;
packet.press_diff2 = press_diff2;
packet.temperature = temperature;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 16);
#endif
 
msg->msgid = MAVLINK_MSG_ID_RAW_PRESSURE;
return mavlink_finalize_message(msg, system_id, component_id, 16);
}
 
/**
* @brief Pack a raw_pressure message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
* @param press_abs Absolute pressure (raw)
* @param press_diff1 Differential pressure 1 (raw)
* @param press_diff2 Differential pressure 2 (raw)
* @param temperature Raw Temperature measurement (raw)
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_raw_pressure_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint64_t usec,int16_t press_abs,int16_t press_diff1,int16_t press_diff2,int16_t temperature)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[16];
_mav_put_uint64_t(buf, 0, usec);
_mav_put_int16_t(buf, 8, press_abs);
_mav_put_int16_t(buf, 10, press_diff1);
_mav_put_int16_t(buf, 12, press_diff2);
_mav_put_int16_t(buf, 14, temperature);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 16);
#else
mavlink_raw_pressure_t packet;
packet.usec = usec;
packet.press_abs = press_abs;
packet.press_diff1 = press_diff1;
packet.press_diff2 = press_diff2;
packet.temperature = temperature;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 16);
#endif
 
msg->msgid = MAVLINK_MSG_ID_RAW_PRESSURE;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 16);
}
 
/**
* @brief Encode a raw_pressure struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param raw_pressure C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_raw_pressure_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_raw_pressure_t* raw_pressure)
{
return mavlink_msg_raw_pressure_pack(system_id, component_id, msg, raw_pressure->usec, raw_pressure->press_abs, raw_pressure->press_diff1, raw_pressure->press_diff2, raw_pressure->temperature);
}
 
/**
* @brief Send a raw_pressure message
* @param chan MAVLink channel to send the message
*
* @param usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
* @param press_abs Absolute pressure (raw)
* @param press_diff1 Differential pressure 1 (raw)
* @param press_diff2 Differential pressure 2 (raw)
* @param temperature Raw Temperature measurement (raw)
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_raw_pressure_send(mavlink_channel_t chan, uint64_t usec, int16_t press_abs, int16_t press_diff1, int16_t press_diff2, int16_t temperature)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[16];
_mav_put_uint64_t(buf, 0, usec);
_mav_put_int16_t(buf, 8, press_abs);
_mav_put_int16_t(buf, 10, press_diff1);
_mav_put_int16_t(buf, 12, press_diff2);
_mav_put_int16_t(buf, 14, temperature);
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_PRESSURE, buf, 16);
#else
mavlink_raw_pressure_t packet;
packet.usec = usec;
packet.press_abs = press_abs;
packet.press_diff1 = press_diff1;
packet.press_diff2 = press_diff2;
packet.temperature = temperature;
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_PRESSURE, (const char *)&packet, 16);
#endif
}
 
#endif
 
// MESSAGE RAW_PRESSURE UNPACKING
 
 
/**
* @brief Get field usec from raw_pressure message
*
* @return Timestamp (microseconds since UNIX epoch or microseconds since system boot)
*/
static inline uint64_t mavlink_msg_raw_pressure_get_usec(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint64_t(msg, 0);
}
 
/**
* @brief Get field press_abs from raw_pressure message
*
* @return Absolute pressure (raw)
*/
static inline int16_t mavlink_msg_raw_pressure_get_press_abs(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 8);
}
 
/**
* @brief Get field press_diff1 from raw_pressure message
*
* @return Differential pressure 1 (raw)
*/
static inline int16_t mavlink_msg_raw_pressure_get_press_diff1(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 10);
}
 
/**
* @brief Get field press_diff2 from raw_pressure message
*
* @return Differential pressure 2 (raw)
*/
static inline int16_t mavlink_msg_raw_pressure_get_press_diff2(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 12);
}
 
/**
* @brief Get field temperature from raw_pressure message
*
* @return Raw Temperature measurement (raw)
*/
static inline int16_t mavlink_msg_raw_pressure_get_temperature(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 14);
}
 
/**
* @brief Decode a raw_pressure message into a struct
*
* @param msg The message to decode
* @param raw_pressure C-struct to decode the message contents into
*/
static inline void mavlink_msg_raw_pressure_decode(const mavlink_message_t* msg, mavlink_raw_pressure_t* raw_pressure)
{
#if MAVLINK_NEED_BYTE_SWAP
raw_pressure->usec = mavlink_msg_raw_pressure_get_usec(msg);
raw_pressure->press_abs = mavlink_msg_raw_pressure_get_press_abs(msg);
raw_pressure->press_diff1 = mavlink_msg_raw_pressure_get_press_diff1(msg);
raw_pressure->press_diff2 = mavlink_msg_raw_pressure_get_press_diff2(msg);
raw_pressure->temperature = mavlink_msg_raw_pressure_get_temperature(msg);
#else
memcpy(raw_pressure, _MAV_PAYLOAD(msg), 16);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v0.9/common/mavlink_msg_rc_channels_override.h
0,0 → 1,342
// MESSAGE RC_CHANNELS_OVERRIDE PACKING
 
#define MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE 70
 
typedef struct __mavlink_rc_channels_override_t
{
uint8_t target_system; ///< System ID
uint8_t target_component; ///< Component ID
uint16_t chan1_raw; ///< RC channel 1 value, in microseconds
uint16_t chan2_raw; ///< RC channel 2 value, in microseconds
uint16_t chan3_raw; ///< RC channel 3 value, in microseconds
uint16_t chan4_raw; ///< RC channel 4 value, in microseconds
uint16_t chan5_raw; ///< RC channel 5 value, in microseconds
uint16_t chan6_raw; ///< RC channel 6 value, in microseconds
uint16_t chan7_raw; ///< RC channel 7 value, in microseconds
uint16_t chan8_raw; ///< RC channel 8 value, in microseconds
} mavlink_rc_channels_override_t;
 
#define MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN 18
#define MAVLINK_MSG_ID_70_LEN 18
 
 
 
#define MAVLINK_MESSAGE_INFO_RC_CHANNELS_OVERRIDE { \
"RC_CHANNELS_OVERRIDE", \
10, \
{ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_rc_channels_override_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_rc_channels_override_t, target_component) }, \
{ "chan1_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_rc_channels_override_t, chan1_raw) }, \
{ "chan2_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_rc_channels_override_t, chan2_raw) }, \
{ "chan3_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_rc_channels_override_t, chan3_raw) }, \
{ "chan4_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_rc_channels_override_t, chan4_raw) }, \
{ "chan5_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 10, offsetof(mavlink_rc_channels_override_t, chan5_raw) }, \
{ "chan6_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_rc_channels_override_t, chan6_raw) }, \
{ "chan7_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 14, offsetof(mavlink_rc_channels_override_t, chan7_raw) }, \
{ "chan8_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_rc_channels_override_t, chan8_raw) }, \
} \
}
 
 
/**
* @brief Pack a rc_channels_override message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param target_system System ID
* @param target_component Component ID
* @param chan1_raw RC channel 1 value, in microseconds
* @param chan2_raw RC channel 2 value, in microseconds
* @param chan3_raw RC channel 3 value, in microseconds
* @param chan4_raw RC channel 4 value, in microseconds
* @param chan5_raw RC channel 5 value, in microseconds
* @param chan6_raw RC channel 6 value, in microseconds
* @param chan7_raw RC channel 7 value, in microseconds
* @param chan8_raw RC channel 8 value, in microseconds
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_rc_channels_override_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t target_system, uint8_t target_component, uint16_t chan1_raw, uint16_t chan2_raw, uint16_t chan3_raw, uint16_t chan4_raw, uint16_t chan5_raw, uint16_t chan6_raw, uint16_t chan7_raw, uint16_t chan8_raw)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[18];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
_mav_put_uint16_t(buf, 2, chan1_raw);
_mav_put_uint16_t(buf, 4, chan2_raw);
_mav_put_uint16_t(buf, 6, chan3_raw);
_mav_put_uint16_t(buf, 8, chan4_raw);
_mav_put_uint16_t(buf, 10, chan5_raw);
_mav_put_uint16_t(buf, 12, chan6_raw);
_mav_put_uint16_t(buf, 14, chan7_raw);
_mav_put_uint16_t(buf, 16, chan8_raw);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 18);
#else
mavlink_rc_channels_override_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
packet.chan1_raw = chan1_raw;
packet.chan2_raw = chan2_raw;
packet.chan3_raw = chan3_raw;
packet.chan4_raw = chan4_raw;
packet.chan5_raw = chan5_raw;
packet.chan6_raw = chan6_raw;
packet.chan7_raw = chan7_raw;
packet.chan8_raw = chan8_raw;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 18);
#endif
 
msg->msgid = MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE;
return mavlink_finalize_message(msg, system_id, component_id, 18);
}
 
/**
* @brief Pack a rc_channels_override message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param target_system System ID
* @param target_component Component ID
* @param chan1_raw RC channel 1 value, in microseconds
* @param chan2_raw RC channel 2 value, in microseconds
* @param chan3_raw RC channel 3 value, in microseconds
* @param chan4_raw RC channel 4 value, in microseconds
* @param chan5_raw RC channel 5 value, in microseconds
* @param chan6_raw RC channel 6 value, in microseconds
* @param chan7_raw RC channel 7 value, in microseconds
* @param chan8_raw RC channel 8 value, in microseconds
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_rc_channels_override_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,uint16_t chan1_raw,uint16_t chan2_raw,uint16_t chan3_raw,uint16_t chan4_raw,uint16_t chan5_raw,uint16_t chan6_raw,uint16_t chan7_raw,uint16_t chan8_raw)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[18];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
_mav_put_uint16_t(buf, 2, chan1_raw);
_mav_put_uint16_t(buf, 4, chan2_raw);
_mav_put_uint16_t(buf, 6, chan3_raw);
_mav_put_uint16_t(buf, 8, chan4_raw);
_mav_put_uint16_t(buf, 10, chan5_raw);
_mav_put_uint16_t(buf, 12, chan6_raw);
_mav_put_uint16_t(buf, 14, chan7_raw);
_mav_put_uint16_t(buf, 16, chan8_raw);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 18);
#else
mavlink_rc_channels_override_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
packet.chan1_raw = chan1_raw;
packet.chan2_raw = chan2_raw;
packet.chan3_raw = chan3_raw;
packet.chan4_raw = chan4_raw;
packet.chan5_raw = chan5_raw;
packet.chan6_raw = chan6_raw;
packet.chan7_raw = chan7_raw;
packet.chan8_raw = chan8_raw;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 18);
#endif
 
msg->msgid = MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 18);
}
 
/**
* @brief Encode a rc_channels_override struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param rc_channels_override C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_rc_channels_override_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_rc_channels_override_t* rc_channels_override)
{
return mavlink_msg_rc_channels_override_pack(system_id, component_id, msg, rc_channels_override->target_system, rc_channels_override->target_component, rc_channels_override->chan1_raw, rc_channels_override->chan2_raw, rc_channels_override->chan3_raw, rc_channels_override->chan4_raw, rc_channels_override->chan5_raw, rc_channels_override->chan6_raw, rc_channels_override->chan7_raw, rc_channels_override->chan8_raw);
}
 
/**
* @brief Send a rc_channels_override message
* @param chan MAVLink channel to send the message
*
* @param target_system System ID
* @param target_component Component ID
* @param chan1_raw RC channel 1 value, in microseconds
* @param chan2_raw RC channel 2 value, in microseconds
* @param chan3_raw RC channel 3 value, in microseconds
* @param chan4_raw RC channel 4 value, in microseconds
* @param chan5_raw RC channel 5 value, in microseconds
* @param chan6_raw RC channel 6 value, in microseconds
* @param chan7_raw RC channel 7 value, in microseconds
* @param chan8_raw RC channel 8 value, in microseconds
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_rc_channels_override_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t chan1_raw, uint16_t chan2_raw, uint16_t chan3_raw, uint16_t chan4_raw, uint16_t chan5_raw, uint16_t chan6_raw, uint16_t chan7_raw, uint16_t chan8_raw)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[18];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
_mav_put_uint16_t(buf, 2, chan1_raw);
_mav_put_uint16_t(buf, 4, chan2_raw);
_mav_put_uint16_t(buf, 6, chan3_raw);
_mav_put_uint16_t(buf, 8, chan4_raw);
_mav_put_uint16_t(buf, 10, chan5_raw);
_mav_put_uint16_t(buf, 12, chan6_raw);
_mav_put_uint16_t(buf, 14, chan7_raw);
_mav_put_uint16_t(buf, 16, chan8_raw);
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE, buf, 18);
#else
mavlink_rc_channels_override_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
packet.chan1_raw = chan1_raw;
packet.chan2_raw = chan2_raw;
packet.chan3_raw = chan3_raw;
packet.chan4_raw = chan4_raw;
packet.chan5_raw = chan5_raw;
packet.chan6_raw = chan6_raw;
packet.chan7_raw = chan7_raw;
packet.chan8_raw = chan8_raw;
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE, (const char *)&packet, 18);
#endif
}
 
#endif
 
// MESSAGE RC_CHANNELS_OVERRIDE UNPACKING
 
 
/**
* @brief Get field target_system from rc_channels_override message
*
* @return System ID
*/
static inline uint8_t mavlink_msg_rc_channels_override_get_target_system(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 0);
}
 
/**
* @brief Get field target_component from rc_channels_override message
*
* @return Component ID
*/
static inline uint8_t mavlink_msg_rc_channels_override_get_target_component(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 1);
}
 
/**
* @brief Get field chan1_raw from rc_channels_override message
*
* @return RC channel 1 value, in microseconds
*/
static inline uint16_t mavlink_msg_rc_channels_override_get_chan1_raw(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 2);
}
 
/**
* @brief Get field chan2_raw from rc_channels_override message
*
* @return RC channel 2 value, in microseconds
*/
static inline uint16_t mavlink_msg_rc_channels_override_get_chan2_raw(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 4);
}
 
/**
* @brief Get field chan3_raw from rc_channels_override message
*
* @return RC channel 3 value, in microseconds
*/
static inline uint16_t mavlink_msg_rc_channels_override_get_chan3_raw(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 6);
}
 
/**
* @brief Get field chan4_raw from rc_channels_override message
*
* @return RC channel 4 value, in microseconds
*/
static inline uint16_t mavlink_msg_rc_channels_override_get_chan4_raw(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 8);
}
 
/**
* @brief Get field chan5_raw from rc_channels_override message
*
* @return RC channel 5 value, in microseconds
*/
static inline uint16_t mavlink_msg_rc_channels_override_get_chan5_raw(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 10);
}
 
/**
* @brief Get field chan6_raw from rc_channels_override message
*
* @return RC channel 6 value, in microseconds
*/
static inline uint16_t mavlink_msg_rc_channels_override_get_chan6_raw(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 12);
}
 
/**
* @brief Get field chan7_raw from rc_channels_override message
*
* @return RC channel 7 value, in microseconds
*/
static inline uint16_t mavlink_msg_rc_channels_override_get_chan7_raw(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 14);
}
 
/**
* @brief Get field chan8_raw from rc_channels_override message
*
* @return RC channel 8 value, in microseconds
*/
static inline uint16_t mavlink_msg_rc_channels_override_get_chan8_raw(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 16);
}
 
/**
* @brief Decode a rc_channels_override message into a struct
*
* @param msg The message to decode
* @param rc_channels_override C-struct to decode the message contents into
*/
static inline void mavlink_msg_rc_channels_override_decode(const mavlink_message_t* msg, mavlink_rc_channels_override_t* rc_channels_override)
{
#if MAVLINK_NEED_BYTE_SWAP
rc_channels_override->target_system = mavlink_msg_rc_channels_override_get_target_system(msg);
rc_channels_override->target_component = mavlink_msg_rc_channels_override_get_target_component(msg);
rc_channels_override->chan1_raw = mavlink_msg_rc_channels_override_get_chan1_raw(msg);
rc_channels_override->chan2_raw = mavlink_msg_rc_channels_override_get_chan2_raw(msg);
rc_channels_override->chan3_raw = mavlink_msg_rc_channels_override_get_chan3_raw(msg);
rc_channels_override->chan4_raw = mavlink_msg_rc_channels_override_get_chan4_raw(msg);
rc_channels_override->chan5_raw = mavlink_msg_rc_channels_override_get_chan5_raw(msg);
rc_channels_override->chan6_raw = mavlink_msg_rc_channels_override_get_chan6_raw(msg);
rc_channels_override->chan7_raw = mavlink_msg_rc_channels_override_get_chan7_raw(msg);
rc_channels_override->chan8_raw = mavlink_msg_rc_channels_override_get_chan8_raw(msg);
#else
memcpy(rc_channels_override, _MAV_PAYLOAD(msg), 18);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v0.9/common/mavlink_msg_rc_channels_raw.h
0,0 → 1,320
// MESSAGE RC_CHANNELS_RAW PACKING
 
#define MAVLINK_MSG_ID_RC_CHANNELS_RAW 35
 
typedef struct __mavlink_rc_channels_raw_t
{
uint16_t chan1_raw; ///< RC channel 1 value, in microseconds
uint16_t chan2_raw; ///< RC channel 2 value, in microseconds
uint16_t chan3_raw; ///< RC channel 3 value, in microseconds
uint16_t chan4_raw; ///< RC channel 4 value, in microseconds
uint16_t chan5_raw; ///< RC channel 5 value, in microseconds
uint16_t chan6_raw; ///< RC channel 6 value, in microseconds
uint16_t chan7_raw; ///< RC channel 7 value, in microseconds
uint16_t chan8_raw; ///< RC channel 8 value, in microseconds
uint8_t rssi; ///< Receive signal strength indicator, 0: 0%, 255: 100%
} mavlink_rc_channels_raw_t;
 
#define MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN 17
#define MAVLINK_MSG_ID_35_LEN 17
 
 
 
#define MAVLINK_MESSAGE_INFO_RC_CHANNELS_RAW { \
"RC_CHANNELS_RAW", \
9, \
{ { "chan1_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_rc_channels_raw_t, chan1_raw) }, \
{ "chan2_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_rc_channels_raw_t, chan2_raw) }, \
{ "chan3_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_rc_channels_raw_t, chan3_raw) }, \
{ "chan4_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_rc_channels_raw_t, chan4_raw) }, \
{ "chan5_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_rc_channels_raw_t, chan5_raw) }, \
{ "chan6_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 10, offsetof(mavlink_rc_channels_raw_t, chan6_raw) }, \
{ "chan7_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_rc_channels_raw_t, chan7_raw) }, \
{ "chan8_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 14, offsetof(mavlink_rc_channels_raw_t, chan8_raw) }, \
{ "rssi", NULL, MAVLINK_TYPE_UINT8_T, 0, 16, offsetof(mavlink_rc_channels_raw_t, rssi) }, \
} \
}
 
 
/**
* @brief Pack a rc_channels_raw message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param chan1_raw RC channel 1 value, in microseconds
* @param chan2_raw RC channel 2 value, in microseconds
* @param chan3_raw RC channel 3 value, in microseconds
* @param chan4_raw RC channel 4 value, in microseconds
* @param chan5_raw RC channel 5 value, in microseconds
* @param chan6_raw RC channel 6 value, in microseconds
* @param chan7_raw RC channel 7 value, in microseconds
* @param chan8_raw RC channel 8 value, in microseconds
* @param rssi Receive signal strength indicator, 0: 0%, 255: 100%
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_rc_channels_raw_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint16_t chan1_raw, uint16_t chan2_raw, uint16_t chan3_raw, uint16_t chan4_raw, uint16_t chan5_raw, uint16_t chan6_raw, uint16_t chan7_raw, uint16_t chan8_raw, uint8_t rssi)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[17];
_mav_put_uint16_t(buf, 0, chan1_raw);
_mav_put_uint16_t(buf, 2, chan2_raw);
_mav_put_uint16_t(buf, 4, chan3_raw);
_mav_put_uint16_t(buf, 6, chan4_raw);
_mav_put_uint16_t(buf, 8, chan5_raw);
_mav_put_uint16_t(buf, 10, chan6_raw);
_mav_put_uint16_t(buf, 12, chan7_raw);
_mav_put_uint16_t(buf, 14, chan8_raw);
_mav_put_uint8_t(buf, 16, rssi);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 17);
#else
mavlink_rc_channels_raw_t packet;
packet.chan1_raw = chan1_raw;
packet.chan2_raw = chan2_raw;
packet.chan3_raw = chan3_raw;
packet.chan4_raw = chan4_raw;
packet.chan5_raw = chan5_raw;
packet.chan6_raw = chan6_raw;
packet.chan7_raw = chan7_raw;
packet.chan8_raw = chan8_raw;
packet.rssi = rssi;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 17);
#endif
 
msg->msgid = MAVLINK_MSG_ID_RC_CHANNELS_RAW;
return mavlink_finalize_message(msg, system_id, component_id, 17);
}
 
/**
* @brief Pack a rc_channels_raw message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param chan1_raw RC channel 1 value, in microseconds
* @param chan2_raw RC channel 2 value, in microseconds
* @param chan3_raw RC channel 3 value, in microseconds
* @param chan4_raw RC channel 4 value, in microseconds
* @param chan5_raw RC channel 5 value, in microseconds
* @param chan6_raw RC channel 6 value, in microseconds
* @param chan7_raw RC channel 7 value, in microseconds
* @param chan8_raw RC channel 8 value, in microseconds
* @param rssi Receive signal strength indicator, 0: 0%, 255: 100%
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_rc_channels_raw_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint16_t chan1_raw,uint16_t chan2_raw,uint16_t chan3_raw,uint16_t chan4_raw,uint16_t chan5_raw,uint16_t chan6_raw,uint16_t chan7_raw,uint16_t chan8_raw,uint8_t rssi)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[17];
_mav_put_uint16_t(buf, 0, chan1_raw);
_mav_put_uint16_t(buf, 2, chan2_raw);
_mav_put_uint16_t(buf, 4, chan3_raw);
_mav_put_uint16_t(buf, 6, chan4_raw);
_mav_put_uint16_t(buf, 8, chan5_raw);
_mav_put_uint16_t(buf, 10, chan6_raw);
_mav_put_uint16_t(buf, 12, chan7_raw);
_mav_put_uint16_t(buf, 14, chan8_raw);
_mav_put_uint8_t(buf, 16, rssi);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 17);
#else
mavlink_rc_channels_raw_t packet;
packet.chan1_raw = chan1_raw;
packet.chan2_raw = chan2_raw;
packet.chan3_raw = chan3_raw;
packet.chan4_raw = chan4_raw;
packet.chan5_raw = chan5_raw;
packet.chan6_raw = chan6_raw;
packet.chan7_raw = chan7_raw;
packet.chan8_raw = chan8_raw;
packet.rssi = rssi;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 17);
#endif
 
msg->msgid = MAVLINK_MSG_ID_RC_CHANNELS_RAW;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 17);
}
 
/**
* @brief Encode a rc_channels_raw struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param rc_channels_raw C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_rc_channels_raw_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_rc_channels_raw_t* rc_channels_raw)
{
return mavlink_msg_rc_channels_raw_pack(system_id, component_id, msg, rc_channels_raw->chan1_raw, rc_channels_raw->chan2_raw, rc_channels_raw->chan3_raw, rc_channels_raw->chan4_raw, rc_channels_raw->chan5_raw, rc_channels_raw->chan6_raw, rc_channels_raw->chan7_raw, rc_channels_raw->chan8_raw, rc_channels_raw->rssi);
}
 
/**
* @brief Send a rc_channels_raw message
* @param chan MAVLink channel to send the message
*
* @param chan1_raw RC channel 1 value, in microseconds
* @param chan2_raw RC channel 2 value, in microseconds
* @param chan3_raw RC channel 3 value, in microseconds
* @param chan4_raw RC channel 4 value, in microseconds
* @param chan5_raw RC channel 5 value, in microseconds
* @param chan6_raw RC channel 6 value, in microseconds
* @param chan7_raw RC channel 7 value, in microseconds
* @param chan8_raw RC channel 8 value, in microseconds
* @param rssi Receive signal strength indicator, 0: 0%, 255: 100%
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_rc_channels_raw_send(mavlink_channel_t chan, uint16_t chan1_raw, uint16_t chan2_raw, uint16_t chan3_raw, uint16_t chan4_raw, uint16_t chan5_raw, uint16_t chan6_raw, uint16_t chan7_raw, uint16_t chan8_raw, uint8_t rssi)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[17];
_mav_put_uint16_t(buf, 0, chan1_raw);
_mav_put_uint16_t(buf, 2, chan2_raw);
_mav_put_uint16_t(buf, 4, chan3_raw);
_mav_put_uint16_t(buf, 6, chan4_raw);
_mav_put_uint16_t(buf, 8, chan5_raw);
_mav_put_uint16_t(buf, 10, chan6_raw);
_mav_put_uint16_t(buf, 12, chan7_raw);
_mav_put_uint16_t(buf, 14, chan8_raw);
_mav_put_uint8_t(buf, 16, rssi);
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_RAW, buf, 17);
#else
mavlink_rc_channels_raw_t packet;
packet.chan1_raw = chan1_raw;
packet.chan2_raw = chan2_raw;
packet.chan3_raw = chan3_raw;
packet.chan4_raw = chan4_raw;
packet.chan5_raw = chan5_raw;
packet.chan6_raw = chan6_raw;
packet.chan7_raw = chan7_raw;
packet.chan8_raw = chan8_raw;
packet.rssi = rssi;
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_RAW, (const char *)&packet, 17);
#endif
}
 
#endif
 
// MESSAGE RC_CHANNELS_RAW UNPACKING
 
 
/**
* @brief Get field chan1_raw from rc_channels_raw message
*
* @return RC channel 1 value, in microseconds
*/
static inline uint16_t mavlink_msg_rc_channels_raw_get_chan1_raw(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 0);
}
 
/**
* @brief Get field chan2_raw from rc_channels_raw message
*
* @return RC channel 2 value, in microseconds
*/
static inline uint16_t mavlink_msg_rc_channels_raw_get_chan2_raw(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 2);
}
 
/**
* @brief Get field chan3_raw from rc_channels_raw message
*
* @return RC channel 3 value, in microseconds
*/
static inline uint16_t mavlink_msg_rc_channels_raw_get_chan3_raw(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 4);
}
 
/**
* @brief Get field chan4_raw from rc_channels_raw message
*
* @return RC channel 4 value, in microseconds
*/
static inline uint16_t mavlink_msg_rc_channels_raw_get_chan4_raw(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 6);
}
 
/**
* @brief Get field chan5_raw from rc_channels_raw message
*
* @return RC channel 5 value, in microseconds
*/
static inline uint16_t mavlink_msg_rc_channels_raw_get_chan5_raw(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 8);
}
 
/**
* @brief Get field chan6_raw from rc_channels_raw message
*
* @return RC channel 6 value, in microseconds
*/
static inline uint16_t mavlink_msg_rc_channels_raw_get_chan6_raw(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 10);
}
 
/**
* @brief Get field chan7_raw from rc_channels_raw message
*
* @return RC channel 7 value, in microseconds
*/
static inline uint16_t mavlink_msg_rc_channels_raw_get_chan7_raw(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 12);
}
 
/**
* @brief Get field chan8_raw from rc_channels_raw message
*
* @return RC channel 8 value, in microseconds
*/
static inline uint16_t mavlink_msg_rc_channels_raw_get_chan8_raw(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 14);
}
 
/**
* @brief Get field rssi from rc_channels_raw message
*
* @return Receive signal strength indicator, 0: 0%, 255: 100%
*/
static inline uint8_t mavlink_msg_rc_channels_raw_get_rssi(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 16);
}
 
/**
* @brief Decode a rc_channels_raw message into a struct
*
* @param msg The message to decode
* @param rc_channels_raw C-struct to decode the message contents into
*/
static inline void mavlink_msg_rc_channels_raw_decode(const mavlink_message_t* msg, mavlink_rc_channels_raw_t* rc_channels_raw)
{
#if MAVLINK_NEED_BYTE_SWAP
rc_channels_raw->chan1_raw = mavlink_msg_rc_channels_raw_get_chan1_raw(msg);
rc_channels_raw->chan2_raw = mavlink_msg_rc_channels_raw_get_chan2_raw(msg);
rc_channels_raw->chan3_raw = mavlink_msg_rc_channels_raw_get_chan3_raw(msg);
rc_channels_raw->chan4_raw = mavlink_msg_rc_channels_raw_get_chan4_raw(msg);
rc_channels_raw->chan5_raw = mavlink_msg_rc_channels_raw_get_chan5_raw(msg);
rc_channels_raw->chan6_raw = mavlink_msg_rc_channels_raw_get_chan6_raw(msg);
rc_channels_raw->chan7_raw = mavlink_msg_rc_channels_raw_get_chan7_raw(msg);
rc_channels_raw->chan8_raw = mavlink_msg_rc_channels_raw_get_chan8_raw(msg);
rc_channels_raw->rssi = mavlink_msg_rc_channels_raw_get_rssi(msg);
#else
memcpy(rc_channels_raw, _MAV_PAYLOAD(msg), 17);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v0.9/common/mavlink_msg_rc_channels_scaled.h
0,0 → 1,320
// MESSAGE RC_CHANNELS_SCALED PACKING
 
#define MAVLINK_MSG_ID_RC_CHANNELS_SCALED 36
 
typedef struct __mavlink_rc_channels_scaled_t
{
int16_t chan1_scaled; ///< RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
int16_t chan2_scaled; ///< RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
int16_t chan3_scaled; ///< RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
int16_t chan4_scaled; ///< RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
int16_t chan5_scaled; ///< RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
int16_t chan6_scaled; ///< RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
int16_t chan7_scaled; ///< RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
int16_t chan8_scaled; ///< RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
uint8_t rssi; ///< Receive signal strength indicator, 0: 0%, 255: 100%
} mavlink_rc_channels_scaled_t;
 
#define MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN 17
#define MAVLINK_MSG_ID_36_LEN 17
 
 
 
#define MAVLINK_MESSAGE_INFO_RC_CHANNELS_SCALED { \
"RC_CHANNELS_SCALED", \
9, \
{ { "chan1_scaled", NULL, MAVLINK_TYPE_INT16_T, 0, 0, offsetof(mavlink_rc_channels_scaled_t, chan1_scaled) }, \
{ "chan2_scaled", NULL, MAVLINK_TYPE_INT16_T, 0, 2, offsetof(mavlink_rc_channels_scaled_t, chan2_scaled) }, \
{ "chan3_scaled", NULL, MAVLINK_TYPE_INT16_T, 0, 4, offsetof(mavlink_rc_channels_scaled_t, chan3_scaled) }, \
{ "chan4_scaled", NULL, MAVLINK_TYPE_INT16_T, 0, 6, offsetof(mavlink_rc_channels_scaled_t, chan4_scaled) }, \
{ "chan5_scaled", NULL, MAVLINK_TYPE_INT16_T, 0, 8, offsetof(mavlink_rc_channels_scaled_t, chan5_scaled) }, \
{ "chan6_scaled", NULL, MAVLINK_TYPE_INT16_T, 0, 10, offsetof(mavlink_rc_channels_scaled_t, chan6_scaled) }, \
{ "chan7_scaled", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_rc_channels_scaled_t, chan7_scaled) }, \
{ "chan8_scaled", NULL, MAVLINK_TYPE_INT16_T, 0, 14, offsetof(mavlink_rc_channels_scaled_t, chan8_scaled) }, \
{ "rssi", NULL, MAVLINK_TYPE_UINT8_T, 0, 16, offsetof(mavlink_rc_channels_scaled_t, rssi) }, \
} \
}
 
 
/**
* @brief Pack a rc_channels_scaled message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param chan1_scaled RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
* @param chan2_scaled RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
* @param chan3_scaled RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
* @param chan4_scaled RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
* @param chan5_scaled RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
* @param chan6_scaled RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
* @param chan7_scaled RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
* @param chan8_scaled RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
* @param rssi Receive signal strength indicator, 0: 0%, 255: 100%
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_rc_channels_scaled_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
int16_t chan1_scaled, int16_t chan2_scaled, int16_t chan3_scaled, int16_t chan4_scaled, int16_t chan5_scaled, int16_t chan6_scaled, int16_t chan7_scaled, int16_t chan8_scaled, uint8_t rssi)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[17];
_mav_put_int16_t(buf, 0, chan1_scaled);
_mav_put_int16_t(buf, 2, chan2_scaled);
_mav_put_int16_t(buf, 4, chan3_scaled);
_mav_put_int16_t(buf, 6, chan4_scaled);
_mav_put_int16_t(buf, 8, chan5_scaled);
_mav_put_int16_t(buf, 10, chan6_scaled);
_mav_put_int16_t(buf, 12, chan7_scaled);
_mav_put_int16_t(buf, 14, chan8_scaled);
_mav_put_uint8_t(buf, 16, rssi);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 17);
#else
mavlink_rc_channels_scaled_t packet;
packet.chan1_scaled = chan1_scaled;
packet.chan2_scaled = chan2_scaled;
packet.chan3_scaled = chan3_scaled;
packet.chan4_scaled = chan4_scaled;
packet.chan5_scaled = chan5_scaled;
packet.chan6_scaled = chan6_scaled;
packet.chan7_scaled = chan7_scaled;
packet.chan8_scaled = chan8_scaled;
packet.rssi = rssi;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 17);
#endif
 
msg->msgid = MAVLINK_MSG_ID_RC_CHANNELS_SCALED;
return mavlink_finalize_message(msg, system_id, component_id, 17);
}
 
/**
* @brief Pack a rc_channels_scaled message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param chan1_scaled RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
* @param chan2_scaled RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
* @param chan3_scaled RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
* @param chan4_scaled RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
* @param chan5_scaled RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
* @param chan6_scaled RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
* @param chan7_scaled RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
* @param chan8_scaled RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
* @param rssi Receive signal strength indicator, 0: 0%, 255: 100%
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_rc_channels_scaled_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
int16_t chan1_scaled,int16_t chan2_scaled,int16_t chan3_scaled,int16_t chan4_scaled,int16_t chan5_scaled,int16_t chan6_scaled,int16_t chan7_scaled,int16_t chan8_scaled,uint8_t rssi)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[17];
_mav_put_int16_t(buf, 0, chan1_scaled);
_mav_put_int16_t(buf, 2, chan2_scaled);
_mav_put_int16_t(buf, 4, chan3_scaled);
_mav_put_int16_t(buf, 6, chan4_scaled);
_mav_put_int16_t(buf, 8, chan5_scaled);
_mav_put_int16_t(buf, 10, chan6_scaled);
_mav_put_int16_t(buf, 12, chan7_scaled);
_mav_put_int16_t(buf, 14, chan8_scaled);
_mav_put_uint8_t(buf, 16, rssi);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 17);
#else
mavlink_rc_channels_scaled_t packet;
packet.chan1_scaled = chan1_scaled;
packet.chan2_scaled = chan2_scaled;
packet.chan3_scaled = chan3_scaled;
packet.chan4_scaled = chan4_scaled;
packet.chan5_scaled = chan5_scaled;
packet.chan6_scaled = chan6_scaled;
packet.chan7_scaled = chan7_scaled;
packet.chan8_scaled = chan8_scaled;
packet.rssi = rssi;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 17);
#endif
 
msg->msgid = MAVLINK_MSG_ID_RC_CHANNELS_SCALED;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 17);
}
 
/**
* @brief Encode a rc_channels_scaled struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param rc_channels_scaled C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_rc_channels_scaled_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_rc_channels_scaled_t* rc_channels_scaled)
{
return mavlink_msg_rc_channels_scaled_pack(system_id, component_id, msg, rc_channels_scaled->chan1_scaled, rc_channels_scaled->chan2_scaled, rc_channels_scaled->chan3_scaled, rc_channels_scaled->chan4_scaled, rc_channels_scaled->chan5_scaled, rc_channels_scaled->chan6_scaled, rc_channels_scaled->chan7_scaled, rc_channels_scaled->chan8_scaled, rc_channels_scaled->rssi);
}
 
/**
* @brief Send a rc_channels_scaled message
* @param chan MAVLink channel to send the message
*
* @param chan1_scaled RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
* @param chan2_scaled RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
* @param chan3_scaled RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
* @param chan4_scaled RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
* @param chan5_scaled RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
* @param chan6_scaled RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
* @param chan7_scaled RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
* @param chan8_scaled RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
* @param rssi Receive signal strength indicator, 0: 0%, 255: 100%
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_rc_channels_scaled_send(mavlink_channel_t chan, int16_t chan1_scaled, int16_t chan2_scaled, int16_t chan3_scaled, int16_t chan4_scaled, int16_t chan5_scaled, int16_t chan6_scaled, int16_t chan7_scaled, int16_t chan8_scaled, uint8_t rssi)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[17];
_mav_put_int16_t(buf, 0, chan1_scaled);
_mav_put_int16_t(buf, 2, chan2_scaled);
_mav_put_int16_t(buf, 4, chan3_scaled);
_mav_put_int16_t(buf, 6, chan4_scaled);
_mav_put_int16_t(buf, 8, chan5_scaled);
_mav_put_int16_t(buf, 10, chan6_scaled);
_mav_put_int16_t(buf, 12, chan7_scaled);
_mav_put_int16_t(buf, 14, chan8_scaled);
_mav_put_uint8_t(buf, 16, rssi);
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_SCALED, buf, 17);
#else
mavlink_rc_channels_scaled_t packet;
packet.chan1_scaled = chan1_scaled;
packet.chan2_scaled = chan2_scaled;
packet.chan3_scaled = chan3_scaled;
packet.chan4_scaled = chan4_scaled;
packet.chan5_scaled = chan5_scaled;
packet.chan6_scaled = chan6_scaled;
packet.chan7_scaled = chan7_scaled;
packet.chan8_scaled = chan8_scaled;
packet.rssi = rssi;
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_SCALED, (const char *)&packet, 17);
#endif
}
 
#endif
 
// MESSAGE RC_CHANNELS_SCALED UNPACKING
 
 
/**
* @brief Get field chan1_scaled from rc_channels_scaled message
*
* @return RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
*/
static inline int16_t mavlink_msg_rc_channels_scaled_get_chan1_scaled(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 0);
}
 
/**
* @brief Get field chan2_scaled from rc_channels_scaled message
*
* @return RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
*/
static inline int16_t mavlink_msg_rc_channels_scaled_get_chan2_scaled(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 2);
}
 
/**
* @brief Get field chan3_scaled from rc_channels_scaled message
*
* @return RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
*/
static inline int16_t mavlink_msg_rc_channels_scaled_get_chan3_scaled(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 4);
}
 
/**
* @brief Get field chan4_scaled from rc_channels_scaled message
*
* @return RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
*/
static inline int16_t mavlink_msg_rc_channels_scaled_get_chan4_scaled(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 6);
}
 
/**
* @brief Get field chan5_scaled from rc_channels_scaled message
*
* @return RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
*/
static inline int16_t mavlink_msg_rc_channels_scaled_get_chan5_scaled(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 8);
}
 
/**
* @brief Get field chan6_scaled from rc_channels_scaled message
*
* @return RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
*/
static inline int16_t mavlink_msg_rc_channels_scaled_get_chan6_scaled(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 10);
}
 
/**
* @brief Get field chan7_scaled from rc_channels_scaled message
*
* @return RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
*/
static inline int16_t mavlink_msg_rc_channels_scaled_get_chan7_scaled(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 12);
}
 
/**
* @brief Get field chan8_scaled from rc_channels_scaled message
*
* @return RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
*/
static inline int16_t mavlink_msg_rc_channels_scaled_get_chan8_scaled(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 14);
}
 
/**
* @brief Get field rssi from rc_channels_scaled message
*
* @return Receive signal strength indicator, 0: 0%, 255: 100%
*/
static inline uint8_t mavlink_msg_rc_channels_scaled_get_rssi(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 16);
}
 
/**
* @brief Decode a rc_channels_scaled message into a struct
*
* @param msg The message to decode
* @param rc_channels_scaled C-struct to decode the message contents into
*/
static inline void mavlink_msg_rc_channels_scaled_decode(const mavlink_message_t* msg, mavlink_rc_channels_scaled_t* rc_channels_scaled)
{
#if MAVLINK_NEED_BYTE_SWAP
rc_channels_scaled->chan1_scaled = mavlink_msg_rc_channels_scaled_get_chan1_scaled(msg);
rc_channels_scaled->chan2_scaled = mavlink_msg_rc_channels_scaled_get_chan2_scaled(msg);
rc_channels_scaled->chan3_scaled = mavlink_msg_rc_channels_scaled_get_chan3_scaled(msg);
rc_channels_scaled->chan4_scaled = mavlink_msg_rc_channels_scaled_get_chan4_scaled(msg);
rc_channels_scaled->chan5_scaled = mavlink_msg_rc_channels_scaled_get_chan5_scaled(msg);
rc_channels_scaled->chan6_scaled = mavlink_msg_rc_channels_scaled_get_chan6_scaled(msg);
rc_channels_scaled->chan7_scaled = mavlink_msg_rc_channels_scaled_get_chan7_scaled(msg);
rc_channels_scaled->chan8_scaled = mavlink_msg_rc_channels_scaled_get_chan8_scaled(msg);
rc_channels_scaled->rssi = mavlink_msg_rc_channels_scaled_get_rssi(msg);
#else
memcpy(rc_channels_scaled, _MAV_PAYLOAD(msg), 17);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v0.9/common/mavlink_msg_request_data_stream.h
0,0 → 1,232
// MESSAGE REQUEST_DATA_STREAM PACKING
 
#define MAVLINK_MSG_ID_REQUEST_DATA_STREAM 66
 
typedef struct __mavlink_request_data_stream_t
{
uint8_t target_system; ///< The target requested to send the message stream.
uint8_t target_component; ///< The target requested to send the message stream.
uint8_t req_stream_id; ///< The ID of the requested message type
uint16_t req_message_rate; ///< Update rate in Hertz
uint8_t start_stop; ///< 1 to start sending, 0 to stop sending.
} mavlink_request_data_stream_t;
 
#define MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN 6
#define MAVLINK_MSG_ID_66_LEN 6
 
 
 
#define MAVLINK_MESSAGE_INFO_REQUEST_DATA_STREAM { \
"REQUEST_DATA_STREAM", \
5, \
{ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_request_data_stream_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_request_data_stream_t, target_component) }, \
{ "req_stream_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_request_data_stream_t, req_stream_id) }, \
{ "req_message_rate", NULL, MAVLINK_TYPE_UINT16_T, 0, 3, offsetof(mavlink_request_data_stream_t, req_message_rate) }, \
{ "start_stop", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_request_data_stream_t, start_stop) }, \
} \
}
 
 
/**
* @brief Pack a request_data_stream message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param target_system The target requested to send the message stream.
* @param target_component The target requested to send the message stream.
* @param req_stream_id The ID of the requested message type
* @param req_message_rate Update rate in Hertz
* @param start_stop 1 to start sending, 0 to stop sending.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_request_data_stream_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t target_system, uint8_t target_component, uint8_t req_stream_id, uint16_t req_message_rate, uint8_t start_stop)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[6];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
_mav_put_uint8_t(buf, 2, req_stream_id);
_mav_put_uint16_t(buf, 3, req_message_rate);
_mav_put_uint8_t(buf, 5, start_stop);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 6);
#else
mavlink_request_data_stream_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
packet.req_stream_id = req_stream_id;
packet.req_message_rate = req_message_rate;
packet.start_stop = start_stop;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 6);
#endif
 
msg->msgid = MAVLINK_MSG_ID_REQUEST_DATA_STREAM;
return mavlink_finalize_message(msg, system_id, component_id, 6);
}
 
/**
* @brief Pack a request_data_stream message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param target_system The target requested to send the message stream.
* @param target_component The target requested to send the message stream.
* @param req_stream_id The ID of the requested message type
* @param req_message_rate Update rate in Hertz
* @param start_stop 1 to start sending, 0 to stop sending.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_request_data_stream_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 req_stream_id,uint16_t req_message_rate,uint8_t start_stop)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[6];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
_mav_put_uint8_t(buf, 2, req_stream_id);
_mav_put_uint16_t(buf, 3, req_message_rate);
_mav_put_uint8_t(buf, 5, start_stop);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 6);
#else
mavlink_request_data_stream_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
packet.req_stream_id = req_stream_id;
packet.req_message_rate = req_message_rate;
packet.start_stop = start_stop;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 6);
#endif
 
msg->msgid = MAVLINK_MSG_ID_REQUEST_DATA_STREAM;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 6);
}
 
/**
* @brief Encode a request_data_stream struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param request_data_stream C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_request_data_stream_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_request_data_stream_t* request_data_stream)
{
return mavlink_msg_request_data_stream_pack(system_id, component_id, msg, request_data_stream->target_system, request_data_stream->target_component, request_data_stream->req_stream_id, request_data_stream->req_message_rate, request_data_stream->start_stop);
}
 
/**
* @brief Send a request_data_stream message
* @param chan MAVLink channel to send the message
*
* @param target_system The target requested to send the message stream.
* @param target_component The target requested to send the message stream.
* @param req_stream_id The ID of the requested message type
* @param req_message_rate Update rate in Hertz
* @param start_stop 1 to start sending, 0 to stop sending.
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_request_data_stream_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t req_stream_id, uint16_t req_message_rate, uint8_t start_stop)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[6];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
_mav_put_uint8_t(buf, 2, req_stream_id);
_mav_put_uint16_t(buf, 3, req_message_rate);
_mav_put_uint8_t(buf, 5, start_stop);
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_REQUEST_DATA_STREAM, buf, 6);
#else
mavlink_request_data_stream_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
packet.req_stream_id = req_stream_id;
packet.req_message_rate = req_message_rate;
packet.start_stop = start_stop;
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_REQUEST_DATA_STREAM, (const char *)&packet, 6);
#endif
}
 
#endif
 
// MESSAGE REQUEST_DATA_STREAM UNPACKING
 
 
/**
* @brief Get field target_system from request_data_stream message
*
* @return The target requested to send the message stream.
*/
static inline uint8_t mavlink_msg_request_data_stream_get_target_system(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 0);
}
 
/**
* @brief Get field target_component from request_data_stream message
*
* @return The target requested to send the message stream.
*/
static inline uint8_t mavlink_msg_request_data_stream_get_target_component(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 1);
}
 
/**
* @brief Get field req_stream_id from request_data_stream message
*
* @return The ID of the requested message type
*/
static inline uint8_t mavlink_msg_request_data_stream_get_req_stream_id(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 2);
}
 
/**
* @brief Get field req_message_rate from request_data_stream message
*
* @return Update rate in Hertz
*/
static inline uint16_t mavlink_msg_request_data_stream_get_req_message_rate(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 3);
}
 
/**
* @brief Get field start_stop from request_data_stream message
*
* @return 1 to start sending, 0 to stop sending.
*/
static inline uint8_t mavlink_msg_request_data_stream_get_start_stop(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 5);
}
 
/**
* @brief Decode a request_data_stream message into a struct
*
* @param msg The message to decode
* @param request_data_stream C-struct to decode the message contents into
*/
static inline void mavlink_msg_request_data_stream_decode(const mavlink_message_t* msg, mavlink_request_data_stream_t* request_data_stream)
{
#if MAVLINK_NEED_BYTE_SWAP
request_data_stream->target_system = mavlink_msg_request_data_stream_get_target_system(msg);
request_data_stream->target_component = mavlink_msg_request_data_stream_get_target_component(msg);
request_data_stream->req_stream_id = mavlink_msg_request_data_stream_get_req_stream_id(msg);
request_data_stream->req_message_rate = mavlink_msg_request_data_stream_get_req_message_rate(msg);
request_data_stream->start_stop = mavlink_msg_request_data_stream_get_start_stop(msg);
#else
memcpy(request_data_stream, _MAV_PAYLOAD(msg), 6);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v0.9/common/mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint.h
0,0 → 1,232
// MESSAGE ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT PACKING
 
#define MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT 58
 
typedef struct __mavlink_roll_pitch_yaw_speed_thrust_setpoint_t
{
uint64_t time_us; ///< Timestamp in micro seconds since unix epoch
float roll_speed; ///< Desired roll angular speed in rad/s
float pitch_speed; ///< Desired pitch angular speed in rad/s
float yaw_speed; ///< Desired yaw angular speed in rad/s
float thrust; ///< Collective thrust, normalized to 0 .. 1
} mavlink_roll_pitch_yaw_speed_thrust_setpoint_t;
 
#define MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT_LEN 24
#define MAVLINK_MSG_ID_58_LEN 24
 
 
 
#define MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT { \
"ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT", \
5, \
{ { "time_us", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_roll_pitch_yaw_speed_thrust_setpoint_t, time_us) }, \
{ "roll_speed", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_roll_pitch_yaw_speed_thrust_setpoint_t, roll_speed) }, \
{ "pitch_speed", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_roll_pitch_yaw_speed_thrust_setpoint_t, pitch_speed) }, \
{ "yaw_speed", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_roll_pitch_yaw_speed_thrust_setpoint_t, yaw_speed) }, \
{ "thrust", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_roll_pitch_yaw_speed_thrust_setpoint_t, thrust) }, \
} \
}
 
 
/**
* @brief Pack a roll_pitch_yaw_speed_thrust_setpoint message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param time_us Timestamp in micro seconds since unix epoch
* @param roll_speed Desired roll angular speed in rad/s
* @param pitch_speed Desired pitch angular speed in rad/s
* @param yaw_speed Desired yaw angular speed in rad/s
* @param thrust Collective thrust, normalized to 0 .. 1
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint64_t time_us, float roll_speed, float pitch_speed, float yaw_speed, float thrust)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[24];
_mav_put_uint64_t(buf, 0, time_us);
_mav_put_float(buf, 8, roll_speed);
_mav_put_float(buf, 12, pitch_speed);
_mav_put_float(buf, 16, yaw_speed);
_mav_put_float(buf, 20, thrust);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 24);
#else
mavlink_roll_pitch_yaw_speed_thrust_setpoint_t packet;
packet.time_us = time_us;
packet.roll_speed = roll_speed;
packet.pitch_speed = pitch_speed;
packet.yaw_speed = yaw_speed;
packet.thrust = thrust;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 24);
#endif
 
msg->msgid = MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT;
return mavlink_finalize_message(msg, system_id, component_id, 24);
}
 
/**
* @brief Pack a roll_pitch_yaw_speed_thrust_setpoint message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param time_us Timestamp in micro seconds since unix epoch
* @param roll_speed Desired roll angular speed in rad/s
* @param pitch_speed Desired pitch angular speed in rad/s
* @param yaw_speed Desired yaw angular speed in rad/s
* @param thrust Collective thrust, normalized to 0 .. 1
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint64_t time_us,float roll_speed,float pitch_speed,float yaw_speed,float thrust)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[24];
_mav_put_uint64_t(buf, 0, time_us);
_mav_put_float(buf, 8, roll_speed);
_mav_put_float(buf, 12, pitch_speed);
_mav_put_float(buf, 16, yaw_speed);
_mav_put_float(buf, 20, thrust);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 24);
#else
mavlink_roll_pitch_yaw_speed_thrust_setpoint_t packet;
packet.time_us = time_us;
packet.roll_speed = roll_speed;
packet.pitch_speed = pitch_speed;
packet.yaw_speed = yaw_speed;
packet.thrust = thrust;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 24);
#endif
 
msg->msgid = MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 24);
}
 
/**
* @brief Encode a roll_pitch_yaw_speed_thrust_setpoint struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param roll_pitch_yaw_speed_thrust_setpoint C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_roll_pitch_yaw_speed_thrust_setpoint_t* roll_pitch_yaw_speed_thrust_setpoint)
{
return mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_pack(system_id, component_id, msg, roll_pitch_yaw_speed_thrust_setpoint->time_us, roll_pitch_yaw_speed_thrust_setpoint->roll_speed, roll_pitch_yaw_speed_thrust_setpoint->pitch_speed, roll_pitch_yaw_speed_thrust_setpoint->yaw_speed, roll_pitch_yaw_speed_thrust_setpoint->thrust);
}
 
/**
* @brief Send a roll_pitch_yaw_speed_thrust_setpoint message
* @param chan MAVLink channel to send the message
*
* @param time_us Timestamp in micro seconds since unix epoch
* @param roll_speed Desired roll angular speed in rad/s
* @param pitch_speed Desired pitch angular speed in rad/s
* @param yaw_speed Desired yaw angular speed in rad/s
* @param thrust Collective thrust, normalized to 0 .. 1
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_send(mavlink_channel_t chan, uint64_t time_us, float roll_speed, float pitch_speed, float yaw_speed, float thrust)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[24];
_mav_put_uint64_t(buf, 0, time_us);
_mav_put_float(buf, 8, roll_speed);
_mav_put_float(buf, 12, pitch_speed);
_mav_put_float(buf, 16, yaw_speed);
_mav_put_float(buf, 20, thrust);
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT, buf, 24);
#else
mavlink_roll_pitch_yaw_speed_thrust_setpoint_t packet;
packet.time_us = time_us;
packet.roll_speed = roll_speed;
packet.pitch_speed = pitch_speed;
packet.yaw_speed = yaw_speed;
packet.thrust = thrust;
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT, (const char *)&packet, 24);
#endif
}
 
#endif
 
// MESSAGE ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT UNPACKING
 
 
/**
* @brief Get field time_us from roll_pitch_yaw_speed_thrust_setpoint message
*
* @return Timestamp in micro seconds since unix epoch
*/
static inline uint64_t mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_get_time_us(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint64_t(msg, 0);
}
 
/**
* @brief Get field roll_speed from roll_pitch_yaw_speed_thrust_setpoint message
*
* @return Desired roll angular speed in rad/s
*/
static inline float mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_get_roll_speed(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 8);
}
 
/**
* @brief Get field pitch_speed from roll_pitch_yaw_speed_thrust_setpoint message
*
* @return Desired pitch angular speed in rad/s
*/
static inline float mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_get_pitch_speed(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 12);
}
 
/**
* @brief Get field yaw_speed from roll_pitch_yaw_speed_thrust_setpoint message
*
* @return Desired yaw angular speed in rad/s
*/
static inline float mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_get_yaw_speed(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 16);
}
 
/**
* @brief Get field thrust from roll_pitch_yaw_speed_thrust_setpoint message
*
* @return Collective thrust, normalized to 0 .. 1
*/
static inline float mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_get_thrust(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 20);
}
 
/**
* @brief Decode a roll_pitch_yaw_speed_thrust_setpoint message into a struct
*
* @param msg The message to decode
* @param roll_pitch_yaw_speed_thrust_setpoint C-struct to decode the message contents into
*/
static inline void mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_decode(const mavlink_message_t* msg, mavlink_roll_pitch_yaw_speed_thrust_setpoint_t* roll_pitch_yaw_speed_thrust_setpoint)
{
#if MAVLINK_NEED_BYTE_SWAP
roll_pitch_yaw_speed_thrust_setpoint->time_us = mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_get_time_us(msg);
roll_pitch_yaw_speed_thrust_setpoint->roll_speed = mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_get_roll_speed(msg);
roll_pitch_yaw_speed_thrust_setpoint->pitch_speed = mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_get_pitch_speed(msg);
roll_pitch_yaw_speed_thrust_setpoint->yaw_speed = mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_get_yaw_speed(msg);
roll_pitch_yaw_speed_thrust_setpoint->thrust = mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_get_thrust(msg);
#else
memcpy(roll_pitch_yaw_speed_thrust_setpoint, _MAV_PAYLOAD(msg), 24);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v0.9/common/mavlink_msg_roll_pitch_yaw_thrust_setpoint.h
0,0 → 1,232
// MESSAGE ROLL_PITCH_YAW_THRUST_SETPOINT PACKING
 
#define MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT 57
 
typedef struct __mavlink_roll_pitch_yaw_thrust_setpoint_t
{
uint64_t time_us; ///< Timestamp in micro seconds since unix epoch
float roll; ///< Desired roll angle in radians
float pitch; ///< Desired pitch angle in radians
float yaw; ///< Desired yaw angle in radians
float thrust; ///< Collective thrust, normalized to 0 .. 1
} mavlink_roll_pitch_yaw_thrust_setpoint_t;
 
#define MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT_LEN 24
#define MAVLINK_MSG_ID_57_LEN 24
 
 
 
#define MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_THRUST_SETPOINT { \
"ROLL_PITCH_YAW_THRUST_SETPOINT", \
5, \
{ { "time_us", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_roll_pitch_yaw_thrust_setpoint_t, time_us) }, \
{ "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_roll_pitch_yaw_thrust_setpoint_t, roll) }, \
{ "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_roll_pitch_yaw_thrust_setpoint_t, pitch) }, \
{ "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_roll_pitch_yaw_thrust_setpoint_t, yaw) }, \
{ "thrust", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_roll_pitch_yaw_thrust_setpoint_t, thrust) }, \
} \
}
 
 
/**
* @brief Pack a roll_pitch_yaw_thrust_setpoint message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param time_us Timestamp in micro seconds since unix epoch
* @param roll Desired roll angle in radians
* @param pitch Desired pitch angle in radians
* @param yaw Desired yaw angle in radians
* @param thrust Collective thrust, normalized to 0 .. 1
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_roll_pitch_yaw_thrust_setpoint_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint64_t time_us, float roll, float pitch, float yaw, float thrust)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[24];
_mav_put_uint64_t(buf, 0, time_us);
_mav_put_float(buf, 8, roll);
_mav_put_float(buf, 12, pitch);
_mav_put_float(buf, 16, yaw);
_mav_put_float(buf, 20, thrust);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 24);
#else
mavlink_roll_pitch_yaw_thrust_setpoint_t packet;
packet.time_us = time_us;
packet.roll = roll;
packet.pitch = pitch;
packet.yaw = yaw;
packet.thrust = thrust;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 24);
#endif
 
msg->msgid = MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT;
return mavlink_finalize_message(msg, system_id, component_id, 24);
}
 
/**
* @brief Pack a roll_pitch_yaw_thrust_setpoint message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param time_us Timestamp in micro seconds since unix epoch
* @param roll Desired roll angle in radians
* @param pitch Desired pitch angle in radians
* @param yaw Desired yaw angle in radians
* @param thrust Collective thrust, normalized to 0 .. 1
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_roll_pitch_yaw_thrust_setpoint_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint64_t time_us,float roll,float pitch,float yaw,float thrust)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[24];
_mav_put_uint64_t(buf, 0, time_us);
_mav_put_float(buf, 8, roll);
_mav_put_float(buf, 12, pitch);
_mav_put_float(buf, 16, yaw);
_mav_put_float(buf, 20, thrust);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 24);
#else
mavlink_roll_pitch_yaw_thrust_setpoint_t packet;
packet.time_us = time_us;
packet.roll = roll;
packet.pitch = pitch;
packet.yaw = yaw;
packet.thrust = thrust;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 24);
#endif
 
msg->msgid = MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 24);
}
 
/**
* @brief Encode a roll_pitch_yaw_thrust_setpoint struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param roll_pitch_yaw_thrust_setpoint C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_roll_pitch_yaw_thrust_setpoint_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_roll_pitch_yaw_thrust_setpoint_t* roll_pitch_yaw_thrust_setpoint)
{
return mavlink_msg_roll_pitch_yaw_thrust_setpoint_pack(system_id, component_id, msg, roll_pitch_yaw_thrust_setpoint->time_us, roll_pitch_yaw_thrust_setpoint->roll, roll_pitch_yaw_thrust_setpoint->pitch, roll_pitch_yaw_thrust_setpoint->yaw, roll_pitch_yaw_thrust_setpoint->thrust);
}
 
/**
* @brief Send a roll_pitch_yaw_thrust_setpoint message
* @param chan MAVLink channel to send the message
*
* @param time_us Timestamp in micro seconds since unix epoch
* @param roll Desired roll angle in radians
* @param pitch Desired pitch angle in radians
* @param yaw Desired yaw angle in radians
* @param thrust Collective thrust, normalized to 0 .. 1
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_roll_pitch_yaw_thrust_setpoint_send(mavlink_channel_t chan, uint64_t time_us, float roll, float pitch, float yaw, float thrust)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[24];
_mav_put_uint64_t(buf, 0, time_us);
_mav_put_float(buf, 8, roll);
_mav_put_float(buf, 12, pitch);
_mav_put_float(buf, 16, yaw);
_mav_put_float(buf, 20, thrust);
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT, buf, 24);
#else
mavlink_roll_pitch_yaw_thrust_setpoint_t packet;
packet.time_us = time_us;
packet.roll = roll;
packet.pitch = pitch;
packet.yaw = yaw;
packet.thrust = thrust;
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT, (const char *)&packet, 24);
#endif
}
 
#endif
 
// MESSAGE ROLL_PITCH_YAW_THRUST_SETPOINT UNPACKING
 
 
/**
* @brief Get field time_us from roll_pitch_yaw_thrust_setpoint message
*
* @return Timestamp in micro seconds since unix epoch
*/
static inline uint64_t mavlink_msg_roll_pitch_yaw_thrust_setpoint_get_time_us(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint64_t(msg, 0);
}
 
/**
* @brief Get field roll from roll_pitch_yaw_thrust_setpoint message
*
* @return Desired roll angle in radians
*/
static inline float mavlink_msg_roll_pitch_yaw_thrust_setpoint_get_roll(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 8);
}
 
/**
* @brief Get field pitch from roll_pitch_yaw_thrust_setpoint message
*
* @return Desired pitch angle in radians
*/
static inline float mavlink_msg_roll_pitch_yaw_thrust_setpoint_get_pitch(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 12);
}
 
/**
* @brief Get field yaw from roll_pitch_yaw_thrust_setpoint message
*
* @return Desired yaw angle in radians
*/
static inline float mavlink_msg_roll_pitch_yaw_thrust_setpoint_get_yaw(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 16);
}
 
/**
* @brief Get field thrust from roll_pitch_yaw_thrust_setpoint message
*
* @return Collective thrust, normalized to 0 .. 1
*/
static inline float mavlink_msg_roll_pitch_yaw_thrust_setpoint_get_thrust(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 20);
}
 
/**
* @brief Decode a roll_pitch_yaw_thrust_setpoint message into a struct
*
* @param msg The message to decode
* @param roll_pitch_yaw_thrust_setpoint C-struct to decode the message contents into
*/
static inline void mavlink_msg_roll_pitch_yaw_thrust_setpoint_decode(const mavlink_message_t* msg, mavlink_roll_pitch_yaw_thrust_setpoint_t* roll_pitch_yaw_thrust_setpoint)
{
#if MAVLINK_NEED_BYTE_SWAP
roll_pitch_yaw_thrust_setpoint->time_us = mavlink_msg_roll_pitch_yaw_thrust_setpoint_get_time_us(msg);
roll_pitch_yaw_thrust_setpoint->roll = mavlink_msg_roll_pitch_yaw_thrust_setpoint_get_roll(msg);
roll_pitch_yaw_thrust_setpoint->pitch = mavlink_msg_roll_pitch_yaw_thrust_setpoint_get_pitch(msg);
roll_pitch_yaw_thrust_setpoint->yaw = mavlink_msg_roll_pitch_yaw_thrust_setpoint_get_yaw(msg);
roll_pitch_yaw_thrust_setpoint->thrust = mavlink_msg_roll_pitch_yaw_thrust_setpoint_get_thrust(msg);
#else
memcpy(roll_pitch_yaw_thrust_setpoint, _MAV_PAYLOAD(msg), 24);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v0.9/common/mavlink_msg_safety_allowed_area.h
0,0 → 1,276
// MESSAGE SAFETY_ALLOWED_AREA PACKING
 
#define MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA 54
 
typedef struct __mavlink_safety_allowed_area_t
{
uint8_t frame; ///< Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down.
float p1x; ///< x position 1 / Latitude 1
float p1y; ///< y position 1 / Longitude 1
float p1z; ///< z position 1 / Altitude 1
float p2x; ///< x position 2 / Latitude 2
float p2y; ///< y position 2 / Longitude 2
float p2z; ///< z position 2 / Altitude 2
} mavlink_safety_allowed_area_t;
 
#define MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN 25
#define MAVLINK_MSG_ID_54_LEN 25
 
 
 
#define MAVLINK_MESSAGE_INFO_SAFETY_ALLOWED_AREA { \
"SAFETY_ALLOWED_AREA", \
7, \
{ { "frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_safety_allowed_area_t, frame) }, \
{ "p1x", NULL, MAVLINK_TYPE_FLOAT, 0, 1, offsetof(mavlink_safety_allowed_area_t, p1x) }, \
{ "p1y", NULL, MAVLINK_TYPE_FLOAT, 0, 5, offsetof(mavlink_safety_allowed_area_t, p1y) }, \
{ "p1z", NULL, MAVLINK_TYPE_FLOAT, 0, 9, offsetof(mavlink_safety_allowed_area_t, p1z) }, \
{ "p2x", NULL, MAVLINK_TYPE_FLOAT, 0, 13, offsetof(mavlink_safety_allowed_area_t, p2x) }, \
{ "p2y", NULL, MAVLINK_TYPE_FLOAT, 0, 17, offsetof(mavlink_safety_allowed_area_t, p2y) }, \
{ "p2z", NULL, MAVLINK_TYPE_FLOAT, 0, 21, offsetof(mavlink_safety_allowed_area_t, p2z) }, \
} \
}
 
 
/**
* @brief Pack a safety_allowed_area message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param frame Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down.
* @param p1x x position 1 / Latitude 1
* @param p1y y position 1 / Longitude 1
* @param p1z z position 1 / Altitude 1
* @param p2x x position 2 / Latitude 2
* @param p2y y position 2 / Longitude 2
* @param p2z z position 2 / Altitude 2
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_safety_allowed_area_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t frame, float p1x, float p1y, float p1z, float p2x, float p2y, float p2z)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[25];
_mav_put_uint8_t(buf, 0, frame);
_mav_put_float(buf, 1, p1x);
_mav_put_float(buf, 5, p1y);
_mav_put_float(buf, 9, p1z);
_mav_put_float(buf, 13, p2x);
_mav_put_float(buf, 17, p2y);
_mav_put_float(buf, 21, p2z);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 25);
#else
mavlink_safety_allowed_area_t packet;
packet.frame = frame;
packet.p1x = p1x;
packet.p1y = p1y;
packet.p1z = p1z;
packet.p2x = p2x;
packet.p2y = p2y;
packet.p2z = p2z;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 25);
#endif
 
msg->msgid = MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA;
return mavlink_finalize_message(msg, system_id, component_id, 25);
}
 
/**
* @brief Pack a safety_allowed_area message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param frame Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down.
* @param p1x x position 1 / Latitude 1
* @param p1y y position 1 / Longitude 1
* @param p1z z position 1 / Altitude 1
* @param p2x x position 2 / Latitude 2
* @param p2y y position 2 / Longitude 2
* @param p2z z position 2 / Altitude 2
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_safety_allowed_area_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint8_t frame,float p1x,float p1y,float p1z,float p2x,float p2y,float p2z)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[25];
_mav_put_uint8_t(buf, 0, frame);
_mav_put_float(buf, 1, p1x);
_mav_put_float(buf, 5, p1y);
_mav_put_float(buf, 9, p1z);
_mav_put_float(buf, 13, p2x);
_mav_put_float(buf, 17, p2y);
_mav_put_float(buf, 21, p2z);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 25);
#else
mavlink_safety_allowed_area_t packet;
packet.frame = frame;
packet.p1x = p1x;
packet.p1y = p1y;
packet.p1z = p1z;
packet.p2x = p2x;
packet.p2y = p2y;
packet.p2z = p2z;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 25);
#endif
 
msg->msgid = MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 25);
}
 
/**
* @brief Encode a safety_allowed_area struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param safety_allowed_area C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_safety_allowed_area_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_safety_allowed_area_t* safety_allowed_area)
{
return mavlink_msg_safety_allowed_area_pack(system_id, component_id, msg, safety_allowed_area->frame, safety_allowed_area->p1x, safety_allowed_area->p1y, safety_allowed_area->p1z, safety_allowed_area->p2x, safety_allowed_area->p2y, safety_allowed_area->p2z);
}
 
/**
* @brief Send a safety_allowed_area message
* @param chan MAVLink channel to send the message
*
* @param frame Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down.
* @param p1x x position 1 / Latitude 1
* @param p1y y position 1 / Longitude 1
* @param p1z z position 1 / Altitude 1
* @param p2x x position 2 / Latitude 2
* @param p2y y position 2 / Longitude 2
* @param p2z z position 2 / Altitude 2
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_safety_allowed_area_send(mavlink_channel_t chan, uint8_t frame, float p1x, float p1y, float p1z, float p2x, float p2y, float p2z)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[25];
_mav_put_uint8_t(buf, 0, frame);
_mav_put_float(buf, 1, p1x);
_mav_put_float(buf, 5, p1y);
_mav_put_float(buf, 9, p1z);
_mav_put_float(buf, 13, p2x);
_mav_put_float(buf, 17, p2y);
_mav_put_float(buf, 21, p2z);
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA, buf, 25);
#else
mavlink_safety_allowed_area_t packet;
packet.frame = frame;
packet.p1x = p1x;
packet.p1y = p1y;
packet.p1z = p1z;
packet.p2x = p2x;
packet.p2y = p2y;
packet.p2z = p2z;
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA, (const char *)&packet, 25);
#endif
}
 
#endif
 
// MESSAGE SAFETY_ALLOWED_AREA UNPACKING
 
 
/**
* @brief Get field frame from safety_allowed_area message
*
* @return Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down.
*/
static inline uint8_t mavlink_msg_safety_allowed_area_get_frame(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 0);
}
 
/**
* @brief Get field p1x from safety_allowed_area message
*
* @return x position 1 / Latitude 1
*/
static inline float mavlink_msg_safety_allowed_area_get_p1x(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 1);
}
 
/**
* @brief Get field p1y from safety_allowed_area message
*
* @return y position 1 / Longitude 1
*/
static inline float mavlink_msg_safety_allowed_area_get_p1y(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 5);
}
 
/**
* @brief Get field p1z from safety_allowed_area message
*
* @return z position 1 / Altitude 1
*/
static inline float mavlink_msg_safety_allowed_area_get_p1z(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 9);
}
 
/**
* @brief Get field p2x from safety_allowed_area message
*
* @return x position 2 / Latitude 2
*/
static inline float mavlink_msg_safety_allowed_area_get_p2x(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 13);
}
 
/**
* @brief Get field p2y from safety_allowed_area message
*
* @return y position 2 / Longitude 2
*/
static inline float mavlink_msg_safety_allowed_area_get_p2y(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 17);
}
 
/**
* @brief Get field p2z from safety_allowed_area message
*
* @return z position 2 / Altitude 2
*/
static inline float mavlink_msg_safety_allowed_area_get_p2z(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 21);
}
 
/**
* @brief Decode a safety_allowed_area message into a struct
*
* @param msg The message to decode
* @param safety_allowed_area C-struct to decode the message contents into
*/
static inline void mavlink_msg_safety_allowed_area_decode(const mavlink_message_t* msg, mavlink_safety_allowed_area_t* safety_allowed_area)
{
#if MAVLINK_NEED_BYTE_SWAP
safety_allowed_area->frame = mavlink_msg_safety_allowed_area_get_frame(msg);
safety_allowed_area->p1x = mavlink_msg_safety_allowed_area_get_p1x(msg);
safety_allowed_area->p1y = mavlink_msg_safety_allowed_area_get_p1y(msg);
safety_allowed_area->p1z = mavlink_msg_safety_allowed_area_get_p1z(msg);
safety_allowed_area->p2x = mavlink_msg_safety_allowed_area_get_p2x(msg);
safety_allowed_area->p2y = mavlink_msg_safety_allowed_area_get_p2y(msg);
safety_allowed_area->p2z = mavlink_msg_safety_allowed_area_get_p2z(msg);
#else
memcpy(safety_allowed_area, _MAV_PAYLOAD(msg), 25);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v0.9/common/mavlink_msg_safety_set_allowed_area.h
0,0 → 1,320
// MESSAGE SAFETY_SET_ALLOWED_AREA PACKING
 
#define MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA 53
 
typedef struct __mavlink_safety_set_allowed_area_t
{
uint8_t target_system; ///< System ID
uint8_t target_component; ///< Component ID
uint8_t frame; ///< Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down.
float p1x; ///< x position 1 / Latitude 1
float p1y; ///< y position 1 / Longitude 1
float p1z; ///< z position 1 / Altitude 1
float p2x; ///< x position 2 / Latitude 2
float p2y; ///< y position 2 / Longitude 2
float p2z; ///< z position 2 / Altitude 2
} mavlink_safety_set_allowed_area_t;
 
#define MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN 27
#define MAVLINK_MSG_ID_53_LEN 27
 
 
 
#define MAVLINK_MESSAGE_INFO_SAFETY_SET_ALLOWED_AREA { \
"SAFETY_SET_ALLOWED_AREA", \
9, \
{ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_safety_set_allowed_area_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_safety_set_allowed_area_t, target_component) }, \
{ "frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_safety_set_allowed_area_t, frame) }, \
{ "p1x", NULL, MAVLINK_TYPE_FLOAT, 0, 3, offsetof(mavlink_safety_set_allowed_area_t, p1x) }, \
{ "p1y", NULL, MAVLINK_TYPE_FLOAT, 0, 7, offsetof(mavlink_safety_set_allowed_area_t, p1y) }, \
{ "p1z", NULL, MAVLINK_TYPE_FLOAT, 0, 11, offsetof(mavlink_safety_set_allowed_area_t, p1z) }, \
{ "p2x", NULL, MAVLINK_TYPE_FLOAT, 0, 15, offsetof(mavlink_safety_set_allowed_area_t, p2x) }, \
{ "p2y", NULL, MAVLINK_TYPE_FLOAT, 0, 19, offsetof(mavlink_safety_set_allowed_area_t, p2y) }, \
{ "p2z", NULL, MAVLINK_TYPE_FLOAT, 0, 23, offsetof(mavlink_safety_set_allowed_area_t, p2z) }, \
} \
}
 
 
/**
* @brief Pack a safety_set_allowed_area message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param target_system System ID
* @param target_component Component ID
* @param frame Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down.
* @param p1x x position 1 / Latitude 1
* @param p1y y position 1 / Longitude 1
* @param p1z z position 1 / Altitude 1
* @param p2x x position 2 / Latitude 2
* @param p2y y position 2 / Longitude 2
* @param p2z z position 2 / Altitude 2
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_safety_set_allowed_area_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t target_system, uint8_t target_component, uint8_t frame, float p1x, float p1y, float p1z, float p2x, float p2y, float p2z)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[27];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
_mav_put_uint8_t(buf, 2, frame);
_mav_put_float(buf, 3, p1x);
_mav_put_float(buf, 7, p1y);
_mav_put_float(buf, 11, p1z);
_mav_put_float(buf, 15, p2x);
_mav_put_float(buf, 19, p2y);
_mav_put_float(buf, 23, p2z);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 27);
#else
mavlink_safety_set_allowed_area_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
packet.frame = frame;
packet.p1x = p1x;
packet.p1y = p1y;
packet.p1z = p1z;
packet.p2x = p2x;
packet.p2y = p2y;
packet.p2z = p2z;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 27);
#endif
 
msg->msgid = MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA;
return mavlink_finalize_message(msg, system_id, component_id, 27);
}
 
/**
* @brief Pack a safety_set_allowed_area message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param target_system System ID
* @param target_component Component ID
* @param frame Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down.
* @param p1x x position 1 / Latitude 1
* @param p1y y position 1 / Longitude 1
* @param p1z z position 1 / Altitude 1
* @param p2x x position 2 / Latitude 2
* @param p2y y position 2 / Longitude 2
* @param p2z z position 2 / Altitude 2
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_safety_set_allowed_area_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 frame,float p1x,float p1y,float p1z,float p2x,float p2y,float p2z)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[27];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
_mav_put_uint8_t(buf, 2, frame);
_mav_put_float(buf, 3, p1x);
_mav_put_float(buf, 7, p1y);
_mav_put_float(buf, 11, p1z);
_mav_put_float(buf, 15, p2x);
_mav_put_float(buf, 19, p2y);
_mav_put_float(buf, 23, p2z);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 27);
#else
mavlink_safety_set_allowed_area_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
packet.frame = frame;
packet.p1x = p1x;
packet.p1y = p1y;
packet.p1z = p1z;
packet.p2x = p2x;
packet.p2y = p2y;
packet.p2z = p2z;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 27);
#endif
 
msg->msgid = MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 27);
}
 
/**
* @brief Encode a safety_set_allowed_area struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param safety_set_allowed_area C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_safety_set_allowed_area_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_safety_set_allowed_area_t* safety_set_allowed_area)
{
return mavlink_msg_safety_set_allowed_area_pack(system_id, component_id, msg, safety_set_allowed_area->target_system, safety_set_allowed_area->target_component, safety_set_allowed_area->frame, safety_set_allowed_area->p1x, safety_set_allowed_area->p1y, safety_set_allowed_area->p1z, safety_set_allowed_area->p2x, safety_set_allowed_area->p2y, safety_set_allowed_area->p2z);
}
 
/**
* @brief Send a safety_set_allowed_area message
* @param chan MAVLink channel to send the message
*
* @param target_system System ID
* @param target_component Component ID
* @param frame Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down.
* @param p1x x position 1 / Latitude 1
* @param p1y y position 1 / Longitude 1
* @param p1z z position 1 / Altitude 1
* @param p2x x position 2 / Latitude 2
* @param p2y y position 2 / Longitude 2
* @param p2z z position 2 / Altitude 2
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_safety_set_allowed_area_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t frame, float p1x, float p1y, float p1z, float p2x, float p2y, float p2z)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[27];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
_mav_put_uint8_t(buf, 2, frame);
_mav_put_float(buf, 3, p1x);
_mav_put_float(buf, 7, p1y);
_mav_put_float(buf, 11, p1z);
_mav_put_float(buf, 15, p2x);
_mav_put_float(buf, 19, p2y);
_mav_put_float(buf, 23, p2z);
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA, buf, 27);
#else
mavlink_safety_set_allowed_area_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
packet.frame = frame;
packet.p1x = p1x;
packet.p1y = p1y;
packet.p1z = p1z;
packet.p2x = p2x;
packet.p2y = p2y;
packet.p2z = p2z;
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA, (const char *)&packet, 27);
#endif
}
 
#endif
 
// MESSAGE SAFETY_SET_ALLOWED_AREA UNPACKING
 
 
/**
* @brief Get field target_system from safety_set_allowed_area message
*
* @return System ID
*/
static inline uint8_t mavlink_msg_safety_set_allowed_area_get_target_system(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 0);
}
 
/**
* @brief Get field target_component from safety_set_allowed_area message
*
* @return Component ID
*/
static inline uint8_t mavlink_msg_safety_set_allowed_area_get_target_component(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 1);
}
 
/**
* @brief Get field frame from safety_set_allowed_area message
*
* @return Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down.
*/
static inline uint8_t mavlink_msg_safety_set_allowed_area_get_frame(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 2);
}
 
/**
* @brief Get field p1x from safety_set_allowed_area message
*
* @return x position 1 / Latitude 1
*/
static inline float mavlink_msg_safety_set_allowed_area_get_p1x(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 3);
}
 
/**
* @brief Get field p1y from safety_set_allowed_area message
*
* @return y position 1 / Longitude 1
*/
static inline float mavlink_msg_safety_set_allowed_area_get_p1y(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 7);
}
 
/**
* @brief Get field p1z from safety_set_allowed_area message
*
* @return z position 1 / Altitude 1
*/
static inline float mavlink_msg_safety_set_allowed_area_get_p1z(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 11);
}
 
/**
* @brief Get field p2x from safety_set_allowed_area message
*
* @return x position 2 / Latitude 2
*/
static inline float mavlink_msg_safety_set_allowed_area_get_p2x(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 15);
}
 
/**
* @brief Get field p2y from safety_set_allowed_area message
*
* @return y position 2 / Longitude 2
*/
static inline float mavlink_msg_safety_set_allowed_area_get_p2y(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 19);
}
 
/**
* @brief Get field p2z from safety_set_allowed_area message
*
* @return z position 2 / Altitude 2
*/
static inline float mavlink_msg_safety_set_allowed_area_get_p2z(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 23);
}
 
/**
* @brief Decode a safety_set_allowed_area message into a struct
*
* @param msg The message to decode
* @param safety_set_allowed_area C-struct to decode the message contents into
*/
static inline void mavlink_msg_safety_set_allowed_area_decode(const mavlink_message_t* msg, mavlink_safety_set_allowed_area_t* safety_set_allowed_area)
{
#if MAVLINK_NEED_BYTE_SWAP
safety_set_allowed_area->target_system = mavlink_msg_safety_set_allowed_area_get_target_system(msg);
safety_set_allowed_area->target_component = mavlink_msg_safety_set_allowed_area_get_target_component(msg);
safety_set_allowed_area->frame = mavlink_msg_safety_set_allowed_area_get_frame(msg);
safety_set_allowed_area->p1x = mavlink_msg_safety_set_allowed_area_get_p1x(msg);
safety_set_allowed_area->p1y = mavlink_msg_safety_set_allowed_area_get_p1y(msg);
safety_set_allowed_area->p1z = mavlink_msg_safety_set_allowed_area_get_p1z(msg);
safety_set_allowed_area->p2x = mavlink_msg_safety_set_allowed_area_get_p2x(msg);
safety_set_allowed_area->p2y = mavlink_msg_safety_set_allowed_area_get_p2y(msg);
safety_set_allowed_area->p2z = mavlink_msg_safety_set_allowed_area_get_p2z(msg);
#else
memcpy(safety_set_allowed_area, _MAV_PAYLOAD(msg), 27);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v0.9/common/mavlink_msg_scaled_imu.h
0,0 → 1,342
// MESSAGE SCALED_IMU PACKING
 
#define MAVLINK_MSG_ID_SCALED_IMU 26
 
typedef struct __mavlink_scaled_imu_t
{
uint64_t usec; ///< Timestamp (microseconds since UNIX epoch or microseconds since system boot)
int16_t xacc; ///< X acceleration (mg)
int16_t yacc; ///< Y acceleration (mg)
int16_t zacc; ///< Z acceleration (mg)
int16_t xgyro; ///< Angular speed around X axis (millirad /sec)
int16_t ygyro; ///< Angular speed around Y axis (millirad /sec)
int16_t zgyro; ///< Angular speed around Z axis (millirad /sec)
int16_t xmag; ///< X Magnetic field (milli tesla)
int16_t ymag; ///< Y Magnetic field (milli tesla)
int16_t zmag; ///< Z Magnetic field (milli tesla)
} mavlink_scaled_imu_t;
 
#define MAVLINK_MSG_ID_SCALED_IMU_LEN 26
#define MAVLINK_MSG_ID_26_LEN 26
 
 
 
#define MAVLINK_MESSAGE_INFO_SCALED_IMU { \
"SCALED_IMU", \
10, \
{ { "usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_scaled_imu_t, usec) }, \
{ "xacc", NULL, MAVLINK_TYPE_INT16_T, 0, 8, offsetof(mavlink_scaled_imu_t, xacc) }, \
{ "yacc", NULL, MAVLINK_TYPE_INT16_T, 0, 10, offsetof(mavlink_scaled_imu_t, yacc) }, \
{ "zacc", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_scaled_imu_t, zacc) }, \
{ "xgyro", NULL, MAVLINK_TYPE_INT16_T, 0, 14, offsetof(mavlink_scaled_imu_t, xgyro) }, \
{ "ygyro", NULL, MAVLINK_TYPE_INT16_T, 0, 16, offsetof(mavlink_scaled_imu_t, ygyro) }, \
{ "zgyro", NULL, MAVLINK_TYPE_INT16_T, 0, 18, offsetof(mavlink_scaled_imu_t, zgyro) }, \
{ "xmag", NULL, MAVLINK_TYPE_INT16_T, 0, 20, offsetof(mavlink_scaled_imu_t, xmag) }, \
{ "ymag", NULL, MAVLINK_TYPE_INT16_T, 0, 22, offsetof(mavlink_scaled_imu_t, ymag) }, \
{ "zmag", NULL, MAVLINK_TYPE_INT16_T, 0, 24, offsetof(mavlink_scaled_imu_t, zmag) }, \
} \
}
 
 
/**
* @brief Pack a scaled_imu message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
* @param xacc X acceleration (mg)
* @param yacc Y acceleration (mg)
* @param zacc Z acceleration (mg)
* @param xgyro Angular speed around X axis (millirad /sec)
* @param ygyro Angular speed around Y axis (millirad /sec)
* @param zgyro Angular speed around Z axis (millirad /sec)
* @param xmag X Magnetic field (milli tesla)
* @param ymag Y Magnetic field (milli tesla)
* @param zmag Z Magnetic field (milli tesla)
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_scaled_imu_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint64_t usec, int16_t xacc, int16_t yacc, int16_t zacc, int16_t xgyro, int16_t ygyro, int16_t zgyro, int16_t xmag, int16_t ymag, int16_t zmag)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[26];
_mav_put_uint64_t(buf, 0, usec);
_mav_put_int16_t(buf, 8, xacc);
_mav_put_int16_t(buf, 10, yacc);
_mav_put_int16_t(buf, 12, zacc);
_mav_put_int16_t(buf, 14, xgyro);
_mav_put_int16_t(buf, 16, ygyro);
_mav_put_int16_t(buf, 18, zgyro);
_mav_put_int16_t(buf, 20, xmag);
_mav_put_int16_t(buf, 22, ymag);
_mav_put_int16_t(buf, 24, zmag);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 26);
#else
mavlink_scaled_imu_t packet;
packet.usec = usec;
packet.xacc = xacc;
packet.yacc = yacc;
packet.zacc = zacc;
packet.xgyro = xgyro;
packet.ygyro = ygyro;
packet.zgyro = zgyro;
packet.xmag = xmag;
packet.ymag = ymag;
packet.zmag = zmag;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 26);
#endif
 
msg->msgid = MAVLINK_MSG_ID_SCALED_IMU;
return mavlink_finalize_message(msg, system_id, component_id, 26);
}
 
/**
* @brief Pack a scaled_imu message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
* @param xacc X acceleration (mg)
* @param yacc Y acceleration (mg)
* @param zacc Z acceleration (mg)
* @param xgyro Angular speed around X axis (millirad /sec)
* @param ygyro Angular speed around Y axis (millirad /sec)
* @param zgyro Angular speed around Z axis (millirad /sec)
* @param xmag X Magnetic field (milli tesla)
* @param ymag Y Magnetic field (milli tesla)
* @param zmag Z Magnetic field (milli tesla)
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_scaled_imu_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint64_t usec,int16_t xacc,int16_t yacc,int16_t zacc,int16_t xgyro,int16_t ygyro,int16_t zgyro,int16_t xmag,int16_t ymag,int16_t zmag)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[26];
_mav_put_uint64_t(buf, 0, usec);
_mav_put_int16_t(buf, 8, xacc);
_mav_put_int16_t(buf, 10, yacc);
_mav_put_int16_t(buf, 12, zacc);
_mav_put_int16_t(buf, 14, xgyro);
_mav_put_int16_t(buf, 16, ygyro);
_mav_put_int16_t(buf, 18, zgyro);
_mav_put_int16_t(buf, 20, xmag);
_mav_put_int16_t(buf, 22, ymag);
_mav_put_int16_t(buf, 24, zmag);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 26);
#else
mavlink_scaled_imu_t packet;
packet.usec = usec;
packet.xacc = xacc;
packet.yacc = yacc;
packet.zacc = zacc;
packet.xgyro = xgyro;
packet.ygyro = ygyro;
packet.zgyro = zgyro;
packet.xmag = xmag;
packet.ymag = ymag;
packet.zmag = zmag;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 26);
#endif
 
msg->msgid = MAVLINK_MSG_ID_SCALED_IMU;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 26);
}
 
/**
* @brief Encode a scaled_imu struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param scaled_imu C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_scaled_imu_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_scaled_imu_t* scaled_imu)
{
return mavlink_msg_scaled_imu_pack(system_id, component_id, msg, scaled_imu->usec, scaled_imu->xacc, scaled_imu->yacc, scaled_imu->zacc, scaled_imu->xgyro, scaled_imu->ygyro, scaled_imu->zgyro, scaled_imu->xmag, scaled_imu->ymag, scaled_imu->zmag);
}
 
/**
* @brief Send a scaled_imu message
* @param chan MAVLink channel to send the message
*
* @param usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
* @param xacc X acceleration (mg)
* @param yacc Y acceleration (mg)
* @param zacc Z acceleration (mg)
* @param xgyro Angular speed around X axis (millirad /sec)
* @param ygyro Angular speed around Y axis (millirad /sec)
* @param zgyro Angular speed around Z axis (millirad /sec)
* @param xmag X Magnetic field (milli tesla)
* @param ymag Y Magnetic field (milli tesla)
* @param zmag Z Magnetic field (milli tesla)
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_scaled_imu_send(mavlink_channel_t chan, uint64_t usec, int16_t xacc, int16_t yacc, int16_t zacc, int16_t xgyro, int16_t ygyro, int16_t zgyro, int16_t xmag, int16_t ymag, int16_t zmag)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[26];
_mav_put_uint64_t(buf, 0, usec);
_mav_put_int16_t(buf, 8, xacc);
_mav_put_int16_t(buf, 10, yacc);
_mav_put_int16_t(buf, 12, zacc);
_mav_put_int16_t(buf, 14, xgyro);
_mav_put_int16_t(buf, 16, ygyro);
_mav_put_int16_t(buf, 18, zgyro);
_mav_put_int16_t(buf, 20, xmag);
_mav_put_int16_t(buf, 22, ymag);
_mav_put_int16_t(buf, 24, zmag);
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU, buf, 26);
#else
mavlink_scaled_imu_t packet;
packet.usec = usec;
packet.xacc = xacc;
packet.yacc = yacc;
packet.zacc = zacc;
packet.xgyro = xgyro;
packet.ygyro = ygyro;
packet.zgyro = zgyro;
packet.xmag = xmag;
packet.ymag = ymag;
packet.zmag = zmag;
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU, (const char *)&packet, 26);
#endif
}
 
#endif
 
// MESSAGE SCALED_IMU UNPACKING
 
 
/**
* @brief Get field usec from scaled_imu message
*
* @return Timestamp (microseconds since UNIX epoch or microseconds since system boot)
*/
static inline uint64_t mavlink_msg_scaled_imu_get_usec(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint64_t(msg, 0);
}
 
/**
* @brief Get field xacc from scaled_imu message
*
* @return X acceleration (mg)
*/
static inline int16_t mavlink_msg_scaled_imu_get_xacc(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 8);
}
 
/**
* @brief Get field yacc from scaled_imu message
*
* @return Y acceleration (mg)
*/
static inline int16_t mavlink_msg_scaled_imu_get_yacc(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 10);
}
 
/**
* @brief Get field zacc from scaled_imu message
*
* @return Z acceleration (mg)
*/
static inline int16_t mavlink_msg_scaled_imu_get_zacc(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 12);
}
 
/**
* @brief Get field xgyro from scaled_imu message
*
* @return Angular speed around X axis (millirad /sec)
*/
static inline int16_t mavlink_msg_scaled_imu_get_xgyro(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 14);
}
 
/**
* @brief Get field ygyro from scaled_imu message
*
* @return Angular speed around Y axis (millirad /sec)
*/
static inline int16_t mavlink_msg_scaled_imu_get_ygyro(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 16);
}
 
/**
* @brief Get field zgyro from scaled_imu message
*
* @return Angular speed around Z axis (millirad /sec)
*/
static inline int16_t mavlink_msg_scaled_imu_get_zgyro(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 18);
}
 
/**
* @brief Get field xmag from scaled_imu message
*
* @return X Magnetic field (milli tesla)
*/
static inline int16_t mavlink_msg_scaled_imu_get_xmag(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 20);
}
 
/**
* @brief Get field ymag from scaled_imu message
*
* @return Y Magnetic field (milli tesla)
*/
static inline int16_t mavlink_msg_scaled_imu_get_ymag(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 22);
}
 
/**
* @brief Get field zmag from scaled_imu message
*
* @return Z Magnetic field (milli tesla)
*/
static inline int16_t mavlink_msg_scaled_imu_get_zmag(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 24);
}
 
/**
* @brief Decode a scaled_imu message into a struct
*
* @param msg The message to decode
* @param scaled_imu C-struct to decode the message contents into
*/
static inline void mavlink_msg_scaled_imu_decode(const mavlink_message_t* msg, mavlink_scaled_imu_t* scaled_imu)
{
#if MAVLINK_NEED_BYTE_SWAP
scaled_imu->usec = mavlink_msg_scaled_imu_get_usec(msg);
scaled_imu->xacc = mavlink_msg_scaled_imu_get_xacc(msg);
scaled_imu->yacc = mavlink_msg_scaled_imu_get_yacc(msg);
scaled_imu->zacc = mavlink_msg_scaled_imu_get_zacc(msg);
scaled_imu->xgyro = mavlink_msg_scaled_imu_get_xgyro(msg);
scaled_imu->ygyro = mavlink_msg_scaled_imu_get_ygyro(msg);
scaled_imu->zgyro = mavlink_msg_scaled_imu_get_zgyro(msg);
scaled_imu->xmag = mavlink_msg_scaled_imu_get_xmag(msg);
scaled_imu->ymag = mavlink_msg_scaled_imu_get_ymag(msg);
scaled_imu->zmag = mavlink_msg_scaled_imu_get_zmag(msg);
#else
memcpy(scaled_imu, _MAV_PAYLOAD(msg), 26);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v0.9/common/mavlink_msg_scaled_pressure.h
0,0 → 1,210
// MESSAGE SCALED_PRESSURE PACKING
 
#define MAVLINK_MSG_ID_SCALED_PRESSURE 38
 
typedef struct __mavlink_scaled_pressure_t
{
uint64_t usec; ///< Timestamp (microseconds since UNIX epoch or microseconds since system boot)
float press_abs; ///< Absolute pressure (hectopascal)
float press_diff; ///< Differential pressure 1 (hectopascal)
int16_t temperature; ///< Temperature measurement (0.01 degrees celsius)
} mavlink_scaled_pressure_t;
 
#define MAVLINK_MSG_ID_SCALED_PRESSURE_LEN 18
#define MAVLINK_MSG_ID_38_LEN 18
 
 
 
#define MAVLINK_MESSAGE_INFO_SCALED_PRESSURE { \
"SCALED_PRESSURE", \
4, \
{ { "usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_scaled_pressure_t, usec) }, \
{ "press_abs", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_scaled_pressure_t, press_abs) }, \
{ "press_diff", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_scaled_pressure_t, press_diff) }, \
{ "temperature", NULL, MAVLINK_TYPE_INT16_T, 0, 16, offsetof(mavlink_scaled_pressure_t, temperature) }, \
} \
}
 
 
/**
* @brief Pack a scaled_pressure message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
* @param press_abs Absolute pressure (hectopascal)
* @param press_diff Differential pressure 1 (hectopascal)
* @param temperature Temperature measurement (0.01 degrees celsius)
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_scaled_pressure_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint64_t usec, float press_abs, float press_diff, int16_t temperature)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[18];
_mav_put_uint64_t(buf, 0, usec);
_mav_put_float(buf, 8, press_abs);
_mav_put_float(buf, 12, press_diff);
_mav_put_int16_t(buf, 16, temperature);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 18);
#else
mavlink_scaled_pressure_t packet;
packet.usec = usec;
packet.press_abs = press_abs;
packet.press_diff = press_diff;
packet.temperature = temperature;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 18);
#endif
 
msg->msgid = MAVLINK_MSG_ID_SCALED_PRESSURE;
return mavlink_finalize_message(msg, system_id, component_id, 18);
}
 
/**
* @brief Pack a scaled_pressure message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
* @param press_abs Absolute pressure (hectopascal)
* @param press_diff Differential pressure 1 (hectopascal)
* @param temperature Temperature measurement (0.01 degrees celsius)
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_scaled_pressure_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint64_t usec,float press_abs,float press_diff,int16_t temperature)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[18];
_mav_put_uint64_t(buf, 0, usec);
_mav_put_float(buf, 8, press_abs);
_mav_put_float(buf, 12, press_diff);
_mav_put_int16_t(buf, 16, temperature);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 18);
#else
mavlink_scaled_pressure_t packet;
packet.usec = usec;
packet.press_abs = press_abs;
packet.press_diff = press_diff;
packet.temperature = temperature;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 18);
#endif
 
msg->msgid = MAVLINK_MSG_ID_SCALED_PRESSURE;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 18);
}
 
/**
* @brief Encode a scaled_pressure struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param scaled_pressure C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_scaled_pressure_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_scaled_pressure_t* scaled_pressure)
{
return mavlink_msg_scaled_pressure_pack(system_id, component_id, msg, scaled_pressure->usec, scaled_pressure->press_abs, scaled_pressure->press_diff, scaled_pressure->temperature);
}
 
/**
* @brief Send a scaled_pressure message
* @param chan MAVLink channel to send the message
*
* @param usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
* @param press_abs Absolute pressure (hectopascal)
* @param press_diff Differential pressure 1 (hectopascal)
* @param temperature Temperature measurement (0.01 degrees celsius)
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_scaled_pressure_send(mavlink_channel_t chan, uint64_t usec, float press_abs, float press_diff, int16_t temperature)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[18];
_mav_put_uint64_t(buf, 0, usec);
_mav_put_float(buf, 8, press_abs);
_mav_put_float(buf, 12, press_diff);
_mav_put_int16_t(buf, 16, temperature);
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_PRESSURE, buf, 18);
#else
mavlink_scaled_pressure_t packet;
packet.usec = usec;
packet.press_abs = press_abs;
packet.press_diff = press_diff;
packet.temperature = temperature;
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_PRESSURE, (const char *)&packet, 18);
#endif
}
 
#endif
 
// MESSAGE SCALED_PRESSURE UNPACKING
 
 
/**
* @brief Get field usec from scaled_pressure message
*
* @return Timestamp (microseconds since UNIX epoch or microseconds since system boot)
*/
static inline uint64_t mavlink_msg_scaled_pressure_get_usec(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint64_t(msg, 0);
}
 
/**
* @brief Get field press_abs from scaled_pressure message
*
* @return Absolute pressure (hectopascal)
*/
static inline float mavlink_msg_scaled_pressure_get_press_abs(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 8);
}
 
/**
* @brief Get field press_diff from scaled_pressure message
*
* @return Differential pressure 1 (hectopascal)
*/
static inline float mavlink_msg_scaled_pressure_get_press_diff(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 12);
}
 
/**
* @brief Get field temperature from scaled_pressure message
*
* @return Temperature measurement (0.01 degrees celsius)
*/
static inline int16_t mavlink_msg_scaled_pressure_get_temperature(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 16);
}
 
/**
* @brief Decode a scaled_pressure message into a struct
*
* @param msg The message to decode
* @param scaled_pressure C-struct to decode the message contents into
*/
static inline void mavlink_msg_scaled_pressure_decode(const mavlink_message_t* msg, mavlink_scaled_pressure_t* scaled_pressure)
{
#if MAVLINK_NEED_BYTE_SWAP
scaled_pressure->usec = mavlink_msg_scaled_pressure_get_usec(msg);
scaled_pressure->press_abs = mavlink_msg_scaled_pressure_get_press_abs(msg);
scaled_pressure->press_diff = mavlink_msg_scaled_pressure_get_press_diff(msg);
scaled_pressure->temperature = mavlink_msg_scaled_pressure_get_temperature(msg);
#else
memcpy(scaled_pressure, _MAV_PAYLOAD(msg), 18);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v0.9/common/mavlink_msg_servo_output_raw.h
0,0 → 1,298
// MESSAGE SERVO_OUTPUT_RAW PACKING
 
#define MAVLINK_MSG_ID_SERVO_OUTPUT_RAW 37
 
typedef struct __mavlink_servo_output_raw_t
{
uint16_t servo1_raw; ///< Servo output 1 value, in microseconds
uint16_t servo2_raw; ///< Servo output 2 value, in microseconds
uint16_t servo3_raw; ///< Servo output 3 value, in microseconds
uint16_t servo4_raw; ///< Servo output 4 value, in microseconds
uint16_t servo5_raw; ///< Servo output 5 value, in microseconds
uint16_t servo6_raw; ///< Servo output 6 value, in microseconds
uint16_t servo7_raw; ///< Servo output 7 value, in microseconds
uint16_t servo8_raw; ///< Servo output 8 value, in microseconds
} mavlink_servo_output_raw_t;
 
#define MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN 16
#define MAVLINK_MSG_ID_37_LEN 16
 
 
 
#define MAVLINK_MESSAGE_INFO_SERVO_OUTPUT_RAW { \
"SERVO_OUTPUT_RAW", \
8, \
{ { "servo1_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_servo_output_raw_t, servo1_raw) }, \
{ "servo2_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_servo_output_raw_t, servo2_raw) }, \
{ "servo3_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_servo_output_raw_t, servo3_raw) }, \
{ "servo4_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_servo_output_raw_t, servo4_raw) }, \
{ "servo5_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_servo_output_raw_t, servo5_raw) }, \
{ "servo6_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 10, offsetof(mavlink_servo_output_raw_t, servo6_raw) }, \
{ "servo7_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_servo_output_raw_t, servo7_raw) }, \
{ "servo8_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 14, offsetof(mavlink_servo_output_raw_t, servo8_raw) }, \
} \
}
 
 
/**
* @brief Pack a servo_output_raw message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param servo1_raw Servo output 1 value, in microseconds
* @param servo2_raw Servo output 2 value, in microseconds
* @param servo3_raw Servo output 3 value, in microseconds
* @param servo4_raw Servo output 4 value, in microseconds
* @param servo5_raw Servo output 5 value, in microseconds
* @param servo6_raw Servo output 6 value, in microseconds
* @param servo7_raw Servo output 7 value, in microseconds
* @param servo8_raw Servo output 8 value, in microseconds
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_servo_output_raw_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint16_t servo1_raw, uint16_t servo2_raw, uint16_t servo3_raw, uint16_t servo4_raw, uint16_t servo5_raw, uint16_t servo6_raw, uint16_t servo7_raw, uint16_t servo8_raw)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[16];
_mav_put_uint16_t(buf, 0, servo1_raw);
_mav_put_uint16_t(buf, 2, servo2_raw);
_mav_put_uint16_t(buf, 4, servo3_raw);
_mav_put_uint16_t(buf, 6, servo4_raw);
_mav_put_uint16_t(buf, 8, servo5_raw);
_mav_put_uint16_t(buf, 10, servo6_raw);
_mav_put_uint16_t(buf, 12, servo7_raw);
_mav_put_uint16_t(buf, 14, servo8_raw);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 16);
#else
mavlink_servo_output_raw_t packet;
packet.servo1_raw = servo1_raw;
packet.servo2_raw = servo2_raw;
packet.servo3_raw = servo3_raw;
packet.servo4_raw = servo4_raw;
packet.servo5_raw = servo5_raw;
packet.servo6_raw = servo6_raw;
packet.servo7_raw = servo7_raw;
packet.servo8_raw = servo8_raw;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 16);
#endif
 
msg->msgid = MAVLINK_MSG_ID_SERVO_OUTPUT_RAW;
return mavlink_finalize_message(msg, system_id, component_id, 16);
}
 
/**
* @brief Pack a servo_output_raw message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param servo1_raw Servo output 1 value, in microseconds
* @param servo2_raw Servo output 2 value, in microseconds
* @param servo3_raw Servo output 3 value, in microseconds
* @param servo4_raw Servo output 4 value, in microseconds
* @param servo5_raw Servo output 5 value, in microseconds
* @param servo6_raw Servo output 6 value, in microseconds
* @param servo7_raw Servo output 7 value, in microseconds
* @param servo8_raw Servo output 8 value, in microseconds
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_servo_output_raw_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint16_t servo1_raw,uint16_t servo2_raw,uint16_t servo3_raw,uint16_t servo4_raw,uint16_t servo5_raw,uint16_t servo6_raw,uint16_t servo7_raw,uint16_t servo8_raw)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[16];
_mav_put_uint16_t(buf, 0, servo1_raw);
_mav_put_uint16_t(buf, 2, servo2_raw);
_mav_put_uint16_t(buf, 4, servo3_raw);
_mav_put_uint16_t(buf, 6, servo4_raw);
_mav_put_uint16_t(buf, 8, servo5_raw);
_mav_put_uint16_t(buf, 10, servo6_raw);
_mav_put_uint16_t(buf, 12, servo7_raw);
_mav_put_uint16_t(buf, 14, servo8_raw);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 16);
#else
mavlink_servo_output_raw_t packet;
packet.servo1_raw = servo1_raw;
packet.servo2_raw = servo2_raw;
packet.servo3_raw = servo3_raw;
packet.servo4_raw = servo4_raw;
packet.servo5_raw = servo5_raw;
packet.servo6_raw = servo6_raw;
packet.servo7_raw = servo7_raw;
packet.servo8_raw = servo8_raw;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 16);
#endif
 
msg->msgid = MAVLINK_MSG_ID_SERVO_OUTPUT_RAW;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 16);
}
 
/**
* @brief Encode a servo_output_raw struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param servo_output_raw C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_servo_output_raw_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_servo_output_raw_t* servo_output_raw)
{
return mavlink_msg_servo_output_raw_pack(system_id, component_id, msg, servo_output_raw->servo1_raw, servo_output_raw->servo2_raw, servo_output_raw->servo3_raw, servo_output_raw->servo4_raw, servo_output_raw->servo5_raw, servo_output_raw->servo6_raw, servo_output_raw->servo7_raw, servo_output_raw->servo8_raw);
}
 
/**
* @brief Send a servo_output_raw message
* @param chan MAVLink channel to send the message
*
* @param servo1_raw Servo output 1 value, in microseconds
* @param servo2_raw Servo output 2 value, in microseconds
* @param servo3_raw Servo output 3 value, in microseconds
* @param servo4_raw Servo output 4 value, in microseconds
* @param servo5_raw Servo output 5 value, in microseconds
* @param servo6_raw Servo output 6 value, in microseconds
* @param servo7_raw Servo output 7 value, in microseconds
* @param servo8_raw Servo output 8 value, in microseconds
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_servo_output_raw_send(mavlink_channel_t chan, uint16_t servo1_raw, uint16_t servo2_raw, uint16_t servo3_raw, uint16_t servo4_raw, uint16_t servo5_raw, uint16_t servo6_raw, uint16_t servo7_raw, uint16_t servo8_raw)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[16];
_mav_put_uint16_t(buf, 0, servo1_raw);
_mav_put_uint16_t(buf, 2, servo2_raw);
_mav_put_uint16_t(buf, 4, servo3_raw);
_mav_put_uint16_t(buf, 6, servo4_raw);
_mav_put_uint16_t(buf, 8, servo5_raw);
_mav_put_uint16_t(buf, 10, servo6_raw);
_mav_put_uint16_t(buf, 12, servo7_raw);
_mav_put_uint16_t(buf, 14, servo8_raw);
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW, buf, 16);
#else
mavlink_servo_output_raw_t packet;
packet.servo1_raw = servo1_raw;
packet.servo2_raw = servo2_raw;
packet.servo3_raw = servo3_raw;
packet.servo4_raw = servo4_raw;
packet.servo5_raw = servo5_raw;
packet.servo6_raw = servo6_raw;
packet.servo7_raw = servo7_raw;
packet.servo8_raw = servo8_raw;
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW, (const char *)&packet, 16);
#endif
}
 
#endif
 
// MESSAGE SERVO_OUTPUT_RAW UNPACKING
 
 
/**
* @brief Get field servo1_raw from servo_output_raw message
*
* @return Servo output 1 value, in microseconds
*/
static inline uint16_t mavlink_msg_servo_output_raw_get_servo1_raw(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 0);
}
 
/**
* @brief Get field servo2_raw from servo_output_raw message
*
* @return Servo output 2 value, in microseconds
*/
static inline uint16_t mavlink_msg_servo_output_raw_get_servo2_raw(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 2);
}
 
/**
* @brief Get field servo3_raw from servo_output_raw message
*
* @return Servo output 3 value, in microseconds
*/
static inline uint16_t mavlink_msg_servo_output_raw_get_servo3_raw(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 4);
}
 
/**
* @brief Get field servo4_raw from servo_output_raw message
*
* @return Servo output 4 value, in microseconds
*/
static inline uint16_t mavlink_msg_servo_output_raw_get_servo4_raw(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 6);
}
 
/**
* @brief Get field servo5_raw from servo_output_raw message
*
* @return Servo output 5 value, in microseconds
*/
static inline uint16_t mavlink_msg_servo_output_raw_get_servo5_raw(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 8);
}
 
/**
* @brief Get field servo6_raw from servo_output_raw message
*
* @return Servo output 6 value, in microseconds
*/
static inline uint16_t mavlink_msg_servo_output_raw_get_servo6_raw(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 10);
}
 
/**
* @brief Get field servo7_raw from servo_output_raw message
*
* @return Servo output 7 value, in microseconds
*/
static inline uint16_t mavlink_msg_servo_output_raw_get_servo7_raw(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 12);
}
 
/**
* @brief Get field servo8_raw from servo_output_raw message
*
* @return Servo output 8 value, in microseconds
*/
static inline uint16_t mavlink_msg_servo_output_raw_get_servo8_raw(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 14);
}
 
/**
* @brief Decode a servo_output_raw message into a struct
*
* @param msg The message to decode
* @param servo_output_raw C-struct to decode the message contents into
*/
static inline void mavlink_msg_servo_output_raw_decode(const mavlink_message_t* msg, mavlink_servo_output_raw_t* servo_output_raw)
{
#if MAVLINK_NEED_BYTE_SWAP
servo_output_raw->servo1_raw = mavlink_msg_servo_output_raw_get_servo1_raw(msg);
servo_output_raw->servo2_raw = mavlink_msg_servo_output_raw_get_servo2_raw(msg);
servo_output_raw->servo3_raw = mavlink_msg_servo_output_raw_get_servo3_raw(msg);
servo_output_raw->servo4_raw = mavlink_msg_servo_output_raw_get_servo4_raw(msg);
servo_output_raw->servo5_raw = mavlink_msg_servo_output_raw_get_servo5_raw(msg);
servo_output_raw->servo6_raw = mavlink_msg_servo_output_raw_get_servo6_raw(msg);
servo_output_raw->servo7_raw = mavlink_msg_servo_output_raw_get_servo7_raw(msg);
servo_output_raw->servo8_raw = mavlink_msg_servo_output_raw_get_servo8_raw(msg);
#else
memcpy(servo_output_raw, _MAV_PAYLOAD(msg), 16);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v0.9/common/mavlink_msg_set_altitude.h
0,0 → 1,166
// MESSAGE SET_ALTITUDE PACKING
 
#define MAVLINK_MSG_ID_SET_ALTITUDE 65
 
typedef struct __mavlink_set_altitude_t
{
uint8_t target; ///< The system setting the altitude
uint32_t mode; ///< The new altitude in meters
} mavlink_set_altitude_t;
 
#define MAVLINK_MSG_ID_SET_ALTITUDE_LEN 5
#define MAVLINK_MSG_ID_65_LEN 5
 
 
 
#define MAVLINK_MESSAGE_INFO_SET_ALTITUDE { \
"SET_ALTITUDE", \
2, \
{ { "target", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_set_altitude_t, target) }, \
{ "mode", NULL, MAVLINK_TYPE_UINT32_T, 0, 1, offsetof(mavlink_set_altitude_t, mode) }, \
} \
}
 
 
/**
* @brief Pack a set_altitude message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param target The system setting the altitude
* @param mode The new altitude in meters
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_set_altitude_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t target, uint32_t mode)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[5];
_mav_put_uint8_t(buf, 0, target);
_mav_put_uint32_t(buf, 1, mode);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 5);
#else
mavlink_set_altitude_t packet;
packet.target = target;
packet.mode = mode;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 5);
#endif
 
msg->msgid = MAVLINK_MSG_ID_SET_ALTITUDE;
return mavlink_finalize_message(msg, system_id, component_id, 5);
}
 
/**
* @brief Pack a set_altitude message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param target The system setting the altitude
* @param mode The new altitude in meters
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_set_altitude_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint8_t target,uint32_t mode)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[5];
_mav_put_uint8_t(buf, 0, target);
_mav_put_uint32_t(buf, 1, mode);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 5);
#else
mavlink_set_altitude_t packet;
packet.target = target;
packet.mode = mode;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 5);
#endif
 
msg->msgid = MAVLINK_MSG_ID_SET_ALTITUDE;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 5);
}
 
/**
* @brief Encode a set_altitude struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param set_altitude C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_set_altitude_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_altitude_t* set_altitude)
{
return mavlink_msg_set_altitude_pack(system_id, component_id, msg, set_altitude->target, set_altitude->mode);
}
 
/**
* @brief Send a set_altitude message
* @param chan MAVLink channel to send the message
*
* @param target The system setting the altitude
* @param mode The new altitude in meters
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_set_altitude_send(mavlink_channel_t chan, uint8_t target, uint32_t mode)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[5];
_mav_put_uint8_t(buf, 0, target);
_mav_put_uint32_t(buf, 1, mode);
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ALTITUDE, buf, 5);
#else
mavlink_set_altitude_t packet;
packet.target = target;
packet.mode = mode;
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ALTITUDE, (const char *)&packet, 5);
#endif
}
 
#endif
 
// MESSAGE SET_ALTITUDE UNPACKING
 
 
/**
* @brief Get field target from set_altitude message
*
* @return The system setting the altitude
*/
static inline uint8_t mavlink_msg_set_altitude_get_target(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 0);
}
 
/**
* @brief Get field mode from set_altitude message
*
* @return The new altitude in meters
*/
static inline uint32_t mavlink_msg_set_altitude_get_mode(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint32_t(msg, 1);
}
 
/**
* @brief Decode a set_altitude message into a struct
*
* @param msg The message to decode
* @param set_altitude C-struct to decode the message contents into
*/
static inline void mavlink_msg_set_altitude_decode(const mavlink_message_t* msg, mavlink_set_altitude_t* set_altitude)
{
#if MAVLINK_NEED_BYTE_SWAP
set_altitude->target = mavlink_msg_set_altitude_get_target(msg);
set_altitude->mode = mavlink_msg_set_altitude_get_mode(msg);
#else
memcpy(set_altitude, _MAV_PAYLOAD(msg), 5);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v0.9/common/mavlink_msg_set_mode.h
0,0 → 1,166
// MESSAGE SET_MODE PACKING
 
#define MAVLINK_MSG_ID_SET_MODE 11
 
typedef struct __mavlink_set_mode_t
{
uint8_t target; ///< The system setting the mode
uint8_t mode; ///< The new mode
} mavlink_set_mode_t;
 
#define MAVLINK_MSG_ID_SET_MODE_LEN 2
#define MAVLINK_MSG_ID_11_LEN 2
 
 
 
#define MAVLINK_MESSAGE_INFO_SET_MODE { \
"SET_MODE", \
2, \
{ { "target", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_set_mode_t, target) }, \
{ "mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_set_mode_t, mode) }, \
} \
}
 
 
/**
* @brief Pack a set_mode message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param target The system setting the mode
* @param mode The new mode
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_set_mode_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t target, uint8_t mode)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[2];
_mav_put_uint8_t(buf, 0, target);
_mav_put_uint8_t(buf, 1, mode);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 2);
#else
mavlink_set_mode_t packet;
packet.target = target;
packet.mode = mode;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 2);
#endif
 
msg->msgid = MAVLINK_MSG_ID_SET_MODE;
return mavlink_finalize_message(msg, system_id, component_id, 2);
}
 
/**
* @brief Pack a set_mode message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param target The system setting the mode
* @param mode The new mode
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_set_mode_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint8_t target,uint8_t mode)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[2];
_mav_put_uint8_t(buf, 0, target);
_mav_put_uint8_t(buf, 1, mode);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 2);
#else
mavlink_set_mode_t packet;
packet.target = target;
packet.mode = mode;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 2);
#endif
 
msg->msgid = MAVLINK_MSG_ID_SET_MODE;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 2);
}
 
/**
* @brief Encode a set_mode struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param set_mode C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_set_mode_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_mode_t* set_mode)
{
return mavlink_msg_set_mode_pack(system_id, component_id, msg, set_mode->target, set_mode->mode);
}
 
/**
* @brief Send a set_mode message
* @param chan MAVLink channel to send the message
*
* @param target The system setting the mode
* @param mode The new mode
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_set_mode_send(mavlink_channel_t chan, uint8_t target, uint8_t mode)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[2];
_mav_put_uint8_t(buf, 0, target);
_mav_put_uint8_t(buf, 1, mode);
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_MODE, buf, 2);
#else
mavlink_set_mode_t packet;
packet.target = target;
packet.mode = mode;
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_MODE, (const char *)&packet, 2);
#endif
}
 
#endif
 
// MESSAGE SET_MODE UNPACKING
 
 
/**
* @brief Get field target from set_mode message
*
* @return The system setting the mode
*/
static inline uint8_t mavlink_msg_set_mode_get_target(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 0);
}
 
/**
* @brief Get field mode from set_mode message
*
* @return The new mode
*/
static inline uint8_t mavlink_msg_set_mode_get_mode(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 1);
}
 
/**
* @brief Decode a set_mode message into a struct
*
* @param msg The message to decode
* @param set_mode C-struct to decode the message contents into
*/
static inline void mavlink_msg_set_mode_decode(const mavlink_message_t* msg, mavlink_set_mode_t* set_mode)
{
#if MAVLINK_NEED_BYTE_SWAP
set_mode->target = mavlink_msg_set_mode_get_target(msg);
set_mode->mode = mavlink_msg_set_mode_get_mode(msg);
#else
memcpy(set_mode, _MAV_PAYLOAD(msg), 2);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v0.9/common/mavlink_msg_set_nav_mode.h
0,0 → 1,166
// MESSAGE SET_NAV_MODE PACKING
 
#define MAVLINK_MSG_ID_SET_NAV_MODE 12
 
typedef struct __mavlink_set_nav_mode_t
{
uint8_t target; ///< The system setting the mode
uint8_t nav_mode; ///< The new navigation mode
} mavlink_set_nav_mode_t;
 
#define MAVLINK_MSG_ID_SET_NAV_MODE_LEN 2
#define MAVLINK_MSG_ID_12_LEN 2
 
 
 
#define MAVLINK_MESSAGE_INFO_SET_NAV_MODE { \
"SET_NAV_MODE", \
2, \
{ { "target", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_set_nav_mode_t, target) }, \
{ "nav_mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_set_nav_mode_t, nav_mode) }, \
} \
}
 
 
/**
* @brief Pack a set_nav_mode message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param target The system setting the mode
* @param nav_mode The new navigation mode
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_set_nav_mode_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t target, uint8_t nav_mode)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[2];
_mav_put_uint8_t(buf, 0, target);
_mav_put_uint8_t(buf, 1, nav_mode);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 2);
#else
mavlink_set_nav_mode_t packet;
packet.target = target;
packet.nav_mode = nav_mode;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 2);
#endif
 
msg->msgid = MAVLINK_MSG_ID_SET_NAV_MODE;
return mavlink_finalize_message(msg, system_id, component_id, 2);
}
 
/**
* @brief Pack a set_nav_mode message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param target The system setting the mode
* @param nav_mode The new navigation mode
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_set_nav_mode_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint8_t target,uint8_t nav_mode)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[2];
_mav_put_uint8_t(buf, 0, target);
_mav_put_uint8_t(buf, 1, nav_mode);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 2);
#else
mavlink_set_nav_mode_t packet;
packet.target = target;
packet.nav_mode = nav_mode;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 2);
#endif
 
msg->msgid = MAVLINK_MSG_ID_SET_NAV_MODE;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 2);
}
 
/**
* @brief Encode a set_nav_mode struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param set_nav_mode C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_set_nav_mode_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_nav_mode_t* set_nav_mode)
{
return mavlink_msg_set_nav_mode_pack(system_id, component_id, msg, set_nav_mode->target, set_nav_mode->nav_mode);
}
 
/**
* @brief Send a set_nav_mode message
* @param chan MAVLink channel to send the message
*
* @param target The system setting the mode
* @param nav_mode The new navigation mode
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_set_nav_mode_send(mavlink_channel_t chan, uint8_t target, uint8_t nav_mode)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[2];
_mav_put_uint8_t(buf, 0, target);
_mav_put_uint8_t(buf, 1, nav_mode);
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_NAV_MODE, buf, 2);
#else
mavlink_set_nav_mode_t packet;
packet.target = target;
packet.nav_mode = nav_mode;
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_NAV_MODE, (const char *)&packet, 2);
#endif
}
 
#endif
 
// MESSAGE SET_NAV_MODE UNPACKING
 
 
/**
* @brief Get field target from set_nav_mode message
*
* @return The system setting the mode
*/
static inline uint8_t mavlink_msg_set_nav_mode_get_target(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 0);
}
 
/**
* @brief Get field nav_mode from set_nav_mode message
*
* @return The new navigation mode
*/
static inline uint8_t mavlink_msg_set_nav_mode_get_nav_mode(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 1);
}
 
/**
* @brief Decode a set_nav_mode message into a struct
*
* @param msg The message to decode
* @param set_nav_mode C-struct to decode the message contents into
*/
static inline void mavlink_msg_set_nav_mode_decode(const mavlink_message_t* msg, mavlink_set_nav_mode_t* set_nav_mode)
{
#if MAVLINK_NEED_BYTE_SWAP
set_nav_mode->target = mavlink_msg_set_nav_mode_get_target(msg);
set_nav_mode->nav_mode = mavlink_msg_set_nav_mode_get_nav_mode(msg);
#else
memcpy(set_nav_mode, _MAV_PAYLOAD(msg), 2);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v0.9/common/mavlink_msg_set_roll_pitch_yaw_speed_thrust.h
0,0 → 1,254
// MESSAGE SET_ROLL_PITCH_YAW_SPEED_THRUST PACKING
 
#define MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED_THRUST 56
 
typedef struct __mavlink_set_roll_pitch_yaw_speed_thrust_t
{
uint8_t target_system; ///< System ID
uint8_t target_component; ///< Component ID
float roll_speed; ///< Desired roll angular speed in rad/s
float pitch_speed; ///< Desired pitch angular speed in rad/s
float yaw_speed; ///< Desired yaw angular speed in rad/s
float thrust; ///< Collective thrust, normalized to 0 .. 1
} mavlink_set_roll_pitch_yaw_speed_thrust_t;
 
#define MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED_THRUST_LEN 18
#define MAVLINK_MSG_ID_56_LEN 18
 
 
 
#define MAVLINK_MESSAGE_INFO_SET_ROLL_PITCH_YAW_SPEED_THRUST { \
"SET_ROLL_PITCH_YAW_SPEED_THRUST", \
6, \
{ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_set_roll_pitch_yaw_speed_thrust_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_set_roll_pitch_yaw_speed_thrust_t, target_component) }, \
{ "roll_speed", NULL, MAVLINK_TYPE_FLOAT, 0, 2, offsetof(mavlink_set_roll_pitch_yaw_speed_thrust_t, roll_speed) }, \
{ "pitch_speed", NULL, MAVLINK_TYPE_FLOAT, 0, 6, offsetof(mavlink_set_roll_pitch_yaw_speed_thrust_t, pitch_speed) }, \
{ "yaw_speed", NULL, MAVLINK_TYPE_FLOAT, 0, 10, offsetof(mavlink_set_roll_pitch_yaw_speed_thrust_t, yaw_speed) }, \
{ "thrust", NULL, MAVLINK_TYPE_FLOAT, 0, 14, offsetof(mavlink_set_roll_pitch_yaw_speed_thrust_t, thrust) }, \
} \
}
 
 
/**
* @brief Pack a set_roll_pitch_yaw_speed_thrust message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param target_system System ID
* @param target_component Component ID
* @param roll_speed Desired roll angular speed in rad/s
* @param pitch_speed Desired pitch angular speed in rad/s
* @param yaw_speed Desired yaw angular speed in rad/s
* @param thrust Collective thrust, normalized to 0 .. 1
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_set_roll_pitch_yaw_speed_thrust_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t target_system, uint8_t target_component, float roll_speed, float pitch_speed, float yaw_speed, float thrust)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[18];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
_mav_put_float(buf, 2, roll_speed);
_mav_put_float(buf, 6, pitch_speed);
_mav_put_float(buf, 10, yaw_speed);
_mav_put_float(buf, 14, thrust);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 18);
#else
mavlink_set_roll_pitch_yaw_speed_thrust_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
packet.roll_speed = roll_speed;
packet.pitch_speed = pitch_speed;
packet.yaw_speed = yaw_speed;
packet.thrust = thrust;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 18);
#endif
 
msg->msgid = MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED_THRUST;
return mavlink_finalize_message(msg, system_id, component_id, 18);
}
 
/**
* @brief Pack a set_roll_pitch_yaw_speed_thrust message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param target_system System ID
* @param target_component Component ID
* @param roll_speed Desired roll angular speed in rad/s
* @param pitch_speed Desired pitch angular speed in rad/s
* @param yaw_speed Desired yaw angular speed in rad/s
* @param thrust Collective thrust, normalized to 0 .. 1
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_set_roll_pitch_yaw_speed_thrust_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,float roll_speed,float pitch_speed,float yaw_speed,float thrust)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[18];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
_mav_put_float(buf, 2, roll_speed);
_mav_put_float(buf, 6, pitch_speed);
_mav_put_float(buf, 10, yaw_speed);
_mav_put_float(buf, 14, thrust);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 18);
#else
mavlink_set_roll_pitch_yaw_speed_thrust_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
packet.roll_speed = roll_speed;
packet.pitch_speed = pitch_speed;
packet.yaw_speed = yaw_speed;
packet.thrust = thrust;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 18);
#endif
 
msg->msgid = MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED_THRUST;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 18);
}
 
/**
* @brief Encode a set_roll_pitch_yaw_speed_thrust struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param set_roll_pitch_yaw_speed_thrust C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_set_roll_pitch_yaw_speed_thrust_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_roll_pitch_yaw_speed_thrust_t* set_roll_pitch_yaw_speed_thrust)
{
return mavlink_msg_set_roll_pitch_yaw_speed_thrust_pack(system_id, component_id, msg, set_roll_pitch_yaw_speed_thrust->target_system, set_roll_pitch_yaw_speed_thrust->target_component, set_roll_pitch_yaw_speed_thrust->roll_speed, set_roll_pitch_yaw_speed_thrust->pitch_speed, set_roll_pitch_yaw_speed_thrust->yaw_speed, set_roll_pitch_yaw_speed_thrust->thrust);
}
 
/**
* @brief Send a set_roll_pitch_yaw_speed_thrust message
* @param chan MAVLink channel to send the message
*
* @param target_system System ID
* @param target_component Component ID
* @param roll_speed Desired roll angular speed in rad/s
* @param pitch_speed Desired pitch angular speed in rad/s
* @param yaw_speed Desired yaw angular speed in rad/s
* @param thrust Collective thrust, normalized to 0 .. 1
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_set_roll_pitch_yaw_speed_thrust_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, float roll_speed, float pitch_speed, float yaw_speed, float thrust)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[18];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
_mav_put_float(buf, 2, roll_speed);
_mav_put_float(buf, 6, pitch_speed);
_mav_put_float(buf, 10, yaw_speed);
_mav_put_float(buf, 14, thrust);
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED_THRUST, buf, 18);
#else
mavlink_set_roll_pitch_yaw_speed_thrust_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
packet.roll_speed = roll_speed;
packet.pitch_speed = pitch_speed;
packet.yaw_speed = yaw_speed;
packet.thrust = thrust;
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED_THRUST, (const char *)&packet, 18);
#endif
}
 
#endif
 
// MESSAGE SET_ROLL_PITCH_YAW_SPEED_THRUST UNPACKING
 
 
/**
* @brief Get field target_system from set_roll_pitch_yaw_speed_thrust message
*
* @return System ID
*/
static inline uint8_t mavlink_msg_set_roll_pitch_yaw_speed_thrust_get_target_system(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 0);
}
 
/**
* @brief Get field target_component from set_roll_pitch_yaw_speed_thrust message
*
* @return Component ID
*/
static inline uint8_t mavlink_msg_set_roll_pitch_yaw_speed_thrust_get_target_component(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 1);
}
 
/**
* @brief Get field roll_speed from set_roll_pitch_yaw_speed_thrust message
*
* @return Desired roll angular speed in rad/s
*/
static inline float mavlink_msg_set_roll_pitch_yaw_speed_thrust_get_roll_speed(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 2);
}
 
/**
* @brief Get field pitch_speed from set_roll_pitch_yaw_speed_thrust message
*
* @return Desired pitch angular speed in rad/s
*/
static inline float mavlink_msg_set_roll_pitch_yaw_speed_thrust_get_pitch_speed(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 6);
}
 
/**
* @brief Get field yaw_speed from set_roll_pitch_yaw_speed_thrust message
*
* @return Desired yaw angular speed in rad/s
*/
static inline float mavlink_msg_set_roll_pitch_yaw_speed_thrust_get_yaw_speed(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 10);
}
 
/**
* @brief Get field thrust from set_roll_pitch_yaw_speed_thrust message
*
* @return Collective thrust, normalized to 0 .. 1
*/
static inline float mavlink_msg_set_roll_pitch_yaw_speed_thrust_get_thrust(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 14);
}
 
/**
* @brief Decode a set_roll_pitch_yaw_speed_thrust message into a struct
*
* @param msg The message to decode
* @param set_roll_pitch_yaw_speed_thrust C-struct to decode the message contents into
*/
static inline void mavlink_msg_set_roll_pitch_yaw_speed_thrust_decode(const mavlink_message_t* msg, mavlink_set_roll_pitch_yaw_speed_thrust_t* set_roll_pitch_yaw_speed_thrust)
{
#if MAVLINK_NEED_BYTE_SWAP
set_roll_pitch_yaw_speed_thrust->target_system = mavlink_msg_set_roll_pitch_yaw_speed_thrust_get_target_system(msg);
set_roll_pitch_yaw_speed_thrust->target_component = mavlink_msg_set_roll_pitch_yaw_speed_thrust_get_target_component(msg);
set_roll_pitch_yaw_speed_thrust->roll_speed = mavlink_msg_set_roll_pitch_yaw_speed_thrust_get_roll_speed(msg);
set_roll_pitch_yaw_speed_thrust->pitch_speed = mavlink_msg_set_roll_pitch_yaw_speed_thrust_get_pitch_speed(msg);
set_roll_pitch_yaw_speed_thrust->yaw_speed = mavlink_msg_set_roll_pitch_yaw_speed_thrust_get_yaw_speed(msg);
set_roll_pitch_yaw_speed_thrust->thrust = mavlink_msg_set_roll_pitch_yaw_speed_thrust_get_thrust(msg);
#else
memcpy(set_roll_pitch_yaw_speed_thrust, _MAV_PAYLOAD(msg), 18);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v0.9/common/mavlink_msg_set_roll_pitch_yaw_thrust.h
0,0 → 1,254
// MESSAGE SET_ROLL_PITCH_YAW_THRUST PACKING
 
#define MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST 55
 
typedef struct __mavlink_set_roll_pitch_yaw_thrust_t
{
uint8_t target_system; ///< System ID
uint8_t target_component; ///< Component ID
float roll; ///< Desired roll angle in radians
float pitch; ///< Desired pitch angle in radians
float yaw; ///< Desired yaw angle in radians
float thrust; ///< Collective thrust, normalized to 0 .. 1
} mavlink_set_roll_pitch_yaw_thrust_t;
 
#define MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST_LEN 18
#define MAVLINK_MSG_ID_55_LEN 18
 
 
 
#define MAVLINK_MESSAGE_INFO_SET_ROLL_PITCH_YAW_THRUST { \
"SET_ROLL_PITCH_YAW_THRUST", \
6, \
{ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_set_roll_pitch_yaw_thrust_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_set_roll_pitch_yaw_thrust_t, target_component) }, \
{ "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 2, offsetof(mavlink_set_roll_pitch_yaw_thrust_t, roll) }, \
{ "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 6, offsetof(mavlink_set_roll_pitch_yaw_thrust_t, pitch) }, \
{ "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 10, offsetof(mavlink_set_roll_pitch_yaw_thrust_t, yaw) }, \
{ "thrust", NULL, MAVLINK_TYPE_FLOAT, 0, 14, offsetof(mavlink_set_roll_pitch_yaw_thrust_t, thrust) }, \
} \
}
 
 
/**
* @brief Pack a set_roll_pitch_yaw_thrust message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param target_system System ID
* @param target_component Component ID
* @param roll Desired roll angle in radians
* @param pitch Desired pitch angle in radians
* @param yaw Desired yaw angle in radians
* @param thrust Collective thrust, normalized to 0 .. 1
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_set_roll_pitch_yaw_thrust_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t target_system, uint8_t target_component, float roll, float pitch, float yaw, float thrust)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[18];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
_mav_put_float(buf, 2, roll);
_mav_put_float(buf, 6, pitch);
_mav_put_float(buf, 10, yaw);
_mav_put_float(buf, 14, thrust);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 18);
#else
mavlink_set_roll_pitch_yaw_thrust_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
packet.roll = roll;
packet.pitch = pitch;
packet.yaw = yaw;
packet.thrust = thrust;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 18);
#endif
 
msg->msgid = MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST;
return mavlink_finalize_message(msg, system_id, component_id, 18);
}
 
/**
* @brief Pack a set_roll_pitch_yaw_thrust message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param target_system System ID
* @param target_component Component ID
* @param roll Desired roll angle in radians
* @param pitch Desired pitch angle in radians
* @param yaw Desired yaw angle in radians
* @param thrust Collective thrust, normalized to 0 .. 1
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_set_roll_pitch_yaw_thrust_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,float roll,float pitch,float yaw,float thrust)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[18];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
_mav_put_float(buf, 2, roll);
_mav_put_float(buf, 6, pitch);
_mav_put_float(buf, 10, yaw);
_mav_put_float(buf, 14, thrust);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 18);
#else
mavlink_set_roll_pitch_yaw_thrust_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
packet.roll = roll;
packet.pitch = pitch;
packet.yaw = yaw;
packet.thrust = thrust;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 18);
#endif
 
msg->msgid = MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 18);
}
 
/**
* @brief Encode a set_roll_pitch_yaw_thrust struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param set_roll_pitch_yaw_thrust C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_set_roll_pitch_yaw_thrust_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_roll_pitch_yaw_thrust_t* set_roll_pitch_yaw_thrust)
{
return mavlink_msg_set_roll_pitch_yaw_thrust_pack(system_id, component_id, msg, set_roll_pitch_yaw_thrust->target_system, set_roll_pitch_yaw_thrust->target_component, set_roll_pitch_yaw_thrust->roll, set_roll_pitch_yaw_thrust->pitch, set_roll_pitch_yaw_thrust->yaw, set_roll_pitch_yaw_thrust->thrust);
}
 
/**
* @brief Send a set_roll_pitch_yaw_thrust message
* @param chan MAVLink channel to send the message
*
* @param target_system System ID
* @param target_component Component ID
* @param roll Desired roll angle in radians
* @param pitch Desired pitch angle in radians
* @param yaw Desired yaw angle in radians
* @param thrust Collective thrust, normalized to 0 .. 1
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_set_roll_pitch_yaw_thrust_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, float roll, float pitch, float yaw, float thrust)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[18];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
_mav_put_float(buf, 2, roll);
_mav_put_float(buf, 6, pitch);
_mav_put_float(buf, 10, yaw);
_mav_put_float(buf, 14, thrust);
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST, buf, 18);
#else
mavlink_set_roll_pitch_yaw_thrust_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
packet.roll = roll;
packet.pitch = pitch;
packet.yaw = yaw;
packet.thrust = thrust;
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST, (const char *)&packet, 18);
#endif
}
 
#endif
 
// MESSAGE SET_ROLL_PITCH_YAW_THRUST UNPACKING
 
 
/**
* @brief Get field target_system from set_roll_pitch_yaw_thrust message
*
* @return System ID
*/
static inline uint8_t mavlink_msg_set_roll_pitch_yaw_thrust_get_target_system(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 0);
}
 
/**
* @brief Get field target_component from set_roll_pitch_yaw_thrust message
*
* @return Component ID
*/
static inline uint8_t mavlink_msg_set_roll_pitch_yaw_thrust_get_target_component(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 1);
}
 
/**
* @brief Get field roll from set_roll_pitch_yaw_thrust message
*
* @return Desired roll angle in radians
*/
static inline float mavlink_msg_set_roll_pitch_yaw_thrust_get_roll(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 2);
}
 
/**
* @brief Get field pitch from set_roll_pitch_yaw_thrust message
*
* @return Desired pitch angle in radians
*/
static inline float mavlink_msg_set_roll_pitch_yaw_thrust_get_pitch(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 6);
}
 
/**
* @brief Get field yaw from set_roll_pitch_yaw_thrust message
*
* @return Desired yaw angle in radians
*/
static inline float mavlink_msg_set_roll_pitch_yaw_thrust_get_yaw(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 10);
}
 
/**
* @brief Get field thrust from set_roll_pitch_yaw_thrust message
*
* @return Collective thrust, normalized to 0 .. 1
*/
static inline float mavlink_msg_set_roll_pitch_yaw_thrust_get_thrust(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 14);
}
 
/**
* @brief Decode a set_roll_pitch_yaw_thrust message into a struct
*
* @param msg The message to decode
* @param set_roll_pitch_yaw_thrust C-struct to decode the message contents into
*/
static inline void mavlink_msg_set_roll_pitch_yaw_thrust_decode(const mavlink_message_t* msg, mavlink_set_roll_pitch_yaw_thrust_t* set_roll_pitch_yaw_thrust)
{
#if MAVLINK_NEED_BYTE_SWAP
set_roll_pitch_yaw_thrust->target_system = mavlink_msg_set_roll_pitch_yaw_thrust_get_target_system(msg);
set_roll_pitch_yaw_thrust->target_component = mavlink_msg_set_roll_pitch_yaw_thrust_get_target_component(msg);
set_roll_pitch_yaw_thrust->roll = mavlink_msg_set_roll_pitch_yaw_thrust_get_roll(msg);
set_roll_pitch_yaw_thrust->pitch = mavlink_msg_set_roll_pitch_yaw_thrust_get_pitch(msg);
set_roll_pitch_yaw_thrust->yaw = mavlink_msg_set_roll_pitch_yaw_thrust_get_yaw(msg);
set_roll_pitch_yaw_thrust->thrust = mavlink_msg_set_roll_pitch_yaw_thrust_get_thrust(msg);
#else
memcpy(set_roll_pitch_yaw_thrust, _MAV_PAYLOAD(msg), 18);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v0.9/common/mavlink_msg_state_correction.h
0,0 → 1,320
// MESSAGE STATE_CORRECTION PACKING
 
#define MAVLINK_MSG_ID_STATE_CORRECTION 64
 
typedef struct __mavlink_state_correction_t
{
float xErr; ///< x position error
float yErr; ///< y position error
float zErr; ///< z position error
float rollErr; ///< roll error (radians)
float pitchErr; ///< pitch error (radians)
float yawErr; ///< yaw error (radians)
float vxErr; ///< x velocity
float vyErr; ///< y velocity
float vzErr; ///< z velocity
} mavlink_state_correction_t;
 
#define MAVLINK_MSG_ID_STATE_CORRECTION_LEN 36
#define MAVLINK_MSG_ID_64_LEN 36
 
 
 
#define MAVLINK_MESSAGE_INFO_STATE_CORRECTION { \
"STATE_CORRECTION", \
9, \
{ { "xErr", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_state_correction_t, xErr) }, \
{ "yErr", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_state_correction_t, yErr) }, \
{ "zErr", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_state_correction_t, zErr) }, \
{ "rollErr", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_state_correction_t, rollErr) }, \
{ "pitchErr", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_state_correction_t, pitchErr) }, \
{ "yawErr", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_state_correction_t, yawErr) }, \
{ "vxErr", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_state_correction_t, vxErr) }, \
{ "vyErr", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_state_correction_t, vyErr) }, \
{ "vzErr", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_state_correction_t, vzErr) }, \
} \
}
 
 
/**
* @brief Pack a state_correction message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param xErr x position error
* @param yErr y position error
* @param zErr z position error
* @param rollErr roll error (radians)
* @param pitchErr pitch error (radians)
* @param yawErr yaw error (radians)
* @param vxErr x velocity
* @param vyErr y velocity
* @param vzErr z velocity
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_state_correction_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
float xErr, float yErr, float zErr, float rollErr, float pitchErr, float yawErr, float vxErr, float vyErr, float vzErr)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[36];
_mav_put_float(buf, 0, xErr);
_mav_put_float(buf, 4, yErr);
_mav_put_float(buf, 8, zErr);
_mav_put_float(buf, 12, rollErr);
_mav_put_float(buf, 16, pitchErr);
_mav_put_float(buf, 20, yawErr);
_mav_put_float(buf, 24, vxErr);
_mav_put_float(buf, 28, vyErr);
_mav_put_float(buf, 32, vzErr);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 36);
#else
mavlink_state_correction_t packet;
packet.xErr = xErr;
packet.yErr = yErr;
packet.zErr = zErr;
packet.rollErr = rollErr;
packet.pitchErr = pitchErr;
packet.yawErr = yawErr;
packet.vxErr = vxErr;
packet.vyErr = vyErr;
packet.vzErr = vzErr;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 36);
#endif
 
msg->msgid = MAVLINK_MSG_ID_STATE_CORRECTION;
return mavlink_finalize_message(msg, system_id, component_id, 36);
}
 
/**
* @brief Pack a state_correction message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param xErr x position error
* @param yErr y position error
* @param zErr z position error
* @param rollErr roll error (radians)
* @param pitchErr pitch error (radians)
* @param yawErr yaw error (radians)
* @param vxErr x velocity
* @param vyErr y velocity
* @param vzErr z velocity
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_state_correction_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
float xErr,float yErr,float zErr,float rollErr,float pitchErr,float yawErr,float vxErr,float vyErr,float vzErr)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[36];
_mav_put_float(buf, 0, xErr);
_mav_put_float(buf, 4, yErr);
_mav_put_float(buf, 8, zErr);
_mav_put_float(buf, 12, rollErr);
_mav_put_float(buf, 16, pitchErr);
_mav_put_float(buf, 20, yawErr);
_mav_put_float(buf, 24, vxErr);
_mav_put_float(buf, 28, vyErr);
_mav_put_float(buf, 32, vzErr);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 36);
#else
mavlink_state_correction_t packet;
packet.xErr = xErr;
packet.yErr = yErr;
packet.zErr = zErr;
packet.rollErr = rollErr;
packet.pitchErr = pitchErr;
packet.yawErr = yawErr;
packet.vxErr = vxErr;
packet.vyErr = vyErr;
packet.vzErr = vzErr;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 36);
#endif
 
msg->msgid = MAVLINK_MSG_ID_STATE_CORRECTION;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 36);
}
 
/**
* @brief Encode a state_correction struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param state_correction C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_state_correction_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_state_correction_t* state_correction)
{
return mavlink_msg_state_correction_pack(system_id, component_id, msg, state_correction->xErr, state_correction->yErr, state_correction->zErr, state_correction->rollErr, state_correction->pitchErr, state_correction->yawErr, state_correction->vxErr, state_correction->vyErr, state_correction->vzErr);
}
 
/**
* @brief Send a state_correction message
* @param chan MAVLink channel to send the message
*
* @param xErr x position error
* @param yErr y position error
* @param zErr z position error
* @param rollErr roll error (radians)
* @param pitchErr pitch error (radians)
* @param yawErr yaw error (radians)
* @param vxErr x velocity
* @param vyErr y velocity
* @param vzErr z velocity
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_state_correction_send(mavlink_channel_t chan, float xErr, float yErr, float zErr, float rollErr, float pitchErr, float yawErr, float vxErr, float vyErr, float vzErr)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[36];
_mav_put_float(buf, 0, xErr);
_mav_put_float(buf, 4, yErr);
_mav_put_float(buf, 8, zErr);
_mav_put_float(buf, 12, rollErr);
_mav_put_float(buf, 16, pitchErr);
_mav_put_float(buf, 20, yawErr);
_mav_put_float(buf, 24, vxErr);
_mav_put_float(buf, 28, vyErr);
_mav_put_float(buf, 32, vzErr);
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_STATE_CORRECTION, buf, 36);
#else
mavlink_state_correction_t packet;
packet.xErr = xErr;
packet.yErr = yErr;
packet.zErr = zErr;
packet.rollErr = rollErr;
packet.pitchErr = pitchErr;
packet.yawErr = yawErr;
packet.vxErr = vxErr;
packet.vyErr = vyErr;
packet.vzErr = vzErr;
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_STATE_CORRECTION, (const char *)&packet, 36);
#endif
}
 
#endif
 
// MESSAGE STATE_CORRECTION UNPACKING
 
 
/**
* @brief Get field xErr from state_correction message
*
* @return x position error
*/
static inline float mavlink_msg_state_correction_get_xErr(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 0);
}
 
/**
* @brief Get field yErr from state_correction message
*
* @return y position error
*/
static inline float mavlink_msg_state_correction_get_yErr(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 4);
}
 
/**
* @brief Get field zErr from state_correction message
*
* @return z position error
*/
static inline float mavlink_msg_state_correction_get_zErr(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 8);
}
 
/**
* @brief Get field rollErr from state_correction message
*
* @return roll error (radians)
*/
static inline float mavlink_msg_state_correction_get_rollErr(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 12);
}
 
/**
* @brief Get field pitchErr from state_correction message
*
* @return pitch error (radians)
*/
static inline float mavlink_msg_state_correction_get_pitchErr(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 16);
}
 
/**
* @brief Get field yawErr from state_correction message
*
* @return yaw error (radians)
*/
static inline float mavlink_msg_state_correction_get_yawErr(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 20);
}
 
/**
* @brief Get field vxErr from state_correction message
*
* @return x velocity
*/
static inline float mavlink_msg_state_correction_get_vxErr(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 24);
}
 
/**
* @brief Get field vyErr from state_correction message
*
* @return y velocity
*/
static inline float mavlink_msg_state_correction_get_vyErr(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 28);
}
 
/**
* @brief Get field vzErr from state_correction message
*
* @return z velocity
*/
static inline float mavlink_msg_state_correction_get_vzErr(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 32);
}
 
/**
* @brief Decode a state_correction message into a struct
*
* @param msg The message to decode
* @param state_correction C-struct to decode the message contents into
*/
static inline void mavlink_msg_state_correction_decode(const mavlink_message_t* msg, mavlink_state_correction_t* state_correction)
{
#if MAVLINK_NEED_BYTE_SWAP
state_correction->xErr = mavlink_msg_state_correction_get_xErr(msg);
state_correction->yErr = mavlink_msg_state_correction_get_yErr(msg);
state_correction->zErr = mavlink_msg_state_correction_get_zErr(msg);
state_correction->rollErr = mavlink_msg_state_correction_get_rollErr(msg);
state_correction->pitchErr = mavlink_msg_state_correction_get_pitchErr(msg);
state_correction->yawErr = mavlink_msg_state_correction_get_yawErr(msg);
state_correction->vxErr = mavlink_msg_state_correction_get_vxErr(msg);
state_correction->vyErr = mavlink_msg_state_correction_get_vyErr(msg);
state_correction->vzErr = mavlink_msg_state_correction_get_vzErr(msg);
#else
memcpy(state_correction, _MAV_PAYLOAD(msg), 36);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v0.9/common/mavlink_msg_statustext.h
0,0 → 1,160
// MESSAGE STATUSTEXT PACKING
 
#define MAVLINK_MSG_ID_STATUSTEXT 254
 
typedef struct __mavlink_statustext_t
{
uint8_t severity; ///< Severity of status, 0 = info message, 255 = critical fault
int8_t text[50]; ///< Status text message, without null termination character
} mavlink_statustext_t;
 
#define MAVLINK_MSG_ID_STATUSTEXT_LEN 51
#define MAVLINK_MSG_ID_254_LEN 51
 
#define MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN 50
 
#define MAVLINK_MESSAGE_INFO_STATUSTEXT { \
"STATUSTEXT", \
2, \
{ { "severity", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_statustext_t, severity) }, \
{ "text", NULL, MAVLINK_TYPE_INT8_T, 50, 1, offsetof(mavlink_statustext_t, text) }, \
} \
}
 
 
/**
* @brief Pack a statustext message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param severity Severity of status, 0 = info message, 255 = critical fault
* @param text Status text message, without null termination character
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_statustext_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t severity, const int8_t *text)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[51];
_mav_put_uint8_t(buf, 0, severity);
_mav_put_int8_t_array(buf, 1, text, 50);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 51);
#else
mavlink_statustext_t packet;
packet.severity = severity;
mav_array_memcpy(packet.text, text, sizeof(int8_t)*50);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 51);
#endif
 
msg->msgid = MAVLINK_MSG_ID_STATUSTEXT;
return mavlink_finalize_message(msg, system_id, component_id, 51);
}
 
/**
* @brief Pack a statustext message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param severity Severity of status, 0 = info message, 255 = critical fault
* @param text Status text message, without null termination character
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_statustext_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint8_t severity,const int8_t *text)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[51];
_mav_put_uint8_t(buf, 0, severity);
_mav_put_int8_t_array(buf, 1, text, 50);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 51);
#else
mavlink_statustext_t packet;
packet.severity = severity;
mav_array_memcpy(packet.text, text, sizeof(int8_t)*50);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 51);
#endif
 
msg->msgid = MAVLINK_MSG_ID_STATUSTEXT;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 51);
}
 
/**
* @brief Encode a statustext struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param statustext C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_statustext_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_statustext_t* statustext)
{
return mavlink_msg_statustext_pack(system_id, component_id, msg, statustext->severity, statustext->text);
}
 
/**
* @brief Send a statustext message
* @param chan MAVLink channel to send the message
*
* @param severity Severity of status, 0 = info message, 255 = critical fault
* @param text Status text message, without null termination character
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_statustext_send(mavlink_channel_t chan, uint8_t severity, const int8_t *text)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[51];
_mav_put_uint8_t(buf, 0, severity);
_mav_put_int8_t_array(buf, 1, text, 50);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_STATUSTEXT, buf, 51);
#else
mavlink_statustext_t packet;
packet.severity = severity;
mav_array_memcpy(packet.text, text, sizeof(int8_t)*50);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_STATUSTEXT, (const char *)&packet, 51);
#endif
}
 
#endif
 
// MESSAGE STATUSTEXT UNPACKING
 
 
/**
* @brief Get field severity from statustext message
*
* @return Severity of status, 0 = info message, 255 = critical fault
*/
static inline uint8_t mavlink_msg_statustext_get_severity(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 0);
}
 
/**
* @brief Get field text from statustext message
*
* @return Status text message, without null termination character
*/
static inline uint16_t mavlink_msg_statustext_get_text(const mavlink_message_t* msg, int8_t *text)
{
return _MAV_RETURN_int8_t_array(msg, text, 50, 1);
}
 
/**
* @brief Decode a statustext message into a struct
*
* @param msg The message to decode
* @param statustext C-struct to decode the message contents into
*/
static inline void mavlink_msg_statustext_decode(const mavlink_message_t* msg, mavlink_statustext_t* statustext)
{
#if MAVLINK_NEED_BYTE_SWAP
statustext->severity = mavlink_msg_statustext_get_severity(msg);
mavlink_msg_statustext_get_text(msg, statustext->text);
#else
memcpy(statustext, _MAV_PAYLOAD(msg), 51);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v0.9/common/mavlink_msg_sys_status.h
0,0 → 1,276
// MESSAGE SYS_STATUS PACKING
 
#define MAVLINK_MSG_ID_SYS_STATUS 34
 
typedef struct __mavlink_sys_status_t
{
uint8_t mode; ///< System mode, see MAV_MODE ENUM in mavlink/include/mavlink_types.h
uint8_t nav_mode; ///< Navigation mode, see MAV_NAV_MODE ENUM
uint8_t status; ///< System status flag, see MAV_STATUS ENUM
uint16_t load; ///< Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000
uint16_t vbat; ///< Battery voltage, in millivolts (1 = 1 millivolt)
uint16_t battery_remaining; ///< Remaining battery energy: (0%: 0, 100%: 1000)
uint16_t packet_drop; ///< Dropped packets (packets that were corrupted on reception on the MAV)
} mavlink_sys_status_t;
 
#define MAVLINK_MSG_ID_SYS_STATUS_LEN 11
#define MAVLINK_MSG_ID_34_LEN 11
 
 
 
#define MAVLINK_MESSAGE_INFO_SYS_STATUS { \
"SYS_STATUS", \
7, \
{ { "mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_sys_status_t, mode) }, \
{ "nav_mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_sys_status_t, nav_mode) }, \
{ "status", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_sys_status_t, status) }, \
{ "load", NULL, MAVLINK_TYPE_UINT16_T, 0, 3, offsetof(mavlink_sys_status_t, load) }, \
{ "vbat", NULL, MAVLINK_TYPE_UINT16_T, 0, 5, offsetof(mavlink_sys_status_t, vbat) }, \
{ "battery_remaining", NULL, MAVLINK_TYPE_UINT16_T, 0, 7, offsetof(mavlink_sys_status_t, battery_remaining) }, \
{ "packet_drop", NULL, MAVLINK_TYPE_UINT16_T, 0, 9, offsetof(mavlink_sys_status_t, packet_drop) }, \
} \
}
 
 
/**
* @brief Pack a sys_status message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param mode System mode, see MAV_MODE ENUM in mavlink/include/mavlink_types.h
* @param nav_mode Navigation mode, see MAV_NAV_MODE ENUM
* @param status System status flag, see MAV_STATUS ENUM
* @param load Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000
* @param vbat Battery voltage, in millivolts (1 = 1 millivolt)
* @param battery_remaining Remaining battery energy: (0%: 0, 100%: 1000)
* @param packet_drop Dropped packets (packets that were corrupted on reception on the MAV)
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_sys_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t mode, uint8_t nav_mode, uint8_t status, uint16_t load, uint16_t vbat, uint16_t battery_remaining, uint16_t packet_drop)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[11];
_mav_put_uint8_t(buf, 0, mode);
_mav_put_uint8_t(buf, 1, nav_mode);
_mav_put_uint8_t(buf, 2, status);
_mav_put_uint16_t(buf, 3, load);
_mav_put_uint16_t(buf, 5, vbat);
_mav_put_uint16_t(buf, 7, battery_remaining);
_mav_put_uint16_t(buf, 9, packet_drop);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 11);
#else
mavlink_sys_status_t packet;
packet.mode = mode;
packet.nav_mode = nav_mode;
packet.status = status;
packet.load = load;
packet.vbat = vbat;
packet.battery_remaining = battery_remaining;
packet.packet_drop = packet_drop;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 11);
#endif
 
msg->msgid = MAVLINK_MSG_ID_SYS_STATUS;
return mavlink_finalize_message(msg, system_id, component_id, 11);
}
 
/**
* @brief Pack a sys_status message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param mode System mode, see MAV_MODE ENUM in mavlink/include/mavlink_types.h
* @param nav_mode Navigation mode, see MAV_NAV_MODE ENUM
* @param status System status flag, see MAV_STATUS ENUM
* @param load Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000
* @param vbat Battery voltage, in millivolts (1 = 1 millivolt)
* @param battery_remaining Remaining battery energy: (0%: 0, 100%: 1000)
* @param packet_drop Dropped packets (packets that were corrupted on reception on the MAV)
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_sys_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint8_t mode,uint8_t nav_mode,uint8_t status,uint16_t load,uint16_t vbat,uint16_t battery_remaining,uint16_t packet_drop)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[11];
_mav_put_uint8_t(buf, 0, mode);
_mav_put_uint8_t(buf, 1, nav_mode);
_mav_put_uint8_t(buf, 2, status);
_mav_put_uint16_t(buf, 3, load);
_mav_put_uint16_t(buf, 5, vbat);
_mav_put_uint16_t(buf, 7, battery_remaining);
_mav_put_uint16_t(buf, 9, packet_drop);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 11);
#else
mavlink_sys_status_t packet;
packet.mode = mode;
packet.nav_mode = nav_mode;
packet.status = status;
packet.load = load;
packet.vbat = vbat;
packet.battery_remaining = battery_remaining;
packet.packet_drop = packet_drop;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 11);
#endif
 
msg->msgid = MAVLINK_MSG_ID_SYS_STATUS;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 11);
}
 
/**
* @brief Encode a sys_status struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param sys_status C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_sys_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_sys_status_t* sys_status)
{
return mavlink_msg_sys_status_pack(system_id, component_id, msg, sys_status->mode, sys_status->nav_mode, sys_status->status, sys_status->load, sys_status->vbat, sys_status->battery_remaining, sys_status->packet_drop);
}
 
/**
* @brief Send a sys_status message
* @param chan MAVLink channel to send the message
*
* @param mode System mode, see MAV_MODE ENUM in mavlink/include/mavlink_types.h
* @param nav_mode Navigation mode, see MAV_NAV_MODE ENUM
* @param status System status flag, see MAV_STATUS ENUM
* @param load Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000
* @param vbat Battery voltage, in millivolts (1 = 1 millivolt)
* @param battery_remaining Remaining battery energy: (0%: 0, 100%: 1000)
* @param packet_drop Dropped packets (packets that were corrupted on reception on the MAV)
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_sys_status_send(mavlink_channel_t chan, uint8_t mode, uint8_t nav_mode, uint8_t status, uint16_t load, uint16_t vbat, uint16_t battery_remaining, uint16_t packet_drop)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[11];
_mav_put_uint8_t(buf, 0, mode);
_mav_put_uint8_t(buf, 1, nav_mode);
_mav_put_uint8_t(buf, 2, status);
_mav_put_uint16_t(buf, 3, load);
_mav_put_uint16_t(buf, 5, vbat);
_mav_put_uint16_t(buf, 7, battery_remaining);
_mav_put_uint16_t(buf, 9, packet_drop);
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYS_STATUS, buf, 11);
#else
mavlink_sys_status_t packet;
packet.mode = mode;
packet.nav_mode = nav_mode;
packet.status = status;
packet.load = load;
packet.vbat = vbat;
packet.battery_remaining = battery_remaining;
packet.packet_drop = packet_drop;
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYS_STATUS, (const char *)&packet, 11);
#endif
}
 
#endif
 
// MESSAGE SYS_STATUS UNPACKING
 
 
/**
* @brief Get field mode from sys_status message
*
* @return System mode, see MAV_MODE ENUM in mavlink/include/mavlink_types.h
*/
static inline uint8_t mavlink_msg_sys_status_get_mode(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 0);
}
 
/**
* @brief Get field nav_mode from sys_status message
*
* @return Navigation mode, see MAV_NAV_MODE ENUM
*/
static inline uint8_t mavlink_msg_sys_status_get_nav_mode(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 1);
}
 
/**
* @brief Get field status from sys_status message
*
* @return System status flag, see MAV_STATUS ENUM
*/
static inline uint8_t mavlink_msg_sys_status_get_status(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 2);
}
 
/**
* @brief Get field load from sys_status message
*
* @return Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000
*/
static inline uint16_t mavlink_msg_sys_status_get_load(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 3);
}
 
/**
* @brief Get field vbat from sys_status message
*
* @return Battery voltage, in millivolts (1 = 1 millivolt)
*/
static inline uint16_t mavlink_msg_sys_status_get_vbat(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 5);
}
 
/**
* @brief Get field battery_remaining from sys_status message
*
* @return Remaining battery energy: (0%: 0, 100%: 1000)
*/
static inline uint16_t mavlink_msg_sys_status_get_battery_remaining(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 7);
}
 
/**
* @brief Get field packet_drop from sys_status message
*
* @return Dropped packets (packets that were corrupted on reception on the MAV)
*/
static inline uint16_t mavlink_msg_sys_status_get_packet_drop(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 9);
}
 
/**
* @brief Decode a sys_status message into a struct
*
* @param msg The message to decode
* @param sys_status C-struct to decode the message contents into
*/
static inline void mavlink_msg_sys_status_decode(const mavlink_message_t* msg, mavlink_sys_status_t* sys_status)
{
#if MAVLINK_NEED_BYTE_SWAP
sys_status->mode = mavlink_msg_sys_status_get_mode(msg);
sys_status->nav_mode = mavlink_msg_sys_status_get_nav_mode(msg);
sys_status->status = mavlink_msg_sys_status_get_status(msg);
sys_status->load = mavlink_msg_sys_status_get_load(msg);
sys_status->vbat = mavlink_msg_sys_status_get_vbat(msg);
sys_status->battery_remaining = mavlink_msg_sys_status_get_battery_remaining(msg);
sys_status->packet_drop = mavlink_msg_sys_status_get_packet_drop(msg);
#else
memcpy(sys_status, _MAV_PAYLOAD(msg), 11);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v0.9/common/mavlink_msg_system_time.h
0,0 → 1,144
// MESSAGE SYSTEM_TIME PACKING
 
#define MAVLINK_MSG_ID_SYSTEM_TIME 2
 
typedef struct __mavlink_system_time_t
{
uint64_t time_usec; ///< Timestamp of the master clock in microseconds since UNIX epoch.
} mavlink_system_time_t;
 
#define MAVLINK_MSG_ID_SYSTEM_TIME_LEN 8
#define MAVLINK_MSG_ID_2_LEN 8
 
 
 
#define MAVLINK_MESSAGE_INFO_SYSTEM_TIME { \
"SYSTEM_TIME", \
1, \
{ { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_system_time_t, time_usec) }, \
} \
}
 
 
/**
* @brief Pack a system_time message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param time_usec Timestamp of the master clock in microseconds since UNIX epoch.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_system_time_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint64_t time_usec)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[8];
_mav_put_uint64_t(buf, 0, time_usec);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 8);
#else
mavlink_system_time_t packet;
packet.time_usec = time_usec;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 8);
#endif
 
msg->msgid = MAVLINK_MSG_ID_SYSTEM_TIME;
return mavlink_finalize_message(msg, system_id, component_id, 8);
}
 
/**
* @brief Pack a system_time message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param time_usec Timestamp of the master clock in microseconds since UNIX epoch.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_system_time_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint64_t time_usec)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[8];
_mav_put_uint64_t(buf, 0, time_usec);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 8);
#else
mavlink_system_time_t packet;
packet.time_usec = time_usec;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 8);
#endif
 
msg->msgid = MAVLINK_MSG_ID_SYSTEM_TIME;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 8);
}
 
/**
* @brief Encode a system_time struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param system_time C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_system_time_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_system_time_t* system_time)
{
return mavlink_msg_system_time_pack(system_id, component_id, msg, system_time->time_usec);
}
 
/**
* @brief Send a system_time message
* @param chan MAVLink channel to send the message
*
* @param time_usec Timestamp of the master clock in microseconds since UNIX epoch.
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_system_time_send(mavlink_channel_t chan, uint64_t time_usec)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[8];
_mav_put_uint64_t(buf, 0, time_usec);
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYSTEM_TIME, buf, 8);
#else
mavlink_system_time_t packet;
packet.time_usec = time_usec;
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYSTEM_TIME, (const char *)&packet, 8);
#endif
}
 
#endif
 
// MESSAGE SYSTEM_TIME UNPACKING
 
 
/**
* @brief Get field time_usec from system_time message
*
* @return Timestamp of the master clock in microseconds since UNIX epoch.
*/
static inline uint64_t mavlink_msg_system_time_get_time_usec(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint64_t(msg, 0);
}
 
/**
* @brief Decode a system_time message into a struct
*
* @param msg The message to decode
* @param system_time C-struct to decode the message contents into
*/
static inline void mavlink_msg_system_time_decode(const mavlink_message_t* msg, mavlink_system_time_t* system_time)
{
#if MAVLINK_NEED_BYTE_SWAP
system_time->time_usec = mavlink_msg_system_time_get_time_usec(msg);
#else
memcpy(system_time, _MAV_PAYLOAD(msg), 8);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v0.9/common/mavlink_msg_system_time_utc.h
0,0 → 1,166
// MESSAGE SYSTEM_TIME_UTC PACKING
 
#define MAVLINK_MSG_ID_SYSTEM_TIME_UTC 4
 
typedef struct __mavlink_system_time_utc_t
{
uint32_t utc_date; ///< GPS UTC date ddmmyy
uint32_t utc_time; ///< GPS UTC time hhmmss
} mavlink_system_time_utc_t;
 
#define MAVLINK_MSG_ID_SYSTEM_TIME_UTC_LEN 8
#define MAVLINK_MSG_ID_4_LEN 8
 
 
 
#define MAVLINK_MESSAGE_INFO_SYSTEM_TIME_UTC { \
"SYSTEM_TIME_UTC", \
2, \
{ { "utc_date", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_system_time_utc_t, utc_date) }, \
{ "utc_time", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_system_time_utc_t, utc_time) }, \
} \
}
 
 
/**
* @brief Pack a system_time_utc message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param utc_date GPS UTC date ddmmyy
* @param utc_time GPS UTC time hhmmss
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_system_time_utc_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint32_t utc_date, uint32_t utc_time)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[8];
_mav_put_uint32_t(buf, 0, utc_date);
_mav_put_uint32_t(buf, 4, utc_time);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 8);
#else
mavlink_system_time_utc_t packet;
packet.utc_date = utc_date;
packet.utc_time = utc_time;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 8);
#endif
 
msg->msgid = MAVLINK_MSG_ID_SYSTEM_TIME_UTC;
return mavlink_finalize_message(msg, system_id, component_id, 8);
}
 
/**
* @brief Pack a system_time_utc message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param utc_date GPS UTC date ddmmyy
* @param utc_time GPS UTC time hhmmss
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_system_time_utc_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint32_t utc_date,uint32_t utc_time)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[8];
_mav_put_uint32_t(buf, 0, utc_date);
_mav_put_uint32_t(buf, 4, utc_time);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 8);
#else
mavlink_system_time_utc_t packet;
packet.utc_date = utc_date;
packet.utc_time = utc_time;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 8);
#endif
 
msg->msgid = MAVLINK_MSG_ID_SYSTEM_TIME_UTC;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 8);
}
 
/**
* @brief Encode a system_time_utc struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param system_time_utc C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_system_time_utc_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_system_time_utc_t* system_time_utc)
{
return mavlink_msg_system_time_utc_pack(system_id, component_id, msg, system_time_utc->utc_date, system_time_utc->utc_time);
}
 
/**
* @brief Send a system_time_utc message
* @param chan MAVLink channel to send the message
*
* @param utc_date GPS UTC date ddmmyy
* @param utc_time GPS UTC time hhmmss
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_system_time_utc_send(mavlink_channel_t chan, uint32_t utc_date, uint32_t utc_time)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[8];
_mav_put_uint32_t(buf, 0, utc_date);
_mav_put_uint32_t(buf, 4, utc_time);
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYSTEM_TIME_UTC, buf, 8);
#else
mavlink_system_time_utc_t packet;
packet.utc_date = utc_date;
packet.utc_time = utc_time;
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYSTEM_TIME_UTC, (const char *)&packet, 8);
#endif
}
 
#endif
 
// MESSAGE SYSTEM_TIME_UTC UNPACKING
 
 
/**
* @brief Get field utc_date from system_time_utc message
*
* @return GPS UTC date ddmmyy
*/
static inline uint32_t mavlink_msg_system_time_utc_get_utc_date(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint32_t(msg, 0);
}
 
/**
* @brief Get field utc_time from system_time_utc message
*
* @return GPS UTC time hhmmss
*/
static inline uint32_t mavlink_msg_system_time_utc_get_utc_time(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint32_t(msg, 4);
}
 
/**
* @brief Decode a system_time_utc message into a struct
*
* @param msg The message to decode
* @param system_time_utc C-struct to decode the message contents into
*/
static inline void mavlink_msg_system_time_utc_decode(const mavlink_message_t* msg, mavlink_system_time_utc_t* system_time_utc)
{
#if MAVLINK_NEED_BYTE_SWAP
system_time_utc->utc_date = mavlink_msg_system_time_utc_get_utc_date(msg);
system_time_utc->utc_time = mavlink_msg_system_time_utc_get_utc_time(msg);
#else
memcpy(system_time_utc, _MAV_PAYLOAD(msg), 8);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v0.9/common/mavlink_msg_vfr_hud.h
0,0 → 1,254
// MESSAGE VFR_HUD PACKING
 
#define MAVLINK_MSG_ID_VFR_HUD 74
 
typedef struct __mavlink_vfr_hud_t
{
float airspeed; ///< Current airspeed in m/s
float groundspeed; ///< Current ground speed in m/s
int16_t heading; ///< Current heading in degrees, in compass units (0..360, 0=north)
uint16_t throttle; ///< Current throttle setting in integer percent, 0 to 100
float alt; ///< Current altitude (MSL), in meters
float climb; ///< Current climb rate in meters/second
} mavlink_vfr_hud_t;
 
#define MAVLINK_MSG_ID_VFR_HUD_LEN 20
#define MAVLINK_MSG_ID_74_LEN 20
 
 
 
#define MAVLINK_MESSAGE_INFO_VFR_HUD { \
"VFR_HUD", \
6, \
{ { "airspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_vfr_hud_t, airspeed) }, \
{ "groundspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_vfr_hud_t, groundspeed) }, \
{ "heading", NULL, MAVLINK_TYPE_INT16_T, 0, 8, offsetof(mavlink_vfr_hud_t, heading) }, \
{ "throttle", NULL, MAVLINK_TYPE_UINT16_T, 0, 10, offsetof(mavlink_vfr_hud_t, throttle) }, \
{ "alt", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_vfr_hud_t, alt) }, \
{ "climb", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_vfr_hud_t, climb) }, \
} \
}
 
 
/**
* @brief Pack a vfr_hud message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param airspeed Current airspeed in m/s
* @param groundspeed Current ground speed in m/s
* @param heading Current heading in degrees, in compass units (0..360, 0=north)
* @param throttle Current throttle setting in integer percent, 0 to 100
* @param alt Current altitude (MSL), in meters
* @param climb Current climb rate in meters/second
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_vfr_hud_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
float airspeed, float groundspeed, int16_t heading, uint16_t throttle, float alt, float climb)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[20];
_mav_put_float(buf, 0, airspeed);
_mav_put_float(buf, 4, groundspeed);
_mav_put_int16_t(buf, 8, heading);
_mav_put_uint16_t(buf, 10, throttle);
_mav_put_float(buf, 12, alt);
_mav_put_float(buf, 16, climb);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 20);
#else
mavlink_vfr_hud_t packet;
packet.airspeed = airspeed;
packet.groundspeed = groundspeed;
packet.heading = heading;
packet.throttle = throttle;
packet.alt = alt;
packet.climb = climb;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 20);
#endif
 
msg->msgid = MAVLINK_MSG_ID_VFR_HUD;
return mavlink_finalize_message(msg, system_id, component_id, 20);
}
 
/**
* @brief Pack a vfr_hud message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param airspeed Current airspeed in m/s
* @param groundspeed Current ground speed in m/s
* @param heading Current heading in degrees, in compass units (0..360, 0=north)
* @param throttle Current throttle setting in integer percent, 0 to 100
* @param alt Current altitude (MSL), in meters
* @param climb Current climb rate in meters/second
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_vfr_hud_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
float airspeed,float groundspeed,int16_t heading,uint16_t throttle,float alt,float climb)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[20];
_mav_put_float(buf, 0, airspeed);
_mav_put_float(buf, 4, groundspeed);
_mav_put_int16_t(buf, 8, heading);
_mav_put_uint16_t(buf, 10, throttle);
_mav_put_float(buf, 12, alt);
_mav_put_float(buf, 16, climb);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 20);
#else
mavlink_vfr_hud_t packet;
packet.airspeed = airspeed;
packet.groundspeed = groundspeed;
packet.heading = heading;
packet.throttle = throttle;
packet.alt = alt;
packet.climb = climb;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 20);
#endif
 
msg->msgid = MAVLINK_MSG_ID_VFR_HUD;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 20);
}
 
/**
* @brief Encode a vfr_hud struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param vfr_hud C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_vfr_hud_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_vfr_hud_t* vfr_hud)
{
return mavlink_msg_vfr_hud_pack(system_id, component_id, msg, vfr_hud->airspeed, vfr_hud->groundspeed, vfr_hud->heading, vfr_hud->throttle, vfr_hud->alt, vfr_hud->climb);
}
 
/**
* @brief Send a vfr_hud message
* @param chan MAVLink channel to send the message
*
* @param airspeed Current airspeed in m/s
* @param groundspeed Current ground speed in m/s
* @param heading Current heading in degrees, in compass units (0..360, 0=north)
* @param throttle Current throttle setting in integer percent, 0 to 100
* @param alt Current altitude (MSL), in meters
* @param climb Current climb rate in meters/second
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_vfr_hud_send(mavlink_channel_t chan, float airspeed, float groundspeed, int16_t heading, uint16_t throttle, float alt, float climb)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[20];
_mav_put_float(buf, 0, airspeed);
_mav_put_float(buf, 4, groundspeed);
_mav_put_int16_t(buf, 8, heading);
_mav_put_uint16_t(buf, 10, throttle);
_mav_put_float(buf, 12, alt);
_mav_put_float(buf, 16, climb);
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VFR_HUD, buf, 20);
#else
mavlink_vfr_hud_t packet;
packet.airspeed = airspeed;
packet.groundspeed = groundspeed;
packet.heading = heading;
packet.throttle = throttle;
packet.alt = alt;
packet.climb = climb;
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VFR_HUD, (const char *)&packet, 20);
#endif
}
 
#endif
 
// MESSAGE VFR_HUD UNPACKING
 
 
/**
* @brief Get field airspeed from vfr_hud message
*
* @return Current airspeed in m/s
*/
static inline float mavlink_msg_vfr_hud_get_airspeed(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 0);
}
 
/**
* @brief Get field groundspeed from vfr_hud message
*
* @return Current ground speed in m/s
*/
static inline float mavlink_msg_vfr_hud_get_groundspeed(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 4);
}
 
/**
* @brief Get field heading from vfr_hud message
*
* @return Current heading in degrees, in compass units (0..360, 0=north)
*/
static inline int16_t mavlink_msg_vfr_hud_get_heading(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 8);
}
 
/**
* @brief Get field throttle from vfr_hud message
*
* @return Current throttle setting in integer percent, 0 to 100
*/
static inline uint16_t mavlink_msg_vfr_hud_get_throttle(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 10);
}
 
/**
* @brief Get field alt from vfr_hud message
*
* @return Current altitude (MSL), in meters
*/
static inline float mavlink_msg_vfr_hud_get_alt(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 12);
}
 
/**
* @brief Get field climb from vfr_hud message
*
* @return Current climb rate in meters/second
*/
static inline float mavlink_msg_vfr_hud_get_climb(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 16);
}
 
/**
* @brief Decode a vfr_hud message into a struct
*
* @param msg The message to decode
* @param vfr_hud C-struct to decode the message contents into
*/
static inline void mavlink_msg_vfr_hud_decode(const mavlink_message_t* msg, mavlink_vfr_hud_t* vfr_hud)
{
#if MAVLINK_NEED_BYTE_SWAP
vfr_hud->airspeed = mavlink_msg_vfr_hud_get_airspeed(msg);
vfr_hud->groundspeed = mavlink_msg_vfr_hud_get_groundspeed(msg);
vfr_hud->heading = mavlink_msg_vfr_hud_get_heading(msg);
vfr_hud->throttle = mavlink_msg_vfr_hud_get_throttle(msg);
vfr_hud->alt = mavlink_msg_vfr_hud_get_alt(msg);
vfr_hud->climb = mavlink_msg_vfr_hud_get_climb(msg);
#else
memcpy(vfr_hud, _MAV_PAYLOAD(msg), 20);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v0.9/common/mavlink_msg_waypoint.h
0,0 → 1,430
// MESSAGE WAYPOINT PACKING
 
#define MAVLINK_MSG_ID_WAYPOINT 39
 
typedef struct __mavlink_waypoint_t
{
uint8_t target_system; ///< System ID
uint8_t target_component; ///< Component ID
uint16_t seq; ///< Sequence
uint8_t frame; ///< The coordinate system of the waypoint. see MAV_FRAME in mavlink_types.h
uint8_t command; ///< The scheduled action for the waypoint. see MAV_COMMAND in common.xml MAVLink specs
uint8_t current; ///< false:0, true:1
uint8_t autocontinue; ///< autocontinue to next wp
float param1; ///< PARAM1 / For NAV command waypoints: Radius in which the waypoint is accepted as reached, in meters
float param2; ///< PARAM2 / For NAV command waypoints: Time that the MAV should stay inside the PARAM1 radius before advancing, in milliseconds
float param3; ///< PARAM3 / For LOITER command waypoints: Orbit to circle around the waypoint, in meters. If positive the orbit direction should be clockwise, if negative the orbit direction should be counter-clockwise.
float param4; ///< PARAM4 / For NAV and LOITER command waypoints: Yaw orientation in degrees, [0..360] 0 = NORTH
float x; ///< PARAM5 / local: x position, global: latitude
float y; ///< PARAM6 / y position: global: longitude
float z; ///< PARAM7 / z position: global: altitude
} mavlink_waypoint_t;
 
#define MAVLINK_MSG_ID_WAYPOINT_LEN 36
#define MAVLINK_MSG_ID_39_LEN 36
 
 
 
#define MAVLINK_MESSAGE_INFO_WAYPOINT { \
"WAYPOINT", \
14, \
{ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_waypoint_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_waypoint_t, target_component) }, \
{ "seq", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_waypoint_t, seq) }, \
{ "frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_waypoint_t, frame) }, \
{ "command", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_waypoint_t, command) }, \
{ "current", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_waypoint_t, current) }, \
{ "autocontinue", NULL, MAVLINK_TYPE_UINT8_T, 0, 7, offsetof(mavlink_waypoint_t, autocontinue) }, \
{ "param1", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_waypoint_t, param1) }, \
{ "param2", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_waypoint_t, param2) }, \
{ "param3", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_waypoint_t, param3) }, \
{ "param4", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_waypoint_t, param4) }, \
{ "x", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_waypoint_t, x) }, \
{ "y", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_waypoint_t, y) }, \
{ "z", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_waypoint_t, z) }, \
} \
}
 
 
/**
* @brief Pack a waypoint message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param target_system System ID
* @param target_component Component ID
* @param seq Sequence
* @param frame The coordinate system of the waypoint. see MAV_FRAME in mavlink_types.h
* @param command The scheduled action for the waypoint. see MAV_COMMAND in common.xml MAVLink specs
* @param current false:0, true:1
* @param autocontinue autocontinue to next wp
* @param param1 PARAM1 / For NAV command waypoints: Radius in which the waypoint is accepted as reached, in meters
* @param param2 PARAM2 / For NAV command waypoints: Time that the MAV should stay inside the PARAM1 radius before advancing, in milliseconds
* @param param3 PARAM3 / For LOITER command waypoints: Orbit to circle around the waypoint, in meters. If positive the orbit direction should be clockwise, if negative the orbit direction should be counter-clockwise.
* @param param4 PARAM4 / For NAV and LOITER command waypoints: Yaw orientation in degrees, [0..360] 0 = NORTH
* @param x PARAM5 / local: x position, global: latitude
* @param y PARAM6 / y position: global: longitude
* @param z PARAM7 / z position: global: altitude
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_waypoint_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t target_system, uint8_t target_component, uint16_t seq, uint8_t frame, uint8_t command, uint8_t current, uint8_t autocontinue, float param1, float param2, float param3, float param4, float x, float y, float z)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[36];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
_mav_put_uint16_t(buf, 2, seq);
_mav_put_uint8_t(buf, 4, frame);
_mav_put_uint8_t(buf, 5, command);
_mav_put_uint8_t(buf, 6, current);
_mav_put_uint8_t(buf, 7, autocontinue);
_mav_put_float(buf, 8, param1);
_mav_put_float(buf, 12, param2);
_mav_put_float(buf, 16, param3);
_mav_put_float(buf, 20, param4);
_mav_put_float(buf, 24, x);
_mav_put_float(buf, 28, y);
_mav_put_float(buf, 32, z);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 36);
#else
mavlink_waypoint_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
packet.seq = seq;
packet.frame = frame;
packet.command = command;
packet.current = current;
packet.autocontinue = autocontinue;
packet.param1 = param1;
packet.param2 = param2;
packet.param3 = param3;
packet.param4 = param4;
packet.x = x;
packet.y = y;
packet.z = z;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 36);
#endif
 
msg->msgid = MAVLINK_MSG_ID_WAYPOINT;
return mavlink_finalize_message(msg, system_id, component_id, 36);
}
 
/**
* @brief Pack a waypoint message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param target_system System ID
* @param target_component Component ID
* @param seq Sequence
* @param frame The coordinate system of the waypoint. see MAV_FRAME in mavlink_types.h
* @param command The scheduled action for the waypoint. see MAV_COMMAND in common.xml MAVLink specs
* @param current false:0, true:1
* @param autocontinue autocontinue to next wp
* @param param1 PARAM1 / For NAV command waypoints: Radius in which the waypoint is accepted as reached, in meters
* @param param2 PARAM2 / For NAV command waypoints: Time that the MAV should stay inside the PARAM1 radius before advancing, in milliseconds
* @param param3 PARAM3 / For LOITER command waypoints: Orbit to circle around the waypoint, in meters. If positive the orbit direction should be clockwise, if negative the orbit direction should be counter-clockwise.
* @param param4 PARAM4 / For NAV and LOITER command waypoints: Yaw orientation in degrees, [0..360] 0 = NORTH
* @param x PARAM5 / local: x position, global: latitude
* @param y PARAM6 / y position: global: longitude
* @param z PARAM7 / z position: global: altitude
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_waypoint_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,uint16_t seq,uint8_t frame,uint8_t command,uint8_t current,uint8_t autocontinue,float param1,float param2,float param3,float param4,float x,float y,float z)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[36];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
_mav_put_uint16_t(buf, 2, seq);
_mav_put_uint8_t(buf, 4, frame);
_mav_put_uint8_t(buf, 5, command);
_mav_put_uint8_t(buf, 6, current);
_mav_put_uint8_t(buf, 7, autocontinue);
_mav_put_float(buf, 8, param1);
_mav_put_float(buf, 12, param2);
_mav_put_float(buf, 16, param3);
_mav_put_float(buf, 20, param4);
_mav_put_float(buf, 24, x);
_mav_put_float(buf, 28, y);
_mav_put_float(buf, 32, z);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 36);
#else
mavlink_waypoint_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
packet.seq = seq;
packet.frame = frame;
packet.command = command;
packet.current = current;
packet.autocontinue = autocontinue;
packet.param1 = param1;
packet.param2 = param2;
packet.param3 = param3;
packet.param4 = param4;
packet.x = x;
packet.y = y;
packet.z = z;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 36);
#endif
 
msg->msgid = MAVLINK_MSG_ID_WAYPOINT;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 36);
}
 
/**
* @brief Encode a waypoint struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param waypoint C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_waypoint_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_waypoint_t* waypoint)
{
return mavlink_msg_waypoint_pack(system_id, component_id, msg, waypoint->target_system, waypoint->target_component, waypoint->seq, waypoint->frame, waypoint->command, waypoint->current, waypoint->autocontinue, waypoint->param1, waypoint->param2, waypoint->param3, waypoint->param4, waypoint->x, waypoint->y, waypoint->z);
}
 
/**
* @brief Send a waypoint message
* @param chan MAVLink channel to send the message
*
* @param target_system System ID
* @param target_component Component ID
* @param seq Sequence
* @param frame The coordinate system of the waypoint. see MAV_FRAME in mavlink_types.h
* @param command The scheduled action for the waypoint. see MAV_COMMAND in common.xml MAVLink specs
* @param current false:0, true:1
* @param autocontinue autocontinue to next wp
* @param param1 PARAM1 / For NAV command waypoints: Radius in which the waypoint is accepted as reached, in meters
* @param param2 PARAM2 / For NAV command waypoints: Time that the MAV should stay inside the PARAM1 radius before advancing, in milliseconds
* @param param3 PARAM3 / For LOITER command waypoints: Orbit to circle around the waypoint, in meters. If positive the orbit direction should be clockwise, if negative the orbit direction should be counter-clockwise.
* @param param4 PARAM4 / For NAV and LOITER command waypoints: Yaw orientation in degrees, [0..360] 0 = NORTH
* @param x PARAM5 / local: x position, global: latitude
* @param y PARAM6 / y position: global: longitude
* @param z PARAM7 / z position: global: altitude
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_waypoint_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t seq, uint8_t frame, uint8_t command, uint8_t current, uint8_t autocontinue, float param1, float param2, float param3, float param4, float x, float y, float z)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[36];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
_mav_put_uint16_t(buf, 2, seq);
_mav_put_uint8_t(buf, 4, frame);
_mav_put_uint8_t(buf, 5, command);
_mav_put_uint8_t(buf, 6, current);
_mav_put_uint8_t(buf, 7, autocontinue);
_mav_put_float(buf, 8, param1);
_mav_put_float(buf, 12, param2);
_mav_put_float(buf, 16, param3);
_mav_put_float(buf, 20, param4);
_mav_put_float(buf, 24, x);
_mav_put_float(buf, 28, y);
_mav_put_float(buf, 32, z);
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WAYPOINT, buf, 36);
#else
mavlink_waypoint_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
packet.seq = seq;
packet.frame = frame;
packet.command = command;
packet.current = current;
packet.autocontinue = autocontinue;
packet.param1 = param1;
packet.param2 = param2;
packet.param3 = param3;
packet.param4 = param4;
packet.x = x;
packet.y = y;
packet.z = z;
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WAYPOINT, (const char *)&packet, 36);
#endif
}
 
#endif
 
// MESSAGE WAYPOINT UNPACKING
 
 
/**
* @brief Get field target_system from waypoint message
*
* @return System ID
*/
static inline uint8_t mavlink_msg_waypoint_get_target_system(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 0);
}
 
/**
* @brief Get field target_component from waypoint message
*
* @return Component ID
*/
static inline uint8_t mavlink_msg_waypoint_get_target_component(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 1);
}
 
/**
* @brief Get field seq from waypoint message
*
* @return Sequence
*/
static inline uint16_t mavlink_msg_waypoint_get_seq(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 2);
}
 
/**
* @brief Get field frame from waypoint message
*
* @return The coordinate system of the waypoint. see MAV_FRAME in mavlink_types.h
*/
static inline uint8_t mavlink_msg_waypoint_get_frame(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 4);
}
 
/**
* @brief Get field command from waypoint message
*
* @return The scheduled action for the waypoint. see MAV_COMMAND in common.xml MAVLink specs
*/
static inline uint8_t mavlink_msg_waypoint_get_command(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 5);
}
 
/**
* @brief Get field current from waypoint message
*
* @return false:0, true:1
*/
static inline uint8_t mavlink_msg_waypoint_get_current(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 6);
}
 
/**
* @brief Get field autocontinue from waypoint message
*
* @return autocontinue to next wp
*/
static inline uint8_t mavlink_msg_waypoint_get_autocontinue(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 7);
}
 
/**
* @brief Get field param1 from waypoint message
*
* @return PARAM1 / For NAV command waypoints: Radius in which the waypoint is accepted as reached, in meters
*/
static inline float mavlink_msg_waypoint_get_param1(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 8);
}
 
/**
* @brief Get field param2 from waypoint message
*
* @return PARAM2 / For NAV command waypoints: Time that the MAV should stay inside the PARAM1 radius before advancing, in milliseconds
*/
static inline float mavlink_msg_waypoint_get_param2(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 12);
}
 
/**
* @brief Get field param3 from waypoint message
*
* @return PARAM3 / For LOITER command waypoints: Orbit to circle around the waypoint, in meters. If positive the orbit direction should be clockwise, if negative the orbit direction should be counter-clockwise.
*/
static inline float mavlink_msg_waypoint_get_param3(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 16);
}
 
/**
* @brief Get field param4 from waypoint message
*
* @return PARAM4 / For NAV and LOITER command waypoints: Yaw orientation in degrees, [0..360] 0 = NORTH
*/
static inline float mavlink_msg_waypoint_get_param4(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 20);
}
 
/**
* @brief Get field x from waypoint message
*
* @return PARAM5 / local: x position, global: latitude
*/
static inline float mavlink_msg_waypoint_get_x(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 24);
}
 
/**
* @brief Get field y from waypoint message
*
* @return PARAM6 / y position: global: longitude
*/
static inline float mavlink_msg_waypoint_get_y(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 28);
}
 
/**
* @brief Get field z from waypoint message
*
* @return PARAM7 / z position: global: altitude
*/
static inline float mavlink_msg_waypoint_get_z(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 32);
}
 
/**
* @brief Decode a waypoint message into a struct
*
* @param msg The message to decode
* @param waypoint C-struct to decode the message contents into
*/
static inline void mavlink_msg_waypoint_decode(const mavlink_message_t* msg, mavlink_waypoint_t* waypoint)
{
#if MAVLINK_NEED_BYTE_SWAP
waypoint->target_system = mavlink_msg_waypoint_get_target_system(msg);
waypoint->target_component = mavlink_msg_waypoint_get_target_component(msg);
waypoint->seq = mavlink_msg_waypoint_get_seq(msg);
waypoint->frame = mavlink_msg_waypoint_get_frame(msg);
waypoint->command = mavlink_msg_waypoint_get_command(msg);
waypoint->current = mavlink_msg_waypoint_get_current(msg);
waypoint->autocontinue = mavlink_msg_waypoint_get_autocontinue(msg);
waypoint->param1 = mavlink_msg_waypoint_get_param1(msg);
waypoint->param2 = mavlink_msg_waypoint_get_param2(msg);
waypoint->param3 = mavlink_msg_waypoint_get_param3(msg);
waypoint->param4 = mavlink_msg_waypoint_get_param4(msg);
waypoint->x = mavlink_msg_waypoint_get_x(msg);
waypoint->y = mavlink_msg_waypoint_get_y(msg);
waypoint->z = mavlink_msg_waypoint_get_z(msg);
#else
memcpy(waypoint, _MAV_PAYLOAD(msg), 36);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v0.9/common/mavlink_msg_waypoint_ack.h
0,0 → 1,188
// MESSAGE WAYPOINT_ACK PACKING
 
#define MAVLINK_MSG_ID_WAYPOINT_ACK 47
 
typedef struct __mavlink_waypoint_ack_t
{
uint8_t target_system; ///< System ID
uint8_t target_component; ///< Component ID
uint8_t type; ///< 0: OK, 1: Error
} mavlink_waypoint_ack_t;
 
#define MAVLINK_MSG_ID_WAYPOINT_ACK_LEN 3
#define MAVLINK_MSG_ID_47_LEN 3
 
 
 
#define MAVLINK_MESSAGE_INFO_WAYPOINT_ACK { \
"WAYPOINT_ACK", \
3, \
{ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_waypoint_ack_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_waypoint_ack_t, target_component) }, \
{ "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_waypoint_ack_t, type) }, \
} \
}
 
 
/**
* @brief Pack a waypoint_ack message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param target_system System ID
* @param target_component Component ID
* @param type 0: OK, 1: Error
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_waypoint_ack_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t target_system, uint8_t target_component, uint8_t type)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[3];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
_mav_put_uint8_t(buf, 2, type);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 3);
#else
mavlink_waypoint_ack_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
packet.type = type;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 3);
#endif
 
msg->msgid = MAVLINK_MSG_ID_WAYPOINT_ACK;
return mavlink_finalize_message(msg, system_id, component_id, 3);
}
 
/**
* @brief Pack a waypoint_ack message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param target_system System ID
* @param target_component Component ID
* @param type 0: OK, 1: Error
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_waypoint_ack_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 type)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[3];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
_mav_put_uint8_t(buf, 2, type);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 3);
#else
mavlink_waypoint_ack_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
packet.type = type;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 3);
#endif
 
msg->msgid = MAVLINK_MSG_ID_WAYPOINT_ACK;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 3);
}
 
/**
* @brief Encode a waypoint_ack struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param waypoint_ack C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_waypoint_ack_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_waypoint_ack_t* waypoint_ack)
{
return mavlink_msg_waypoint_ack_pack(system_id, component_id, msg, waypoint_ack->target_system, waypoint_ack->target_component, waypoint_ack->type);
}
 
/**
* @brief Send a waypoint_ack message
* @param chan MAVLink channel to send the message
*
* @param target_system System ID
* @param target_component Component ID
* @param type 0: OK, 1: Error
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_waypoint_ack_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t type)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[3];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
_mav_put_uint8_t(buf, 2, type);
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WAYPOINT_ACK, buf, 3);
#else
mavlink_waypoint_ack_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
packet.type = type;
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WAYPOINT_ACK, (const char *)&packet, 3);
#endif
}
 
#endif
 
// MESSAGE WAYPOINT_ACK UNPACKING
 
 
/**
* @brief Get field target_system from waypoint_ack message
*
* @return System ID
*/
static inline uint8_t mavlink_msg_waypoint_ack_get_target_system(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 0);
}
 
/**
* @brief Get field target_component from waypoint_ack message
*
* @return Component ID
*/
static inline uint8_t mavlink_msg_waypoint_ack_get_target_component(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 1);
}
 
/**
* @brief Get field type from waypoint_ack message
*
* @return 0: OK, 1: Error
*/
static inline uint8_t mavlink_msg_waypoint_ack_get_type(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 2);
}
 
/**
* @brief Decode a waypoint_ack message into a struct
*
* @param msg The message to decode
* @param waypoint_ack C-struct to decode the message contents into
*/
static inline void mavlink_msg_waypoint_ack_decode(const mavlink_message_t* msg, mavlink_waypoint_ack_t* waypoint_ack)
{
#if MAVLINK_NEED_BYTE_SWAP
waypoint_ack->target_system = mavlink_msg_waypoint_ack_get_target_system(msg);
waypoint_ack->target_component = mavlink_msg_waypoint_ack_get_target_component(msg);
waypoint_ack->type = mavlink_msg_waypoint_ack_get_type(msg);
#else
memcpy(waypoint_ack, _MAV_PAYLOAD(msg), 3);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v0.9/common/mavlink_msg_waypoint_clear_all.h
0,0 → 1,166
// MESSAGE WAYPOINT_CLEAR_ALL PACKING
 
#define MAVLINK_MSG_ID_WAYPOINT_CLEAR_ALL 45
 
typedef struct __mavlink_waypoint_clear_all_t
{
uint8_t target_system; ///< System ID
uint8_t target_component; ///< Component ID
} mavlink_waypoint_clear_all_t;
 
#define MAVLINK_MSG_ID_WAYPOINT_CLEAR_ALL_LEN 2
#define MAVLINK_MSG_ID_45_LEN 2
 
 
 
#define MAVLINK_MESSAGE_INFO_WAYPOINT_CLEAR_ALL { \
"WAYPOINT_CLEAR_ALL", \
2, \
{ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_waypoint_clear_all_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_waypoint_clear_all_t, target_component) }, \
} \
}
 
 
/**
* @brief Pack a waypoint_clear_all message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param target_system System ID
* @param target_component Component ID
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_waypoint_clear_all_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t target_system, uint8_t target_component)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[2];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 2);
#else
mavlink_waypoint_clear_all_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 2);
#endif
 
msg->msgid = MAVLINK_MSG_ID_WAYPOINT_CLEAR_ALL;
return mavlink_finalize_message(msg, system_id, component_id, 2);
}
 
/**
* @brief Pack a waypoint_clear_all message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param target_system System ID
* @param target_component Component ID
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_waypoint_clear_all_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)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[2];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 2);
#else
mavlink_waypoint_clear_all_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 2);
#endif
 
msg->msgid = MAVLINK_MSG_ID_WAYPOINT_CLEAR_ALL;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 2);
}
 
/**
* @brief Encode a waypoint_clear_all struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param waypoint_clear_all C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_waypoint_clear_all_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_waypoint_clear_all_t* waypoint_clear_all)
{
return mavlink_msg_waypoint_clear_all_pack(system_id, component_id, msg, waypoint_clear_all->target_system, waypoint_clear_all->target_component);
}
 
/**
* @brief Send a waypoint_clear_all message
* @param chan MAVLink channel to send the message
*
* @param target_system System ID
* @param target_component Component ID
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_waypoint_clear_all_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[2];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WAYPOINT_CLEAR_ALL, buf, 2);
#else
mavlink_waypoint_clear_all_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WAYPOINT_CLEAR_ALL, (const char *)&packet, 2);
#endif
}
 
#endif
 
// MESSAGE WAYPOINT_CLEAR_ALL UNPACKING
 
 
/**
* @brief Get field target_system from waypoint_clear_all message
*
* @return System ID
*/
static inline uint8_t mavlink_msg_waypoint_clear_all_get_target_system(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 0);
}
 
/**
* @brief Get field target_component from waypoint_clear_all message
*
* @return Component ID
*/
static inline uint8_t mavlink_msg_waypoint_clear_all_get_target_component(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 1);
}
 
/**
* @brief Decode a waypoint_clear_all message into a struct
*
* @param msg The message to decode
* @param waypoint_clear_all C-struct to decode the message contents into
*/
static inline void mavlink_msg_waypoint_clear_all_decode(const mavlink_message_t* msg, mavlink_waypoint_clear_all_t* waypoint_clear_all)
{
#if MAVLINK_NEED_BYTE_SWAP
waypoint_clear_all->target_system = mavlink_msg_waypoint_clear_all_get_target_system(msg);
waypoint_clear_all->target_component = mavlink_msg_waypoint_clear_all_get_target_component(msg);
#else
memcpy(waypoint_clear_all, _MAV_PAYLOAD(msg), 2);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v0.9/common/mavlink_msg_waypoint_count.h
0,0 → 1,188
// MESSAGE WAYPOINT_COUNT PACKING
 
#define MAVLINK_MSG_ID_WAYPOINT_COUNT 44
 
typedef struct __mavlink_waypoint_count_t
{
uint8_t target_system; ///< System ID
uint8_t target_component; ///< Component ID
uint16_t count; ///< Number of Waypoints in the Sequence
} mavlink_waypoint_count_t;
 
#define MAVLINK_MSG_ID_WAYPOINT_COUNT_LEN 4
#define MAVLINK_MSG_ID_44_LEN 4
 
 
 
#define MAVLINK_MESSAGE_INFO_WAYPOINT_COUNT { \
"WAYPOINT_COUNT", \
3, \
{ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_waypoint_count_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_waypoint_count_t, target_component) }, \
{ "count", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_waypoint_count_t, count) }, \
} \
}
 
 
/**
* @brief Pack a waypoint_count message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param target_system System ID
* @param target_component Component ID
* @param count Number of Waypoints in the Sequence
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_waypoint_count_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t target_system, uint8_t target_component, uint16_t count)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[4];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
_mav_put_uint16_t(buf, 2, count);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 4);
#else
mavlink_waypoint_count_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
packet.count = count;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 4);
#endif
 
msg->msgid = MAVLINK_MSG_ID_WAYPOINT_COUNT;
return mavlink_finalize_message(msg, system_id, component_id, 4);
}
 
/**
* @brief Pack a waypoint_count message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param target_system System ID
* @param target_component Component ID
* @param count Number of Waypoints in the Sequence
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_waypoint_count_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,uint16_t count)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[4];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
_mav_put_uint16_t(buf, 2, count);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 4);
#else
mavlink_waypoint_count_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
packet.count = count;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 4);
#endif
 
msg->msgid = MAVLINK_MSG_ID_WAYPOINT_COUNT;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 4);
}
 
/**
* @brief Encode a waypoint_count struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param waypoint_count C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_waypoint_count_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_waypoint_count_t* waypoint_count)
{
return mavlink_msg_waypoint_count_pack(system_id, component_id, msg, waypoint_count->target_system, waypoint_count->target_component, waypoint_count->count);
}
 
/**
* @brief Send a waypoint_count message
* @param chan MAVLink channel to send the message
*
* @param target_system System ID
* @param target_component Component ID
* @param count Number of Waypoints in the Sequence
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_waypoint_count_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t count)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[4];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
_mav_put_uint16_t(buf, 2, count);
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WAYPOINT_COUNT, buf, 4);
#else
mavlink_waypoint_count_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
packet.count = count;
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WAYPOINT_COUNT, (const char *)&packet, 4);
#endif
}
 
#endif
 
// MESSAGE WAYPOINT_COUNT UNPACKING
 
 
/**
* @brief Get field target_system from waypoint_count message
*
* @return System ID
*/
static inline uint8_t mavlink_msg_waypoint_count_get_target_system(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 0);
}
 
/**
* @brief Get field target_component from waypoint_count message
*
* @return Component ID
*/
static inline uint8_t mavlink_msg_waypoint_count_get_target_component(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 1);
}
 
/**
* @brief Get field count from waypoint_count message
*
* @return Number of Waypoints in the Sequence
*/
static inline uint16_t mavlink_msg_waypoint_count_get_count(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 2);
}
 
/**
* @brief Decode a waypoint_count message into a struct
*
* @param msg The message to decode
* @param waypoint_count C-struct to decode the message contents into
*/
static inline void mavlink_msg_waypoint_count_decode(const mavlink_message_t* msg, mavlink_waypoint_count_t* waypoint_count)
{
#if MAVLINK_NEED_BYTE_SWAP
waypoint_count->target_system = mavlink_msg_waypoint_count_get_target_system(msg);
waypoint_count->target_component = mavlink_msg_waypoint_count_get_target_component(msg);
waypoint_count->count = mavlink_msg_waypoint_count_get_count(msg);
#else
memcpy(waypoint_count, _MAV_PAYLOAD(msg), 4);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v0.9/common/mavlink_msg_waypoint_current.h
0,0 → 1,144
// MESSAGE WAYPOINT_CURRENT PACKING
 
#define MAVLINK_MSG_ID_WAYPOINT_CURRENT 42
 
typedef struct __mavlink_waypoint_current_t
{
uint16_t seq; ///< Sequence
} mavlink_waypoint_current_t;
 
#define MAVLINK_MSG_ID_WAYPOINT_CURRENT_LEN 2
#define MAVLINK_MSG_ID_42_LEN 2
 
 
 
#define MAVLINK_MESSAGE_INFO_WAYPOINT_CURRENT { \
"WAYPOINT_CURRENT", \
1, \
{ { "seq", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_waypoint_current_t, seq) }, \
} \
}
 
 
/**
* @brief Pack a waypoint_current message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param seq Sequence
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_waypoint_current_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint16_t seq)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[2];
_mav_put_uint16_t(buf, 0, seq);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 2);
#else
mavlink_waypoint_current_t packet;
packet.seq = seq;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 2);
#endif
 
msg->msgid = MAVLINK_MSG_ID_WAYPOINT_CURRENT;
return mavlink_finalize_message(msg, system_id, component_id, 2);
}
 
/**
* @brief Pack a waypoint_current message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param seq Sequence
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_waypoint_current_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint16_t seq)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[2];
_mav_put_uint16_t(buf, 0, seq);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 2);
#else
mavlink_waypoint_current_t packet;
packet.seq = seq;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 2);
#endif
 
msg->msgid = MAVLINK_MSG_ID_WAYPOINT_CURRENT;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 2);
}
 
/**
* @brief Encode a waypoint_current struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param waypoint_current C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_waypoint_current_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_waypoint_current_t* waypoint_current)
{
return mavlink_msg_waypoint_current_pack(system_id, component_id, msg, waypoint_current->seq);
}
 
/**
* @brief Send a waypoint_current message
* @param chan MAVLink channel to send the message
*
* @param seq Sequence
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_waypoint_current_send(mavlink_channel_t chan, uint16_t seq)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[2];
_mav_put_uint16_t(buf, 0, seq);
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WAYPOINT_CURRENT, buf, 2);
#else
mavlink_waypoint_current_t packet;
packet.seq = seq;
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WAYPOINT_CURRENT, (const char *)&packet, 2);
#endif
}
 
#endif
 
// MESSAGE WAYPOINT_CURRENT UNPACKING
 
 
/**
* @brief Get field seq from waypoint_current message
*
* @return Sequence
*/
static inline uint16_t mavlink_msg_waypoint_current_get_seq(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 0);
}
 
/**
* @brief Decode a waypoint_current message into a struct
*
* @param msg The message to decode
* @param waypoint_current C-struct to decode the message contents into
*/
static inline void mavlink_msg_waypoint_current_decode(const mavlink_message_t* msg, mavlink_waypoint_current_t* waypoint_current)
{
#if MAVLINK_NEED_BYTE_SWAP
waypoint_current->seq = mavlink_msg_waypoint_current_get_seq(msg);
#else
memcpy(waypoint_current, _MAV_PAYLOAD(msg), 2);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v0.9/common/mavlink_msg_waypoint_reached.h
0,0 → 1,144
// MESSAGE WAYPOINT_REACHED PACKING
 
#define MAVLINK_MSG_ID_WAYPOINT_REACHED 46
 
typedef struct __mavlink_waypoint_reached_t
{
uint16_t seq; ///< Sequence
} mavlink_waypoint_reached_t;
 
#define MAVLINK_MSG_ID_WAYPOINT_REACHED_LEN 2
#define MAVLINK_MSG_ID_46_LEN 2
 
 
 
#define MAVLINK_MESSAGE_INFO_WAYPOINT_REACHED { \
"WAYPOINT_REACHED", \
1, \
{ { "seq", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_waypoint_reached_t, seq) }, \
} \
}
 
 
/**
* @brief Pack a waypoint_reached message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param seq Sequence
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_waypoint_reached_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint16_t seq)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[2];
_mav_put_uint16_t(buf, 0, seq);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 2);
#else
mavlink_waypoint_reached_t packet;
packet.seq = seq;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 2);
#endif
 
msg->msgid = MAVLINK_MSG_ID_WAYPOINT_REACHED;
return mavlink_finalize_message(msg, system_id, component_id, 2);
}
 
/**
* @brief Pack a waypoint_reached message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param seq Sequence
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_waypoint_reached_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint16_t seq)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[2];
_mav_put_uint16_t(buf, 0, seq);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 2);
#else
mavlink_waypoint_reached_t packet;
packet.seq = seq;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 2);
#endif
 
msg->msgid = MAVLINK_MSG_ID_WAYPOINT_REACHED;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 2);
}
 
/**
* @brief Encode a waypoint_reached struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param waypoint_reached C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_waypoint_reached_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_waypoint_reached_t* waypoint_reached)
{
return mavlink_msg_waypoint_reached_pack(system_id, component_id, msg, waypoint_reached->seq);
}
 
/**
* @brief Send a waypoint_reached message
* @param chan MAVLink channel to send the message
*
* @param seq Sequence
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_waypoint_reached_send(mavlink_channel_t chan, uint16_t seq)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[2];
_mav_put_uint16_t(buf, 0, seq);
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WAYPOINT_REACHED, buf, 2);
#else
mavlink_waypoint_reached_t packet;
packet.seq = seq;
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WAYPOINT_REACHED, (const char *)&packet, 2);
#endif
}
 
#endif
 
// MESSAGE WAYPOINT_REACHED UNPACKING
 
 
/**
* @brief Get field seq from waypoint_reached message
*
* @return Sequence
*/
static inline uint16_t mavlink_msg_waypoint_reached_get_seq(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 0);
}
 
/**
* @brief Decode a waypoint_reached message into a struct
*
* @param msg The message to decode
* @param waypoint_reached C-struct to decode the message contents into
*/
static inline void mavlink_msg_waypoint_reached_decode(const mavlink_message_t* msg, mavlink_waypoint_reached_t* waypoint_reached)
{
#if MAVLINK_NEED_BYTE_SWAP
waypoint_reached->seq = mavlink_msg_waypoint_reached_get_seq(msg);
#else
memcpy(waypoint_reached, _MAV_PAYLOAD(msg), 2);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v0.9/common/mavlink_msg_waypoint_request.h
0,0 → 1,188
// MESSAGE WAYPOINT_REQUEST PACKING
 
#define MAVLINK_MSG_ID_WAYPOINT_REQUEST 40
 
typedef struct __mavlink_waypoint_request_t
{
uint8_t target_system; ///< System ID
uint8_t target_component; ///< Component ID
uint16_t seq; ///< Sequence
} mavlink_waypoint_request_t;
 
#define MAVLINK_MSG_ID_WAYPOINT_REQUEST_LEN 4
#define MAVLINK_MSG_ID_40_LEN 4
 
 
 
#define MAVLINK_MESSAGE_INFO_WAYPOINT_REQUEST { \
"WAYPOINT_REQUEST", \
3, \
{ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_waypoint_request_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_waypoint_request_t, target_component) }, \
{ "seq", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_waypoint_request_t, seq) }, \
} \
}
 
 
/**
* @brief Pack a waypoint_request message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param target_system System ID
* @param target_component Component ID
* @param seq Sequence
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_waypoint_request_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t target_system, uint8_t target_component, uint16_t seq)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[4];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
_mav_put_uint16_t(buf, 2, seq);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 4);
#else
mavlink_waypoint_request_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
packet.seq = seq;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 4);
#endif
 
msg->msgid = MAVLINK_MSG_ID_WAYPOINT_REQUEST;
return mavlink_finalize_message(msg, system_id, component_id, 4);
}
 
/**
* @brief Pack a waypoint_request message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param target_system System ID
* @param target_component Component ID
* @param seq Sequence
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_waypoint_request_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,uint16_t seq)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[4];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
_mav_put_uint16_t(buf, 2, seq);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 4);
#else
mavlink_waypoint_request_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
packet.seq = seq;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 4);
#endif
 
msg->msgid = MAVLINK_MSG_ID_WAYPOINT_REQUEST;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 4);
}
 
/**
* @brief Encode a waypoint_request struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param waypoint_request C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_waypoint_request_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_waypoint_request_t* waypoint_request)
{
return mavlink_msg_waypoint_request_pack(system_id, component_id, msg, waypoint_request->target_system, waypoint_request->target_component, waypoint_request->seq);
}
 
/**
* @brief Send a waypoint_request message
* @param chan MAVLink channel to send the message
*
* @param target_system System ID
* @param target_component Component ID
* @param seq Sequence
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_waypoint_request_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t seq)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[4];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
_mav_put_uint16_t(buf, 2, seq);
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WAYPOINT_REQUEST, buf, 4);
#else
mavlink_waypoint_request_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
packet.seq = seq;
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WAYPOINT_REQUEST, (const char *)&packet, 4);
#endif
}
 
#endif
 
// MESSAGE WAYPOINT_REQUEST UNPACKING
 
 
/**
* @brief Get field target_system from waypoint_request message
*
* @return System ID
*/
static inline uint8_t mavlink_msg_waypoint_request_get_target_system(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 0);
}
 
/**
* @brief Get field target_component from waypoint_request message
*
* @return Component ID
*/
static inline uint8_t mavlink_msg_waypoint_request_get_target_component(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 1);
}
 
/**
* @brief Get field seq from waypoint_request message
*
* @return Sequence
*/
static inline uint16_t mavlink_msg_waypoint_request_get_seq(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 2);
}
 
/**
* @brief Decode a waypoint_request message into a struct
*
* @param msg The message to decode
* @param waypoint_request C-struct to decode the message contents into
*/
static inline void mavlink_msg_waypoint_request_decode(const mavlink_message_t* msg, mavlink_waypoint_request_t* waypoint_request)
{
#if MAVLINK_NEED_BYTE_SWAP
waypoint_request->target_system = mavlink_msg_waypoint_request_get_target_system(msg);
waypoint_request->target_component = mavlink_msg_waypoint_request_get_target_component(msg);
waypoint_request->seq = mavlink_msg_waypoint_request_get_seq(msg);
#else
memcpy(waypoint_request, _MAV_PAYLOAD(msg), 4);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v0.9/common/mavlink_msg_waypoint_request_list.h
0,0 → 1,166
// MESSAGE WAYPOINT_REQUEST_LIST PACKING
 
#define MAVLINK_MSG_ID_WAYPOINT_REQUEST_LIST 43
 
typedef struct __mavlink_waypoint_request_list_t
{
uint8_t target_system; ///< System ID
uint8_t target_component; ///< Component ID
} mavlink_waypoint_request_list_t;
 
#define MAVLINK_MSG_ID_WAYPOINT_REQUEST_LIST_LEN 2
#define MAVLINK_MSG_ID_43_LEN 2
 
 
 
#define MAVLINK_MESSAGE_INFO_WAYPOINT_REQUEST_LIST { \
"WAYPOINT_REQUEST_LIST", \
2, \
{ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_waypoint_request_list_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_waypoint_request_list_t, target_component) }, \
} \
}
 
 
/**
* @brief Pack a waypoint_request_list message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param target_system System ID
* @param target_component Component ID
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_waypoint_request_list_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t target_system, uint8_t target_component)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[2];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 2);
#else
mavlink_waypoint_request_list_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 2);
#endif
 
msg->msgid = MAVLINK_MSG_ID_WAYPOINT_REQUEST_LIST;
return mavlink_finalize_message(msg, system_id, component_id, 2);
}
 
/**
* @brief Pack a waypoint_request_list message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param target_system System ID
* @param target_component Component ID
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_waypoint_request_list_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)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[2];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 2);
#else
mavlink_waypoint_request_list_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 2);
#endif
 
msg->msgid = MAVLINK_MSG_ID_WAYPOINT_REQUEST_LIST;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 2);
}
 
/**
* @brief Encode a waypoint_request_list struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param waypoint_request_list C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_waypoint_request_list_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_waypoint_request_list_t* waypoint_request_list)
{
return mavlink_msg_waypoint_request_list_pack(system_id, component_id, msg, waypoint_request_list->target_system, waypoint_request_list->target_component);
}
 
/**
* @brief Send a waypoint_request_list message
* @param chan MAVLink channel to send the message
*
* @param target_system System ID
* @param target_component Component ID
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_waypoint_request_list_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[2];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WAYPOINT_REQUEST_LIST, buf, 2);
#else
mavlink_waypoint_request_list_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WAYPOINT_REQUEST_LIST, (const char *)&packet, 2);
#endif
}
 
#endif
 
// MESSAGE WAYPOINT_REQUEST_LIST UNPACKING
 
 
/**
* @brief Get field target_system from waypoint_request_list message
*
* @return System ID
*/
static inline uint8_t mavlink_msg_waypoint_request_list_get_target_system(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 0);
}
 
/**
* @brief Get field target_component from waypoint_request_list message
*
* @return Component ID
*/
static inline uint8_t mavlink_msg_waypoint_request_list_get_target_component(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 1);
}
 
/**
* @brief Decode a waypoint_request_list message into a struct
*
* @param msg The message to decode
* @param waypoint_request_list C-struct to decode the message contents into
*/
static inline void mavlink_msg_waypoint_request_list_decode(const mavlink_message_t* msg, mavlink_waypoint_request_list_t* waypoint_request_list)
{
#if MAVLINK_NEED_BYTE_SWAP
waypoint_request_list->target_system = mavlink_msg_waypoint_request_list_get_target_system(msg);
waypoint_request_list->target_component = mavlink_msg_waypoint_request_list_get_target_component(msg);
#else
memcpy(waypoint_request_list, _MAV_PAYLOAD(msg), 2);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v0.9/common/mavlink_msg_waypoint_set_current.h
0,0 → 1,188
// MESSAGE WAYPOINT_SET_CURRENT PACKING
 
#define MAVLINK_MSG_ID_WAYPOINT_SET_CURRENT 41
 
typedef struct __mavlink_waypoint_set_current_t
{
uint8_t target_system; ///< System ID
uint8_t target_component; ///< Component ID
uint16_t seq; ///< Sequence
} mavlink_waypoint_set_current_t;
 
#define MAVLINK_MSG_ID_WAYPOINT_SET_CURRENT_LEN 4
#define MAVLINK_MSG_ID_41_LEN 4
 
 
 
#define MAVLINK_MESSAGE_INFO_WAYPOINT_SET_CURRENT { \
"WAYPOINT_SET_CURRENT", \
3, \
{ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_waypoint_set_current_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_waypoint_set_current_t, target_component) }, \
{ "seq", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_waypoint_set_current_t, seq) }, \
} \
}
 
 
/**
* @brief Pack a waypoint_set_current message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param target_system System ID
* @param target_component Component ID
* @param seq Sequence
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_waypoint_set_current_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t target_system, uint8_t target_component, uint16_t seq)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[4];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
_mav_put_uint16_t(buf, 2, seq);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 4);
#else
mavlink_waypoint_set_current_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
packet.seq = seq;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 4);
#endif
 
msg->msgid = MAVLINK_MSG_ID_WAYPOINT_SET_CURRENT;
return mavlink_finalize_message(msg, system_id, component_id, 4);
}
 
/**
* @brief Pack a waypoint_set_current message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param target_system System ID
* @param target_component Component ID
* @param seq Sequence
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_waypoint_set_current_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,uint16_t seq)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[4];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
_mav_put_uint16_t(buf, 2, seq);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 4);
#else
mavlink_waypoint_set_current_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
packet.seq = seq;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 4);
#endif
 
msg->msgid = MAVLINK_MSG_ID_WAYPOINT_SET_CURRENT;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 4);
}
 
/**
* @brief Encode a waypoint_set_current struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param waypoint_set_current C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_waypoint_set_current_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_waypoint_set_current_t* waypoint_set_current)
{
return mavlink_msg_waypoint_set_current_pack(system_id, component_id, msg, waypoint_set_current->target_system, waypoint_set_current->target_component, waypoint_set_current->seq);
}
 
/**
* @brief Send a waypoint_set_current message
* @param chan MAVLink channel to send the message
*
* @param target_system System ID
* @param target_component Component ID
* @param seq Sequence
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_waypoint_set_current_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t seq)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[4];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
_mav_put_uint16_t(buf, 2, seq);
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WAYPOINT_SET_CURRENT, buf, 4);
#else
mavlink_waypoint_set_current_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
packet.seq = seq;
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_WAYPOINT_SET_CURRENT, (const char *)&packet, 4);
#endif
}
 
#endif
 
// MESSAGE WAYPOINT_SET_CURRENT UNPACKING
 
 
/**
* @brief Get field target_system from waypoint_set_current message
*
* @return System ID
*/
static inline uint8_t mavlink_msg_waypoint_set_current_get_target_system(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 0);
}
 
/**
* @brief Get field target_component from waypoint_set_current message
*
* @return Component ID
*/
static inline uint8_t mavlink_msg_waypoint_set_current_get_target_component(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 1);
}
 
/**
* @brief Get field seq from waypoint_set_current message
*
* @return Sequence
*/
static inline uint16_t mavlink_msg_waypoint_set_current_get_seq(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 2);
}
 
/**
* @brief Decode a waypoint_set_current message into a struct
*
* @param msg The message to decode
* @param waypoint_set_current C-struct to decode the message contents into
*/
static inline void mavlink_msg_waypoint_set_current_decode(const mavlink_message_t* msg, mavlink_waypoint_set_current_t* waypoint_set_current)
{
#if MAVLINK_NEED_BYTE_SWAP
waypoint_set_current->target_system = mavlink_msg_waypoint_set_current_get_target_system(msg);
waypoint_set_current->target_component = mavlink_msg_waypoint_set_current_get_target_component(msg);
waypoint_set_current->seq = mavlink_msg_waypoint_set_current_get_seq(msg);
#else
memcpy(waypoint_set_current, _MAV_PAYLOAD(msg), 4);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v0.9/common/testsuite.h
0,0 → 1,3700
/** @file
* @brief MAVLink comm protocol testsuite generated from common.xml
* @see http://qgroundcontrol.org/mavlink/
*/
#ifndef COMMON_TESTSUITE_H
#define COMMON_TESTSUITE_H
 
#ifdef __cplusplus
extern "C" {
#endif
 
#ifndef MAVLINK_TEST_ALL
#define MAVLINK_TEST_ALL
 
static void mavlink_test_common(uint8_t, uint8_t, mavlink_message_t *last_msg);
 
static void mavlink_test_all(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
 
mavlink_test_common(system_id, component_id, last_msg);
}
#endif
 
 
 
 
static void mavlink_test_heartbeat(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_heartbeat_t packet_in = {
5,
72,
2,
};
mavlink_heartbeat_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.type = packet_in.type;
packet1.autopilot = packet_in.autopilot;
packet1.mavlink_version = packet_in.mavlink_version;
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_heartbeat_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_heartbeat_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_heartbeat_pack(system_id, component_id, &msg , packet1.type , packet1.autopilot );
mavlink_msg_heartbeat_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_heartbeat_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.type , packet1.autopilot );
mavlink_msg_heartbeat_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_heartbeat_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_heartbeat_send(MAVLINK_COMM_1 , packet1.type , packet1.autopilot );
mavlink_msg_heartbeat_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_boot(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_boot_t packet_in = {
963497464,
};
mavlink_boot_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.version = packet_in.version;
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_boot_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_boot_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_boot_pack(system_id, component_id, &msg , packet1.version );
mavlink_msg_boot_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_boot_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.version );
mavlink_msg_boot_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_boot_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_boot_send(MAVLINK_COMM_1 , packet1.version );
mavlink_msg_boot_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_system_time(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_system_time_t packet_in = {
93372036854775807ULL,
};
mavlink_system_time_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.time_usec = packet_in.time_usec;
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_system_time_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_system_time_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_system_time_pack(system_id, component_id, &msg , packet1.time_usec );
mavlink_msg_system_time_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_system_time_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_usec );
mavlink_msg_system_time_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_system_time_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_system_time_send(MAVLINK_COMM_1 , packet1.time_usec );
mavlink_msg_system_time_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_ping(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_ping_t packet_in = {
963497464,
17,
84,
93372036854776185ULL,
};
mavlink_ping_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.seq = packet_in.seq;
packet1.target_system = packet_in.target_system;
packet1.target_component = packet_in.target_component;
packet1.time = packet_in.time;
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_ping_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_ping_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_ping_pack(system_id, component_id, &msg , packet1.seq , packet1.target_system , packet1.target_component , packet1.time );
mavlink_msg_ping_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_ping_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.seq , packet1.target_system , packet1.target_component , packet1.time );
mavlink_msg_ping_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_ping_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_ping_send(MAVLINK_COMM_1 , packet1.seq , packet1.target_system , packet1.target_component , packet1.time );
mavlink_msg_ping_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_system_time_utc(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_system_time_utc_t packet_in = {
963497464,
963497672,
};
mavlink_system_time_utc_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.utc_date = packet_in.utc_date;
packet1.utc_time = packet_in.utc_time;
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_system_time_utc_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_system_time_utc_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_system_time_utc_pack(system_id, component_id, &msg , packet1.utc_date , packet1.utc_time );
mavlink_msg_system_time_utc_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_system_time_utc_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.utc_date , packet1.utc_time );
mavlink_msg_system_time_utc_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_system_time_utc_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_system_time_utc_send(MAVLINK_COMM_1 , packet1.utc_date , packet1.utc_time );
mavlink_msg_system_time_utc_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_change_operator_control(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_change_operator_control_t packet_in = {
5,
72,
139,
"DEFGHIJKLMNOPQRSTUVWXYZA",
};
mavlink_change_operator_control_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.target_system = packet_in.target_system;
packet1.control_request = packet_in.control_request;
packet1.version = packet_in.version;
mav_array_memcpy(packet1.passkey, packet_in.passkey, sizeof(char)*25);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_change_operator_control_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_change_operator_control_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_change_operator_control_pack(system_id, component_id, &msg , packet1.target_system , packet1.control_request , packet1.version , packet1.passkey );
mavlink_msg_change_operator_control_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_change_operator_control_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.control_request , packet1.version , packet1.passkey );
mavlink_msg_change_operator_control_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_change_operator_control_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_change_operator_control_send(MAVLINK_COMM_1 , packet1.target_system , packet1.control_request , packet1.version , packet1.passkey );
mavlink_msg_change_operator_control_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_change_operator_control_ack(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_change_operator_control_ack_t packet_in = {
5,
72,
139,
};
mavlink_change_operator_control_ack_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.gcs_system_id = packet_in.gcs_system_id;
packet1.control_request = packet_in.control_request;
packet1.ack = packet_in.ack;
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_change_operator_control_ack_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_change_operator_control_ack_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_change_operator_control_ack_pack(system_id, component_id, &msg , packet1.gcs_system_id , packet1.control_request , packet1.ack );
mavlink_msg_change_operator_control_ack_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_change_operator_control_ack_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.gcs_system_id , packet1.control_request , packet1.ack );
mavlink_msg_change_operator_control_ack_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_change_operator_control_ack_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_change_operator_control_ack_send(MAVLINK_COMM_1 , packet1.gcs_system_id , packet1.control_request , packet1.ack );
mavlink_msg_change_operator_control_ack_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_auth_key(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_auth_key_t packet_in = {
"ABCDEFGHIJKLMNOPQRSTUVWXYZABCDE",
};
mavlink_auth_key_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
mav_array_memcpy(packet1.key, packet_in.key, sizeof(char)*32);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_auth_key_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_auth_key_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_auth_key_pack(system_id, component_id, &msg , packet1.key );
mavlink_msg_auth_key_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_auth_key_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.key );
mavlink_msg_auth_key_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_auth_key_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_auth_key_send(MAVLINK_COMM_1 , packet1.key );
mavlink_msg_auth_key_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_action_ack(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_action_ack_t packet_in = {
5,
72,
};
mavlink_action_ack_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.action = packet_in.action;
packet1.result = packet_in.result;
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_action_ack_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_action_ack_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_action_ack_pack(system_id, component_id, &msg , packet1.action , packet1.result );
mavlink_msg_action_ack_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_action_ack_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.action , packet1.result );
mavlink_msg_action_ack_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_action_ack_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_action_ack_send(MAVLINK_COMM_1 , packet1.action , packet1.result );
mavlink_msg_action_ack_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_action(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_action_t packet_in = {
5,
72,
139,
};
mavlink_action_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.target = packet_in.target;
packet1.target_component = packet_in.target_component;
packet1.action = packet_in.action;
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_action_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_action_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_action_pack(system_id, component_id, &msg , packet1.target , packet1.target_component , packet1.action );
mavlink_msg_action_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_action_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target , packet1.target_component , packet1.action );
mavlink_msg_action_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_action_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_action_send(MAVLINK_COMM_1 , packet1.target , packet1.target_component , packet1.action );
mavlink_msg_action_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_set_mode(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_set_mode_t packet_in = {
5,
72,
};
mavlink_set_mode_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.target = packet_in.target;
packet1.mode = packet_in.mode;
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_set_mode_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_set_mode_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_set_mode_pack(system_id, component_id, &msg , packet1.target , packet1.mode );
mavlink_msg_set_mode_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_set_mode_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target , packet1.mode );
mavlink_msg_set_mode_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_set_mode_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_set_mode_send(MAVLINK_COMM_1 , packet1.target , packet1.mode );
mavlink_msg_set_mode_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_set_nav_mode(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_set_nav_mode_t packet_in = {
5,
72,
};
mavlink_set_nav_mode_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.target = packet_in.target;
packet1.nav_mode = packet_in.nav_mode;
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_set_nav_mode_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_set_nav_mode_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_set_nav_mode_pack(system_id, component_id, &msg , packet1.target , packet1.nav_mode );
mavlink_msg_set_nav_mode_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_set_nav_mode_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target , packet1.nav_mode );
mavlink_msg_set_nav_mode_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_set_nav_mode_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_set_nav_mode_send(MAVLINK_COMM_1 , packet1.target , packet1.nav_mode );
mavlink_msg_set_nav_mode_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_param_request_read(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_param_request_read_t packet_in = {
5,
72,
{ 139, 140, 141, 142, 143, 144, 145, 146, 147, 148, 149, 150, 151, 152, 153 },
18119,
};
mavlink_param_request_read_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.target_system = packet_in.target_system;
packet1.target_component = packet_in.target_component;
packet1.param_index = packet_in.param_index;
mav_array_memcpy(packet1.param_id, packet_in.param_id, sizeof(int8_t)*15);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_param_request_read_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_param_request_read_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_param_request_read_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.param_id , packet1.param_index );
mavlink_msg_param_request_read_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_param_request_read_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.param_id , packet1.param_index );
mavlink_msg_param_request_read_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_param_request_read_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_param_request_read_send(MAVLINK_COMM_1 , packet1.target_system , packet1.target_component , packet1.param_id , packet1.param_index );
mavlink_msg_param_request_read_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_param_request_list(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_param_request_list_t packet_in = {
5,
72,
};
mavlink_param_request_list_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.target_system = packet_in.target_system;
packet1.target_component = packet_in.target_component;
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_param_request_list_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_param_request_list_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_param_request_list_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component );
mavlink_msg_param_request_list_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_param_request_list_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component );
mavlink_msg_param_request_list_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_param_request_list_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_param_request_list_send(MAVLINK_COMM_1 , packet1.target_system , packet1.target_component );
mavlink_msg_param_request_list_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_param_value(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_param_value_t packet_in = {
{ 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16, 17, 18, 19 },
122.0,
18223,
18327,
};
mavlink_param_value_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.param_value = packet_in.param_value;
packet1.param_count = packet_in.param_count;
packet1.param_index = packet_in.param_index;
mav_array_memcpy(packet1.param_id, packet_in.param_id, sizeof(int8_t)*15);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_param_value_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_param_value_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_param_value_pack(system_id, component_id, &msg , packet1.param_id , packet1.param_value , packet1.param_count , packet1.param_index );
mavlink_msg_param_value_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_param_value_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.param_id , packet1.param_value , packet1.param_count , packet1.param_index );
mavlink_msg_param_value_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_param_value_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_param_value_send(MAVLINK_COMM_1 , packet1.param_id , packet1.param_value , packet1.param_count , packet1.param_index );
mavlink_msg_param_value_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_param_set(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_param_set_t packet_in = {
5,
72,
{ 139, 140, 141, 142, 143, 144, 145, 146, 147, 148, 149, 150, 151, 152, 153 },
136.0,
};
mavlink_param_set_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.target_system = packet_in.target_system;
packet1.target_component = packet_in.target_component;
packet1.param_value = packet_in.param_value;
mav_array_memcpy(packet1.param_id, packet_in.param_id, sizeof(int8_t)*15);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_param_set_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_param_set_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_param_set_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.param_id , packet1.param_value );
mavlink_msg_param_set_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_param_set_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.param_id , packet1.param_value );
mavlink_msg_param_set_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_param_set_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_param_set_send(MAVLINK_COMM_1 , packet1.target_system , packet1.target_component , packet1.param_id , packet1.param_value );
mavlink_msg_param_set_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_gps_raw_int(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_gps_raw_int_t packet_in = {
93372036854775807ULL,
29,
963497932,
963498140,
963498348,
164.0,
192.0,
220.0,
248.0,
};
mavlink_gps_raw_int_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.usec = packet_in.usec;
packet1.fix_type = packet_in.fix_type;
packet1.lat = packet_in.lat;
packet1.lon = packet_in.lon;
packet1.alt = packet_in.alt;
packet1.eph = packet_in.eph;
packet1.epv = packet_in.epv;
packet1.v = packet_in.v;
packet1.hdg = packet_in.hdg;
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_gps_raw_int_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_gps_raw_int_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_gps_raw_int_pack(system_id, component_id, &msg , packet1.usec , packet1.fix_type , packet1.lat , packet1.lon , packet1.alt , packet1.eph , packet1.epv , packet1.v , packet1.hdg );
mavlink_msg_gps_raw_int_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_gps_raw_int_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.usec , packet1.fix_type , packet1.lat , packet1.lon , packet1.alt , packet1.eph , packet1.epv , packet1.v , packet1.hdg );
mavlink_msg_gps_raw_int_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_gps_raw_int_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_gps_raw_int_send(MAVLINK_COMM_1 , packet1.usec , packet1.fix_type , packet1.lat , packet1.lon , packet1.alt , packet1.eph , packet1.epv , packet1.v , packet1.hdg );
mavlink_msg_gps_raw_int_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_scaled_imu(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_scaled_imu_t packet_in = {
93372036854775807ULL,
17651,
17755,
17859,
17963,
18067,
18171,
18275,
18379,
18483,
};
mavlink_scaled_imu_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.usec = packet_in.usec;
packet1.xacc = packet_in.xacc;
packet1.yacc = packet_in.yacc;
packet1.zacc = packet_in.zacc;
packet1.xgyro = packet_in.xgyro;
packet1.ygyro = packet_in.ygyro;
packet1.zgyro = packet_in.zgyro;
packet1.xmag = packet_in.xmag;
packet1.ymag = packet_in.ymag;
packet1.zmag = packet_in.zmag;
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_scaled_imu_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_scaled_imu_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_scaled_imu_pack(system_id, component_id, &msg , packet1.usec , packet1.xacc , packet1.yacc , packet1.zacc , packet1.xgyro , packet1.ygyro , packet1.zgyro , packet1.xmag , packet1.ymag , packet1.zmag );
mavlink_msg_scaled_imu_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_scaled_imu_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.usec , packet1.xacc , packet1.yacc , packet1.zacc , packet1.xgyro , packet1.ygyro , packet1.zgyro , packet1.xmag , packet1.ymag , packet1.zmag );
mavlink_msg_scaled_imu_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_scaled_imu_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_scaled_imu_send(MAVLINK_COMM_1 , packet1.usec , packet1.xacc , packet1.yacc , packet1.zacc , packet1.xgyro , packet1.ygyro , packet1.zgyro , packet1.xmag , packet1.ymag , packet1.zmag );
mavlink_msg_scaled_imu_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_gps_status(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_gps_status_t packet_in = {
5,
{ 72, 73, 74, 75, 76, 77, 78, 79, 80, 81, 82, 83, 84, 85, 86, 87, 88, 89, 90, 91 },
{ 132, 133, 134, 135, 136, 137, 138, 139, 140, 141, 142, 143, 144, 145, 146, 147, 148, 149, 150, 151 },
{ 192, 193, 194, 195, 196, 197, 198, 199, 200, 201, 202, 203, 204, 205, 206, 207, 208, 209, 210, 211 },
{ 252, 253, 254, 255, 0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15 },
{ 56, 57, 58, 59, 60, 61, 62, 63, 64, 65, 66, 67, 68, 69, 70, 71, 72, 73, 74, 75 },
};
mavlink_gps_status_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.satellites_visible = packet_in.satellites_visible;
mav_array_memcpy(packet1.satellite_prn, packet_in.satellite_prn, sizeof(int8_t)*20);
mav_array_memcpy(packet1.satellite_used, packet_in.satellite_used, sizeof(int8_t)*20);
mav_array_memcpy(packet1.satellite_elevation, packet_in.satellite_elevation, sizeof(int8_t)*20);
mav_array_memcpy(packet1.satellite_azimuth, packet_in.satellite_azimuth, sizeof(int8_t)*20);
mav_array_memcpy(packet1.satellite_snr, packet_in.satellite_snr, sizeof(int8_t)*20);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_gps_status_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_gps_status_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_gps_status_pack(system_id, component_id, &msg , packet1.satellites_visible , packet1.satellite_prn , packet1.satellite_used , packet1.satellite_elevation , packet1.satellite_azimuth , packet1.satellite_snr );
mavlink_msg_gps_status_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_gps_status_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.satellites_visible , packet1.satellite_prn , packet1.satellite_used , packet1.satellite_elevation , packet1.satellite_azimuth , packet1.satellite_snr );
mavlink_msg_gps_status_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_gps_status_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_gps_status_send(MAVLINK_COMM_1 , packet1.satellites_visible , packet1.satellite_prn , packet1.satellite_used , packet1.satellite_elevation , packet1.satellite_azimuth , packet1.satellite_snr );
mavlink_msg_gps_status_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_raw_imu(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_raw_imu_t packet_in = {
93372036854775807ULL,
17651,
17755,
17859,
17963,
18067,
18171,
18275,
18379,
18483,
};
mavlink_raw_imu_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.usec = packet_in.usec;
packet1.xacc = packet_in.xacc;
packet1.yacc = packet_in.yacc;
packet1.zacc = packet_in.zacc;
packet1.xgyro = packet_in.xgyro;
packet1.ygyro = packet_in.ygyro;
packet1.zgyro = packet_in.zgyro;
packet1.xmag = packet_in.xmag;
packet1.ymag = packet_in.ymag;
packet1.zmag = packet_in.zmag;
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_raw_imu_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_raw_imu_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_raw_imu_pack(system_id, component_id, &msg , packet1.usec , packet1.xacc , packet1.yacc , packet1.zacc , packet1.xgyro , packet1.ygyro , packet1.zgyro , packet1.xmag , packet1.ymag , packet1.zmag );
mavlink_msg_raw_imu_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_raw_imu_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.usec , packet1.xacc , packet1.yacc , packet1.zacc , packet1.xgyro , packet1.ygyro , packet1.zgyro , packet1.xmag , packet1.ymag , packet1.zmag );
mavlink_msg_raw_imu_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_raw_imu_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_raw_imu_send(MAVLINK_COMM_1 , packet1.usec , packet1.xacc , packet1.yacc , packet1.zacc , packet1.xgyro , packet1.ygyro , packet1.zgyro , packet1.xmag , packet1.ymag , packet1.zmag );
mavlink_msg_raw_imu_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_raw_pressure(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_raw_pressure_t packet_in = {
93372036854775807ULL,
17651,
17755,
17859,
17963,
};
mavlink_raw_pressure_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.usec = packet_in.usec;
packet1.press_abs = packet_in.press_abs;
packet1.press_diff1 = packet_in.press_diff1;
packet1.press_diff2 = packet_in.press_diff2;
packet1.temperature = packet_in.temperature;
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_raw_pressure_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_raw_pressure_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_raw_pressure_pack(system_id, component_id, &msg , packet1.usec , packet1.press_abs , packet1.press_diff1 , packet1.press_diff2 , packet1.temperature );
mavlink_msg_raw_pressure_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_raw_pressure_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.usec , packet1.press_abs , packet1.press_diff1 , packet1.press_diff2 , packet1.temperature );
mavlink_msg_raw_pressure_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_raw_pressure_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_raw_pressure_send(MAVLINK_COMM_1 , packet1.usec , packet1.press_abs , packet1.press_diff1 , packet1.press_diff2 , packet1.temperature );
mavlink_msg_raw_pressure_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_scaled_pressure(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_scaled_pressure_t packet_in = {
93372036854775807ULL,
73.0,
101.0,
18067,
};
mavlink_scaled_pressure_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.usec = packet_in.usec;
packet1.press_abs = packet_in.press_abs;
packet1.press_diff = packet_in.press_diff;
packet1.temperature = packet_in.temperature;
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_scaled_pressure_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_scaled_pressure_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_scaled_pressure_pack(system_id, component_id, &msg , packet1.usec , packet1.press_abs , packet1.press_diff , packet1.temperature );
mavlink_msg_scaled_pressure_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_scaled_pressure_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.usec , packet1.press_abs , packet1.press_diff , packet1.temperature );
mavlink_msg_scaled_pressure_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_scaled_pressure_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_scaled_pressure_send(MAVLINK_COMM_1 , packet1.usec , packet1.press_abs , packet1.press_diff , packet1.temperature );
mavlink_msg_scaled_pressure_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_attitude(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_attitude_t packet_in = {
93372036854775807ULL,
73.0,
101.0,
129.0,
157.0,
185.0,
213.0,
};
mavlink_attitude_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.usec = packet_in.usec;
packet1.roll = packet_in.roll;
packet1.pitch = packet_in.pitch;
packet1.yaw = packet_in.yaw;
packet1.rollspeed = packet_in.rollspeed;
packet1.pitchspeed = packet_in.pitchspeed;
packet1.yawspeed = packet_in.yawspeed;
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_attitude_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_attitude_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_attitude_pack(system_id, component_id, &msg , packet1.usec , packet1.roll , packet1.pitch , packet1.yaw , packet1.rollspeed , packet1.pitchspeed , packet1.yawspeed );
mavlink_msg_attitude_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_attitude_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.usec , packet1.roll , packet1.pitch , packet1.yaw , packet1.rollspeed , packet1.pitchspeed , packet1.yawspeed );
mavlink_msg_attitude_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_attitude_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_attitude_send(MAVLINK_COMM_1 , packet1.usec , packet1.roll , packet1.pitch , packet1.yaw , packet1.rollspeed , packet1.pitchspeed , packet1.yawspeed );
mavlink_msg_attitude_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_local_position(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_local_position_t packet_in = {
93372036854775807ULL,
73.0,
101.0,
129.0,
157.0,
185.0,
213.0,
};
mavlink_local_position_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.usec = packet_in.usec;
packet1.x = packet_in.x;
packet1.y = packet_in.y;
packet1.z = packet_in.z;
packet1.vx = packet_in.vx;
packet1.vy = packet_in.vy;
packet1.vz = packet_in.vz;
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_local_position_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_local_position_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_local_position_pack(system_id, component_id, &msg , packet1.usec , packet1.x , packet1.y , packet1.z , packet1.vx , packet1.vy , packet1.vz );
mavlink_msg_local_position_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_local_position_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.usec , packet1.x , packet1.y , packet1.z , packet1.vx , packet1.vy , packet1.vz );
mavlink_msg_local_position_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_local_position_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_local_position_send(MAVLINK_COMM_1 , packet1.usec , packet1.x , packet1.y , packet1.z , packet1.vx , packet1.vy , packet1.vz );
mavlink_msg_local_position_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_global_position(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_global_position_t packet_in = {
93372036854775807ULL,
73.0,
101.0,
129.0,
157.0,
185.0,
213.0,
};
mavlink_global_position_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.usec = packet_in.usec;
packet1.lat = packet_in.lat;
packet1.lon = packet_in.lon;
packet1.alt = packet_in.alt;
packet1.vx = packet_in.vx;
packet1.vy = packet_in.vy;
packet1.vz = packet_in.vz;
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_global_position_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_global_position_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_global_position_pack(system_id, component_id, &msg , packet1.usec , packet1.lat , packet1.lon , packet1.alt , packet1.vx , packet1.vy , packet1.vz );
mavlink_msg_global_position_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_global_position_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.usec , packet1.lat , packet1.lon , packet1.alt , packet1.vx , packet1.vy , packet1.vz );
mavlink_msg_global_position_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_global_position_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_global_position_send(MAVLINK_COMM_1 , packet1.usec , packet1.lat , packet1.lon , packet1.alt , packet1.vx , packet1.vy , packet1.vz );
mavlink_msg_global_position_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_gps_raw(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_gps_raw_t packet_in = {
93372036854775807ULL,
29,
80.0,
108.0,
136.0,
164.0,
192.0,
220.0,
248.0,
};
mavlink_gps_raw_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.usec = packet_in.usec;
packet1.fix_type = packet_in.fix_type;
packet1.lat = packet_in.lat;
packet1.lon = packet_in.lon;
packet1.alt = packet_in.alt;
packet1.eph = packet_in.eph;
packet1.epv = packet_in.epv;
packet1.v = packet_in.v;
packet1.hdg = packet_in.hdg;
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_gps_raw_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_gps_raw_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_gps_raw_pack(system_id, component_id, &msg , packet1.usec , packet1.fix_type , packet1.lat , packet1.lon , packet1.alt , packet1.eph , packet1.epv , packet1.v , packet1.hdg );
mavlink_msg_gps_raw_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_gps_raw_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.usec , packet1.fix_type , packet1.lat , packet1.lon , packet1.alt , packet1.eph , packet1.epv , packet1.v , packet1.hdg );
mavlink_msg_gps_raw_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_gps_raw_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_gps_raw_send(MAVLINK_COMM_1 , packet1.usec , packet1.fix_type , packet1.lat , packet1.lon , packet1.alt , packet1.eph , packet1.epv , packet1.v , packet1.hdg );
mavlink_msg_gps_raw_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_sys_status(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_sys_status_t packet_in = {
5,
72,
139,
17391,
17495,
17599,
17703,
};
mavlink_sys_status_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.mode = packet_in.mode;
packet1.nav_mode = packet_in.nav_mode;
packet1.status = packet_in.status;
packet1.load = packet_in.load;
packet1.vbat = packet_in.vbat;
packet1.battery_remaining = packet_in.battery_remaining;
packet1.packet_drop = packet_in.packet_drop;
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_sys_status_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_sys_status_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_sys_status_pack(system_id, component_id, &msg , packet1.mode , packet1.nav_mode , packet1.status , packet1.load , packet1.vbat , packet1.battery_remaining , packet1.packet_drop );
mavlink_msg_sys_status_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_sys_status_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.mode , packet1.nav_mode , packet1.status , packet1.load , packet1.vbat , packet1.battery_remaining , packet1.packet_drop );
mavlink_msg_sys_status_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_sys_status_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_sys_status_send(MAVLINK_COMM_1 , packet1.mode , packet1.nav_mode , packet1.status , packet1.load , packet1.vbat , packet1.battery_remaining , packet1.packet_drop );
mavlink_msg_sys_status_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_rc_channels_raw(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_rc_channels_raw_t packet_in = {
17235,
17339,
17443,
17547,
17651,
17755,
17859,
17963,
53,
};
mavlink_rc_channels_raw_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.chan1_raw = packet_in.chan1_raw;
packet1.chan2_raw = packet_in.chan2_raw;
packet1.chan3_raw = packet_in.chan3_raw;
packet1.chan4_raw = packet_in.chan4_raw;
packet1.chan5_raw = packet_in.chan5_raw;
packet1.chan6_raw = packet_in.chan6_raw;
packet1.chan7_raw = packet_in.chan7_raw;
packet1.chan8_raw = packet_in.chan8_raw;
packet1.rssi = packet_in.rssi;
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_rc_channels_raw_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_rc_channels_raw_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_rc_channels_raw_pack(system_id, component_id, &msg , packet1.chan1_raw , packet1.chan2_raw , packet1.chan3_raw , packet1.chan4_raw , packet1.chan5_raw , packet1.chan6_raw , packet1.chan7_raw , packet1.chan8_raw , packet1.rssi );
mavlink_msg_rc_channels_raw_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_rc_channels_raw_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.chan1_raw , packet1.chan2_raw , packet1.chan3_raw , packet1.chan4_raw , packet1.chan5_raw , packet1.chan6_raw , packet1.chan7_raw , packet1.chan8_raw , packet1.rssi );
mavlink_msg_rc_channels_raw_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_rc_channels_raw_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_rc_channels_raw_send(MAVLINK_COMM_1 , packet1.chan1_raw , packet1.chan2_raw , packet1.chan3_raw , packet1.chan4_raw , packet1.chan5_raw , packet1.chan6_raw , packet1.chan7_raw , packet1.chan8_raw , packet1.rssi );
mavlink_msg_rc_channels_raw_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_rc_channels_scaled(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_rc_channels_scaled_t packet_in = {
17235,
17339,
17443,
17547,
17651,
17755,
17859,
17963,
53,
};
mavlink_rc_channels_scaled_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.chan1_scaled = packet_in.chan1_scaled;
packet1.chan2_scaled = packet_in.chan2_scaled;
packet1.chan3_scaled = packet_in.chan3_scaled;
packet1.chan4_scaled = packet_in.chan4_scaled;
packet1.chan5_scaled = packet_in.chan5_scaled;
packet1.chan6_scaled = packet_in.chan6_scaled;
packet1.chan7_scaled = packet_in.chan7_scaled;
packet1.chan8_scaled = packet_in.chan8_scaled;
packet1.rssi = packet_in.rssi;
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_rc_channels_scaled_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_rc_channels_scaled_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_rc_channels_scaled_pack(system_id, component_id, &msg , packet1.chan1_scaled , packet1.chan2_scaled , packet1.chan3_scaled , packet1.chan4_scaled , packet1.chan5_scaled , packet1.chan6_scaled , packet1.chan7_scaled , packet1.chan8_scaled , packet1.rssi );
mavlink_msg_rc_channels_scaled_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_rc_channels_scaled_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.chan1_scaled , packet1.chan2_scaled , packet1.chan3_scaled , packet1.chan4_scaled , packet1.chan5_scaled , packet1.chan6_scaled , packet1.chan7_scaled , packet1.chan8_scaled , packet1.rssi );
mavlink_msg_rc_channels_scaled_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_rc_channels_scaled_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_rc_channels_scaled_send(MAVLINK_COMM_1 , packet1.chan1_scaled , packet1.chan2_scaled , packet1.chan3_scaled , packet1.chan4_scaled , packet1.chan5_scaled , packet1.chan6_scaled , packet1.chan7_scaled , packet1.chan8_scaled , packet1.rssi );
mavlink_msg_rc_channels_scaled_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_servo_output_raw(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_servo_output_raw_t packet_in = {
17235,
17339,
17443,
17547,
17651,
17755,
17859,
17963,
};
mavlink_servo_output_raw_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.servo1_raw = packet_in.servo1_raw;
packet1.servo2_raw = packet_in.servo2_raw;
packet1.servo3_raw = packet_in.servo3_raw;
packet1.servo4_raw = packet_in.servo4_raw;
packet1.servo5_raw = packet_in.servo5_raw;
packet1.servo6_raw = packet_in.servo6_raw;
packet1.servo7_raw = packet_in.servo7_raw;
packet1.servo8_raw = packet_in.servo8_raw;
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_servo_output_raw_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_servo_output_raw_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_servo_output_raw_pack(system_id, component_id, &msg , packet1.servo1_raw , packet1.servo2_raw , packet1.servo3_raw , packet1.servo4_raw , packet1.servo5_raw , packet1.servo6_raw , packet1.servo7_raw , packet1.servo8_raw );
mavlink_msg_servo_output_raw_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_servo_output_raw_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.servo1_raw , packet1.servo2_raw , packet1.servo3_raw , packet1.servo4_raw , packet1.servo5_raw , packet1.servo6_raw , packet1.servo7_raw , packet1.servo8_raw );
mavlink_msg_servo_output_raw_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_servo_output_raw_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_servo_output_raw_send(MAVLINK_COMM_1 , packet1.servo1_raw , packet1.servo2_raw , packet1.servo3_raw , packet1.servo4_raw , packet1.servo5_raw , packet1.servo6_raw , packet1.servo7_raw , packet1.servo8_raw );
mavlink_msg_servo_output_raw_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_waypoint(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_waypoint_t packet_in = {
5,
72,
17339,
17,
84,
151,
218,
73.0,
101.0,
129.0,
157.0,
185.0,
213.0,
241.0,
};
mavlink_waypoint_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.target_system = packet_in.target_system;
packet1.target_component = packet_in.target_component;
packet1.seq = packet_in.seq;
packet1.frame = packet_in.frame;
packet1.command = packet_in.command;
packet1.current = packet_in.current;
packet1.autocontinue = packet_in.autocontinue;
packet1.param1 = packet_in.param1;
packet1.param2 = packet_in.param2;
packet1.param3 = packet_in.param3;
packet1.param4 = packet_in.param4;
packet1.x = packet_in.x;
packet1.y = packet_in.y;
packet1.z = packet_in.z;
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_waypoint_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_waypoint_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_waypoint_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.seq , packet1.frame , packet1.command , packet1.current , packet1.autocontinue , packet1.param1 , packet1.param2 , packet1.param3 , packet1.param4 , packet1.x , packet1.y , packet1.z );
mavlink_msg_waypoint_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_waypoint_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.seq , packet1.frame , packet1.command , packet1.current , packet1.autocontinue , packet1.param1 , packet1.param2 , packet1.param3 , packet1.param4 , packet1.x , packet1.y , packet1.z );
mavlink_msg_waypoint_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_waypoint_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_waypoint_send(MAVLINK_COMM_1 , packet1.target_system , packet1.target_component , packet1.seq , packet1.frame , packet1.command , packet1.current , packet1.autocontinue , packet1.param1 , packet1.param2 , packet1.param3 , packet1.param4 , packet1.x , packet1.y , packet1.z );
mavlink_msg_waypoint_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_waypoint_request(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_waypoint_request_t packet_in = {
5,
72,
17339,
};
mavlink_waypoint_request_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.target_system = packet_in.target_system;
packet1.target_component = packet_in.target_component;
packet1.seq = packet_in.seq;
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_waypoint_request_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_waypoint_request_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_waypoint_request_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.seq );
mavlink_msg_waypoint_request_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_waypoint_request_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.seq );
mavlink_msg_waypoint_request_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_waypoint_request_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_waypoint_request_send(MAVLINK_COMM_1 , packet1.target_system , packet1.target_component , packet1.seq );
mavlink_msg_waypoint_request_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_waypoint_set_current(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_waypoint_set_current_t packet_in = {
5,
72,
17339,
};
mavlink_waypoint_set_current_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.target_system = packet_in.target_system;
packet1.target_component = packet_in.target_component;
packet1.seq = packet_in.seq;
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_waypoint_set_current_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_waypoint_set_current_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_waypoint_set_current_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.seq );
mavlink_msg_waypoint_set_current_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_waypoint_set_current_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.seq );
mavlink_msg_waypoint_set_current_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_waypoint_set_current_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_waypoint_set_current_send(MAVLINK_COMM_1 , packet1.target_system , packet1.target_component , packet1.seq );
mavlink_msg_waypoint_set_current_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_waypoint_current(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_waypoint_current_t packet_in = {
17235,
};
mavlink_waypoint_current_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.seq = packet_in.seq;
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_waypoint_current_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_waypoint_current_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_waypoint_current_pack(system_id, component_id, &msg , packet1.seq );
mavlink_msg_waypoint_current_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_waypoint_current_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.seq );
mavlink_msg_waypoint_current_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_waypoint_current_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_waypoint_current_send(MAVLINK_COMM_1 , packet1.seq );
mavlink_msg_waypoint_current_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_waypoint_request_list(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_waypoint_request_list_t packet_in = {
5,
72,
};
mavlink_waypoint_request_list_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.target_system = packet_in.target_system;
packet1.target_component = packet_in.target_component;
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_waypoint_request_list_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_waypoint_request_list_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_waypoint_request_list_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component );
mavlink_msg_waypoint_request_list_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_waypoint_request_list_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component );
mavlink_msg_waypoint_request_list_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_waypoint_request_list_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_waypoint_request_list_send(MAVLINK_COMM_1 , packet1.target_system , packet1.target_component );
mavlink_msg_waypoint_request_list_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_waypoint_count(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_waypoint_count_t packet_in = {
5,
72,
17339,
};
mavlink_waypoint_count_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.target_system = packet_in.target_system;
packet1.target_component = packet_in.target_component;
packet1.count = packet_in.count;
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_waypoint_count_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_waypoint_count_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_waypoint_count_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.count );
mavlink_msg_waypoint_count_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_waypoint_count_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.count );
mavlink_msg_waypoint_count_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_waypoint_count_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_waypoint_count_send(MAVLINK_COMM_1 , packet1.target_system , packet1.target_component , packet1.count );
mavlink_msg_waypoint_count_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_waypoint_clear_all(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_waypoint_clear_all_t packet_in = {
5,
72,
};
mavlink_waypoint_clear_all_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.target_system = packet_in.target_system;
packet1.target_component = packet_in.target_component;
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_waypoint_clear_all_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_waypoint_clear_all_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_waypoint_clear_all_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component );
mavlink_msg_waypoint_clear_all_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_waypoint_clear_all_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component );
mavlink_msg_waypoint_clear_all_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_waypoint_clear_all_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_waypoint_clear_all_send(MAVLINK_COMM_1 , packet1.target_system , packet1.target_component );
mavlink_msg_waypoint_clear_all_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_waypoint_reached(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_waypoint_reached_t packet_in = {
17235,
};
mavlink_waypoint_reached_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.seq = packet_in.seq;
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_waypoint_reached_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_waypoint_reached_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_waypoint_reached_pack(system_id, component_id, &msg , packet1.seq );
mavlink_msg_waypoint_reached_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_waypoint_reached_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.seq );
mavlink_msg_waypoint_reached_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_waypoint_reached_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_waypoint_reached_send(MAVLINK_COMM_1 , packet1.seq );
mavlink_msg_waypoint_reached_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_waypoint_ack(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_waypoint_ack_t packet_in = {
5,
72,
139,
};
mavlink_waypoint_ack_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.target_system = packet_in.target_system;
packet1.target_component = packet_in.target_component;
packet1.type = packet_in.type;
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_waypoint_ack_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_waypoint_ack_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_waypoint_ack_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.type );
mavlink_msg_waypoint_ack_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_waypoint_ack_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.type );
mavlink_msg_waypoint_ack_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_waypoint_ack_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_waypoint_ack_send(MAVLINK_COMM_1 , packet1.target_system , packet1.target_component , packet1.type );
mavlink_msg_waypoint_ack_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_gps_set_global_origin(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_gps_set_global_origin_t packet_in = {
5,
72,
963497568,
963497776,
963497984,
};
mavlink_gps_set_global_origin_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.target_system = packet_in.target_system;
packet1.target_component = packet_in.target_component;
packet1.latitude = packet_in.latitude;
packet1.longitude = packet_in.longitude;
packet1.altitude = packet_in.altitude;
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_gps_set_global_origin_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_gps_set_global_origin_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_gps_set_global_origin_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.latitude , packet1.longitude , packet1.altitude );
mavlink_msg_gps_set_global_origin_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_gps_set_global_origin_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.latitude , packet1.longitude , packet1.altitude );
mavlink_msg_gps_set_global_origin_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_gps_set_global_origin_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_gps_set_global_origin_send(MAVLINK_COMM_1 , packet1.target_system , packet1.target_component , packet1.latitude , packet1.longitude , packet1.altitude );
mavlink_msg_gps_set_global_origin_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_gps_local_origin_set(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_gps_local_origin_set_t packet_in = {
963497464,
963497672,
963497880,
};
mavlink_gps_local_origin_set_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.latitude = packet_in.latitude;
packet1.longitude = packet_in.longitude;
packet1.altitude = packet_in.altitude;
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_gps_local_origin_set_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_gps_local_origin_set_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_gps_local_origin_set_pack(system_id, component_id, &msg , packet1.latitude , packet1.longitude , packet1.altitude );
mavlink_msg_gps_local_origin_set_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_gps_local_origin_set_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.latitude , packet1.longitude , packet1.altitude );
mavlink_msg_gps_local_origin_set_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_gps_local_origin_set_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_gps_local_origin_set_send(MAVLINK_COMM_1 , packet1.latitude , packet1.longitude , packet1.altitude );
mavlink_msg_gps_local_origin_set_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_local_position_setpoint_set(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_local_position_setpoint_set_t packet_in = {
5,
72,
31.0,
59.0,
87.0,
115.0,
};
mavlink_local_position_setpoint_set_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.target_system = packet_in.target_system;
packet1.target_component = packet_in.target_component;
packet1.x = packet_in.x;
packet1.y = packet_in.y;
packet1.z = packet_in.z;
packet1.yaw = packet_in.yaw;
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_local_position_setpoint_set_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_local_position_setpoint_set_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_local_position_setpoint_set_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.x , packet1.y , packet1.z , packet1.yaw );
mavlink_msg_local_position_setpoint_set_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_local_position_setpoint_set_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.x , packet1.y , packet1.z , packet1.yaw );
mavlink_msg_local_position_setpoint_set_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_local_position_setpoint_set_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_local_position_setpoint_set_send(MAVLINK_COMM_1 , packet1.target_system , packet1.target_component , packet1.x , packet1.y , packet1.z , packet1.yaw );
mavlink_msg_local_position_setpoint_set_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_local_position_setpoint(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_local_position_setpoint_t packet_in = {
17.0,
45.0,
73.0,
101.0,
};
mavlink_local_position_setpoint_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.x = packet_in.x;
packet1.y = packet_in.y;
packet1.z = packet_in.z;
packet1.yaw = packet_in.yaw;
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_local_position_setpoint_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_local_position_setpoint_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_local_position_setpoint_pack(system_id, component_id, &msg , packet1.x , packet1.y , packet1.z , packet1.yaw );
mavlink_msg_local_position_setpoint_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_local_position_setpoint_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.x , packet1.y , packet1.z , packet1.yaw );
mavlink_msg_local_position_setpoint_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_local_position_setpoint_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_local_position_setpoint_send(MAVLINK_COMM_1 , packet1.x , packet1.y , packet1.z , packet1.yaw );
mavlink_msg_local_position_setpoint_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_control_status(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_control_status_t packet_in = {
5,
72,
139,
206,
17,
84,
151,
218,
};
mavlink_control_status_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.position_fix = packet_in.position_fix;
packet1.vision_fix = packet_in.vision_fix;
packet1.gps_fix = packet_in.gps_fix;
packet1.ahrs_health = packet_in.ahrs_health;
packet1.control_att = packet_in.control_att;
packet1.control_pos_xy = packet_in.control_pos_xy;
packet1.control_pos_z = packet_in.control_pos_z;
packet1.control_pos_yaw = packet_in.control_pos_yaw;
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_control_status_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_control_status_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_control_status_pack(system_id, component_id, &msg , packet1.position_fix , packet1.vision_fix , packet1.gps_fix , packet1.ahrs_health , packet1.control_att , packet1.control_pos_xy , packet1.control_pos_z , packet1.control_pos_yaw );
mavlink_msg_control_status_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_control_status_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.position_fix , packet1.vision_fix , packet1.gps_fix , packet1.ahrs_health , packet1.control_att , packet1.control_pos_xy , packet1.control_pos_z , packet1.control_pos_yaw );
mavlink_msg_control_status_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_control_status_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_control_status_send(MAVLINK_COMM_1 , packet1.position_fix , packet1.vision_fix , packet1.gps_fix , packet1.ahrs_health , packet1.control_att , packet1.control_pos_xy , packet1.control_pos_z , packet1.control_pos_yaw );
mavlink_msg_control_status_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_safety_set_allowed_area(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_safety_set_allowed_area_t packet_in = {
5,
72,
139,
38.0,
66.0,
94.0,
122.0,
150.0,
178.0,
};
mavlink_safety_set_allowed_area_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.target_system = packet_in.target_system;
packet1.target_component = packet_in.target_component;
packet1.frame = packet_in.frame;
packet1.p1x = packet_in.p1x;
packet1.p1y = packet_in.p1y;
packet1.p1z = packet_in.p1z;
packet1.p2x = packet_in.p2x;
packet1.p2y = packet_in.p2y;
packet1.p2z = packet_in.p2z;
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_safety_set_allowed_area_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_safety_set_allowed_area_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_safety_set_allowed_area_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.frame , packet1.p1x , packet1.p1y , packet1.p1z , packet1.p2x , packet1.p2y , packet1.p2z );
mavlink_msg_safety_set_allowed_area_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_safety_set_allowed_area_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.frame , packet1.p1x , packet1.p1y , packet1.p1z , packet1.p2x , packet1.p2y , packet1.p2z );
mavlink_msg_safety_set_allowed_area_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_safety_set_allowed_area_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_safety_set_allowed_area_send(MAVLINK_COMM_1 , packet1.target_system , packet1.target_component , packet1.frame , packet1.p1x , packet1.p1y , packet1.p1z , packet1.p2x , packet1.p2y , packet1.p2z );
mavlink_msg_safety_set_allowed_area_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_safety_allowed_area(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_safety_allowed_area_t packet_in = {
5,
24.0,
52.0,
80.0,
108.0,
136.0,
164.0,
};
mavlink_safety_allowed_area_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.frame = packet_in.frame;
packet1.p1x = packet_in.p1x;
packet1.p1y = packet_in.p1y;
packet1.p1z = packet_in.p1z;
packet1.p2x = packet_in.p2x;
packet1.p2y = packet_in.p2y;
packet1.p2z = packet_in.p2z;
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_safety_allowed_area_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_safety_allowed_area_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_safety_allowed_area_pack(system_id, component_id, &msg , packet1.frame , packet1.p1x , packet1.p1y , packet1.p1z , packet1.p2x , packet1.p2y , packet1.p2z );
mavlink_msg_safety_allowed_area_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_safety_allowed_area_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.frame , packet1.p1x , packet1.p1y , packet1.p1z , packet1.p2x , packet1.p2y , packet1.p2z );
mavlink_msg_safety_allowed_area_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_safety_allowed_area_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_safety_allowed_area_send(MAVLINK_COMM_1 , packet1.frame , packet1.p1x , packet1.p1y , packet1.p1z , packet1.p2x , packet1.p2y , packet1.p2z );
mavlink_msg_safety_allowed_area_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_set_roll_pitch_yaw_thrust(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_set_roll_pitch_yaw_thrust_t packet_in = {
5,
72,
31.0,
59.0,
87.0,
115.0,
};
mavlink_set_roll_pitch_yaw_thrust_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.target_system = packet_in.target_system;
packet1.target_component = packet_in.target_component;
packet1.roll = packet_in.roll;
packet1.pitch = packet_in.pitch;
packet1.yaw = packet_in.yaw;
packet1.thrust = packet_in.thrust;
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_set_roll_pitch_yaw_thrust_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_set_roll_pitch_yaw_thrust_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_set_roll_pitch_yaw_thrust_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.roll , packet1.pitch , packet1.yaw , packet1.thrust );
mavlink_msg_set_roll_pitch_yaw_thrust_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_set_roll_pitch_yaw_thrust_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.roll , packet1.pitch , packet1.yaw , packet1.thrust );
mavlink_msg_set_roll_pitch_yaw_thrust_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_set_roll_pitch_yaw_thrust_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_set_roll_pitch_yaw_thrust_send(MAVLINK_COMM_1 , packet1.target_system , packet1.target_component , packet1.roll , packet1.pitch , packet1.yaw , packet1.thrust );
mavlink_msg_set_roll_pitch_yaw_thrust_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_set_roll_pitch_yaw_speed_thrust(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_set_roll_pitch_yaw_speed_thrust_t packet_in = {
5,
72,
31.0,
59.0,
87.0,
115.0,
};
mavlink_set_roll_pitch_yaw_speed_thrust_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.target_system = packet_in.target_system;
packet1.target_component = packet_in.target_component;
packet1.roll_speed = packet_in.roll_speed;
packet1.pitch_speed = packet_in.pitch_speed;
packet1.yaw_speed = packet_in.yaw_speed;
packet1.thrust = packet_in.thrust;
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_set_roll_pitch_yaw_speed_thrust_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_set_roll_pitch_yaw_speed_thrust_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_set_roll_pitch_yaw_speed_thrust_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.roll_speed , packet1.pitch_speed , packet1.yaw_speed , packet1.thrust );
mavlink_msg_set_roll_pitch_yaw_speed_thrust_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_set_roll_pitch_yaw_speed_thrust_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.roll_speed , packet1.pitch_speed , packet1.yaw_speed , packet1.thrust );
mavlink_msg_set_roll_pitch_yaw_speed_thrust_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_set_roll_pitch_yaw_speed_thrust_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_set_roll_pitch_yaw_speed_thrust_send(MAVLINK_COMM_1 , packet1.target_system , packet1.target_component , packet1.roll_speed , packet1.pitch_speed , packet1.yaw_speed , packet1.thrust );
mavlink_msg_set_roll_pitch_yaw_speed_thrust_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_roll_pitch_yaw_thrust_setpoint(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_roll_pitch_yaw_thrust_setpoint_t packet_in = {
93372036854775807ULL,
73.0,
101.0,
129.0,
157.0,
};
mavlink_roll_pitch_yaw_thrust_setpoint_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.time_us = packet_in.time_us;
packet1.roll = packet_in.roll;
packet1.pitch = packet_in.pitch;
packet1.yaw = packet_in.yaw;
packet1.thrust = packet_in.thrust;
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_roll_pitch_yaw_thrust_setpoint_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_roll_pitch_yaw_thrust_setpoint_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_roll_pitch_yaw_thrust_setpoint_pack(system_id, component_id, &msg , packet1.time_us , packet1.roll , packet1.pitch , packet1.yaw , packet1.thrust );
mavlink_msg_roll_pitch_yaw_thrust_setpoint_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_roll_pitch_yaw_thrust_setpoint_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_us , packet1.roll , packet1.pitch , packet1.yaw , packet1.thrust );
mavlink_msg_roll_pitch_yaw_thrust_setpoint_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_roll_pitch_yaw_thrust_setpoint_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_roll_pitch_yaw_thrust_setpoint_send(MAVLINK_COMM_1 , packet1.time_us , packet1.roll , packet1.pitch , packet1.yaw , packet1.thrust );
mavlink_msg_roll_pitch_yaw_thrust_setpoint_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_roll_pitch_yaw_speed_thrust_setpoint(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_roll_pitch_yaw_speed_thrust_setpoint_t packet_in = {
93372036854775807ULL,
73.0,
101.0,
129.0,
157.0,
};
mavlink_roll_pitch_yaw_speed_thrust_setpoint_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.time_us = packet_in.time_us;
packet1.roll_speed = packet_in.roll_speed;
packet1.pitch_speed = packet_in.pitch_speed;
packet1.yaw_speed = packet_in.yaw_speed;
packet1.thrust = packet_in.thrust;
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_pack(system_id, component_id, &msg , packet1.time_us , packet1.roll_speed , packet1.pitch_speed , packet1.yaw_speed , packet1.thrust );
mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_us , packet1.roll_speed , packet1.pitch_speed , packet1.yaw_speed , packet1.thrust );
mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_send(MAVLINK_COMM_1 , packet1.time_us , packet1.roll_speed , packet1.pitch_speed , packet1.yaw_speed , packet1.thrust );
mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_nav_controller_output(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_nav_controller_output_t packet_in = {
17.0,
45.0,
17651,
17755,
17859,
115.0,
143.0,
171.0,
};
mavlink_nav_controller_output_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.nav_roll = packet_in.nav_roll;
packet1.nav_pitch = packet_in.nav_pitch;
packet1.nav_bearing = packet_in.nav_bearing;
packet1.target_bearing = packet_in.target_bearing;
packet1.wp_dist = packet_in.wp_dist;
packet1.alt_error = packet_in.alt_error;
packet1.aspd_error = packet_in.aspd_error;
packet1.xtrack_error = packet_in.xtrack_error;
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_nav_controller_output_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_nav_controller_output_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_nav_controller_output_pack(system_id, component_id, &msg , packet1.nav_roll , packet1.nav_pitch , packet1.nav_bearing , packet1.target_bearing , packet1.wp_dist , packet1.alt_error , packet1.aspd_error , packet1.xtrack_error );
mavlink_msg_nav_controller_output_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_nav_controller_output_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.nav_roll , packet1.nav_pitch , packet1.nav_bearing , packet1.target_bearing , packet1.wp_dist , packet1.alt_error , packet1.aspd_error , packet1.xtrack_error );
mavlink_msg_nav_controller_output_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_nav_controller_output_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_nav_controller_output_send(MAVLINK_COMM_1 , packet1.nav_roll , packet1.nav_pitch , packet1.nav_bearing , packet1.target_bearing , packet1.wp_dist , packet1.alt_error , packet1.aspd_error , packet1.xtrack_error );
mavlink_msg_nav_controller_output_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_position_target(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_position_target_t packet_in = {
17.0,
45.0,
73.0,
101.0,
};
mavlink_position_target_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.x = packet_in.x;
packet1.y = packet_in.y;
packet1.z = packet_in.z;
packet1.yaw = packet_in.yaw;
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_position_target_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_position_target_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_position_target_pack(system_id, component_id, &msg , packet1.x , packet1.y , packet1.z , packet1.yaw );
mavlink_msg_position_target_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_position_target_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.x , packet1.y , packet1.z , packet1.yaw );
mavlink_msg_position_target_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_position_target_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_position_target_send(MAVLINK_COMM_1 , packet1.x , packet1.y , packet1.z , packet1.yaw );
mavlink_msg_position_target_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_state_correction(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_state_correction_t packet_in = {
17.0,
45.0,
73.0,
101.0,
129.0,
157.0,
185.0,
213.0,
241.0,
};
mavlink_state_correction_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.xErr = packet_in.xErr;
packet1.yErr = packet_in.yErr;
packet1.zErr = packet_in.zErr;
packet1.rollErr = packet_in.rollErr;
packet1.pitchErr = packet_in.pitchErr;
packet1.yawErr = packet_in.yawErr;
packet1.vxErr = packet_in.vxErr;
packet1.vyErr = packet_in.vyErr;
packet1.vzErr = packet_in.vzErr;
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_state_correction_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_state_correction_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_state_correction_pack(system_id, component_id, &msg , packet1.xErr , packet1.yErr , packet1.zErr , packet1.rollErr , packet1.pitchErr , packet1.yawErr , packet1.vxErr , packet1.vyErr , packet1.vzErr );
mavlink_msg_state_correction_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_state_correction_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.xErr , packet1.yErr , packet1.zErr , packet1.rollErr , packet1.pitchErr , packet1.yawErr , packet1.vxErr , packet1.vyErr , packet1.vzErr );
mavlink_msg_state_correction_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_state_correction_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_state_correction_send(MAVLINK_COMM_1 , packet1.xErr , packet1.yErr , packet1.zErr , packet1.rollErr , packet1.pitchErr , packet1.yawErr , packet1.vxErr , packet1.vyErr , packet1.vzErr );
mavlink_msg_state_correction_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_set_altitude(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_set_altitude_t packet_in = {
5,
963497516,
};
mavlink_set_altitude_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.target = packet_in.target;
packet1.mode = packet_in.mode;
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_set_altitude_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_set_altitude_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_set_altitude_pack(system_id, component_id, &msg , packet1.target , packet1.mode );
mavlink_msg_set_altitude_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_set_altitude_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target , packet1.mode );
mavlink_msg_set_altitude_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_set_altitude_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_set_altitude_send(MAVLINK_COMM_1 , packet1.target , packet1.mode );
mavlink_msg_set_altitude_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_request_data_stream(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_request_data_stream_t packet_in = {
5,
72,
139,
17391,
84,
};
mavlink_request_data_stream_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.target_system = packet_in.target_system;
packet1.target_component = packet_in.target_component;
packet1.req_stream_id = packet_in.req_stream_id;
packet1.req_message_rate = packet_in.req_message_rate;
packet1.start_stop = packet_in.start_stop;
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_request_data_stream_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_request_data_stream_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_request_data_stream_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.req_stream_id , packet1.req_message_rate , packet1.start_stop );
mavlink_msg_request_data_stream_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_request_data_stream_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.req_stream_id , packet1.req_message_rate , packet1.start_stop );
mavlink_msg_request_data_stream_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_request_data_stream_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_request_data_stream_send(MAVLINK_COMM_1 , packet1.target_system , packet1.target_component , packet1.req_stream_id , packet1.req_message_rate , packet1.start_stop );
mavlink_msg_request_data_stream_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_hil_state(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_hil_state_t packet_in = {
93372036854775807ULL,
73.0,
101.0,
129.0,
157.0,
185.0,
213.0,
963499128,
963499336,
963499544,
19523,
19627,
19731,
19835,
19939,
20043,
};
mavlink_hil_state_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.usec = packet_in.usec;
packet1.roll = packet_in.roll;
packet1.pitch = packet_in.pitch;
packet1.yaw = packet_in.yaw;
packet1.rollspeed = packet_in.rollspeed;
packet1.pitchspeed = packet_in.pitchspeed;
packet1.yawspeed = packet_in.yawspeed;
packet1.lat = packet_in.lat;
packet1.lon = packet_in.lon;
packet1.alt = packet_in.alt;
packet1.vx = packet_in.vx;
packet1.vy = packet_in.vy;
packet1.vz = packet_in.vz;
packet1.xacc = packet_in.xacc;
packet1.yacc = packet_in.yacc;
packet1.zacc = packet_in.zacc;
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_hil_state_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_hil_state_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_hil_state_pack(system_id, component_id, &msg , packet1.usec , packet1.roll , packet1.pitch , packet1.yaw , packet1.rollspeed , packet1.pitchspeed , packet1.yawspeed , packet1.lat , packet1.lon , packet1.alt , packet1.vx , packet1.vy , packet1.vz , packet1.xacc , packet1.yacc , packet1.zacc );
mavlink_msg_hil_state_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_hil_state_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.usec , packet1.roll , packet1.pitch , packet1.yaw , packet1.rollspeed , packet1.pitchspeed , packet1.yawspeed , packet1.lat , packet1.lon , packet1.alt , packet1.vx , packet1.vy , packet1.vz , packet1.xacc , packet1.yacc , packet1.zacc );
mavlink_msg_hil_state_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_hil_state_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_hil_state_send(MAVLINK_COMM_1 , packet1.usec , packet1.roll , packet1.pitch , packet1.yaw , packet1.rollspeed , packet1.pitchspeed , packet1.yawspeed , packet1.lat , packet1.lon , packet1.alt , packet1.vx , packet1.vy , packet1.vz , packet1.xacc , packet1.yacc , packet1.zacc );
mavlink_msg_hil_state_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_hil_controls(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_hil_controls_t packet_in = {
93372036854775807ULL,
73.0,
101.0,
129.0,
157.0,
77,
144,
};
mavlink_hil_controls_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.time_us = packet_in.time_us;
packet1.roll_ailerons = packet_in.roll_ailerons;
packet1.pitch_elevator = packet_in.pitch_elevator;
packet1.yaw_rudder = packet_in.yaw_rudder;
packet1.throttle = packet_in.throttle;
packet1.mode = packet_in.mode;
packet1.nav_mode = packet_in.nav_mode;
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_hil_controls_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_hil_controls_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_hil_controls_pack(system_id, component_id, &msg , packet1.time_us , packet1.roll_ailerons , packet1.pitch_elevator , packet1.yaw_rudder , packet1.throttle , packet1.mode , packet1.nav_mode );
mavlink_msg_hil_controls_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_hil_controls_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_us , packet1.roll_ailerons , packet1.pitch_elevator , packet1.yaw_rudder , packet1.throttle , packet1.mode , packet1.nav_mode );
mavlink_msg_hil_controls_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_hil_controls_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_hil_controls_send(MAVLINK_COMM_1 , packet1.time_us , packet1.roll_ailerons , packet1.pitch_elevator , packet1.yaw_rudder , packet1.throttle , packet1.mode , packet1.nav_mode );
mavlink_msg_hil_controls_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_manual_control(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_manual_control_t packet_in = {
5,
24.0,
52.0,
80.0,
108.0,
120,
187,
254,
65,
};
mavlink_manual_control_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.target = packet_in.target;
packet1.roll = packet_in.roll;
packet1.pitch = packet_in.pitch;
packet1.yaw = packet_in.yaw;
packet1.thrust = packet_in.thrust;
packet1.roll_manual = packet_in.roll_manual;
packet1.pitch_manual = packet_in.pitch_manual;
packet1.yaw_manual = packet_in.yaw_manual;
packet1.thrust_manual = packet_in.thrust_manual;
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_manual_control_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_manual_control_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_manual_control_pack(system_id, component_id, &msg , packet1.target , packet1.roll , packet1.pitch , packet1.yaw , packet1.thrust , packet1.roll_manual , packet1.pitch_manual , packet1.yaw_manual , packet1.thrust_manual );
mavlink_msg_manual_control_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_manual_control_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target , packet1.roll , packet1.pitch , packet1.yaw , packet1.thrust , packet1.roll_manual , packet1.pitch_manual , packet1.yaw_manual , packet1.thrust_manual );
mavlink_msg_manual_control_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_manual_control_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_manual_control_send(MAVLINK_COMM_1 , packet1.target , packet1.roll , packet1.pitch , packet1.yaw , packet1.thrust , packet1.roll_manual , packet1.pitch_manual , packet1.yaw_manual , packet1.thrust_manual );
mavlink_msg_manual_control_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_rc_channels_override(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_rc_channels_override_t packet_in = {
5,
72,
17339,
17443,
17547,
17651,
17755,
17859,
17963,
18067,
};
mavlink_rc_channels_override_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.target_system = packet_in.target_system;
packet1.target_component = packet_in.target_component;
packet1.chan1_raw = packet_in.chan1_raw;
packet1.chan2_raw = packet_in.chan2_raw;
packet1.chan3_raw = packet_in.chan3_raw;
packet1.chan4_raw = packet_in.chan4_raw;
packet1.chan5_raw = packet_in.chan5_raw;
packet1.chan6_raw = packet_in.chan6_raw;
packet1.chan7_raw = packet_in.chan7_raw;
packet1.chan8_raw = packet_in.chan8_raw;
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_rc_channels_override_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_rc_channels_override_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_rc_channels_override_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.chan1_raw , packet1.chan2_raw , packet1.chan3_raw , packet1.chan4_raw , packet1.chan5_raw , packet1.chan6_raw , packet1.chan7_raw , packet1.chan8_raw );
mavlink_msg_rc_channels_override_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_rc_channels_override_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.chan1_raw , packet1.chan2_raw , packet1.chan3_raw , packet1.chan4_raw , packet1.chan5_raw , packet1.chan6_raw , packet1.chan7_raw , packet1.chan8_raw );
mavlink_msg_rc_channels_override_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_rc_channels_override_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_rc_channels_override_send(MAVLINK_COMM_1 , packet1.target_system , packet1.target_component , packet1.chan1_raw , packet1.chan2_raw , packet1.chan3_raw , packet1.chan4_raw , packet1.chan5_raw , packet1.chan6_raw , packet1.chan7_raw , packet1.chan8_raw );
mavlink_msg_rc_channels_override_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_global_position_int(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_global_position_int_t packet_in = {
963497464,
963497672,
963497880,
17859,
17963,
18067,
};
mavlink_global_position_int_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.lat = packet_in.lat;
packet1.lon = packet_in.lon;
packet1.alt = packet_in.alt;
packet1.vx = packet_in.vx;
packet1.vy = packet_in.vy;
packet1.vz = packet_in.vz;
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_global_position_int_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_global_position_int_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_global_position_int_pack(system_id, component_id, &msg , packet1.lat , packet1.lon , packet1.alt , packet1.vx , packet1.vy , packet1.vz );
mavlink_msg_global_position_int_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_global_position_int_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.lat , packet1.lon , packet1.alt , packet1.vx , packet1.vy , packet1.vz );
mavlink_msg_global_position_int_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_global_position_int_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_global_position_int_send(MAVLINK_COMM_1 , packet1.lat , packet1.lon , packet1.alt , packet1.vx , packet1.vy , packet1.vz );
mavlink_msg_global_position_int_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_vfr_hud(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_vfr_hud_t packet_in = {
17.0,
45.0,
17651,
17755,
101.0,
129.0,
};
mavlink_vfr_hud_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.airspeed = packet_in.airspeed;
packet1.groundspeed = packet_in.groundspeed;
packet1.heading = packet_in.heading;
packet1.throttle = packet_in.throttle;
packet1.alt = packet_in.alt;
packet1.climb = packet_in.climb;
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_vfr_hud_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_vfr_hud_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_vfr_hud_pack(system_id, component_id, &msg , packet1.airspeed , packet1.groundspeed , packet1.heading , packet1.throttle , packet1.alt , packet1.climb );
mavlink_msg_vfr_hud_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_vfr_hud_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.airspeed , packet1.groundspeed , packet1.heading , packet1.throttle , packet1.alt , packet1.climb );
mavlink_msg_vfr_hud_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_vfr_hud_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_vfr_hud_send(MAVLINK_COMM_1 , packet1.airspeed , packet1.groundspeed , packet1.heading , packet1.throttle , packet1.alt , packet1.climb );
mavlink_msg_vfr_hud_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_command(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_command_t packet_in = {
5,
72,
139,
206,
45.0,
73.0,
101.0,
129.0,
};
mavlink_command_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.target_system = packet_in.target_system;
packet1.target_component = packet_in.target_component;
packet1.command = packet_in.command;
packet1.confirmation = packet_in.confirmation;
packet1.param1 = packet_in.param1;
packet1.param2 = packet_in.param2;
packet1.param3 = packet_in.param3;
packet1.param4 = packet_in.param4;
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_command_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_command_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_command_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.command , packet1.confirmation , packet1.param1 , packet1.param2 , packet1.param3 , packet1.param4 );
mavlink_msg_command_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_command_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.command , packet1.confirmation , packet1.param1 , packet1.param2 , packet1.param3 , packet1.param4 );
mavlink_msg_command_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_command_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_command_send(MAVLINK_COMM_1 , packet1.target_system , packet1.target_component , packet1.command , packet1.confirmation , packet1.param1 , packet1.param2 , packet1.param3 , packet1.param4 );
mavlink_msg_command_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_command_ack(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_command_ack_t packet_in = {
17.0,
45.0,
};
mavlink_command_ack_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.command = packet_in.command;
packet1.result = packet_in.result;
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_command_ack_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_command_ack_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_command_ack_pack(system_id, component_id, &msg , packet1.command , packet1.result );
mavlink_msg_command_ack_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_command_ack_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.command , packet1.result );
mavlink_msg_command_ack_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_command_ack_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_command_ack_send(MAVLINK_COMM_1 , packet1.command , packet1.result );
mavlink_msg_command_ack_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_optical_flow(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_optical_flow_t packet_in = {
93372036854775807ULL,
29,
17703,
17807,
108,
115.0,
};
mavlink_optical_flow_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.time = packet_in.time;
packet1.sensor_id = packet_in.sensor_id;
packet1.flow_x = packet_in.flow_x;
packet1.flow_y = packet_in.flow_y;
packet1.quality = packet_in.quality;
packet1.ground_distance = packet_in.ground_distance;
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_optical_flow_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_optical_flow_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_optical_flow_pack(system_id, component_id, &msg , packet1.time , packet1.sensor_id , packet1.flow_x , packet1.flow_y , packet1.quality , packet1.ground_distance );
mavlink_msg_optical_flow_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_optical_flow_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time , packet1.sensor_id , packet1.flow_x , packet1.flow_y , packet1.quality , packet1.ground_distance );
mavlink_msg_optical_flow_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_optical_flow_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_optical_flow_send(MAVLINK_COMM_1 , packet1.time , packet1.sensor_id , packet1.flow_x , packet1.flow_y , packet1.quality , packet1.ground_distance );
mavlink_msg_optical_flow_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_object_detection_event(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_object_detection_event_t packet_in = {
963497464,
17443,
151,
"HIJKLMNOPQRSTUVWXYZ",
22,
213.0,
241.0,
};
mavlink_object_detection_event_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.time = packet_in.time;
packet1.object_id = packet_in.object_id;
packet1.type = packet_in.type;
packet1.quality = packet_in.quality;
packet1.bearing = packet_in.bearing;
packet1.distance = packet_in.distance;
mav_array_memcpy(packet1.name, packet_in.name, sizeof(char)*20);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_object_detection_event_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_object_detection_event_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_object_detection_event_pack(system_id, component_id, &msg , packet1.time , packet1.object_id , packet1.type , packet1.name , packet1.quality , packet1.bearing , packet1.distance );
mavlink_msg_object_detection_event_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_object_detection_event_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time , packet1.object_id , packet1.type , packet1.name , packet1.quality , packet1.bearing , packet1.distance );
mavlink_msg_object_detection_event_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_object_detection_event_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_object_detection_event_send(MAVLINK_COMM_1 , packet1.time , packet1.object_id , packet1.type , packet1.name , packet1.quality , packet1.bearing , packet1.distance );
mavlink_msg_object_detection_event_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_debug_vect(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_debug_vect_t packet_in = {
"ABCDEFGHI",
93372036854776437ULL,
143.0,
171.0,
199.0,
};
mavlink_debug_vect_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.usec = packet_in.usec;
packet1.x = packet_in.x;
packet1.y = packet_in.y;
packet1.z = packet_in.z;
mav_array_memcpy(packet1.name, packet_in.name, sizeof(char)*10);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_debug_vect_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_debug_vect_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_debug_vect_pack(system_id, component_id, &msg , packet1.name , packet1.usec , packet1.x , packet1.y , packet1.z );
mavlink_msg_debug_vect_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_debug_vect_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.name , packet1.usec , packet1.x , packet1.y , packet1.z );
mavlink_msg_debug_vect_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_debug_vect_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_debug_vect_send(MAVLINK_COMM_1 , packet1.name , packet1.usec , packet1.x , packet1.y , packet1.z );
mavlink_msg_debug_vect_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_named_value_float(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_named_value_float_t packet_in = {
"ABCDEFGHI",
87.0,
};
mavlink_named_value_float_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.value = packet_in.value;
mav_array_memcpy(packet1.name, packet_in.name, sizeof(char)*10);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_named_value_float_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_named_value_float_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_named_value_float_pack(system_id, component_id, &msg , packet1.name , packet1.value );
mavlink_msg_named_value_float_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_named_value_float_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.name , packet1.value );
mavlink_msg_named_value_float_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_named_value_float_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_named_value_float_send(MAVLINK_COMM_1 , packet1.name , packet1.value );
mavlink_msg_named_value_float_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_named_value_int(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_named_value_int_t packet_in = {
"ABCDEFGHI",
963497984,
};
mavlink_named_value_int_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.value = packet_in.value;
mav_array_memcpy(packet1.name, packet_in.name, sizeof(char)*10);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_named_value_int_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_named_value_int_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_named_value_int_pack(system_id, component_id, &msg , packet1.name , packet1.value );
mavlink_msg_named_value_int_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_named_value_int_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.name , packet1.value );
mavlink_msg_named_value_int_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_named_value_int_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_named_value_int_send(MAVLINK_COMM_1 , packet1.name , packet1.value );
mavlink_msg_named_value_int_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_statustext(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_statustext_t packet_in = {
5,
{ 72, 73, 74, 75, 76, 77, 78, 79, 80, 81, 82, 83, 84, 85, 86, 87, 88, 89, 90, 91, 92, 93, 94, 95, 96, 97, 98, 99, 100, 101, 102, 103, 104, 105, 106, 107, 108, 109, 110, 111, 112, 113, 114, 115, 116, 117, 118, 119, 120, 121 },
};
mavlink_statustext_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.severity = packet_in.severity;
mav_array_memcpy(packet1.text, packet_in.text, sizeof(int8_t)*50);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_statustext_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_statustext_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_statustext_pack(system_id, component_id, &msg , packet1.severity , packet1.text );
mavlink_msg_statustext_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_statustext_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.severity , packet1.text );
mavlink_msg_statustext_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_statustext_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_statustext_send(MAVLINK_COMM_1 , packet1.severity , packet1.text );
mavlink_msg_statustext_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_debug(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_debug_t packet_in = {
5,
24.0,
};
mavlink_debug_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.ind = packet_in.ind;
packet1.value = packet_in.value;
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_debug_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_debug_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_debug_pack(system_id, component_id, &msg , packet1.ind , packet1.value );
mavlink_msg_debug_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_debug_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.ind , packet1.value );
mavlink_msg_debug_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_debug_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_debug_send(MAVLINK_COMM_1 , packet1.ind , packet1.value );
mavlink_msg_debug_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_common(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_test_heartbeat(system_id, component_id, last_msg);
mavlink_test_boot(system_id, component_id, last_msg);
mavlink_test_system_time(system_id, component_id, last_msg);
mavlink_test_ping(system_id, component_id, last_msg);
mavlink_test_system_time_utc(system_id, component_id, last_msg);
mavlink_test_change_operator_control(system_id, component_id, last_msg);
mavlink_test_change_operator_control_ack(system_id, component_id, last_msg);
mavlink_test_auth_key(system_id, component_id, last_msg);
mavlink_test_action_ack(system_id, component_id, last_msg);
mavlink_test_action(system_id, component_id, last_msg);
mavlink_test_set_mode(system_id, component_id, last_msg);
mavlink_test_set_nav_mode(system_id, component_id, last_msg);
mavlink_test_param_request_read(system_id, component_id, last_msg);
mavlink_test_param_request_list(system_id, component_id, last_msg);
mavlink_test_param_value(system_id, component_id, last_msg);
mavlink_test_param_set(system_id, component_id, last_msg);
mavlink_test_gps_raw_int(system_id, component_id, last_msg);
mavlink_test_scaled_imu(system_id, component_id, last_msg);
mavlink_test_gps_status(system_id, component_id, last_msg);
mavlink_test_raw_imu(system_id, component_id, last_msg);
mavlink_test_raw_pressure(system_id, component_id, last_msg);
mavlink_test_scaled_pressure(system_id, component_id, last_msg);
mavlink_test_attitude(system_id, component_id, last_msg);
mavlink_test_local_position(system_id, component_id, last_msg);
mavlink_test_global_position(system_id, component_id, last_msg);
mavlink_test_gps_raw(system_id, component_id, last_msg);
mavlink_test_sys_status(system_id, component_id, last_msg);
mavlink_test_rc_channels_raw(system_id, component_id, last_msg);
mavlink_test_rc_channels_scaled(system_id, component_id, last_msg);
mavlink_test_servo_output_raw(system_id, component_id, last_msg);
mavlink_test_waypoint(system_id, component_id, last_msg);
mavlink_test_waypoint_request(system_id, component_id, last_msg);
mavlink_test_waypoint_set_current(system_id, component_id, last_msg);
mavlink_test_waypoint_current(system_id, component_id, last_msg);
mavlink_test_waypoint_request_list(system_id, component_id, last_msg);
mavlink_test_waypoint_count(system_id, component_id, last_msg);
mavlink_test_waypoint_clear_all(system_id, component_id, last_msg);
mavlink_test_waypoint_reached(system_id, component_id, last_msg);
mavlink_test_waypoint_ack(system_id, component_id, last_msg);
mavlink_test_gps_set_global_origin(system_id, component_id, last_msg);
mavlink_test_gps_local_origin_set(system_id, component_id, last_msg);
mavlink_test_local_position_setpoint_set(system_id, component_id, last_msg);
mavlink_test_local_position_setpoint(system_id, component_id, last_msg);
mavlink_test_control_status(system_id, component_id, last_msg);
mavlink_test_safety_set_allowed_area(system_id, component_id, last_msg);
mavlink_test_safety_allowed_area(system_id, component_id, last_msg);
mavlink_test_set_roll_pitch_yaw_thrust(system_id, component_id, last_msg);
mavlink_test_set_roll_pitch_yaw_speed_thrust(system_id, component_id, last_msg);
mavlink_test_roll_pitch_yaw_thrust_setpoint(system_id, component_id, last_msg);
mavlink_test_roll_pitch_yaw_speed_thrust_setpoint(system_id, component_id, last_msg);
mavlink_test_nav_controller_output(system_id, component_id, last_msg);
mavlink_test_position_target(system_id, component_id, last_msg);
mavlink_test_state_correction(system_id, component_id, last_msg);
mavlink_test_set_altitude(system_id, component_id, last_msg);
mavlink_test_request_data_stream(system_id, component_id, last_msg);
mavlink_test_hil_state(system_id, component_id, last_msg);
mavlink_test_hil_controls(system_id, component_id, last_msg);
mavlink_test_manual_control(system_id, component_id, last_msg);
mavlink_test_rc_channels_override(system_id, component_id, last_msg);
mavlink_test_global_position_int(system_id, component_id, last_msg);
mavlink_test_vfr_hud(system_id, component_id, last_msg);
mavlink_test_command(system_id, component_id, last_msg);
mavlink_test_command_ack(system_id, component_id, last_msg);
mavlink_test_optical_flow(system_id, component_id, last_msg);
mavlink_test_object_detection_event(system_id, component_id, last_msg);
mavlink_test_debug_vect(system_id, component_id, last_msg);
mavlink_test_named_value_float(system_id, component_id, last_msg);
mavlink_test_named_value_int(system_id, component_id, last_msg);
mavlink_test_statustext(system_id, component_id, last_msg);
mavlink_test_debug(system_id, component_id, last_msg);
}
 
#ifdef __cplusplus
}
#endif // __cplusplus
#endif // COMMON_TESTSUITE_H
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v0.9/common/version.h
0,0 → 1,12
/** @file
* @brief MAVLink comm protocol built from common.xml
* @see http://pixhawk.ethz.ch/software/mavlink
*/
#ifndef MAVLINK_VERSION_H
#define MAVLINK_VERSION_H
 
#define MAVLINK_BUILD_DATE "Mon Apr 30 11:40:11 2012"
#define MAVLINK_WIRE_PROTOCOL_VERSION "0.9"
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 101
#endif // MAVLINK_VERSION_H
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v0.9/mavlink_helpers.h
0,0 → 1,507
#ifndef _MAVLINK_HELPERS_H_
#define _MAVLINK_HELPERS_H_
 
#include "string.h"
#include "checksum.h"
#include "mavlink_types.h"
 
#ifndef MAVLINK_HELPER
#define MAVLINK_HELPER
#endif
 
/*
internal function to give access to the channel status for each channel
*/
MAVLINK_HELPER mavlink_status_t* mavlink_get_channel_status(uint8_t chan)
{
static mavlink_status_t m_mavlink_status[MAVLINK_COMM_NUM_BUFFERS];
return &m_mavlink_status[chan];
}
 
/*
internal function to give access to the channel buffer for each channel
*/
MAVLINK_HELPER mavlink_message_t* mavlink_get_channel_buffer(uint8_t chan)
{
 
#if MAVLINK_EXTERNAL_RX_BUFFER
// No m_mavlink_message array defined in function,
// has to be defined externally
#ifndef m_mavlink_message
#error ERROR: IF #define MAVLINK_EXTERNAL_RX_BUFFER IS SET, THE BUFFER HAS TO BE ALLOCATED OUTSIDE OF THIS FUNCTION (mavlink_message_t m_mavlink_buffer[MAVLINK_COMM_NUM_BUFFERS];)
#endif
#else
static mavlink_message_t m_mavlink_buffer[MAVLINK_COMM_NUM_BUFFERS];
#endif
return &m_mavlink_buffer[chan];
}
 
/**
* @brief Finalize a MAVLink message with channel assignment
*
* This function calculates the checksum and sets length and aircraft id correctly.
* It assumes that the message id and the payload are already correctly set. This function
* can also be used if the message header has already been written before (as in mavlink_msg_xxx_pack
* instead of mavlink_msg_xxx_pack_headerless), it just introduces little extra overhead.
*
* @param msg Message to finalize
* @param system_id Id of the sending (this) system, 1-127
* @param length Message length
*/
#if MAVLINK_CRC_EXTRA
MAVLINK_HELPER uint16_t mavlink_finalize_message_chan(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id,
uint8_t chan, uint8_t length, uint8_t crc_extra)
#else
MAVLINK_HELPER uint16_t mavlink_finalize_message_chan(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id,
uint8_t chan, uint8_t length)
#endif
{
// This code part is the same for all messages;
uint16_t checksum;
msg->magic = MAVLINK_STX;
msg->len = length;
msg->sysid = system_id;
msg->compid = component_id;
// One sequence number per component
msg->seq = mavlink_get_channel_status(chan)->current_tx_seq;
mavlink_get_channel_status(chan)->current_tx_seq = mavlink_get_channel_status(chan)->current_tx_seq+1;
checksum = crc_calculate((uint8_t*)&msg->len, length + MAVLINK_CORE_HEADER_LEN);
#if MAVLINK_CRC_EXTRA
crc_accumulate(crc_extra, &checksum);
#endif
mavlink_ck_a(msg) = (uint8_t)(checksum & 0xFF);
mavlink_ck_b(msg) = (uint8_t)(checksum >> 8);
 
return length + MAVLINK_NUM_NON_PAYLOAD_BYTES;
}
 
 
/**
* @brief Finalize a MAVLink message with MAVLINK_COMM_0 as default channel
*/
#if MAVLINK_CRC_EXTRA
MAVLINK_HELPER uint16_t mavlink_finalize_message(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id,
uint8_t length, uint8_t crc_extra)
{
return mavlink_finalize_message_chan(msg, system_id, component_id, MAVLINK_COMM_0, length, crc_extra);
}
#else
MAVLINK_HELPER uint16_t mavlink_finalize_message(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id,
uint8_t length)
{
return mavlink_finalize_message_chan(msg, system_id, component_id, MAVLINK_COMM_0, length);
}
#endif
 
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
MAVLINK_HELPER void _mavlink_send_uart(mavlink_channel_t chan, const char *buf, uint16_t len);
 
/**
* @brief Finalize a MAVLink message with channel assignment and send
*/
#if MAVLINK_CRC_EXTRA
MAVLINK_HELPER void _mav_finalize_message_chan_send(mavlink_channel_t chan, uint8_t msgid, const char *packet,
uint8_t length, uint8_t crc_extra)
#else
MAVLINK_HELPER void _mav_finalize_message_chan_send(mavlink_channel_t chan, uint8_t msgid, const char *packet, uint8_t length)
#endif
{
uint16_t checksum;
uint8_t buf[MAVLINK_NUM_HEADER_BYTES];
uint8_t ck[2];
mavlink_status_t *status = mavlink_get_channel_status(chan);
buf[0] = MAVLINK_STX;
buf[1] = length;
buf[2] = status->current_tx_seq;
buf[3] = mavlink_system.sysid;
buf[4] = mavlink_system.compid;
buf[5] = msgid;
status->current_tx_seq++;
checksum = crc_calculate((uint8_t*)&buf[1], MAVLINK_CORE_HEADER_LEN);
crc_accumulate_buffer(&checksum, packet, length);
#if MAVLINK_CRC_EXTRA
crc_accumulate(crc_extra, &checksum);
#endif
ck[0] = (uint8_t)(checksum & 0xFF);
ck[1] = (uint8_t)(checksum >> 8);
 
MAVLINK_START_UART_SEND(chan, MAVLINK_NUM_NON_PAYLOAD_BYTES + (uint16_t)length);
_mavlink_send_uart(chan, (const char *)buf, MAVLINK_NUM_HEADER_BYTES);
_mavlink_send_uart(chan, packet, length);
_mavlink_send_uart(chan, (const char *)ck, 2);
MAVLINK_END_UART_SEND(chan, MAVLINK_NUM_NON_PAYLOAD_BYTES + (uint16_t)length);
}
#endif // MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
/**
* @brief Pack a message to send it over a serial byte stream
*/
MAVLINK_HELPER uint16_t mavlink_msg_to_send_buffer(uint8_t *buffer, const mavlink_message_t *msg)
{
memcpy(buffer, (const uint8_t *)&msg->magic, MAVLINK_NUM_NON_PAYLOAD_BYTES + (uint16_t)msg->len);
return MAVLINK_NUM_NON_PAYLOAD_BYTES + (uint16_t)msg->len;
}
 
union __mavlink_bitfield {
uint8_t uint8;
int8_t int8;
uint16_t uint16;
int16_t int16;
uint32_t uint32;
int32_t int32;
};
 
 
MAVLINK_HELPER void mavlink_start_checksum(mavlink_message_t* msg)
{
crc_init(&msg->checksum);
}
 
MAVLINK_HELPER void mavlink_update_checksum(mavlink_message_t* msg, uint8_t c)
{
crc_accumulate(c, &msg->checksum);
}
 
/**
* This is a convenience function which handles the complete MAVLink parsing.
* the function will parse one byte at a time and return the complete packet once
* it could be successfully decoded. Checksum and other failures will be silently
* ignored.
*
* @param chan ID of the current channel. This allows to parse different channels with this function.
* a channel is not a physical message channel like a serial port, but a logic partition of
* the communication streams in this case. COMM_NB is the limit for the number of channels
* on MCU (e.g. ARM7), while COMM_NB_HIGH is the limit for the number of channels in Linux/Windows
* @param c The char to barse
*
* @param returnMsg NULL if no message could be decoded, the message data else
* @return 0 if no message could be decoded, 1 else
*
* A typical use scenario of this function call is:
*
* @code
* #include <inttypes.h> // For fixed-width uint8_t type
*
* mavlink_message_t msg;
* int chan = 0;
*
*
* while(serial.bytesAvailable > 0)
* {
* uint8_t byte = serial.getNextByte();
* if (mavlink_parse_char(chan, byte, &msg))
* {
* printf("Received message with ID %d, sequence: %d from component %d of system %d", msg.msgid, msg.seq, msg.compid, msg.sysid);
* }
* }
*
*
* @endcode
*/
MAVLINK_HELPER uint8_t mavlink_parse_char(uint8_t chan, uint8_t c, mavlink_message_t* r_message, mavlink_status_t* r_mavlink_status)
{
/*
default message crc function. You can override this per-system to
put this data in a different memory segment
*/
#if MAVLINK_CRC_EXTRA
#ifndef MAVLINK_MESSAGE_CRC
static const uint8_t mavlink_message_crcs[256] = MAVLINK_MESSAGE_CRCS;
#define MAVLINK_MESSAGE_CRC(msgid) mavlink_message_crcs[msgid]
#endif
#endif
 
mavlink_message_t* rxmsg = mavlink_get_channel_buffer(chan); ///< The currently decoded message
mavlink_status_t* status = mavlink_get_channel_status(chan); ///< The current decode status
int bufferIndex = 0;
 
status->msg_received = 0;
 
switch (status->parse_state)
{
case MAVLINK_PARSE_STATE_UNINIT:
case MAVLINK_PARSE_STATE_IDLE:
if (c == MAVLINK_STX)
{
status->parse_state = MAVLINK_PARSE_STATE_GOT_STX;
rxmsg->len = 0;
rxmsg->magic = c;
mavlink_start_checksum(rxmsg);
}
break;
 
case MAVLINK_PARSE_STATE_GOT_STX:
if (status->msg_received
/* Support shorter buffers than the
default maximum packet size */
#if (MAVLINK_MAX_PAYLOAD_LEN < 255)
|| c > MAVLINK_MAX_PAYLOAD_LEN
#endif
)
{
status->buffer_overrun++;
status->parse_error++;
status->msg_received = 0;
status->parse_state = MAVLINK_PARSE_STATE_IDLE;
}
else
{
// NOT counting STX, LENGTH, SEQ, SYSID, COMPID, MSGID, CRC1 and CRC2
rxmsg->len = c;
status->packet_idx = 0;
mavlink_update_checksum(rxmsg, c);
status->parse_state = MAVLINK_PARSE_STATE_GOT_LENGTH;
}
break;
 
case MAVLINK_PARSE_STATE_GOT_LENGTH:
rxmsg->seq = c;
mavlink_update_checksum(rxmsg, c);
status->parse_state = MAVLINK_PARSE_STATE_GOT_SEQ;
break;
 
case MAVLINK_PARSE_STATE_GOT_SEQ:
rxmsg->sysid = c;
mavlink_update_checksum(rxmsg, c);
status->parse_state = MAVLINK_PARSE_STATE_GOT_SYSID;
break;
 
case MAVLINK_PARSE_STATE_GOT_SYSID:
rxmsg->compid = c;
mavlink_update_checksum(rxmsg, c);
status->parse_state = MAVLINK_PARSE_STATE_GOT_COMPID;
break;
 
case MAVLINK_PARSE_STATE_GOT_COMPID:
rxmsg->msgid = c;
mavlink_update_checksum(rxmsg, c);
if (rxmsg->len == 0)
{
status->parse_state = MAVLINK_PARSE_STATE_GOT_PAYLOAD;
}
else
{
status->parse_state = MAVLINK_PARSE_STATE_GOT_MSGID;
}
break;
 
case MAVLINK_PARSE_STATE_GOT_MSGID:
_MAV_PAYLOAD_NON_CONST(rxmsg)[status->packet_idx++] = (char)c;
mavlink_update_checksum(rxmsg, c);
if (status->packet_idx == rxmsg->len)
{
status->parse_state = MAVLINK_PARSE_STATE_GOT_PAYLOAD;
}
break;
 
case MAVLINK_PARSE_STATE_GOT_PAYLOAD:
#if MAVLINK_CRC_EXTRA
mavlink_update_checksum(rxmsg, MAVLINK_MESSAGE_CRC(rxmsg->msgid));
#endif
if (c != (rxmsg->checksum & 0xFF)) {
// Check first checksum byte
status->parse_error++;
status->msg_received = 0;
status->parse_state = MAVLINK_PARSE_STATE_IDLE;
if (c == MAVLINK_STX)
{
status->parse_state = MAVLINK_PARSE_STATE_GOT_STX;
rxmsg->len = 0;
mavlink_start_checksum(rxmsg);
}
}
else
{
status->parse_state = MAVLINK_PARSE_STATE_GOT_CRC1;
_MAV_PAYLOAD_NON_CONST(rxmsg)[status->packet_idx] = (char)c;
}
break;
 
case MAVLINK_PARSE_STATE_GOT_CRC1:
if (c != (rxmsg->checksum >> 8)) {
// Check second checksum byte
status->parse_error++;
status->msg_received = 0;
status->parse_state = MAVLINK_PARSE_STATE_IDLE;
if (c == MAVLINK_STX)
{
status->parse_state = MAVLINK_PARSE_STATE_GOT_STX;
rxmsg->len = 0;
mavlink_start_checksum(rxmsg);
}
}
else
{
// Successfully got message
status->msg_received = 1;
status->parse_state = MAVLINK_PARSE_STATE_IDLE;
_MAV_PAYLOAD_NON_CONST(rxmsg)[status->packet_idx+1] = (char)c;
memcpy(r_message, rxmsg, sizeof(mavlink_message_t));
}
break;
}
 
bufferIndex++;
// If a message has been sucessfully decoded, check index
if (status->msg_received == 1)
{
//while(status->current_seq != rxmsg->seq)
//{
// status->packet_rx_drop_count++;
// status->current_seq++;
//}
status->current_rx_seq = rxmsg->seq;
// Initial condition: If no packet has been received so far, drop count is undefined
if (status->packet_rx_success_count == 0) status->packet_rx_drop_count = 0;
// Count this packet as received
status->packet_rx_success_count++;
}
 
r_mavlink_status->current_rx_seq = status->current_rx_seq+1;
r_mavlink_status->packet_rx_success_count = status->packet_rx_success_count;
r_mavlink_status->packet_rx_drop_count = status->parse_error;
status->parse_error = 0;
return status->msg_received;
}
 
/**
* @brief Put a bitfield of length 1-32 bit into the buffer
*
* @param b the value to add, will be encoded in the bitfield
* @param bits number of bits to use to encode b, e.g. 1 for boolean, 2, 3, etc.
* @param packet_index the position in the packet (the index of the first byte to use)
* @param bit_index the position in the byte (the index of the first bit to use)
* @param buffer packet buffer to write into
* @return new position of the last used byte in the buffer
*/
MAVLINK_HELPER uint8_t put_bitfield_n_by_index(int32_t b, uint8_t bits, uint8_t packet_index, uint8_t bit_index, uint8_t* r_bit_index, uint8_t* buffer)
{
uint16_t bits_remain = bits;
// Transform number into network order
int32_t v;
uint8_t i_bit_index, i_byte_index, curr_bits_n;
#if MAVLINK_NEED_BYTE_SWAP
union {
int32_t i;
uint8_t b[4];
} bin, bout;
bin.i = b;
bout.b[0] = bin.b[3];
bout.b[1] = bin.b[2];
bout.b[2] = bin.b[1];
bout.b[3] = bin.b[0];
v = bout.i;
#else
v = b;
#endif
 
// buffer in
// 01100000 01000000 00000000 11110001
// buffer out
// 11110001 00000000 01000000 01100000
 
// Existing partly filled byte (four free slots)
// 0111xxxx
 
// Mask n free bits
// 00001111 = 2^0 + 2^1 + 2^2 + 2^3 = 2^n - 1
// = ((uint32_t)(1 << n)) - 1; // = 2^n - 1
 
// Shift n bits into the right position
// out = in >> n;
 
// Mask and shift bytes
i_bit_index = bit_index;
i_byte_index = packet_index;
if (bit_index > 0)
{
// If bits were available at start, they were available
// in the byte before the current index
i_byte_index--;
}
 
// While bits have not been packed yet
while (bits_remain > 0)
{
// Bits still have to be packed
// there can be more than 8 bits, so
// we might have to pack them into more than one byte
 
// First pack everything we can into the current 'open' byte
//curr_bits_n = bits_remain << 3; // Equals bits_remain mod 8
//FIXME
if (bits_remain <= (uint8_t)(8 - i_bit_index))
{
// Enough space
curr_bits_n = (uint8_t)bits_remain;
}
else
{
curr_bits_n = (8 - i_bit_index);
}
// Pack these n bits into the current byte
// Mask out whatever was at that position with ones (xxx11111)
buffer[i_byte_index] &= (0xFF >> (8 - curr_bits_n));
// Put content to this position, by masking out the non-used part
buffer[i_byte_index] |= ((0x00 << curr_bits_n) & v);
// Increment the bit index
i_bit_index += curr_bits_n;
 
// Now proceed to the next byte, if necessary
bits_remain -= curr_bits_n;
if (bits_remain > 0)
{
// Offer another 8 bits / one byte
i_byte_index++;
i_bit_index = 0;
}
}
*r_bit_index = i_bit_index;
// If a partly filled byte is present, mark this as consumed
if (i_bit_index != 7) i_byte_index++;
return i_byte_index - packet_index;
}
 
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
// To make MAVLink work on your MCU, define comm_send_ch() if you wish
// to send 1 byte at a time, or MAVLINK_SEND_UART_BYTES() to send a
// whole packet at a time
 
/*
 
#include "mavlink_types.h"
 
void comm_send_ch(mavlink_channel_t chan, uint8_t ch)
{
if (chan == MAVLINK_COMM_0)
{
uart0_transmit(ch);
}
if (chan == MAVLINK_COMM_1)
{
uart1_transmit(ch);
}
}
*/
 
MAVLINK_HELPER void _mavlink_send_uart(mavlink_channel_t chan, const char *buf, uint16_t len)
{
#ifdef MAVLINK_SEND_UART_BYTES
/* this is the more efficient approach, if the platform
defines it */
MAVLINK_SEND_UART_BYTES(chan, (uint8_t *)buf, len);
#else
/* fallback to one byte at a time */
uint16_t i;
for (i = 0; i < len; i++) {
comm_send_ch(chan, (uint8_t)buf[i]);
}
#endif
}
#endif // MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
#endif /* _MAVLINK_HELPERS_H_ */
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v0.9/mavlink_types.h
0,0 → 1,323
#ifndef MAVLINK_TYPES_H_
#define MAVLINK_TYPES_H_
 
#include "inttypes.h"
 
enum MAV_CLASS
{
MAV_CLASS_GENERIC = 0, ///< Generic autopilot, full support for everything
MAV_CLASS_PIXHAWK = 1, ///< PIXHAWK autopilot, http://pixhawk.ethz.ch
MAV_CLASS_SLUGS = 2, ///< SLUGS autopilot, http://slugsuav.soe.ucsc.edu
MAV_CLASS_ARDUPILOTMEGA = 3, ///< ArduPilotMega / ArduCopter, http://diydrones.com
MAV_CLASS_OPENPILOT = 4, ///< OpenPilot, http://openpilot.org
MAV_CLASS_GENERIC_MISSION_WAYPOINTS_ONLY = 5, ///< Generic autopilot only supporting simple waypoints
MAV_CLASS_GENERIC_MISSION_NAVIGATION_ONLY = 6, ///< Generic autopilot supporting waypoints and other simple navigation commands
MAV_CLASS_GENERIC_MISSION_FULL = 7, ///< Generic autopilot supporting the full mission command set
MAV_CLASS_NONE = 8, ///< No valid autopilot
MAV_CLASS_NB ///< Number of autopilot classes
};
 
enum MAV_ACTION
{
MAV_ACTION_HOLD = 0,
MAV_ACTION_MOTORS_START = 1,
MAV_ACTION_LAUNCH = 2,
MAV_ACTION_RETURN = 3,
MAV_ACTION_EMCY_LAND = 4,
MAV_ACTION_EMCY_KILL = 5,
MAV_ACTION_CONFIRM_KILL = 6,
MAV_ACTION_CONTINUE = 7,
MAV_ACTION_MOTORS_STOP = 8,
MAV_ACTION_HALT = 9,
MAV_ACTION_SHUTDOWN = 10,
MAV_ACTION_REBOOT = 11,
MAV_ACTION_SET_MANUAL = 12,
MAV_ACTION_SET_AUTO = 13,
MAV_ACTION_STORAGE_READ = 14,
MAV_ACTION_STORAGE_WRITE = 15,
MAV_ACTION_CALIBRATE_RC = 16,
MAV_ACTION_CALIBRATE_GYRO = 17,
MAV_ACTION_CALIBRATE_MAG = 18,
MAV_ACTION_CALIBRATE_ACC = 19,
MAV_ACTION_CALIBRATE_PRESSURE = 20,
MAV_ACTION_REC_START = 21,
MAV_ACTION_REC_PAUSE = 22,
MAV_ACTION_REC_STOP = 23,
MAV_ACTION_TAKEOFF = 24,
MAV_ACTION_NAVIGATE = 25,
MAV_ACTION_LAND = 26,
MAV_ACTION_LOITER = 27,
MAV_ACTION_SET_ORIGIN = 28,
MAV_ACTION_RELAY_ON = 29,
MAV_ACTION_RELAY_OFF = 30,
MAV_ACTION_GET_IMAGE = 31,
MAV_ACTION_VIDEO_START = 32,
MAV_ACTION_VIDEO_STOP = 33,
MAV_ACTION_RESET_MAP = 34,
MAV_ACTION_RESET_PLAN = 35,
MAV_ACTION_DELAY_BEFORE_COMMAND = 36,
MAV_ACTION_ASCEND_AT_RATE = 37,
MAV_ACTION_CHANGE_MODE = 38,
MAV_ACTION_LOITER_MAX_TURNS = 39,
MAV_ACTION_LOITER_MAX_TIME = 40,
MAV_ACTION_START_HILSIM = 41,
MAV_ACTION_STOP_HILSIM = 42,
MAV_ACTION_NB ///< Number of MAV actions
};
 
enum MAV_MODE
{
MAV_MODE_UNINIT = 0, ///< System is in undefined state
MAV_MODE_LOCKED = 1, ///< Motors are blocked, system is safe
MAV_MODE_MANUAL = 2, ///< System is allowed to be active, under manual (RC) control
MAV_MODE_GUIDED = 3, ///< System is allowed to be active, under autonomous control, manual setpoint
MAV_MODE_AUTO = 4, ///< System is allowed to be active, under autonomous control and navigation
MAV_MODE_TEST1 = 5, ///< Generic test mode, for custom use
MAV_MODE_TEST2 = 6, ///< Generic test mode, for custom use
MAV_MODE_TEST3 = 7, ///< Generic test mode, for custom use
MAV_MODE_READY = 8, ///< System is ready, motors are unblocked, but controllers are inactive
MAV_MODE_RC_TRAINING = 9 ///< System is blocked, only RC valued are read and reported back
};
 
enum MAV_STATE
{
MAV_STATE_UNINIT = 0,
MAV_STATE_BOOT,
MAV_STATE_CALIBRATING,
MAV_STATE_STANDBY,
MAV_STATE_ACTIVE,
MAV_STATE_CRITICAL,
MAV_STATE_EMERGENCY,
MAV_STATE_HILSIM,
MAV_STATE_POWEROFF
};
 
enum MAV_NAV
{
MAV_NAV_GROUNDED = 0,
MAV_NAV_LIFTOFF,
MAV_NAV_HOLD,
MAV_NAV_WAYPOINT,
MAV_NAV_VECTOR,
MAV_NAV_RETURNING,
MAV_NAV_LANDING,
MAV_NAV_LOST,
MAV_NAV_LOITER,
MAV_NAV_FREE_DRIFT
};
 
enum MAV_TYPE
{
MAV_GENERIC = 0,
MAV_FIXED_WING = 1,
MAV_QUADROTOR = 2,
MAV_COAXIAL = 3,
MAV_HELICOPTER = 4,
MAV_GROUND = 5,
OCU = 6,
MAV_AIRSHIP = 7,
MAV_FREE_BALLOON = 8,
MAV_ROCKET = 9,
UGV_GROUND_ROVER = 10,
UGV_SURFACE_SHIP = 11
};
 
enum MAV_AUTOPILOT_TYPE
{
MAV_AUTOPILOT_GENERIC = 0,
MAV_AUTOPILOT_PIXHAWK = 1,
MAV_AUTOPILOT_SLUGS = 2,
MAV_AUTOPILOT_ARDUPILOTMEGA = 3,
MAV_AUTOPILOT_NONE = 4
};
 
enum MAV_COMPONENT
{
MAV_COMP_ID_GPS,
MAV_COMP_ID_WAYPOINTPLANNER,
MAV_COMP_ID_BLOBTRACKER,
MAV_COMP_ID_PATHPLANNER,
MAV_COMP_ID_AIRSLAM,
MAV_COMP_ID_MAPPER,
MAV_COMP_ID_CAMERA,
MAV_COMP_ID_RADIO = 68,
MAV_COMP_ID_IMU = 200,
MAV_COMP_ID_IMU_2 = 201,
MAV_COMP_ID_IMU_3 = 202,
MAV_COMP_ID_UDP_BRIDGE = 240,
MAV_COMP_ID_UART_BRIDGE = 241,
MAV_COMP_ID_SYSTEM_CONTROL = 250
};
 
enum MAV_FRAME
{
MAV_FRAME_GLOBAL = 0,
MAV_FRAME_LOCAL = 1,
MAV_FRAME_MISSION = 2,
MAV_FRAME_GLOBAL_RELATIVE_ALT = 3,
MAV_FRAME_LOCAL_ENU = 4
};
 
enum MAVLINK_DATA_STREAM_TYPE
{
MAVLINK_DATA_STREAM_IMG_JPEG,
MAVLINK_DATA_STREAM_IMG_BMP,
MAVLINK_DATA_STREAM_IMG_RAW8U,
MAVLINK_DATA_STREAM_IMG_RAW32U,
MAVLINK_DATA_STREAM_IMG_PGM,
MAVLINK_DATA_STREAM_IMG_PNG
};
 
#ifndef MAVLINK_MAX_PAYLOAD_LEN
// it is possible to override this, but be careful!
#define MAVLINK_MAX_PAYLOAD_LEN 255 ///< Maximum payload length
#endif
 
#define MAVLINK_CORE_HEADER_LEN 5 ///< Length of core header (of the comm. layer): message length (1 byte) + message sequence (1 byte) + message system id (1 byte) + message component id (1 byte) + message type id (1 byte)
#define MAVLINK_NUM_HEADER_BYTES (MAVLINK_CORE_HEADER_LEN + 1) ///< Length of all header bytes, including core and checksum
#define MAVLINK_NUM_CHECKSUM_BYTES 2
#define MAVLINK_NUM_NON_PAYLOAD_BYTES (MAVLINK_NUM_HEADER_BYTES + MAVLINK_NUM_CHECKSUM_BYTES)
 
#define MAVLINK_MAX_PACKET_LEN (MAVLINK_MAX_PAYLOAD_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES) ///< Maximum packet length
 
#define MAVLINK_MSG_ID_EXTENDED_MESSAGE 255
#define MAVLINK_EXTENDED_HEADER_LEN 14
 
#if (defined _MSC_VER) | ((defined __APPLE__) & (defined __MACH__)) | (defined __linux__)
/* full fledged 32bit++ OS */
#define MAVLINK_MAX_EXTENDED_PACKET_LEN 65507
#else
/* small microcontrollers */
#define MAVLINK_MAX_EXTENDED_PACKET_LEN 2048
#endif
 
#define MAVLINK_MAX_EXTENDED_PAYLOAD_LEN (MAVLINK_MAX_EXTENDED_PACKET_LEN - MAVLINK_EXTENDED_HEADER_LEN - MAVLINK_NUM_NON_PAYLOAD_BYTES)
 
typedef struct param_union {
union {
float param_float;
int32_t param_int32;
uint32_t param_uint32;
uint8_t param_uint8;
uint8_t bytes[4];
};
uint8_t type;
} mavlink_param_union_t;
 
typedef struct __mavlink_system {
uint8_t sysid; ///< Used by the MAVLink message_xx_send() convenience function
uint8_t compid; ///< Used by the MAVLink message_xx_send() convenience function
uint8_t type; ///< Unused, can be used by user to store the system's type
uint8_t state; ///< Unused, can be used by user to store the system's state
uint8_t mode; ///< Unused, can be used by user to store the system's mode
uint8_t nav_mode; ///< Unused, can be used by user to store the system's navigation mode
} mavlink_system_t;
 
typedef struct __mavlink_message {
uint16_t checksum; /// sent at end of packet
uint8_t magic; ///< protocol magic marker
uint8_t len; ///< Length of payload
uint8_t seq; ///< Sequence of packet
uint8_t sysid; ///< ID of message sender system/aircraft
uint8_t compid; ///< ID of the message sender component
uint8_t msgid; ///< ID of message in payload
uint64_t payload64[(MAVLINK_MAX_PAYLOAD_LEN+MAVLINK_NUM_CHECKSUM_BYTES+7)/8];
} mavlink_message_t;
 
 
typedef struct __mavlink_extended_message {
mavlink_message_t base_msg;
int32_t extended_payload_len; ///< Length of extended payload if any
uint8_t extended_payload[MAVLINK_MAX_EXTENDED_PAYLOAD_LEN];
} mavlink_extended_message_t;
 
 
typedef enum {
MAVLINK_TYPE_CHAR = 0,
MAVLINK_TYPE_UINT8_T = 1,
MAVLINK_TYPE_INT8_T = 2,
MAVLINK_TYPE_UINT16_T = 3,
MAVLINK_TYPE_INT16_T = 4,
MAVLINK_TYPE_UINT32_T = 5,
MAVLINK_TYPE_INT32_T = 6,
MAVLINK_TYPE_UINT64_T = 7,
MAVLINK_TYPE_INT64_T = 8,
MAVLINK_TYPE_FLOAT = 9,
MAVLINK_TYPE_DOUBLE = 10
} mavlink_message_type_t;
 
#define MAVLINK_MAX_FIELDS 64
 
typedef struct __mavlink_field_info {
const char *name; // name of this field
const char *print_format; // printing format hint, or NULL
mavlink_message_type_t type; // type of this field
unsigned int array_length; // if non-zero, field is an array
unsigned int wire_offset; // offset of each field in the payload
unsigned int structure_offset; // offset in a C structure
} mavlink_field_info_t;
 
// note that in this structure the order of fields is the order
// in the XML file, not necessary the wire order
typedef struct __mavlink_message_info {
const char *name; // name of the message
unsigned num_fields; // how many fields in this message
mavlink_field_info_t fields[MAVLINK_MAX_FIELDS]; // field information
} mavlink_message_info_t;
 
#define _MAV_PAYLOAD(msg) ((const char *)(&((msg)->payload64[0])))
#define _MAV_PAYLOAD_NON_CONST(msg) ((char *)(&((msg)->payload64[0])))
 
// checksum is immediately after the payload bytes
#define mavlink_ck_a(msg) *((msg)->len + (uint8_t *)_MAV_PAYLOAD_NON_CONST(msg))
#define mavlink_ck_b(msg) *(((msg)->len+(uint16_t)1) + (uint8_t *)_MAV_PAYLOAD_NON_CONST(msg))
 
typedef enum {
MAVLINK_COMM_0,
MAVLINK_COMM_1,
MAVLINK_COMM_2,
MAVLINK_COMM_3
} mavlink_channel_t;
 
/*
* applications can set MAVLINK_COMM_NUM_BUFFERS to the maximum number
* of buffers they will use. If more are used, then the result will be
* a stack overrun
*/
#ifndef MAVLINK_COMM_NUM_BUFFERS
#if (defined linux) | (defined __linux) | (defined __MACH__) | (defined _WIN32)
# define MAVLINK_COMM_NUM_BUFFERS 16
#else
# define MAVLINK_COMM_NUM_BUFFERS 4
#endif
#endif
 
typedef enum {
MAVLINK_PARSE_STATE_UNINIT=0,
MAVLINK_PARSE_STATE_IDLE,
MAVLINK_PARSE_STATE_GOT_STX,
MAVLINK_PARSE_STATE_GOT_SEQ,
MAVLINK_PARSE_STATE_GOT_LENGTH,
MAVLINK_PARSE_STATE_GOT_SYSID,
MAVLINK_PARSE_STATE_GOT_COMPID,
MAVLINK_PARSE_STATE_GOT_MSGID,
MAVLINK_PARSE_STATE_GOT_PAYLOAD,
MAVLINK_PARSE_STATE_GOT_CRC1
} mavlink_parse_state_t; ///< The state machine for the comm parser
 
typedef struct __mavlink_status {
uint8_t msg_received; ///< Number of received messages
uint8_t buffer_overrun; ///< Number of buffer overruns
uint8_t parse_error; ///< Number of parse errors
mavlink_parse_state_t parse_state; ///< Parsing state machine
uint8_t packet_idx; ///< Index in current packet
uint8_t current_rx_seq; ///< Sequence number of last packet received
uint8_t current_tx_seq; ///< Sequence number of last packet sent
uint16_t packet_rx_success_count; ///< Received packets
uint16_t packet_rx_drop_count; ///< Number of packet drops
} mavlink_status_t;
 
#define MAVLINK_BIG_ENDIAN 0
#define MAVLINK_LITTLE_ENDIAN 1
 
#endif /* MAVLINK_TYPES_H_ */
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v0.9/protocol.h
0,0 → 1,322
#ifndef _MAVLINK_PROTOCOL_H_
#define _MAVLINK_PROTOCOL_H_
 
#include "string.h"
#include "mavlink_types.h"
 
/*
If you want MAVLink on a system that is native big-endian,
you need to define NATIVE_BIG_ENDIAN
*/
#ifdef NATIVE_BIG_ENDIAN
# define MAVLINK_NEED_BYTE_SWAP (MAVLINK_ENDIAN == MAVLINK_LITTLE_ENDIAN)
#else
# define MAVLINK_NEED_BYTE_SWAP (MAVLINK_ENDIAN != MAVLINK_LITTLE_ENDIAN)
#endif
 
#ifndef MAVLINK_STACK_BUFFER
#define MAVLINK_STACK_BUFFER 0
#endif
 
#ifndef MAVLINK_AVOID_GCC_STACK_BUG
# define MAVLINK_AVOID_GCC_STACK_BUG defined(__GNUC__)
#endif
 
#ifndef MAVLINK_ASSERT
#define MAVLINK_ASSERT(x)
#endif
 
#ifndef MAVLINK_START_UART_SEND
#define MAVLINK_START_UART_SEND(chan, length)
#endif
 
#ifndef MAVLINK_END_UART_SEND
#define MAVLINK_END_UART_SEND(chan, length)
#endif
 
#ifdef MAVLINK_SEPARATE_HELPERS
#define MAVLINK_HELPER
#else
#define MAVLINK_HELPER static inline
#include "mavlink_helpers.h"
#endif // MAVLINK_SEPARATE_HELPERS
 
/* always include the prototypes to ensure we don't get out of sync */
MAVLINK_HELPER mavlink_status_t* mavlink_get_channel_status(uint8_t chan);
#if MAVLINK_CRC_EXTRA
MAVLINK_HELPER uint16_t mavlink_finalize_message_chan(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id,
uint8_t chan, uint8_t length, uint8_t crc_extra);
MAVLINK_HELPER uint16_t mavlink_finalize_message(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id,
uint8_t length, uint8_t crc_extra);
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
MAVLINK_HELPER void _mav_finalize_message_chan_send(mavlink_channel_t chan, uint8_t msgid, const char *packet,
uint8_t length, uint8_t crc_extra);
#endif
#else
MAVLINK_HELPER uint16_t mavlink_finalize_message_chan(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id,
uint8_t chan, uint8_t length);
MAVLINK_HELPER uint16_t mavlink_finalize_message(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id,
uint8_t length);
MAVLINK_HELPER void _mav_finalize_message_chan_send(mavlink_channel_t chan, uint8_t msgid, const char *packet, uint8_t length);
#endif // MAVLINK_CRC_EXTRA
MAVLINK_HELPER uint16_t mavlink_msg_to_send_buffer(uint8_t *buffer, const mavlink_message_t *msg);
MAVLINK_HELPER void mavlink_start_checksum(mavlink_message_t* msg);
MAVLINK_HELPER void mavlink_update_checksum(mavlink_message_t* msg, uint8_t c);
MAVLINK_HELPER uint8_t mavlink_parse_char(uint8_t chan, uint8_t c, mavlink_message_t* r_message, mavlink_status_t* r_mavlink_status);
MAVLINK_HELPER uint8_t put_bitfield_n_by_index(int32_t b, uint8_t bits, uint8_t packet_index, uint8_t bit_index,
uint8_t* r_bit_index, uint8_t* buffer);
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
MAVLINK_HELPER void _mavlink_send_uart(mavlink_channel_t chan, const char *buf, uint16_t len);
#endif
 
/**
* @brief Get the required buffer size for this message
*/
static inline uint16_t mavlink_msg_get_send_buffer_length(const mavlink_message_t* msg)
{
return msg->len + MAVLINK_NUM_NON_PAYLOAD_BYTES;
}
 
#if MAVLINK_NEED_BYTE_SWAP
static inline void byte_swap_2(char *dst, const char *src)
{
dst[0] = src[1];
dst[1] = src[0];
}
static inline void byte_swap_4(char *dst, const char *src)
{
dst[0] = src[3];
dst[1] = src[2];
dst[2] = src[1];
dst[3] = src[0];
}
static inline void byte_swap_8(char *dst, const char *src)
{
dst[0] = src[7];
dst[1] = src[6];
dst[2] = src[5];
dst[3] = src[4];
dst[4] = src[3];
dst[5] = src[2];
dst[6] = src[1];
dst[7] = src[0];
}
#elif !MAVLINK_ALIGNED_FIELDS
static inline void byte_copy_2(char *dst, const char *src)
{
dst[0] = src[0];
dst[1] = src[1];
}
static inline void byte_copy_4(char *dst, const char *src)
{
dst[0] = src[0];
dst[1] = src[1];
dst[2] = src[2];
dst[3] = src[3];
}
static inline void byte_copy_8(char *dst, const char *src)
{
memcpy(dst, src, 8);
}
#endif
 
#define _mav_put_uint8_t(buf, wire_offset, b) buf[wire_offset] = (uint8_t)b
#define _mav_put_int8_t(buf, wire_offset, b) buf[wire_offset] = (int8_t)b
#define _mav_put_char(buf, wire_offset, b) buf[wire_offset] = b
 
#if MAVLINK_NEED_BYTE_SWAP
#define _mav_put_uint16_t(buf, wire_offset, b) byte_swap_2(&buf[wire_offset], (const char *)&b)
#define _mav_put_int16_t(buf, wire_offset, b) byte_swap_2(&buf[wire_offset], (const char *)&b)
#define _mav_put_uint32_t(buf, wire_offset, b) byte_swap_4(&buf[wire_offset], (const char *)&b)
#define _mav_put_int32_t(buf, wire_offset, b) byte_swap_4(&buf[wire_offset], (const char *)&b)
#define _mav_put_uint64_t(buf, wire_offset, b) byte_swap_8(&buf[wire_offset], (const char *)&b)
#define _mav_put_int64_t(buf, wire_offset, b) byte_swap_8(&buf[wire_offset], (const char *)&b)
#define _mav_put_float(buf, wire_offset, b) byte_swap_4(&buf[wire_offset], (const char *)&b)
#define _mav_put_double(buf, wire_offset, b) byte_swap_8(&buf[wire_offset], (const char *)&b)
#elif !MAVLINK_ALIGNED_FIELDS
#define _mav_put_uint16_t(buf, wire_offset, b) byte_copy_2(&buf[wire_offset], (const char *)&b)
#define _mav_put_int16_t(buf, wire_offset, b) byte_copy_2(&buf[wire_offset], (const char *)&b)
#define _mav_put_uint32_t(buf, wire_offset, b) byte_copy_4(&buf[wire_offset], (const char *)&b)
#define _mav_put_int32_t(buf, wire_offset, b) byte_copy_4(&buf[wire_offset], (const char *)&b)
#define _mav_put_uint64_t(buf, wire_offset, b) byte_copy_8(&buf[wire_offset], (const char *)&b)
#define _mav_put_int64_t(buf, wire_offset, b) byte_copy_8(&buf[wire_offset], (const char *)&b)
#define _mav_put_float(buf, wire_offset, b) byte_copy_4(&buf[wire_offset], (const char *)&b)
#define _mav_put_double(buf, wire_offset, b) byte_copy_8(&buf[wire_offset], (const char *)&b)
#else
#define _mav_put_uint16_t(buf, wire_offset, b) *(uint16_t *)&buf[wire_offset] = b
#define _mav_put_int16_t(buf, wire_offset, b) *(int16_t *)&buf[wire_offset] = b
#define _mav_put_uint32_t(buf, wire_offset, b) *(uint32_t *)&buf[wire_offset] = b
#define _mav_put_int32_t(buf, wire_offset, b) *(int32_t *)&buf[wire_offset] = b
#define _mav_put_uint64_t(buf, wire_offset, b) *(uint64_t *)&buf[wire_offset] = b
#define _mav_put_int64_t(buf, wire_offset, b) *(int64_t *)&buf[wire_offset] = b
#define _mav_put_float(buf, wire_offset, b) *(float *)&buf[wire_offset] = b
#define _mav_put_double(buf, wire_offset, b) *(double *)&buf[wire_offset] = b
#endif
 
/*
like memcpy(), but if src is NULL, do a memset to zero
*/
static void mav_array_memcpy(void *dest, const void *src, size_t n)
{
if (src == NULL) {
memset(dest, 0, n);
} else {
memcpy(dest, src, n);
}
}
 
/*
* Place a char array into a buffer
*/
static inline void _mav_put_char_array(char *buf, uint8_t wire_offset, const char *b, uint8_t array_length)
{
mav_array_memcpy(&buf[wire_offset], b, array_length);
 
}
 
/*
* Place a uint8_t array into a buffer
*/
static inline void _mav_put_uint8_t_array(char *buf, uint8_t wire_offset, const uint8_t *b, uint8_t array_length)
{
mav_array_memcpy(&buf[wire_offset], b, array_length);
 
}
 
/*
* Place a int8_t array into a buffer
*/
static inline void _mav_put_int8_t_array(char *buf, uint8_t wire_offset, const int8_t *b, uint8_t array_length)
{
mav_array_memcpy(&buf[wire_offset], b, array_length);
 
}
 
#if MAVLINK_NEED_BYTE_SWAP
#define _MAV_PUT_ARRAY(TYPE, V) \
static inline void _mav_put_ ## TYPE ##_array(char *buf, uint8_t wire_offset, const TYPE *b, uint8_t array_length) \
{ \
if (b == NULL) { \
memset(&buf[wire_offset], 0, array_length*sizeof(TYPE)); \
} else { \
uint16_t i; \
for (i=0; i<array_length; i++) { \
_mav_put_## TYPE (buf, wire_offset+(i*sizeof(TYPE)), b[i]); \
} \
} \
}
#else
#define _MAV_PUT_ARRAY(TYPE, V) \
static inline void _mav_put_ ## TYPE ##_array(char *buf, uint8_t wire_offset, const TYPE *b, uint8_t array_length) \
{ \
mav_array_memcpy(&buf[wire_offset], b, array_length*sizeof(TYPE)); \
}
#endif
 
_MAV_PUT_ARRAY(uint16_t, u16)
_MAV_PUT_ARRAY(uint32_t, u32)
_MAV_PUT_ARRAY(uint64_t, u64)
_MAV_PUT_ARRAY(int16_t, i16)
_MAV_PUT_ARRAY(int32_t, i32)
_MAV_PUT_ARRAY(int64_t, i64)
_MAV_PUT_ARRAY(float, f)
_MAV_PUT_ARRAY(double, d)
 
#define _MAV_RETURN_char(msg, wire_offset) (const char)_MAV_PAYLOAD(msg)[wire_offset]
#define _MAV_RETURN_int8_t(msg, wire_offset) (const int8_t)_MAV_PAYLOAD(msg)[wire_offset]
#define _MAV_RETURN_uint8_t(msg, wire_offset) (const uint8_t)_MAV_PAYLOAD(msg)[wire_offset]
 
#if MAVLINK_NEED_BYTE_SWAP
#define _MAV_MSG_RETURN_TYPE(TYPE, SIZE) \
static inline TYPE _MAV_RETURN_## TYPE(const mavlink_message_t *msg, uint8_t ofs) \
{ TYPE r; byte_swap_## SIZE((char*)&r, &_MAV_PAYLOAD(msg)[ofs]); return r; }
 
_MAV_MSG_RETURN_TYPE(uint16_t, 2)
_MAV_MSG_RETURN_TYPE(int16_t, 2)
_MAV_MSG_RETURN_TYPE(uint32_t, 4)
_MAV_MSG_RETURN_TYPE(int32_t, 4)
_MAV_MSG_RETURN_TYPE(uint64_t, 8)
_MAV_MSG_RETURN_TYPE(int64_t, 8)
_MAV_MSG_RETURN_TYPE(float, 4)
_MAV_MSG_RETURN_TYPE(double, 8)
 
#elif !MAVLINK_ALIGNED_FIELDS
#define _MAV_MSG_RETURN_TYPE(TYPE, SIZE) \
static inline TYPE _MAV_RETURN_## TYPE(const mavlink_message_t *msg, uint8_t ofs) \
{ TYPE r; byte_copy_## SIZE((char*)&r, &_MAV_PAYLOAD(msg)[ofs]); return r; }
 
_MAV_MSG_RETURN_TYPE(uint16_t, 2)
_MAV_MSG_RETURN_TYPE(int16_t, 2)
_MAV_MSG_RETURN_TYPE(uint32_t, 4)
_MAV_MSG_RETURN_TYPE(int32_t, 4)
_MAV_MSG_RETURN_TYPE(uint64_t, 8)
_MAV_MSG_RETURN_TYPE(int64_t, 8)
_MAV_MSG_RETURN_TYPE(float, 4)
_MAV_MSG_RETURN_TYPE(double, 8)
#else // nicely aligned, no swap
#define _MAV_MSG_RETURN_TYPE(TYPE) \
static inline TYPE _MAV_RETURN_## TYPE(const mavlink_message_t *msg, uint8_t ofs) \
{ return *(const TYPE *)(&_MAV_PAYLOAD(msg)[ofs]);}
 
_MAV_MSG_RETURN_TYPE(uint16_t)
_MAV_MSG_RETURN_TYPE(int16_t)
_MAV_MSG_RETURN_TYPE(uint32_t)
_MAV_MSG_RETURN_TYPE(int32_t)
_MAV_MSG_RETURN_TYPE(uint64_t)
_MAV_MSG_RETURN_TYPE(int64_t)
_MAV_MSG_RETURN_TYPE(float)
_MAV_MSG_RETURN_TYPE(double)
#endif // MAVLINK_NEED_BYTE_SWAP
 
static inline uint16_t _MAV_RETURN_char_array(const mavlink_message_t *msg, char *value,
uint8_t array_length, uint8_t wire_offset)
{
memcpy(value, &_MAV_PAYLOAD(msg)[wire_offset], array_length);
return array_length;
}
 
static inline uint16_t _MAV_RETURN_uint8_t_array(const mavlink_message_t *msg, uint8_t *value,
uint8_t array_length, uint8_t wire_offset)
{
memcpy(value, &_MAV_PAYLOAD(msg)[wire_offset], array_length);
return array_length;
}
 
static inline uint16_t _MAV_RETURN_int8_t_array(const mavlink_message_t *msg, int8_t *value,
uint8_t array_length, uint8_t wire_offset)
{
memcpy(value, &_MAV_PAYLOAD(msg)[wire_offset], array_length);
return array_length;
}
 
#if MAVLINK_NEED_BYTE_SWAP
#define _MAV_RETURN_ARRAY(TYPE, V) \
static inline uint16_t _MAV_RETURN_## TYPE ##_array(const mavlink_message_t *msg, TYPE *value, \
uint8_t array_length, uint8_t wire_offset) \
{ \
uint16_t i; \
for (i=0; i<array_length; i++) { \
value[i] = _MAV_RETURN_## TYPE (msg, wire_offset+(i*sizeof(value[0]))); \
} \
return array_length*sizeof(value[0]); \
}
#else
#define _MAV_RETURN_ARRAY(TYPE, V) \
static inline uint16_t _MAV_RETURN_## TYPE ##_array(const mavlink_message_t *msg, TYPE *value, \
uint8_t array_length, uint8_t wire_offset) \
{ \
memcpy(value, &_MAV_PAYLOAD(msg)[wire_offset], array_length*sizeof(TYPE)); \
return array_length*sizeof(TYPE); \
}
#endif
 
_MAV_RETURN_ARRAY(uint16_t, u16)
_MAV_RETURN_ARRAY(uint32_t, u32)
_MAV_RETURN_ARRAY(uint64_t, u64)
_MAV_RETURN_ARRAY(int16_t, i16)
_MAV_RETURN_ARRAY(int32_t, i32)
_MAV_RETURN_ARRAY(int64_t, i64)
_MAV_RETURN_ARRAY(float, f)
_MAV_RETURN_ARRAY(double, d)
 
#endif // _MAVLINK_PROTOCOL_H_
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v1.0/ardupilotmega/ardupilotmega.h
0,0 → 1,151
/** @file
* @brief MAVLink comm protocol generated from ardupilotmega.xml
* @see http://qgroundcontrol.org/mavlink/
*/
#ifndef ARDUPILOTMEGA_H
#define ARDUPILOTMEGA_H
 
#ifdef __cplusplus
extern "C" {
#endif
 
// MESSAGE LENGTHS AND CRCS
 
#ifndef MAVLINK_MESSAGE_LENGTHS
#define MAVLINK_MESSAGE_LENGTHS {9, 31, 12, 0, 14, 28, 3, 32, 0, 0, 0, 6, 0, 0, 0, 0, 0, 0, 0, 0, 20, 2, 25, 23, 30, 101, 22, 26, 16, 14, 28, 32, 28, 28, 22, 22, 21, 6, 6, 37, 4, 4, 2, 2, 4, 2, 2, 3, 13, 12, 19, 17, 15, 15, 27, 25, 18, 18, 20, 20, 9, 54, 26, 0, 36, 0, 6, 4, 0, 21, 18, 0, 0, 0, 20, 0, 33, 3, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 28, 56, 42, 33, 0, 0, 0, 0, 0, 0, 0, 26, 32, 32, 20, 32, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 42, 8, 4, 12, 15, 13, 6, 15, 14, 0, 12, 3, 8, 28, 36, 3, 9, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 36, 30, 18, 18, 51, 9, 0}
#endif
 
#ifndef MAVLINK_MESSAGE_CRCS
#define MAVLINK_MESSAGE_CRCS {50, 124, 137, 0, 237, 217, 104, 119, 0, 0, 0, 89, 0, 0, 0, 0, 0, 0, 0, 0, 214, 159, 220, 168, 24, 23, 170, 144, 67, 115, 39, 246, 185, 104, 237, 244, 222, 212, 9, 254, 230, 28, 28, 132, 221, 232, 11, 153, 41, 39, 214, 223, 141, 33, 15, 3, 100, 24, 239, 238, 30, 200, 183, 0, 130, 0, 148, 21, 0, 52, 124, 0, 0, 0, 20, 0, 152, 143, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 231, 183, 63, 54, 0, 0, 0, 0, 0, 0, 0, 175, 102, 158, 208, 56, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 134, 219, 208, 188, 84, 22, 19, 21, 134, 0, 78, 68, 189, 127, 42, 21, 21, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 204, 49, 170, 44, 83, 46, 0}
#endif
 
#ifndef MAVLINK_MESSAGE_INFO
#define MAVLINK_MESSAGE_INFO {MAVLINK_MESSAGE_INFO_HEARTBEAT, MAVLINK_MESSAGE_INFO_SYS_STATUS, MAVLINK_MESSAGE_INFO_SYSTEM_TIME, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_PING, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL_ACK, MAVLINK_MESSAGE_INFO_AUTH_KEY, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_SET_MODE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_READ, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_LIST, MAVLINK_MESSAGE_INFO_PARAM_VALUE, MAVLINK_MESSAGE_INFO_PARAM_SET, MAVLINK_MESSAGE_INFO_GPS_RAW_INT, MAVLINK_MESSAGE_INFO_GPS_STATUS, MAVLINK_MESSAGE_INFO_SCALED_IMU, MAVLINK_MESSAGE_INFO_RAW_IMU, MAVLINK_MESSAGE_INFO_RAW_PRESSURE, MAVLINK_MESSAGE_INFO_SCALED_PRESSURE, MAVLINK_MESSAGE_INFO_ATTITUDE, MAVLINK_MESSAGE_INFO_ATTITUDE_QUATERNION, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_INT, MAVLINK_MESSAGE_INFO_RC_CHANNELS_SCALED, MAVLINK_MESSAGE_INFO_RC_CHANNELS_RAW, MAVLINK_MESSAGE_INFO_SERVO_OUTPUT_RAW, MAVLINK_MESSAGE_INFO_MISSION_REQUEST_PARTIAL_LIST, MAVLINK_MESSAGE_INFO_MISSION_WRITE_PARTIAL_LIST, MAVLINK_MESSAGE_INFO_MISSION_ITEM, MAVLINK_MESSAGE_INFO_MISSION_REQUEST, MAVLINK_MESSAGE_INFO_MISSION_SET_CURRENT, MAVLINK_MESSAGE_INFO_MISSION_CURRENT, MAVLINK_MESSAGE_INFO_MISSION_REQUEST_LIST, MAVLINK_MESSAGE_INFO_MISSION_COUNT, MAVLINK_MESSAGE_INFO_MISSION_CLEAR_ALL, MAVLINK_MESSAGE_INFO_MISSION_ITEM_REACHED, MAVLINK_MESSAGE_INFO_MISSION_ACK, MAVLINK_MESSAGE_INFO_SET_GPS_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_GPS_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_SET_LOCAL_POSITION_SETPOINT, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_SETPOINT, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_SETPOINT_INT, MAVLINK_MESSAGE_INFO_SET_GLOBAL_POSITION_SETPOINT_INT, MAVLINK_MESSAGE_INFO_SAFETY_SET_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SAFETY_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SET_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_SET_ROLL_PITCH_YAW_SPEED_THRUST, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_SET_QUAD_MOTORS_SETPOINT, MAVLINK_MESSAGE_INFO_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_NAV_CONTROLLER_OUTPUT, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_STATE_CORRECTION, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_REQUEST_DATA_STREAM, MAVLINK_MESSAGE_INFO_DATA_STREAM, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_MANUAL_CONTROL, MAVLINK_MESSAGE_INFO_RC_CHANNELS_OVERRIDE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_VFR_HUD, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_COMMAND_LONG, MAVLINK_MESSAGE_INFO_COMMAND_ACK, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET, MAVLINK_MESSAGE_INFO_HIL_STATE, MAVLINK_MESSAGE_INFO_HIL_CONTROLS, MAVLINK_MESSAGE_INFO_HIL_RC_INPUTS_RAW, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_OPTICAL_FLOW, MAVLINK_MESSAGE_INFO_GLOBAL_VISION_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_VISION_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_VISION_SPEED_ESTIMATE, MAVLINK_MESSAGE_INFO_VICON_POSITION_ESTIMATE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_SENSOR_OFFSETS, MAVLINK_MESSAGE_INFO_SET_MAG_OFFSETS, MAVLINK_MESSAGE_INFO_MEMINFO, MAVLINK_MESSAGE_INFO_AP_ADC, MAVLINK_MESSAGE_INFO_DIGICAM_CONFIGURE, MAVLINK_MESSAGE_INFO_DIGICAM_CONTROL, MAVLINK_MESSAGE_INFO_MOUNT_CONFIGURE, MAVLINK_MESSAGE_INFO_MOUNT_CONTROL, MAVLINK_MESSAGE_INFO_MOUNT_STATUS, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_FENCE_POINT, MAVLINK_MESSAGE_INFO_FENCE_FETCH_POINT, MAVLINK_MESSAGE_INFO_FENCE_STATUS, MAVLINK_MESSAGE_INFO_AHRS, MAVLINK_MESSAGE_INFO_SIMSTATE, MAVLINK_MESSAGE_INFO_HWSTATUS, MAVLINK_MESSAGE_INFO_RADIO, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_MEMORY_VECT, MAVLINK_MESSAGE_INFO_DEBUG_VECT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_FLOAT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_INT, MAVLINK_MESSAGE_INFO_STATUSTEXT, MAVLINK_MESSAGE_INFO_DEBUG, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}}
#endif
 
#include "../protocol.h"
 
#define MAVLINK_ENABLED_ARDUPILOTMEGA
 
// ENUM DEFINITIONS
 
 
/** @brief Enumeration of possible mount operation modes */
#ifndef HAVE_ENUM_MAV_MOUNT_MODE
#define HAVE_ENUM_MAV_MOUNT_MODE
enum MAV_MOUNT_MODE
{
MAV_MOUNT_MODE_RETRACT=0, /* Load and keep safe position (Roll,Pitch,Yaw) from EEPROM and stop stabilization | */
MAV_MOUNT_MODE_NEUTRAL=1, /* Load and keep neutral position (Roll,Pitch,Yaw) from EEPROM. | */
MAV_MOUNT_MODE_MAVLINK_TARGETING=2, /* Load neutral position and start MAVLink Roll,Pitch,Yaw control with stabilization | */
MAV_MOUNT_MODE_RC_TARGETING=3, /* Load neutral position and start RC Roll,Pitch,Yaw control with stabilization | */
MAV_MOUNT_MODE_GPS_POINT=4, /* Load neutral position and start to point to Lat,Lon,Alt | */
MAV_MOUNT_MODE_ENUM_END=5, /* | */
};
#endif
 
/** @brief */
#ifndef HAVE_ENUM_MAV_CMD
#define HAVE_ENUM_MAV_CMD
enum MAV_CMD
{
MAV_CMD_NAV_WAYPOINT=16, /* Navigate to MISSION. |Hold time in decimal seconds. (ignored by fixed wing, time to stay at MISSION for rotary wing)| Acceptance radius in meters (if the sphere with this radius is hit, the MISSION counts as reached)| 0 to pass through the WP, if > 0 radius in meters to pass by WP. Positive value for clockwise orbit, negative value for counter-clockwise orbit. Allows trajectory control.| Desired yaw angle at MISSION (rotary wing)| Latitude| Longitude| Altitude| */
MAV_CMD_NAV_LOITER_UNLIM=17, /* Loiter around this MISSION an unlimited amount of time |Empty| Empty| Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise| Desired yaw angle.| Latitude| Longitude| Altitude| */
MAV_CMD_NAV_LOITER_TURNS=18, /* Loiter around this MISSION for X turns |Turns| Empty| Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise| Desired yaw angle.| Latitude| Longitude| Altitude| */
MAV_CMD_NAV_LOITER_TIME=19, /* Loiter around this MISSION for X seconds |Seconds (decimal)| Empty| Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise| Desired yaw angle.| Latitude| Longitude| Altitude| */
MAV_CMD_NAV_RETURN_TO_LAUNCH=20, /* Return to launch location |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */
MAV_CMD_NAV_LAND=21, /* Land at location |Empty| Empty| Empty| Desired yaw angle.| Latitude| Longitude| Altitude| */
MAV_CMD_NAV_TAKEOFF=22, /* Takeoff from ground / hand |Minimum pitch (if airspeed sensor present), desired pitch without sensor| Empty| Empty| Yaw angle (if magnetometer present), ignored without magnetometer| Latitude| Longitude| Altitude| */
MAV_CMD_NAV_ROI=80, /* Sets the region of interest (ROI) for a sensor set or the vehicle itself. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras. |Region of intereset mode. (see MAV_ROI enum)| MISSION index/ target ID. (see MAV_ROI enum)| ROI index (allows a vehicle to manage multiple ROI's)| Empty| x the location of the fixed ROI (see MAV_FRAME)| y| z| */
MAV_CMD_NAV_PATHPLANNING=81, /* Control autonomous path planning on the MAV. |0: Disable local obstacle avoidance / local path planning (without resetting map), 1: Enable local path planning, 2: Enable and reset local path planning| 0: Disable full path planning (without resetting map), 1: Enable, 2: Enable and reset map/occupancy grid, 3: Enable and reset planned route, but not occupancy grid| Empty| Yaw angle at goal, in compass degrees, [0..360]| Latitude/X of goal| Longitude/Y of goal| Altitude/Z of goal| */
MAV_CMD_NAV_LAST=95, /* NOP - This command is only used to mark the upper limit of the NAV/ACTION commands in the enumeration |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */
MAV_CMD_CONDITION_DELAY=112, /* Delay mission state machine. |Delay in seconds (decimal)| Empty| Empty| Empty| Empty| Empty| Empty| */
MAV_CMD_CONDITION_CHANGE_ALT=113, /* Ascend/descend at rate. Delay mission state machine until desired altitude reached. |Descent / Ascend rate (m/s)| Empty| Empty| Empty| Empty| Empty| Finish Altitude| */
MAV_CMD_CONDITION_DISTANCE=114, /* Delay mission state machine until within desired distance of next NAV point. |Distance (meters)| Empty| Empty| Empty| Empty| Empty| Empty| */
MAV_CMD_CONDITION_YAW=115, /* Reach a certain target angle. |target angle: [0-360], 0 is north| speed during yaw change:[deg per second]| direction: negative: counter clockwise, positive: clockwise [-1,1]| relative offset or absolute angle: [ 1,0]| Empty| Empty| Empty| */
MAV_CMD_CONDITION_LAST=159, /* NOP - This command is only used to mark the upper limit of the CONDITION commands in the enumeration |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */
MAV_CMD_DO_SET_MODE=176, /* Set system mode. |Mode, as defined by ENUM MAV_MODE| Empty| Empty| Empty| Empty| Empty| Empty| */
MAV_CMD_DO_JUMP=177, /* Jump to the desired command in the mission list. Repeat this action only the specified number of times |Sequence number| Repeat count| Empty| Empty| Empty| Empty| Empty| */
MAV_CMD_DO_CHANGE_SPEED=178, /* Change speed and/or throttle set points. |Speed type (0=Airspeed, 1=Ground Speed)| Speed (m/s, -1 indicates no change)| Throttle ( Percent, -1 indicates no change)| Empty| Empty| Empty| Empty| */
MAV_CMD_DO_SET_HOME=179, /* Changes the home location either to the current location or a specified location. |Use current (1=use current location, 0=use specified location)| Empty| Empty| Empty| Latitude| Longitude| Altitude| */
MAV_CMD_DO_SET_PARAMETER=180, /* Set a system parameter. Caution! Use of this command requires knowledge of the numeric enumeration value of the parameter. |Parameter number| Parameter value| Empty| Empty| Empty| Empty| Empty| */
MAV_CMD_DO_SET_RELAY=181, /* Set a relay to a condition. |Relay number| Setting (1=on, 0=off, others possible depending on system hardware)| Empty| Empty| Empty| Empty| Empty| */
MAV_CMD_DO_REPEAT_RELAY=182, /* Cycle a relay on and off for a desired number of cyles with a desired period. |Relay number| Cycle count| Cycle time (seconds, decimal)| Empty| Empty| Empty| Empty| */
MAV_CMD_DO_SET_SERVO=183, /* Set a servo to a desired PWM value. |Servo number| PWM (microseconds, 1000 to 2000 typical)| Empty| Empty| Empty| Empty| Empty| */
MAV_CMD_DO_REPEAT_SERVO=184, /* Cycle a between its nominal setting and a desired PWM for a desired number of cycles with a desired period. |Servo number| PWM (microseconds, 1000 to 2000 typical)| Cycle count| Cycle time (seconds)| Empty| Empty| Empty| */
MAV_CMD_DO_CONTROL_VIDEO=200, /* Control onboard camera system. |Camera ID (-1 for all)| Transmission: 0: disabled, 1: enabled compressed, 2: enabled raw| Transmission mode: 0: video stream, >0: single images every n seconds (decimal)| Recording: 0: disabled, 1: enabled compressed, 2: enabled raw| Empty| Empty| Empty| */
MAV_CMD_DO_DIGICAM_CONFIGURE=202, /* Mission command to configure an on-board camera controller system. |Modes: P, TV, AV, M, Etc| Shutter speed: Divisor number for one second| Aperture: F stop number| ISO number e.g. 80, 100, 200, Etc| Exposure type enumerator| Command Identity| Main engine cut-off time before camera trigger in seconds/10 (0 means no cut-off)| */
MAV_CMD_DO_DIGICAM_CONTROL=203, /* Mission command to control an on-board camera controller system. |Session control e.g. show/hide lens| Zoom's absolute position| Zooming step value to offset zoom from the current position| Focus Locking, Unlocking or Re-locking| Shooting Command| Command Identity| Empty| */
MAV_CMD_DO_MOUNT_CONFIGURE=204, /* Mission command to configure a camera or antenna mount |Mount operation mode (see MAV_MOUNT_MODE enum)| stabilize roll? (1 = yes, 0 = no)| stabilize pitch? (1 = yes, 0 = no)| stabilize yaw? (1 = yes, 0 = no)| Empty| Empty| Empty| */
MAV_CMD_DO_MOUNT_CONTROL=205, /* Mission command to control a camera or antenna mount |pitch(deg*100) or lat, depending on mount mode.| roll(deg*100) or lon depending on mount mode| yaw(deg*100) or alt (in cm) depending on mount mode| Empty| Empty| Empty| Empty| */
MAV_CMD_DO_LAST=240, /* NOP - This command is only used to mark the upper limit of the DO commands in the enumeration |Empty| Empty| Empty| Empty| Empty| Empty| Empty| */
MAV_CMD_PREFLIGHT_CALIBRATION=241, /* Trigger calibration. This command will be only accepted if in pre-flight mode. |Gyro calibration: 0: no, 1: yes| Magnetometer calibration: 0: no, 1: yes| Ground pressure: 0: no, 1: yes| Radio calibration: 0: no, 1: yes| Empty| Empty| Empty| */
MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS=242, /* Set sensor offsets. This command will be only accepted if in pre-flight mode. |Sensor to adjust the offsets for: 0: gyros, 1: accelerometer, 2: magnetometer, 3: barometer, 4: optical flow| X axis offset (or generic dimension 1), in the sensor's raw units| Y axis offset (or generic dimension 2), in the sensor's raw units| Z axis offset (or generic dimension 3), in the sensor's raw units| Generic dimension 4, in the sensor's raw units| Generic dimension 5, in the sensor's raw units| Generic dimension 6, in the sensor's raw units| */
MAV_CMD_PREFLIGHT_STORAGE=245, /* Request storage of different parameter values and logs. This command will be only accepted if in pre-flight mode. |Parameter storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM| Mission storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM| Reserved| Reserved| Empty| Empty| Empty| */
MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN=246, /* Request the reboot or shutdown of system components. |0: Do nothing for autopilot, 1: Reboot autopilot, 2: Shutdown autopilot.| 0: Do nothing for onboard computer, 1: Reboot onboard computer, 2: Shutdown onboard computer.| Reserved| Reserved| Empty| Empty| Empty| */
MAV_CMD_OVERRIDE_GOTO=252, /* Hold / continue the current action |MAV_GOTO_DO_HOLD: hold MAV_GOTO_DO_CONTINUE: continue with next item in mission plan| MAV_GOTO_HOLD_AT_CURRENT_POSITION: Hold at current position MAV_GOTO_HOLD_AT_SPECIFIED_POSITION: hold at specified position| MAV_FRAME coordinate frame of hold point| Desired yaw angle in degrees| Latitude / X position| Longitude / Y position| Altitude / Z position| */
MAV_CMD_MISSION_START=300, /* start running a mission |first_item: the first mission item to run| last_item: the last mission item to run (after this item is run, the mission ends)| */
MAV_CMD_COMPONENT_ARM_DISARM=400, /* Arms / Disarms a component |1 to arm, 0 to disarm| */
MAV_CMD_ENUM_END=401, /* | */
};
#endif
 
/** @brief */
#ifndef HAVE_ENUM_FENCE_ACTION
#define HAVE_ENUM_FENCE_ACTION
enum FENCE_ACTION
{
FENCE_ACTION_NONE=0, /* Disable fenced mode | */
FENCE_ACTION_GUIDED=1, /* Switched to guided mode to return point (fence point 0) | */
FENCE_ACTION_ENUM_END=2, /* | */
};
#endif
 
/** @brief */
#ifndef HAVE_ENUM_FENCE_BREACH
#define HAVE_ENUM_FENCE_BREACH
enum FENCE_BREACH
{
FENCE_BREACH_NONE=0, /* No last fence breach | */
FENCE_BREACH_MINALT=1, /* Breached minimum altitude | */
FENCE_BREACH_MAXALT=2, /* Breached minimum altitude | */
FENCE_BREACH_BOUNDARY=3, /* Breached fence boundary | */
FENCE_BREACH_ENUM_END=4, /* | */
};
#endif
 
#include "../common/common.h"
 
// MAVLINK VERSION
 
#ifndef MAVLINK_VERSION
#define MAVLINK_VERSION 2
#endif
 
#if (MAVLINK_VERSION == 0)
#undef MAVLINK_VERSION
#define MAVLINK_VERSION 2
#endif
 
// MESSAGE DEFINITIONS
#include "./mavlink_msg_sensor_offsets.h"
#include "./mavlink_msg_set_mag_offsets.h"
#include "./mavlink_msg_meminfo.h"
#include "./mavlink_msg_ap_adc.h"
#include "./mavlink_msg_digicam_configure.h"
#include "./mavlink_msg_digicam_control.h"
#include "./mavlink_msg_mount_configure.h"
#include "./mavlink_msg_mount_control.h"
#include "./mavlink_msg_mount_status.h"
#include "./mavlink_msg_fence_point.h"
#include "./mavlink_msg_fence_fetch_point.h"
#include "./mavlink_msg_fence_status.h"
#include "./mavlink_msg_ahrs.h"
#include "./mavlink_msg_simstate.h"
#include "./mavlink_msg_hwstatus.h"
#include "./mavlink_msg_radio.h"
 
#ifdef __cplusplus
}
#endif // __cplusplus
#endif // ARDUPILOTMEGA_H
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v1.0/ardupilotmega/mavlink.h
0,0 → 1,27
/** @file
* @brief MAVLink comm protocol built from ardupilotmega.xml
* @see http://pixhawk.ethz.ch/software/mavlink
*/
#ifndef MAVLINK_H
#define MAVLINK_H
 
#ifndef MAVLINK_STX
#define MAVLINK_STX 254
#endif
 
#ifndef MAVLINK_ENDIAN
#define MAVLINK_ENDIAN MAVLINK_LITTLE_ENDIAN
#endif
 
#ifndef MAVLINK_ALIGNED_FIELDS
#define MAVLINK_ALIGNED_FIELDS 1
#endif
 
#ifndef MAVLINK_CRC_EXTRA
#define MAVLINK_CRC_EXTRA 1
#endif
 
#include "version.h"
#include "ardupilotmega.h"
 
#endif // MAVLINK_H
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_ahrs.h
0,0 → 1,276
// MESSAGE AHRS PACKING
 
#define MAVLINK_MSG_ID_AHRS 163
 
typedef struct __mavlink_ahrs_t
{
float omegaIx; ///< X gyro drift estimate rad/s
float omegaIy; ///< Y gyro drift estimate rad/s
float omegaIz; ///< Z gyro drift estimate rad/s
float accel_weight; ///< average accel_weight
float renorm_val; ///< average renormalisation value
float error_rp; ///< average error_roll_pitch value
float error_yaw; ///< average error_yaw value
} mavlink_ahrs_t;
 
#define MAVLINK_MSG_ID_AHRS_LEN 28
#define MAVLINK_MSG_ID_163_LEN 28
 
 
 
#define MAVLINK_MESSAGE_INFO_AHRS { \
"AHRS", \
7, \
{ { "omegaIx", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_ahrs_t, omegaIx) }, \
{ "omegaIy", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_ahrs_t, omegaIy) }, \
{ "omegaIz", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_ahrs_t, omegaIz) }, \
{ "accel_weight", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_ahrs_t, accel_weight) }, \
{ "renorm_val", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_ahrs_t, renorm_val) }, \
{ "error_rp", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_ahrs_t, error_rp) }, \
{ "error_yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_ahrs_t, error_yaw) }, \
} \
}
 
 
/**
* @brief Pack a ahrs message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param omegaIx X gyro drift estimate rad/s
* @param omegaIy Y gyro drift estimate rad/s
* @param omegaIz Z gyro drift estimate rad/s
* @param accel_weight average accel_weight
* @param renorm_val average renormalisation value
* @param error_rp average error_roll_pitch value
* @param error_yaw average error_yaw value
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_ahrs_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
float omegaIx, float omegaIy, float omegaIz, float accel_weight, float renorm_val, float error_rp, float error_yaw)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[28];
_mav_put_float(buf, 0, omegaIx);
_mav_put_float(buf, 4, omegaIy);
_mav_put_float(buf, 8, omegaIz);
_mav_put_float(buf, 12, accel_weight);
_mav_put_float(buf, 16, renorm_val);
_mav_put_float(buf, 20, error_rp);
_mav_put_float(buf, 24, error_yaw);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 28);
#else
mavlink_ahrs_t packet;
packet.omegaIx = omegaIx;
packet.omegaIy = omegaIy;
packet.omegaIz = omegaIz;
packet.accel_weight = accel_weight;
packet.renorm_val = renorm_val;
packet.error_rp = error_rp;
packet.error_yaw = error_yaw;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 28);
#endif
 
msg->msgid = MAVLINK_MSG_ID_AHRS;
return mavlink_finalize_message(msg, system_id, component_id, 28, 127);
}
 
/**
* @brief Pack a ahrs message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param omegaIx X gyro drift estimate rad/s
* @param omegaIy Y gyro drift estimate rad/s
* @param omegaIz Z gyro drift estimate rad/s
* @param accel_weight average accel_weight
* @param renorm_val average renormalisation value
* @param error_rp average error_roll_pitch value
* @param error_yaw average error_yaw value
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_ahrs_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
float omegaIx,float omegaIy,float omegaIz,float accel_weight,float renorm_val,float error_rp,float error_yaw)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[28];
_mav_put_float(buf, 0, omegaIx);
_mav_put_float(buf, 4, omegaIy);
_mav_put_float(buf, 8, omegaIz);
_mav_put_float(buf, 12, accel_weight);
_mav_put_float(buf, 16, renorm_val);
_mav_put_float(buf, 20, error_rp);
_mav_put_float(buf, 24, error_yaw);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 28);
#else
mavlink_ahrs_t packet;
packet.omegaIx = omegaIx;
packet.omegaIy = omegaIy;
packet.omegaIz = omegaIz;
packet.accel_weight = accel_weight;
packet.renorm_val = renorm_val;
packet.error_rp = error_rp;
packet.error_yaw = error_yaw;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 28);
#endif
 
msg->msgid = MAVLINK_MSG_ID_AHRS;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 28, 127);
}
 
/**
* @brief Encode a ahrs struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param ahrs C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_ahrs_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_ahrs_t* ahrs)
{
return mavlink_msg_ahrs_pack(system_id, component_id, msg, ahrs->omegaIx, ahrs->omegaIy, ahrs->omegaIz, ahrs->accel_weight, ahrs->renorm_val, ahrs->error_rp, ahrs->error_yaw);
}
 
/**
* @brief Send a ahrs message
* @param chan MAVLink channel to send the message
*
* @param omegaIx X gyro drift estimate rad/s
* @param omegaIy Y gyro drift estimate rad/s
* @param omegaIz Z gyro drift estimate rad/s
* @param accel_weight average accel_weight
* @param renorm_val average renormalisation value
* @param error_rp average error_roll_pitch value
* @param error_yaw average error_yaw value
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_ahrs_send(mavlink_channel_t chan, float omegaIx, float omegaIy, float omegaIz, float accel_weight, float renorm_val, float error_rp, float error_yaw)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[28];
_mav_put_float(buf, 0, omegaIx);
_mav_put_float(buf, 4, omegaIy);
_mav_put_float(buf, 8, omegaIz);
_mav_put_float(buf, 12, accel_weight);
_mav_put_float(buf, 16, renorm_val);
_mav_put_float(buf, 20, error_rp);
_mav_put_float(buf, 24, error_yaw);
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AHRS, buf, 28, 127);
#else
mavlink_ahrs_t packet;
packet.omegaIx = omegaIx;
packet.omegaIy = omegaIy;
packet.omegaIz = omegaIz;
packet.accel_weight = accel_weight;
packet.renorm_val = renorm_val;
packet.error_rp = error_rp;
packet.error_yaw = error_yaw;
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AHRS, (const char *)&packet, 28, 127);
#endif
}
 
#endif
 
// MESSAGE AHRS UNPACKING
 
 
/**
* @brief Get field omegaIx from ahrs message
*
* @return X gyro drift estimate rad/s
*/
static inline float mavlink_msg_ahrs_get_omegaIx(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 0);
}
 
/**
* @brief Get field omegaIy from ahrs message
*
* @return Y gyro drift estimate rad/s
*/
static inline float mavlink_msg_ahrs_get_omegaIy(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 4);
}
 
/**
* @brief Get field omegaIz from ahrs message
*
* @return Z gyro drift estimate rad/s
*/
static inline float mavlink_msg_ahrs_get_omegaIz(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 8);
}
 
/**
* @brief Get field accel_weight from ahrs message
*
* @return average accel_weight
*/
static inline float mavlink_msg_ahrs_get_accel_weight(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 12);
}
 
/**
* @brief Get field renorm_val from ahrs message
*
* @return average renormalisation value
*/
static inline float mavlink_msg_ahrs_get_renorm_val(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 16);
}
 
/**
* @brief Get field error_rp from ahrs message
*
* @return average error_roll_pitch value
*/
static inline float mavlink_msg_ahrs_get_error_rp(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 20);
}
 
/**
* @brief Get field error_yaw from ahrs message
*
* @return average error_yaw value
*/
static inline float mavlink_msg_ahrs_get_error_yaw(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 24);
}
 
/**
* @brief Decode a ahrs message into a struct
*
* @param msg The message to decode
* @param ahrs C-struct to decode the message contents into
*/
static inline void mavlink_msg_ahrs_decode(const mavlink_message_t* msg, mavlink_ahrs_t* ahrs)
{
#if MAVLINK_NEED_BYTE_SWAP
ahrs->omegaIx = mavlink_msg_ahrs_get_omegaIx(msg);
ahrs->omegaIy = mavlink_msg_ahrs_get_omegaIy(msg);
ahrs->omegaIz = mavlink_msg_ahrs_get_omegaIz(msg);
ahrs->accel_weight = mavlink_msg_ahrs_get_accel_weight(msg);
ahrs->renorm_val = mavlink_msg_ahrs_get_renorm_val(msg);
ahrs->error_rp = mavlink_msg_ahrs_get_error_rp(msg);
ahrs->error_yaw = mavlink_msg_ahrs_get_error_yaw(msg);
#else
memcpy(ahrs, _MAV_PAYLOAD(msg), 28);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_ap_adc.h
0,0 → 1,254
// MESSAGE AP_ADC PACKING
 
#define MAVLINK_MSG_ID_AP_ADC 153
 
typedef struct __mavlink_ap_adc_t
{
uint16_t adc1; ///< ADC output 1
uint16_t adc2; ///< ADC output 2
uint16_t adc3; ///< ADC output 3
uint16_t adc4; ///< ADC output 4
uint16_t adc5; ///< ADC output 5
uint16_t adc6; ///< ADC output 6
} mavlink_ap_adc_t;
 
#define MAVLINK_MSG_ID_AP_ADC_LEN 12
#define MAVLINK_MSG_ID_153_LEN 12
 
 
 
#define MAVLINK_MESSAGE_INFO_AP_ADC { \
"AP_ADC", \
6, \
{ { "adc1", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_ap_adc_t, adc1) }, \
{ "adc2", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_ap_adc_t, adc2) }, \
{ "adc3", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_ap_adc_t, adc3) }, \
{ "adc4", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_ap_adc_t, adc4) }, \
{ "adc5", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_ap_adc_t, adc5) }, \
{ "adc6", NULL, MAVLINK_TYPE_UINT16_T, 0, 10, offsetof(mavlink_ap_adc_t, adc6) }, \
} \
}
 
 
/**
* @brief Pack a ap_adc message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param adc1 ADC output 1
* @param adc2 ADC output 2
* @param adc3 ADC output 3
* @param adc4 ADC output 4
* @param adc5 ADC output 5
* @param adc6 ADC output 6
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_ap_adc_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint16_t adc1, uint16_t adc2, uint16_t adc3, uint16_t adc4, uint16_t adc5, uint16_t adc6)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[12];
_mav_put_uint16_t(buf, 0, adc1);
_mav_put_uint16_t(buf, 2, adc2);
_mav_put_uint16_t(buf, 4, adc3);
_mav_put_uint16_t(buf, 6, adc4);
_mav_put_uint16_t(buf, 8, adc5);
_mav_put_uint16_t(buf, 10, adc6);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 12);
#else
mavlink_ap_adc_t packet;
packet.adc1 = adc1;
packet.adc2 = adc2;
packet.adc3 = adc3;
packet.adc4 = adc4;
packet.adc5 = adc5;
packet.adc6 = adc6;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 12);
#endif
 
msg->msgid = MAVLINK_MSG_ID_AP_ADC;
return mavlink_finalize_message(msg, system_id, component_id, 12, 188);
}
 
/**
* @brief Pack a ap_adc message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param adc1 ADC output 1
* @param adc2 ADC output 2
* @param adc3 ADC output 3
* @param adc4 ADC output 4
* @param adc5 ADC output 5
* @param adc6 ADC output 6
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_ap_adc_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint16_t adc1,uint16_t adc2,uint16_t adc3,uint16_t adc4,uint16_t adc5,uint16_t adc6)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[12];
_mav_put_uint16_t(buf, 0, adc1);
_mav_put_uint16_t(buf, 2, adc2);
_mav_put_uint16_t(buf, 4, adc3);
_mav_put_uint16_t(buf, 6, adc4);
_mav_put_uint16_t(buf, 8, adc5);
_mav_put_uint16_t(buf, 10, adc6);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 12);
#else
mavlink_ap_adc_t packet;
packet.adc1 = adc1;
packet.adc2 = adc2;
packet.adc3 = adc3;
packet.adc4 = adc4;
packet.adc5 = adc5;
packet.adc6 = adc6;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 12);
#endif
 
msg->msgid = MAVLINK_MSG_ID_AP_ADC;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 12, 188);
}
 
/**
* @brief Encode a ap_adc struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param ap_adc C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_ap_adc_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_ap_adc_t* ap_adc)
{
return mavlink_msg_ap_adc_pack(system_id, component_id, msg, ap_adc->adc1, ap_adc->adc2, ap_adc->adc3, ap_adc->adc4, ap_adc->adc5, ap_adc->adc6);
}
 
/**
* @brief Send a ap_adc message
* @param chan MAVLink channel to send the message
*
* @param adc1 ADC output 1
* @param adc2 ADC output 2
* @param adc3 ADC output 3
* @param adc4 ADC output 4
* @param adc5 ADC output 5
* @param adc6 ADC output 6
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_ap_adc_send(mavlink_channel_t chan, uint16_t adc1, uint16_t adc2, uint16_t adc3, uint16_t adc4, uint16_t adc5, uint16_t adc6)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[12];
_mav_put_uint16_t(buf, 0, adc1);
_mav_put_uint16_t(buf, 2, adc2);
_mav_put_uint16_t(buf, 4, adc3);
_mav_put_uint16_t(buf, 6, adc4);
_mav_put_uint16_t(buf, 8, adc5);
_mav_put_uint16_t(buf, 10, adc6);
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AP_ADC, buf, 12, 188);
#else
mavlink_ap_adc_t packet;
packet.adc1 = adc1;
packet.adc2 = adc2;
packet.adc3 = adc3;
packet.adc4 = adc4;
packet.adc5 = adc5;
packet.adc6 = adc6;
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AP_ADC, (const char *)&packet, 12, 188);
#endif
}
 
#endif
 
// MESSAGE AP_ADC UNPACKING
 
 
/**
* @brief Get field adc1 from ap_adc message
*
* @return ADC output 1
*/
static inline uint16_t mavlink_msg_ap_adc_get_adc1(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 0);
}
 
/**
* @brief Get field adc2 from ap_adc message
*
* @return ADC output 2
*/
static inline uint16_t mavlink_msg_ap_adc_get_adc2(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 2);
}
 
/**
* @brief Get field adc3 from ap_adc message
*
* @return ADC output 3
*/
static inline uint16_t mavlink_msg_ap_adc_get_adc3(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 4);
}
 
/**
* @brief Get field adc4 from ap_adc message
*
* @return ADC output 4
*/
static inline uint16_t mavlink_msg_ap_adc_get_adc4(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 6);
}
 
/**
* @brief Get field adc5 from ap_adc message
*
* @return ADC output 5
*/
static inline uint16_t mavlink_msg_ap_adc_get_adc5(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 8);
}
 
/**
* @brief Get field adc6 from ap_adc message
*
* @return ADC output 6
*/
static inline uint16_t mavlink_msg_ap_adc_get_adc6(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 10);
}
 
/**
* @brief Decode a ap_adc message into a struct
*
* @param msg The message to decode
* @param ap_adc C-struct to decode the message contents into
*/
static inline void mavlink_msg_ap_adc_decode(const mavlink_message_t* msg, mavlink_ap_adc_t* ap_adc)
{
#if MAVLINK_NEED_BYTE_SWAP
ap_adc->adc1 = mavlink_msg_ap_adc_get_adc1(msg);
ap_adc->adc2 = mavlink_msg_ap_adc_get_adc2(msg);
ap_adc->adc3 = mavlink_msg_ap_adc_get_adc3(msg);
ap_adc->adc4 = mavlink_msg_ap_adc_get_adc4(msg);
ap_adc->adc5 = mavlink_msg_ap_adc_get_adc5(msg);
ap_adc->adc6 = mavlink_msg_ap_adc_get_adc6(msg);
#else
memcpy(ap_adc, _MAV_PAYLOAD(msg), 12);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_digicam_configure.h
0,0 → 1,364
// MESSAGE DIGICAM_CONFIGURE PACKING
 
#define MAVLINK_MSG_ID_DIGICAM_CONFIGURE 154
 
typedef struct __mavlink_digicam_configure_t
{
float extra_value; ///< Correspondent value to given extra_param
uint16_t shutter_speed; ///< Divisor number //e.g. 1000 means 1/1000 (0 means ignore)
uint8_t target_system; ///< System ID
uint8_t target_component; ///< Component ID
uint8_t mode; ///< Mode enumeration from 1 to N //P, TV, AV, M, Etc (0 means ignore)
uint8_t aperture; ///< F stop number x 10 //e.g. 28 means 2.8 (0 means ignore)
uint8_t iso; ///< ISO enumeration from 1 to N //e.g. 80, 100, 200, Etc (0 means ignore)
uint8_t exposure_type; ///< Exposure type enumeration from 1 to N (0 means ignore)
uint8_t command_id; ///< Command Identity (incremental loop: 0 to 255)//A command sent multiple times will be executed or pooled just once
uint8_t engine_cut_off; ///< Main engine cut-off time before camera trigger in seconds/10 (0 means no cut-off)
uint8_t extra_param; ///< Extra parameters enumeration (0 means ignore)
} mavlink_digicam_configure_t;
 
#define MAVLINK_MSG_ID_DIGICAM_CONFIGURE_LEN 15
#define MAVLINK_MSG_ID_154_LEN 15
 
 
 
#define MAVLINK_MESSAGE_INFO_DIGICAM_CONFIGURE { \
"DIGICAM_CONFIGURE", \
11, \
{ { "extra_value", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_digicam_configure_t, extra_value) }, \
{ "shutter_speed", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_digicam_configure_t, shutter_speed) }, \
{ "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_digicam_configure_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 7, offsetof(mavlink_digicam_configure_t, target_component) }, \
{ "mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_digicam_configure_t, mode) }, \
{ "aperture", NULL, MAVLINK_TYPE_UINT8_T, 0, 9, offsetof(mavlink_digicam_configure_t, aperture) }, \
{ "iso", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_digicam_configure_t, iso) }, \
{ "exposure_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 11, offsetof(mavlink_digicam_configure_t, exposure_type) }, \
{ "command_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 12, offsetof(mavlink_digicam_configure_t, command_id) }, \
{ "engine_cut_off", NULL, MAVLINK_TYPE_UINT8_T, 0, 13, offsetof(mavlink_digicam_configure_t, engine_cut_off) }, \
{ "extra_param", NULL, MAVLINK_TYPE_UINT8_T, 0, 14, offsetof(mavlink_digicam_configure_t, extra_param) }, \
} \
}
 
 
/**
* @brief Pack a digicam_configure message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param target_system System ID
* @param target_component Component ID
* @param mode Mode enumeration from 1 to N //P, TV, AV, M, Etc (0 means ignore)
* @param shutter_speed Divisor number //e.g. 1000 means 1/1000 (0 means ignore)
* @param aperture F stop number x 10 //e.g. 28 means 2.8 (0 means ignore)
* @param iso ISO enumeration from 1 to N //e.g. 80, 100, 200, Etc (0 means ignore)
* @param exposure_type Exposure type enumeration from 1 to N (0 means ignore)
* @param command_id Command Identity (incremental loop: 0 to 255)//A command sent multiple times will be executed or pooled just once
* @param engine_cut_off Main engine cut-off time before camera trigger in seconds/10 (0 means no cut-off)
* @param extra_param Extra parameters enumeration (0 means ignore)
* @param extra_value Correspondent value to given extra_param
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_digicam_configure_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t target_system, uint8_t target_component, uint8_t mode, uint16_t shutter_speed, uint8_t aperture, uint8_t iso, uint8_t exposure_type, uint8_t command_id, uint8_t engine_cut_off, uint8_t extra_param, float extra_value)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[15];
_mav_put_float(buf, 0, extra_value);
_mav_put_uint16_t(buf, 4, shutter_speed);
_mav_put_uint8_t(buf, 6, target_system);
_mav_put_uint8_t(buf, 7, target_component);
_mav_put_uint8_t(buf, 8, mode);
_mav_put_uint8_t(buf, 9, aperture);
_mav_put_uint8_t(buf, 10, iso);
_mav_put_uint8_t(buf, 11, exposure_type);
_mav_put_uint8_t(buf, 12, command_id);
_mav_put_uint8_t(buf, 13, engine_cut_off);
_mav_put_uint8_t(buf, 14, extra_param);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 15);
#else
mavlink_digicam_configure_t packet;
packet.extra_value = extra_value;
packet.shutter_speed = shutter_speed;
packet.target_system = target_system;
packet.target_component = target_component;
packet.mode = mode;
packet.aperture = aperture;
packet.iso = iso;
packet.exposure_type = exposure_type;
packet.command_id = command_id;
packet.engine_cut_off = engine_cut_off;
packet.extra_param = extra_param;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 15);
#endif
 
msg->msgid = MAVLINK_MSG_ID_DIGICAM_CONFIGURE;
return mavlink_finalize_message(msg, system_id, component_id, 15, 84);
}
 
/**
* @brief Pack a digicam_configure message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param target_system System ID
* @param target_component Component ID
* @param mode Mode enumeration from 1 to N //P, TV, AV, M, Etc (0 means ignore)
* @param shutter_speed Divisor number //e.g. 1000 means 1/1000 (0 means ignore)
* @param aperture F stop number x 10 //e.g. 28 means 2.8 (0 means ignore)
* @param iso ISO enumeration from 1 to N //e.g. 80, 100, 200, Etc (0 means ignore)
* @param exposure_type Exposure type enumeration from 1 to N (0 means ignore)
* @param command_id Command Identity (incremental loop: 0 to 255)//A command sent multiple times will be executed or pooled just once
* @param engine_cut_off Main engine cut-off time before camera trigger in seconds/10 (0 means no cut-off)
* @param extra_param Extra parameters enumeration (0 means ignore)
* @param extra_value Correspondent value to given extra_param
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_digicam_configure_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 mode,uint16_t shutter_speed,uint8_t aperture,uint8_t iso,uint8_t exposure_type,uint8_t command_id,uint8_t engine_cut_off,uint8_t extra_param,float extra_value)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[15];
_mav_put_float(buf, 0, extra_value);
_mav_put_uint16_t(buf, 4, shutter_speed);
_mav_put_uint8_t(buf, 6, target_system);
_mav_put_uint8_t(buf, 7, target_component);
_mav_put_uint8_t(buf, 8, mode);
_mav_put_uint8_t(buf, 9, aperture);
_mav_put_uint8_t(buf, 10, iso);
_mav_put_uint8_t(buf, 11, exposure_type);
_mav_put_uint8_t(buf, 12, command_id);
_mav_put_uint8_t(buf, 13, engine_cut_off);
_mav_put_uint8_t(buf, 14, extra_param);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 15);
#else
mavlink_digicam_configure_t packet;
packet.extra_value = extra_value;
packet.shutter_speed = shutter_speed;
packet.target_system = target_system;
packet.target_component = target_component;
packet.mode = mode;
packet.aperture = aperture;
packet.iso = iso;
packet.exposure_type = exposure_type;
packet.command_id = command_id;
packet.engine_cut_off = engine_cut_off;
packet.extra_param = extra_param;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 15);
#endif
 
msg->msgid = MAVLINK_MSG_ID_DIGICAM_CONFIGURE;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 15, 84);
}
 
/**
* @brief Encode a digicam_configure struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param digicam_configure C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_digicam_configure_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_digicam_configure_t* digicam_configure)
{
return mavlink_msg_digicam_configure_pack(system_id, component_id, msg, digicam_configure->target_system, digicam_configure->target_component, digicam_configure->mode, digicam_configure->shutter_speed, digicam_configure->aperture, digicam_configure->iso, digicam_configure->exposure_type, digicam_configure->command_id, digicam_configure->engine_cut_off, digicam_configure->extra_param, digicam_configure->extra_value);
}
 
/**
* @brief Send a digicam_configure message
* @param chan MAVLink channel to send the message
*
* @param target_system System ID
* @param target_component Component ID
* @param mode Mode enumeration from 1 to N //P, TV, AV, M, Etc (0 means ignore)
* @param shutter_speed Divisor number //e.g. 1000 means 1/1000 (0 means ignore)
* @param aperture F stop number x 10 //e.g. 28 means 2.8 (0 means ignore)
* @param iso ISO enumeration from 1 to N //e.g. 80, 100, 200, Etc (0 means ignore)
* @param exposure_type Exposure type enumeration from 1 to N (0 means ignore)
* @param command_id Command Identity (incremental loop: 0 to 255)//A command sent multiple times will be executed or pooled just once
* @param engine_cut_off Main engine cut-off time before camera trigger in seconds/10 (0 means no cut-off)
* @param extra_param Extra parameters enumeration (0 means ignore)
* @param extra_value Correspondent value to given extra_param
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_digicam_configure_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t mode, uint16_t shutter_speed, uint8_t aperture, uint8_t iso, uint8_t exposure_type, uint8_t command_id, uint8_t engine_cut_off, uint8_t extra_param, float extra_value)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[15];
_mav_put_float(buf, 0, extra_value);
_mav_put_uint16_t(buf, 4, shutter_speed);
_mav_put_uint8_t(buf, 6, target_system);
_mav_put_uint8_t(buf, 7, target_component);
_mav_put_uint8_t(buf, 8, mode);
_mav_put_uint8_t(buf, 9, aperture);
_mav_put_uint8_t(buf, 10, iso);
_mav_put_uint8_t(buf, 11, exposure_type);
_mav_put_uint8_t(buf, 12, command_id);
_mav_put_uint8_t(buf, 13, engine_cut_off);
_mav_put_uint8_t(buf, 14, extra_param);
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DIGICAM_CONFIGURE, buf, 15, 84);
#else
mavlink_digicam_configure_t packet;
packet.extra_value = extra_value;
packet.shutter_speed = shutter_speed;
packet.target_system = target_system;
packet.target_component = target_component;
packet.mode = mode;
packet.aperture = aperture;
packet.iso = iso;
packet.exposure_type = exposure_type;
packet.command_id = command_id;
packet.engine_cut_off = engine_cut_off;
packet.extra_param = extra_param;
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DIGICAM_CONFIGURE, (const char *)&packet, 15, 84);
#endif
}
 
#endif
 
// MESSAGE DIGICAM_CONFIGURE UNPACKING
 
 
/**
* @brief Get field target_system from digicam_configure message
*
* @return System ID
*/
static inline uint8_t mavlink_msg_digicam_configure_get_target_system(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 6);
}
 
/**
* @brief Get field target_component from digicam_configure message
*
* @return Component ID
*/
static inline uint8_t mavlink_msg_digicam_configure_get_target_component(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 7);
}
 
/**
* @brief Get field mode from digicam_configure message
*
* @return Mode enumeration from 1 to N //P, TV, AV, M, Etc (0 means ignore)
*/
static inline uint8_t mavlink_msg_digicam_configure_get_mode(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 8);
}
 
/**
* @brief Get field shutter_speed from digicam_configure message
*
* @return Divisor number //e.g. 1000 means 1/1000 (0 means ignore)
*/
static inline uint16_t mavlink_msg_digicam_configure_get_shutter_speed(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 4);
}
 
/**
* @brief Get field aperture from digicam_configure message
*
* @return F stop number x 10 //e.g. 28 means 2.8 (0 means ignore)
*/
static inline uint8_t mavlink_msg_digicam_configure_get_aperture(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 9);
}
 
/**
* @brief Get field iso from digicam_configure message
*
* @return ISO enumeration from 1 to N //e.g. 80, 100, 200, Etc (0 means ignore)
*/
static inline uint8_t mavlink_msg_digicam_configure_get_iso(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 10);
}
 
/**
* @brief Get field exposure_type from digicam_configure message
*
* @return Exposure type enumeration from 1 to N (0 means ignore)
*/
static inline uint8_t mavlink_msg_digicam_configure_get_exposure_type(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 11);
}
 
/**
* @brief Get field command_id from digicam_configure message
*
* @return Command Identity (incremental loop: 0 to 255)//A command sent multiple times will be executed or pooled just once
*/
static inline uint8_t mavlink_msg_digicam_configure_get_command_id(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 12);
}
 
/**
* @brief Get field engine_cut_off from digicam_configure message
*
* @return Main engine cut-off time before camera trigger in seconds/10 (0 means no cut-off)
*/
static inline uint8_t mavlink_msg_digicam_configure_get_engine_cut_off(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 13);
}
 
/**
* @brief Get field extra_param from digicam_configure message
*
* @return Extra parameters enumeration (0 means ignore)
*/
static inline uint8_t mavlink_msg_digicam_configure_get_extra_param(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 14);
}
 
/**
* @brief Get field extra_value from digicam_configure message
*
* @return Correspondent value to given extra_param
*/
static inline float mavlink_msg_digicam_configure_get_extra_value(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 0);
}
 
/**
* @brief Decode a digicam_configure message into a struct
*
* @param msg The message to decode
* @param digicam_configure C-struct to decode the message contents into
*/
static inline void mavlink_msg_digicam_configure_decode(const mavlink_message_t* msg, mavlink_digicam_configure_t* digicam_configure)
{
#if MAVLINK_NEED_BYTE_SWAP
digicam_configure->extra_value = mavlink_msg_digicam_configure_get_extra_value(msg);
digicam_configure->shutter_speed = mavlink_msg_digicam_configure_get_shutter_speed(msg);
digicam_configure->target_system = mavlink_msg_digicam_configure_get_target_system(msg);
digicam_configure->target_component = mavlink_msg_digicam_configure_get_target_component(msg);
digicam_configure->mode = mavlink_msg_digicam_configure_get_mode(msg);
digicam_configure->aperture = mavlink_msg_digicam_configure_get_aperture(msg);
digicam_configure->iso = mavlink_msg_digicam_configure_get_iso(msg);
digicam_configure->exposure_type = mavlink_msg_digicam_configure_get_exposure_type(msg);
digicam_configure->command_id = mavlink_msg_digicam_configure_get_command_id(msg);
digicam_configure->engine_cut_off = mavlink_msg_digicam_configure_get_engine_cut_off(msg);
digicam_configure->extra_param = mavlink_msg_digicam_configure_get_extra_param(msg);
#else
memcpy(digicam_configure, _MAV_PAYLOAD(msg), 15);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_digicam_control.h
0,0 → 1,342
// MESSAGE DIGICAM_CONTROL PACKING
 
#define MAVLINK_MSG_ID_DIGICAM_CONTROL 155
 
typedef struct __mavlink_digicam_control_t
{
float extra_value; ///< Correspondent value to given extra_param
uint8_t target_system; ///< System ID
uint8_t target_component; ///< Component ID
uint8_t session; ///< 0: stop, 1: start or keep it up //Session control e.g. show/hide lens
uint8_t zoom_pos; ///< 1 to N //Zoom's absolute position (0 means ignore)
int8_t zoom_step; ///< -100 to 100 //Zooming step value to offset zoom from the current position
uint8_t focus_lock; ///< 0: unlock focus or keep unlocked, 1: lock focus or keep locked, 3: re-lock focus
uint8_t shot; ///< 0: ignore, 1: shot or start filming
uint8_t command_id; ///< Command Identity (incremental loop: 0 to 255)//A command sent multiple times will be executed or pooled just once
uint8_t extra_param; ///< Extra parameters enumeration (0 means ignore)
} mavlink_digicam_control_t;
 
#define MAVLINK_MSG_ID_DIGICAM_CONTROL_LEN 13
#define MAVLINK_MSG_ID_155_LEN 13
 
 
 
#define MAVLINK_MESSAGE_INFO_DIGICAM_CONTROL { \
"DIGICAM_CONTROL", \
10, \
{ { "extra_value", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_digicam_control_t, extra_value) }, \
{ "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_digicam_control_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_digicam_control_t, target_component) }, \
{ "session", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_digicam_control_t, session) }, \
{ "zoom_pos", NULL, MAVLINK_TYPE_UINT8_T, 0, 7, offsetof(mavlink_digicam_control_t, zoom_pos) }, \
{ "zoom_step", NULL, MAVLINK_TYPE_INT8_T, 0, 8, offsetof(mavlink_digicam_control_t, zoom_step) }, \
{ "focus_lock", NULL, MAVLINK_TYPE_UINT8_T, 0, 9, offsetof(mavlink_digicam_control_t, focus_lock) }, \
{ "shot", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_digicam_control_t, shot) }, \
{ "command_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 11, offsetof(mavlink_digicam_control_t, command_id) }, \
{ "extra_param", NULL, MAVLINK_TYPE_UINT8_T, 0, 12, offsetof(mavlink_digicam_control_t, extra_param) }, \
} \
}
 
 
/**
* @brief Pack a digicam_control message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param target_system System ID
* @param target_component Component ID
* @param session 0: stop, 1: start or keep it up //Session control e.g. show/hide lens
* @param zoom_pos 1 to N //Zoom's absolute position (0 means ignore)
* @param zoom_step -100 to 100 //Zooming step value to offset zoom from the current position
* @param focus_lock 0: unlock focus or keep unlocked, 1: lock focus or keep locked, 3: re-lock focus
* @param shot 0: ignore, 1: shot or start filming
* @param command_id Command Identity (incremental loop: 0 to 255)//A command sent multiple times will be executed or pooled just once
* @param extra_param Extra parameters enumeration (0 means ignore)
* @param extra_value Correspondent value to given extra_param
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_digicam_control_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t target_system, uint8_t target_component, uint8_t session, uint8_t zoom_pos, int8_t zoom_step, uint8_t focus_lock, uint8_t shot, uint8_t command_id, uint8_t extra_param, float extra_value)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[13];
_mav_put_float(buf, 0, extra_value);
_mav_put_uint8_t(buf, 4, target_system);
_mav_put_uint8_t(buf, 5, target_component);
_mav_put_uint8_t(buf, 6, session);
_mav_put_uint8_t(buf, 7, zoom_pos);
_mav_put_int8_t(buf, 8, zoom_step);
_mav_put_uint8_t(buf, 9, focus_lock);
_mav_put_uint8_t(buf, 10, shot);
_mav_put_uint8_t(buf, 11, command_id);
_mav_put_uint8_t(buf, 12, extra_param);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 13);
#else
mavlink_digicam_control_t packet;
packet.extra_value = extra_value;
packet.target_system = target_system;
packet.target_component = target_component;
packet.session = session;
packet.zoom_pos = zoom_pos;
packet.zoom_step = zoom_step;
packet.focus_lock = focus_lock;
packet.shot = shot;
packet.command_id = command_id;
packet.extra_param = extra_param;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 13);
#endif
 
msg->msgid = MAVLINK_MSG_ID_DIGICAM_CONTROL;
return mavlink_finalize_message(msg, system_id, component_id, 13, 22);
}
 
/**
* @brief Pack a digicam_control message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param target_system System ID
* @param target_component Component ID
* @param session 0: stop, 1: start or keep it up //Session control e.g. show/hide lens
* @param zoom_pos 1 to N //Zoom's absolute position (0 means ignore)
* @param zoom_step -100 to 100 //Zooming step value to offset zoom from the current position
* @param focus_lock 0: unlock focus or keep unlocked, 1: lock focus or keep locked, 3: re-lock focus
* @param shot 0: ignore, 1: shot or start filming
* @param command_id Command Identity (incremental loop: 0 to 255)//A command sent multiple times will be executed or pooled just once
* @param extra_param Extra parameters enumeration (0 means ignore)
* @param extra_value Correspondent value to given extra_param
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_digicam_control_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 session,uint8_t zoom_pos,int8_t zoom_step,uint8_t focus_lock,uint8_t shot,uint8_t command_id,uint8_t extra_param,float extra_value)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[13];
_mav_put_float(buf, 0, extra_value);
_mav_put_uint8_t(buf, 4, target_system);
_mav_put_uint8_t(buf, 5, target_component);
_mav_put_uint8_t(buf, 6, session);
_mav_put_uint8_t(buf, 7, zoom_pos);
_mav_put_int8_t(buf, 8, zoom_step);
_mav_put_uint8_t(buf, 9, focus_lock);
_mav_put_uint8_t(buf, 10, shot);
_mav_put_uint8_t(buf, 11, command_id);
_mav_put_uint8_t(buf, 12, extra_param);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 13);
#else
mavlink_digicam_control_t packet;
packet.extra_value = extra_value;
packet.target_system = target_system;
packet.target_component = target_component;
packet.session = session;
packet.zoom_pos = zoom_pos;
packet.zoom_step = zoom_step;
packet.focus_lock = focus_lock;
packet.shot = shot;
packet.command_id = command_id;
packet.extra_param = extra_param;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 13);
#endif
 
msg->msgid = MAVLINK_MSG_ID_DIGICAM_CONTROL;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 13, 22);
}
 
/**
* @brief Encode a digicam_control struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param digicam_control C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_digicam_control_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_digicam_control_t* digicam_control)
{
return mavlink_msg_digicam_control_pack(system_id, component_id, msg, digicam_control->target_system, digicam_control->target_component, digicam_control->session, digicam_control->zoom_pos, digicam_control->zoom_step, digicam_control->focus_lock, digicam_control->shot, digicam_control->command_id, digicam_control->extra_param, digicam_control->extra_value);
}
 
/**
* @brief Send a digicam_control message
* @param chan MAVLink channel to send the message
*
* @param target_system System ID
* @param target_component Component ID
* @param session 0: stop, 1: start or keep it up //Session control e.g. show/hide lens
* @param zoom_pos 1 to N //Zoom's absolute position (0 means ignore)
* @param zoom_step -100 to 100 //Zooming step value to offset zoom from the current position
* @param focus_lock 0: unlock focus or keep unlocked, 1: lock focus or keep locked, 3: re-lock focus
* @param shot 0: ignore, 1: shot or start filming
* @param command_id Command Identity (incremental loop: 0 to 255)//A command sent multiple times will be executed or pooled just once
* @param extra_param Extra parameters enumeration (0 means ignore)
* @param extra_value Correspondent value to given extra_param
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_digicam_control_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t session, uint8_t zoom_pos, int8_t zoom_step, uint8_t focus_lock, uint8_t shot, uint8_t command_id, uint8_t extra_param, float extra_value)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[13];
_mav_put_float(buf, 0, extra_value);
_mav_put_uint8_t(buf, 4, target_system);
_mav_put_uint8_t(buf, 5, target_component);
_mav_put_uint8_t(buf, 6, session);
_mav_put_uint8_t(buf, 7, zoom_pos);
_mav_put_int8_t(buf, 8, zoom_step);
_mav_put_uint8_t(buf, 9, focus_lock);
_mav_put_uint8_t(buf, 10, shot);
_mav_put_uint8_t(buf, 11, command_id);
_mav_put_uint8_t(buf, 12, extra_param);
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DIGICAM_CONTROL, buf, 13, 22);
#else
mavlink_digicam_control_t packet;
packet.extra_value = extra_value;
packet.target_system = target_system;
packet.target_component = target_component;
packet.session = session;
packet.zoom_pos = zoom_pos;
packet.zoom_step = zoom_step;
packet.focus_lock = focus_lock;
packet.shot = shot;
packet.command_id = command_id;
packet.extra_param = extra_param;
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DIGICAM_CONTROL, (const char *)&packet, 13, 22);
#endif
}
 
#endif
 
// MESSAGE DIGICAM_CONTROL UNPACKING
 
 
/**
* @brief Get field target_system from digicam_control message
*
* @return System ID
*/
static inline uint8_t mavlink_msg_digicam_control_get_target_system(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 4);
}
 
/**
* @brief Get field target_component from digicam_control message
*
* @return Component ID
*/
static inline uint8_t mavlink_msg_digicam_control_get_target_component(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 5);
}
 
/**
* @brief Get field session from digicam_control message
*
* @return 0: stop, 1: start or keep it up //Session control e.g. show/hide lens
*/
static inline uint8_t mavlink_msg_digicam_control_get_session(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 6);
}
 
/**
* @brief Get field zoom_pos from digicam_control message
*
* @return 1 to N //Zoom's absolute position (0 means ignore)
*/
static inline uint8_t mavlink_msg_digicam_control_get_zoom_pos(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 7);
}
 
/**
* @brief Get field zoom_step from digicam_control message
*
* @return -100 to 100 //Zooming step value to offset zoom from the current position
*/
static inline int8_t mavlink_msg_digicam_control_get_zoom_step(const mavlink_message_t* msg)
{
return _MAV_RETURN_int8_t(msg, 8);
}
 
/**
* @brief Get field focus_lock from digicam_control message
*
* @return 0: unlock focus or keep unlocked, 1: lock focus or keep locked, 3: re-lock focus
*/
static inline uint8_t mavlink_msg_digicam_control_get_focus_lock(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 9);
}
 
/**
* @brief Get field shot from digicam_control message
*
* @return 0: ignore, 1: shot or start filming
*/
static inline uint8_t mavlink_msg_digicam_control_get_shot(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 10);
}
 
/**
* @brief Get field command_id from digicam_control message
*
* @return Command Identity (incremental loop: 0 to 255)//A command sent multiple times will be executed or pooled just once
*/
static inline uint8_t mavlink_msg_digicam_control_get_command_id(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 11);
}
 
/**
* @brief Get field extra_param from digicam_control message
*
* @return Extra parameters enumeration (0 means ignore)
*/
static inline uint8_t mavlink_msg_digicam_control_get_extra_param(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 12);
}
 
/**
* @brief Get field extra_value from digicam_control message
*
* @return Correspondent value to given extra_param
*/
static inline float mavlink_msg_digicam_control_get_extra_value(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 0);
}
 
/**
* @brief Decode a digicam_control message into a struct
*
* @param msg The message to decode
* @param digicam_control C-struct to decode the message contents into
*/
static inline void mavlink_msg_digicam_control_decode(const mavlink_message_t* msg, mavlink_digicam_control_t* digicam_control)
{
#if MAVLINK_NEED_BYTE_SWAP
digicam_control->extra_value = mavlink_msg_digicam_control_get_extra_value(msg);
digicam_control->target_system = mavlink_msg_digicam_control_get_target_system(msg);
digicam_control->target_component = mavlink_msg_digicam_control_get_target_component(msg);
digicam_control->session = mavlink_msg_digicam_control_get_session(msg);
digicam_control->zoom_pos = mavlink_msg_digicam_control_get_zoom_pos(msg);
digicam_control->zoom_step = mavlink_msg_digicam_control_get_zoom_step(msg);
digicam_control->focus_lock = mavlink_msg_digicam_control_get_focus_lock(msg);
digicam_control->shot = mavlink_msg_digicam_control_get_shot(msg);
digicam_control->command_id = mavlink_msg_digicam_control_get_command_id(msg);
digicam_control->extra_param = mavlink_msg_digicam_control_get_extra_param(msg);
#else
memcpy(digicam_control, _MAV_PAYLOAD(msg), 13);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_fence_fetch_point.h
0,0 → 1,188
// MESSAGE FENCE_FETCH_POINT PACKING
 
#define MAVLINK_MSG_ID_FENCE_FETCH_POINT 161
 
typedef struct __mavlink_fence_fetch_point_t
{
uint8_t target_system; ///< System ID
uint8_t target_component; ///< Component ID
uint8_t idx; ///< point index (first point is 1, 0 is for return point)
} mavlink_fence_fetch_point_t;
 
#define MAVLINK_MSG_ID_FENCE_FETCH_POINT_LEN 3
#define MAVLINK_MSG_ID_161_LEN 3
 
 
 
#define MAVLINK_MESSAGE_INFO_FENCE_FETCH_POINT { \
"FENCE_FETCH_POINT", \
3, \
{ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_fence_fetch_point_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_fence_fetch_point_t, target_component) }, \
{ "idx", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_fence_fetch_point_t, idx) }, \
} \
}
 
 
/**
* @brief Pack a fence_fetch_point message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param target_system System ID
* @param target_component Component ID
* @param idx point index (first point is 1, 0 is for return point)
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_fence_fetch_point_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t target_system, uint8_t target_component, uint8_t idx)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[3];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
_mav_put_uint8_t(buf, 2, idx);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 3);
#else
mavlink_fence_fetch_point_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
packet.idx = idx;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 3);
#endif
 
msg->msgid = MAVLINK_MSG_ID_FENCE_FETCH_POINT;
return mavlink_finalize_message(msg, system_id, component_id, 3, 68);
}
 
/**
* @brief Pack a fence_fetch_point message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param target_system System ID
* @param target_component Component ID
* @param idx point index (first point is 1, 0 is for return point)
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_fence_fetch_point_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 idx)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[3];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
_mav_put_uint8_t(buf, 2, idx);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 3);
#else
mavlink_fence_fetch_point_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
packet.idx = idx;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 3);
#endif
 
msg->msgid = MAVLINK_MSG_ID_FENCE_FETCH_POINT;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 3, 68);
}
 
/**
* @brief Encode a fence_fetch_point struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param fence_fetch_point C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_fence_fetch_point_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_fence_fetch_point_t* fence_fetch_point)
{
return mavlink_msg_fence_fetch_point_pack(system_id, component_id, msg, fence_fetch_point->target_system, fence_fetch_point->target_component, fence_fetch_point->idx);
}
 
/**
* @brief Send a fence_fetch_point message
* @param chan MAVLink channel to send the message
*
* @param target_system System ID
* @param target_component Component ID
* @param idx point index (first point is 1, 0 is for return point)
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_fence_fetch_point_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t idx)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[3];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
_mav_put_uint8_t(buf, 2, idx);
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FENCE_FETCH_POINT, buf, 3, 68);
#else
mavlink_fence_fetch_point_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
packet.idx = idx;
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FENCE_FETCH_POINT, (const char *)&packet, 3, 68);
#endif
}
 
#endif
 
// MESSAGE FENCE_FETCH_POINT UNPACKING
 
 
/**
* @brief Get field target_system from fence_fetch_point message
*
* @return System ID
*/
static inline uint8_t mavlink_msg_fence_fetch_point_get_target_system(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 0);
}
 
/**
* @brief Get field target_component from fence_fetch_point message
*
* @return Component ID
*/
static inline uint8_t mavlink_msg_fence_fetch_point_get_target_component(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 1);
}
 
/**
* @brief Get field idx from fence_fetch_point message
*
* @return point index (first point is 1, 0 is for return point)
*/
static inline uint8_t mavlink_msg_fence_fetch_point_get_idx(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 2);
}
 
/**
* @brief Decode a fence_fetch_point message into a struct
*
* @param msg The message to decode
* @param fence_fetch_point C-struct to decode the message contents into
*/
static inline void mavlink_msg_fence_fetch_point_decode(const mavlink_message_t* msg, mavlink_fence_fetch_point_t* fence_fetch_point)
{
#if MAVLINK_NEED_BYTE_SWAP
fence_fetch_point->target_system = mavlink_msg_fence_fetch_point_get_target_system(msg);
fence_fetch_point->target_component = mavlink_msg_fence_fetch_point_get_target_component(msg);
fence_fetch_point->idx = mavlink_msg_fence_fetch_point_get_idx(msg);
#else
memcpy(fence_fetch_point, _MAV_PAYLOAD(msg), 3);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_fence_point.h
0,0 → 1,254
// MESSAGE FENCE_POINT PACKING
 
#define MAVLINK_MSG_ID_FENCE_POINT 160
 
typedef struct __mavlink_fence_point_t
{
float lat; ///< Latitude of point
float lng; ///< Longitude of point
uint8_t target_system; ///< System ID
uint8_t target_component; ///< Component ID
uint8_t idx; ///< point index (first point is 1, 0 is for return point)
uint8_t count; ///< total number of points (for sanity checking)
} mavlink_fence_point_t;
 
#define MAVLINK_MSG_ID_FENCE_POINT_LEN 12
#define MAVLINK_MSG_ID_160_LEN 12
 
 
 
#define MAVLINK_MESSAGE_INFO_FENCE_POINT { \
"FENCE_POINT", \
6, \
{ { "lat", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_fence_point_t, lat) }, \
{ "lng", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_fence_point_t, lng) }, \
{ "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_fence_point_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 9, offsetof(mavlink_fence_point_t, target_component) }, \
{ "idx", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_fence_point_t, idx) }, \
{ "count", NULL, MAVLINK_TYPE_UINT8_T, 0, 11, offsetof(mavlink_fence_point_t, count) }, \
} \
}
 
 
/**
* @brief Pack a fence_point message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param target_system System ID
* @param target_component Component ID
* @param idx point index (first point is 1, 0 is for return point)
* @param count total number of points (for sanity checking)
* @param lat Latitude of point
* @param lng Longitude of point
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_fence_point_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t target_system, uint8_t target_component, uint8_t idx, uint8_t count, float lat, float lng)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[12];
_mav_put_float(buf, 0, lat);
_mav_put_float(buf, 4, lng);
_mav_put_uint8_t(buf, 8, target_system);
_mav_put_uint8_t(buf, 9, target_component);
_mav_put_uint8_t(buf, 10, idx);
_mav_put_uint8_t(buf, 11, count);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 12);
#else
mavlink_fence_point_t packet;
packet.lat = lat;
packet.lng = lng;
packet.target_system = target_system;
packet.target_component = target_component;
packet.idx = idx;
packet.count = count;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 12);
#endif
 
msg->msgid = MAVLINK_MSG_ID_FENCE_POINT;
return mavlink_finalize_message(msg, system_id, component_id, 12, 78);
}
 
/**
* @brief Pack a fence_point message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param target_system System ID
* @param target_component Component ID
* @param idx point index (first point is 1, 0 is for return point)
* @param count total number of points (for sanity checking)
* @param lat Latitude of point
* @param lng Longitude of point
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_fence_point_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 idx,uint8_t count,float lat,float lng)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[12];
_mav_put_float(buf, 0, lat);
_mav_put_float(buf, 4, lng);
_mav_put_uint8_t(buf, 8, target_system);
_mav_put_uint8_t(buf, 9, target_component);
_mav_put_uint8_t(buf, 10, idx);
_mav_put_uint8_t(buf, 11, count);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 12);
#else
mavlink_fence_point_t packet;
packet.lat = lat;
packet.lng = lng;
packet.target_system = target_system;
packet.target_component = target_component;
packet.idx = idx;
packet.count = count;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 12);
#endif
 
msg->msgid = MAVLINK_MSG_ID_FENCE_POINT;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 12, 78);
}
 
/**
* @brief Encode a fence_point struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param fence_point C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_fence_point_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_fence_point_t* fence_point)
{
return mavlink_msg_fence_point_pack(system_id, component_id, msg, fence_point->target_system, fence_point->target_component, fence_point->idx, fence_point->count, fence_point->lat, fence_point->lng);
}
 
/**
* @brief Send a fence_point message
* @param chan MAVLink channel to send the message
*
* @param target_system System ID
* @param target_component Component ID
* @param idx point index (first point is 1, 0 is for return point)
* @param count total number of points (for sanity checking)
* @param lat Latitude of point
* @param lng Longitude of point
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_fence_point_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t idx, uint8_t count, float lat, float lng)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[12];
_mav_put_float(buf, 0, lat);
_mav_put_float(buf, 4, lng);
_mav_put_uint8_t(buf, 8, target_system);
_mav_put_uint8_t(buf, 9, target_component);
_mav_put_uint8_t(buf, 10, idx);
_mav_put_uint8_t(buf, 11, count);
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FENCE_POINT, buf, 12, 78);
#else
mavlink_fence_point_t packet;
packet.lat = lat;
packet.lng = lng;
packet.target_system = target_system;
packet.target_component = target_component;
packet.idx = idx;
packet.count = count;
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FENCE_POINT, (const char *)&packet, 12, 78);
#endif
}
 
#endif
 
// MESSAGE FENCE_POINT UNPACKING
 
 
/**
* @brief Get field target_system from fence_point message
*
* @return System ID
*/
static inline uint8_t mavlink_msg_fence_point_get_target_system(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 8);
}
 
/**
* @brief Get field target_component from fence_point message
*
* @return Component ID
*/
static inline uint8_t mavlink_msg_fence_point_get_target_component(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 9);
}
 
/**
* @brief Get field idx from fence_point message
*
* @return point index (first point is 1, 0 is for return point)
*/
static inline uint8_t mavlink_msg_fence_point_get_idx(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 10);
}
 
/**
* @brief Get field count from fence_point message
*
* @return total number of points (for sanity checking)
*/
static inline uint8_t mavlink_msg_fence_point_get_count(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 11);
}
 
/**
* @brief Get field lat from fence_point message
*
* @return Latitude of point
*/
static inline float mavlink_msg_fence_point_get_lat(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 0);
}
 
/**
* @brief Get field lng from fence_point message
*
* @return Longitude of point
*/
static inline float mavlink_msg_fence_point_get_lng(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 4);
}
 
/**
* @brief Decode a fence_point message into a struct
*
* @param msg The message to decode
* @param fence_point C-struct to decode the message contents into
*/
static inline void mavlink_msg_fence_point_decode(const mavlink_message_t* msg, mavlink_fence_point_t* fence_point)
{
#if MAVLINK_NEED_BYTE_SWAP
fence_point->lat = mavlink_msg_fence_point_get_lat(msg);
fence_point->lng = mavlink_msg_fence_point_get_lng(msg);
fence_point->target_system = mavlink_msg_fence_point_get_target_system(msg);
fence_point->target_component = mavlink_msg_fence_point_get_target_component(msg);
fence_point->idx = mavlink_msg_fence_point_get_idx(msg);
fence_point->count = mavlink_msg_fence_point_get_count(msg);
#else
memcpy(fence_point, _MAV_PAYLOAD(msg), 12);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_fence_status.h
0,0 → 1,210
// MESSAGE FENCE_STATUS PACKING
 
#define MAVLINK_MSG_ID_FENCE_STATUS 162
 
typedef struct __mavlink_fence_status_t
{
uint32_t breach_time; ///< time of last breach in milliseconds since boot
uint16_t breach_count; ///< number of fence breaches
uint8_t breach_status; ///< 0 if currently inside fence, 1 if outside
uint8_t breach_type; ///< last breach type (see FENCE_BREACH_* enum)
} mavlink_fence_status_t;
 
#define MAVLINK_MSG_ID_FENCE_STATUS_LEN 8
#define MAVLINK_MSG_ID_162_LEN 8
 
 
 
#define MAVLINK_MESSAGE_INFO_FENCE_STATUS { \
"FENCE_STATUS", \
4, \
{ { "breach_time", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_fence_status_t, breach_time) }, \
{ "breach_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_fence_status_t, breach_count) }, \
{ "breach_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_fence_status_t, breach_status) }, \
{ "breach_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 7, offsetof(mavlink_fence_status_t, breach_type) }, \
} \
}
 
 
/**
* @brief Pack a fence_status message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param breach_status 0 if currently inside fence, 1 if outside
* @param breach_count number of fence breaches
* @param breach_type last breach type (see FENCE_BREACH_* enum)
* @param breach_time time of last breach in milliseconds since boot
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_fence_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t breach_status, uint16_t breach_count, uint8_t breach_type, uint32_t breach_time)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[8];
_mav_put_uint32_t(buf, 0, breach_time);
_mav_put_uint16_t(buf, 4, breach_count);
_mav_put_uint8_t(buf, 6, breach_status);
_mav_put_uint8_t(buf, 7, breach_type);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 8);
#else
mavlink_fence_status_t packet;
packet.breach_time = breach_time;
packet.breach_count = breach_count;
packet.breach_status = breach_status;
packet.breach_type = breach_type;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 8);
#endif
 
msg->msgid = MAVLINK_MSG_ID_FENCE_STATUS;
return mavlink_finalize_message(msg, system_id, component_id, 8, 189);
}
 
/**
* @brief Pack a fence_status message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param breach_status 0 if currently inside fence, 1 if outside
* @param breach_count number of fence breaches
* @param breach_type last breach type (see FENCE_BREACH_* enum)
* @param breach_time time of last breach in milliseconds since boot
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_fence_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint8_t breach_status,uint16_t breach_count,uint8_t breach_type,uint32_t breach_time)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[8];
_mav_put_uint32_t(buf, 0, breach_time);
_mav_put_uint16_t(buf, 4, breach_count);
_mav_put_uint8_t(buf, 6, breach_status);
_mav_put_uint8_t(buf, 7, breach_type);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 8);
#else
mavlink_fence_status_t packet;
packet.breach_time = breach_time;
packet.breach_count = breach_count;
packet.breach_status = breach_status;
packet.breach_type = breach_type;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 8);
#endif
 
msg->msgid = MAVLINK_MSG_ID_FENCE_STATUS;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 8, 189);
}
 
/**
* @brief Encode a fence_status struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param fence_status C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_fence_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_fence_status_t* fence_status)
{
return mavlink_msg_fence_status_pack(system_id, component_id, msg, fence_status->breach_status, fence_status->breach_count, fence_status->breach_type, fence_status->breach_time);
}
 
/**
* @brief Send a fence_status message
* @param chan MAVLink channel to send the message
*
* @param breach_status 0 if currently inside fence, 1 if outside
* @param breach_count number of fence breaches
* @param breach_type last breach type (see FENCE_BREACH_* enum)
* @param breach_time time of last breach in milliseconds since boot
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_fence_status_send(mavlink_channel_t chan, uint8_t breach_status, uint16_t breach_count, uint8_t breach_type, uint32_t breach_time)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[8];
_mav_put_uint32_t(buf, 0, breach_time);
_mav_put_uint16_t(buf, 4, breach_count);
_mav_put_uint8_t(buf, 6, breach_status);
_mav_put_uint8_t(buf, 7, breach_type);
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FENCE_STATUS, buf, 8, 189);
#else
mavlink_fence_status_t packet;
packet.breach_time = breach_time;
packet.breach_count = breach_count;
packet.breach_status = breach_status;
packet.breach_type = breach_type;
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FENCE_STATUS, (const char *)&packet, 8, 189);
#endif
}
 
#endif
 
// MESSAGE FENCE_STATUS UNPACKING
 
 
/**
* @brief Get field breach_status from fence_status message
*
* @return 0 if currently inside fence, 1 if outside
*/
static inline uint8_t mavlink_msg_fence_status_get_breach_status(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 6);
}
 
/**
* @brief Get field breach_count from fence_status message
*
* @return number of fence breaches
*/
static inline uint16_t mavlink_msg_fence_status_get_breach_count(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 4);
}
 
/**
* @brief Get field breach_type from fence_status message
*
* @return last breach type (see FENCE_BREACH_* enum)
*/
static inline uint8_t mavlink_msg_fence_status_get_breach_type(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 7);
}
 
/**
* @brief Get field breach_time from fence_status message
*
* @return time of last breach in milliseconds since boot
*/
static inline uint32_t mavlink_msg_fence_status_get_breach_time(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint32_t(msg, 0);
}
 
/**
* @brief Decode a fence_status message into a struct
*
* @param msg The message to decode
* @param fence_status C-struct to decode the message contents into
*/
static inline void mavlink_msg_fence_status_decode(const mavlink_message_t* msg, mavlink_fence_status_t* fence_status)
{
#if MAVLINK_NEED_BYTE_SWAP
fence_status->breach_time = mavlink_msg_fence_status_get_breach_time(msg);
fence_status->breach_count = mavlink_msg_fence_status_get_breach_count(msg);
fence_status->breach_status = mavlink_msg_fence_status_get_breach_status(msg);
fence_status->breach_type = mavlink_msg_fence_status_get_breach_type(msg);
#else
memcpy(fence_status, _MAV_PAYLOAD(msg), 8);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_hwstatus.h
0,0 → 1,166
// MESSAGE HWSTATUS PACKING
 
#define MAVLINK_MSG_ID_HWSTATUS 165
 
typedef struct __mavlink_hwstatus_t
{
uint16_t Vcc; ///< board voltage (mV)
uint8_t I2Cerr; ///< I2C error count
} mavlink_hwstatus_t;
 
#define MAVLINK_MSG_ID_HWSTATUS_LEN 3
#define MAVLINK_MSG_ID_165_LEN 3
 
 
 
#define MAVLINK_MESSAGE_INFO_HWSTATUS { \
"HWSTATUS", \
2, \
{ { "Vcc", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_hwstatus_t, Vcc) }, \
{ "I2Cerr", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_hwstatus_t, I2Cerr) }, \
} \
}
 
 
/**
* @brief Pack a hwstatus message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param Vcc board voltage (mV)
* @param I2Cerr I2C error count
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_hwstatus_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint16_t Vcc, uint8_t I2Cerr)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[3];
_mav_put_uint16_t(buf, 0, Vcc);
_mav_put_uint8_t(buf, 2, I2Cerr);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 3);
#else
mavlink_hwstatus_t packet;
packet.Vcc = Vcc;
packet.I2Cerr = I2Cerr;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 3);
#endif
 
msg->msgid = MAVLINK_MSG_ID_HWSTATUS;
return mavlink_finalize_message(msg, system_id, component_id, 3, 21);
}
 
/**
* @brief Pack a hwstatus message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param Vcc board voltage (mV)
* @param I2Cerr I2C error count
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_hwstatus_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint16_t Vcc,uint8_t I2Cerr)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[3];
_mav_put_uint16_t(buf, 0, Vcc);
_mav_put_uint8_t(buf, 2, I2Cerr);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 3);
#else
mavlink_hwstatus_t packet;
packet.Vcc = Vcc;
packet.I2Cerr = I2Cerr;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 3);
#endif
 
msg->msgid = MAVLINK_MSG_ID_HWSTATUS;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 3, 21);
}
 
/**
* @brief Encode a hwstatus struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param hwstatus C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_hwstatus_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_hwstatus_t* hwstatus)
{
return mavlink_msg_hwstatus_pack(system_id, component_id, msg, hwstatus->Vcc, hwstatus->I2Cerr);
}
 
/**
* @brief Send a hwstatus message
* @param chan MAVLink channel to send the message
*
* @param Vcc board voltage (mV)
* @param I2Cerr I2C error count
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_hwstatus_send(mavlink_channel_t chan, uint16_t Vcc, uint8_t I2Cerr)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[3];
_mav_put_uint16_t(buf, 0, Vcc);
_mav_put_uint8_t(buf, 2, I2Cerr);
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HWSTATUS, buf, 3, 21);
#else
mavlink_hwstatus_t packet;
packet.Vcc = Vcc;
packet.I2Cerr = I2Cerr;
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HWSTATUS, (const char *)&packet, 3, 21);
#endif
}
 
#endif
 
// MESSAGE HWSTATUS UNPACKING
 
 
/**
* @brief Get field Vcc from hwstatus message
*
* @return board voltage (mV)
*/
static inline uint16_t mavlink_msg_hwstatus_get_Vcc(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 0);
}
 
/**
* @brief Get field I2Cerr from hwstatus message
*
* @return I2C error count
*/
static inline uint8_t mavlink_msg_hwstatus_get_I2Cerr(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 2);
}
 
/**
* @brief Decode a hwstatus message into a struct
*
* @param msg The message to decode
* @param hwstatus C-struct to decode the message contents into
*/
static inline void mavlink_msg_hwstatus_decode(const mavlink_message_t* msg, mavlink_hwstatus_t* hwstatus)
{
#if MAVLINK_NEED_BYTE_SWAP
hwstatus->Vcc = mavlink_msg_hwstatus_get_Vcc(msg);
hwstatus->I2Cerr = mavlink_msg_hwstatus_get_I2Cerr(msg);
#else
memcpy(hwstatus, _MAV_PAYLOAD(msg), 3);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_meminfo.h
0,0 → 1,166
// MESSAGE MEMINFO PACKING
 
#define MAVLINK_MSG_ID_MEMINFO 152
 
typedef struct __mavlink_meminfo_t
{
uint16_t brkval; ///< heap top
uint16_t freemem; ///< free memory
} mavlink_meminfo_t;
 
#define MAVLINK_MSG_ID_MEMINFO_LEN 4
#define MAVLINK_MSG_ID_152_LEN 4
 
 
 
#define MAVLINK_MESSAGE_INFO_MEMINFO { \
"MEMINFO", \
2, \
{ { "brkval", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_meminfo_t, brkval) }, \
{ "freemem", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_meminfo_t, freemem) }, \
} \
}
 
 
/**
* @brief Pack a meminfo message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param brkval heap top
* @param freemem free memory
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_meminfo_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint16_t brkval, uint16_t freemem)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[4];
_mav_put_uint16_t(buf, 0, brkval);
_mav_put_uint16_t(buf, 2, freemem);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 4);
#else
mavlink_meminfo_t packet;
packet.brkval = brkval;
packet.freemem = freemem;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 4);
#endif
 
msg->msgid = MAVLINK_MSG_ID_MEMINFO;
return mavlink_finalize_message(msg, system_id, component_id, 4, 208);
}
 
/**
* @brief Pack a meminfo message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param brkval heap top
* @param freemem free memory
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_meminfo_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint16_t brkval,uint16_t freemem)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[4];
_mav_put_uint16_t(buf, 0, brkval);
_mav_put_uint16_t(buf, 2, freemem);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 4);
#else
mavlink_meminfo_t packet;
packet.brkval = brkval;
packet.freemem = freemem;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 4);
#endif
 
msg->msgid = MAVLINK_MSG_ID_MEMINFO;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 4, 208);
}
 
/**
* @brief Encode a meminfo struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param meminfo C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_meminfo_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_meminfo_t* meminfo)
{
return mavlink_msg_meminfo_pack(system_id, component_id, msg, meminfo->brkval, meminfo->freemem);
}
 
/**
* @brief Send a meminfo message
* @param chan MAVLink channel to send the message
*
* @param brkval heap top
* @param freemem free memory
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_meminfo_send(mavlink_channel_t chan, uint16_t brkval, uint16_t freemem)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[4];
_mav_put_uint16_t(buf, 0, brkval);
_mav_put_uint16_t(buf, 2, freemem);
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MEMINFO, buf, 4, 208);
#else
mavlink_meminfo_t packet;
packet.brkval = brkval;
packet.freemem = freemem;
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MEMINFO, (const char *)&packet, 4, 208);
#endif
}
 
#endif
 
// MESSAGE MEMINFO UNPACKING
 
 
/**
* @brief Get field brkval from meminfo message
*
* @return heap top
*/
static inline uint16_t mavlink_msg_meminfo_get_brkval(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 0);
}
 
/**
* @brief Get field freemem from meminfo message
*
* @return free memory
*/
static inline uint16_t mavlink_msg_meminfo_get_freemem(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 2);
}
 
/**
* @brief Decode a meminfo message into a struct
*
* @param msg The message to decode
* @param meminfo C-struct to decode the message contents into
*/
static inline void mavlink_msg_meminfo_decode(const mavlink_message_t* msg, mavlink_meminfo_t* meminfo)
{
#if MAVLINK_NEED_BYTE_SWAP
meminfo->brkval = mavlink_msg_meminfo_get_brkval(msg);
meminfo->freemem = mavlink_msg_meminfo_get_freemem(msg);
#else
memcpy(meminfo, _MAV_PAYLOAD(msg), 4);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_mount_configure.h
0,0 → 1,254
// MESSAGE MOUNT_CONFIGURE PACKING
 
#define MAVLINK_MSG_ID_MOUNT_CONFIGURE 156
 
typedef struct __mavlink_mount_configure_t
{
uint8_t target_system; ///< System ID
uint8_t target_component; ///< Component ID
uint8_t mount_mode; ///< mount operating mode (see MAV_MOUNT_MODE enum)
uint8_t stab_roll; ///< (1 = yes, 0 = no)
uint8_t stab_pitch; ///< (1 = yes, 0 = no)
uint8_t stab_yaw; ///< (1 = yes, 0 = no)
} mavlink_mount_configure_t;
 
#define MAVLINK_MSG_ID_MOUNT_CONFIGURE_LEN 6
#define MAVLINK_MSG_ID_156_LEN 6
 
 
 
#define MAVLINK_MESSAGE_INFO_MOUNT_CONFIGURE { \
"MOUNT_CONFIGURE", \
6, \
{ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_mount_configure_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_mount_configure_t, target_component) }, \
{ "mount_mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_mount_configure_t, mount_mode) }, \
{ "stab_roll", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_mount_configure_t, stab_roll) }, \
{ "stab_pitch", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_mount_configure_t, stab_pitch) }, \
{ "stab_yaw", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_mount_configure_t, stab_yaw) }, \
} \
}
 
 
/**
* @brief Pack a mount_configure message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param target_system System ID
* @param target_component Component ID
* @param mount_mode mount operating mode (see MAV_MOUNT_MODE enum)
* @param stab_roll (1 = yes, 0 = no)
* @param stab_pitch (1 = yes, 0 = no)
* @param stab_yaw (1 = yes, 0 = no)
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_mount_configure_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t target_system, uint8_t target_component, uint8_t mount_mode, uint8_t stab_roll, uint8_t stab_pitch, uint8_t stab_yaw)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[6];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
_mav_put_uint8_t(buf, 2, mount_mode);
_mav_put_uint8_t(buf, 3, stab_roll);
_mav_put_uint8_t(buf, 4, stab_pitch);
_mav_put_uint8_t(buf, 5, stab_yaw);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 6);
#else
mavlink_mount_configure_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
packet.mount_mode = mount_mode;
packet.stab_roll = stab_roll;
packet.stab_pitch = stab_pitch;
packet.stab_yaw = stab_yaw;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 6);
#endif
 
msg->msgid = MAVLINK_MSG_ID_MOUNT_CONFIGURE;
return mavlink_finalize_message(msg, system_id, component_id, 6, 19);
}
 
/**
* @brief Pack a mount_configure message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param target_system System ID
* @param target_component Component ID
* @param mount_mode mount operating mode (see MAV_MOUNT_MODE enum)
* @param stab_roll (1 = yes, 0 = no)
* @param stab_pitch (1 = yes, 0 = no)
* @param stab_yaw (1 = yes, 0 = no)
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_mount_configure_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 mount_mode,uint8_t stab_roll,uint8_t stab_pitch,uint8_t stab_yaw)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[6];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
_mav_put_uint8_t(buf, 2, mount_mode);
_mav_put_uint8_t(buf, 3, stab_roll);
_mav_put_uint8_t(buf, 4, stab_pitch);
_mav_put_uint8_t(buf, 5, stab_yaw);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 6);
#else
mavlink_mount_configure_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
packet.mount_mode = mount_mode;
packet.stab_roll = stab_roll;
packet.stab_pitch = stab_pitch;
packet.stab_yaw = stab_yaw;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 6);
#endif
 
msg->msgid = MAVLINK_MSG_ID_MOUNT_CONFIGURE;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 6, 19);
}
 
/**
* @brief Encode a mount_configure struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param mount_configure C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_mount_configure_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mount_configure_t* mount_configure)
{
return mavlink_msg_mount_configure_pack(system_id, component_id, msg, mount_configure->target_system, mount_configure->target_component, mount_configure->mount_mode, mount_configure->stab_roll, mount_configure->stab_pitch, mount_configure->stab_yaw);
}
 
/**
* @brief Send a mount_configure message
* @param chan MAVLink channel to send the message
*
* @param target_system System ID
* @param target_component Component ID
* @param mount_mode mount operating mode (see MAV_MOUNT_MODE enum)
* @param stab_roll (1 = yes, 0 = no)
* @param stab_pitch (1 = yes, 0 = no)
* @param stab_yaw (1 = yes, 0 = no)
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_mount_configure_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t mount_mode, uint8_t stab_roll, uint8_t stab_pitch, uint8_t stab_yaw)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[6];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
_mav_put_uint8_t(buf, 2, mount_mode);
_mav_put_uint8_t(buf, 3, stab_roll);
_mav_put_uint8_t(buf, 4, stab_pitch);
_mav_put_uint8_t(buf, 5, stab_yaw);
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MOUNT_CONFIGURE, buf, 6, 19);
#else
mavlink_mount_configure_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
packet.mount_mode = mount_mode;
packet.stab_roll = stab_roll;
packet.stab_pitch = stab_pitch;
packet.stab_yaw = stab_yaw;
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MOUNT_CONFIGURE, (const char *)&packet, 6, 19);
#endif
}
 
#endif
 
// MESSAGE MOUNT_CONFIGURE UNPACKING
 
 
/**
* @brief Get field target_system from mount_configure message
*
* @return System ID
*/
static inline uint8_t mavlink_msg_mount_configure_get_target_system(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 0);
}
 
/**
* @brief Get field target_component from mount_configure message
*
* @return Component ID
*/
static inline uint8_t mavlink_msg_mount_configure_get_target_component(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 1);
}
 
/**
* @brief Get field mount_mode from mount_configure message
*
* @return mount operating mode (see MAV_MOUNT_MODE enum)
*/
static inline uint8_t mavlink_msg_mount_configure_get_mount_mode(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 2);
}
 
/**
* @brief Get field stab_roll from mount_configure message
*
* @return (1 = yes, 0 = no)
*/
static inline uint8_t mavlink_msg_mount_configure_get_stab_roll(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 3);
}
 
/**
* @brief Get field stab_pitch from mount_configure message
*
* @return (1 = yes, 0 = no)
*/
static inline uint8_t mavlink_msg_mount_configure_get_stab_pitch(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 4);
}
 
/**
* @brief Get field stab_yaw from mount_configure message
*
* @return (1 = yes, 0 = no)
*/
static inline uint8_t mavlink_msg_mount_configure_get_stab_yaw(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 5);
}
 
/**
* @brief Decode a mount_configure message into a struct
*
* @param msg The message to decode
* @param mount_configure C-struct to decode the message contents into
*/
static inline void mavlink_msg_mount_configure_decode(const mavlink_message_t* msg, mavlink_mount_configure_t* mount_configure)
{
#if MAVLINK_NEED_BYTE_SWAP
mount_configure->target_system = mavlink_msg_mount_configure_get_target_system(msg);
mount_configure->target_component = mavlink_msg_mount_configure_get_target_component(msg);
mount_configure->mount_mode = mavlink_msg_mount_configure_get_mount_mode(msg);
mount_configure->stab_roll = mavlink_msg_mount_configure_get_stab_roll(msg);
mount_configure->stab_pitch = mavlink_msg_mount_configure_get_stab_pitch(msg);
mount_configure->stab_yaw = mavlink_msg_mount_configure_get_stab_yaw(msg);
#else
memcpy(mount_configure, _MAV_PAYLOAD(msg), 6);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_mount_control.h
0,0 → 1,254
// MESSAGE MOUNT_CONTROL PACKING
 
#define MAVLINK_MSG_ID_MOUNT_CONTROL 157
 
typedef struct __mavlink_mount_control_t
{
int32_t input_a; ///< pitch(deg*100) or lat, depending on mount mode
int32_t input_b; ///< roll(deg*100) or lon depending on mount mode
int32_t input_c; ///< yaw(deg*100) or alt (in cm) depending on mount mode
uint8_t target_system; ///< System ID
uint8_t target_component; ///< Component ID
uint8_t save_position; ///< if "1" it will save current trimmed position on EEPROM (just valid for NEUTRAL and LANDING)
} mavlink_mount_control_t;
 
#define MAVLINK_MSG_ID_MOUNT_CONTROL_LEN 15
#define MAVLINK_MSG_ID_157_LEN 15
 
 
 
#define MAVLINK_MESSAGE_INFO_MOUNT_CONTROL { \
"MOUNT_CONTROL", \
6, \
{ { "input_a", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_mount_control_t, input_a) }, \
{ "input_b", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_mount_control_t, input_b) }, \
{ "input_c", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_mount_control_t, input_c) }, \
{ "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 12, offsetof(mavlink_mount_control_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 13, offsetof(mavlink_mount_control_t, target_component) }, \
{ "save_position", NULL, MAVLINK_TYPE_UINT8_T, 0, 14, offsetof(mavlink_mount_control_t, save_position) }, \
} \
}
 
 
/**
* @brief Pack a mount_control message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param target_system System ID
* @param target_component Component ID
* @param input_a pitch(deg*100) or lat, depending on mount mode
* @param input_b roll(deg*100) or lon depending on mount mode
* @param input_c yaw(deg*100) or alt (in cm) depending on mount mode
* @param save_position if "1" it will save current trimmed position on EEPROM (just valid for NEUTRAL and LANDING)
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_mount_control_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t target_system, uint8_t target_component, int32_t input_a, int32_t input_b, int32_t input_c, uint8_t save_position)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[15];
_mav_put_int32_t(buf, 0, input_a);
_mav_put_int32_t(buf, 4, input_b);
_mav_put_int32_t(buf, 8, input_c);
_mav_put_uint8_t(buf, 12, target_system);
_mav_put_uint8_t(buf, 13, target_component);
_mav_put_uint8_t(buf, 14, save_position);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 15);
#else
mavlink_mount_control_t packet;
packet.input_a = input_a;
packet.input_b = input_b;
packet.input_c = input_c;
packet.target_system = target_system;
packet.target_component = target_component;
packet.save_position = save_position;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 15);
#endif
 
msg->msgid = MAVLINK_MSG_ID_MOUNT_CONTROL;
return mavlink_finalize_message(msg, system_id, component_id, 15, 21);
}
 
/**
* @brief Pack a mount_control message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param target_system System ID
* @param target_component Component ID
* @param input_a pitch(deg*100) or lat, depending on mount mode
* @param input_b roll(deg*100) or lon depending on mount mode
* @param input_c yaw(deg*100) or alt (in cm) depending on mount mode
* @param save_position if "1" it will save current trimmed position on EEPROM (just valid for NEUTRAL and LANDING)
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_mount_control_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,int32_t input_a,int32_t input_b,int32_t input_c,uint8_t save_position)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[15];
_mav_put_int32_t(buf, 0, input_a);
_mav_put_int32_t(buf, 4, input_b);
_mav_put_int32_t(buf, 8, input_c);
_mav_put_uint8_t(buf, 12, target_system);
_mav_put_uint8_t(buf, 13, target_component);
_mav_put_uint8_t(buf, 14, save_position);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 15);
#else
mavlink_mount_control_t packet;
packet.input_a = input_a;
packet.input_b = input_b;
packet.input_c = input_c;
packet.target_system = target_system;
packet.target_component = target_component;
packet.save_position = save_position;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 15);
#endif
 
msg->msgid = MAVLINK_MSG_ID_MOUNT_CONTROL;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 15, 21);
}
 
/**
* @brief Encode a mount_control struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param mount_control C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_mount_control_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mount_control_t* mount_control)
{
return mavlink_msg_mount_control_pack(system_id, component_id, msg, mount_control->target_system, mount_control->target_component, mount_control->input_a, mount_control->input_b, mount_control->input_c, mount_control->save_position);
}
 
/**
* @brief Send a mount_control message
* @param chan MAVLink channel to send the message
*
* @param target_system System ID
* @param target_component Component ID
* @param input_a pitch(deg*100) or lat, depending on mount mode
* @param input_b roll(deg*100) or lon depending on mount mode
* @param input_c yaw(deg*100) or alt (in cm) depending on mount mode
* @param save_position if "1" it will save current trimmed position on EEPROM (just valid for NEUTRAL and LANDING)
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_mount_control_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, int32_t input_a, int32_t input_b, int32_t input_c, uint8_t save_position)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[15];
_mav_put_int32_t(buf, 0, input_a);
_mav_put_int32_t(buf, 4, input_b);
_mav_put_int32_t(buf, 8, input_c);
_mav_put_uint8_t(buf, 12, target_system);
_mav_put_uint8_t(buf, 13, target_component);
_mav_put_uint8_t(buf, 14, save_position);
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MOUNT_CONTROL, buf, 15, 21);
#else
mavlink_mount_control_t packet;
packet.input_a = input_a;
packet.input_b = input_b;
packet.input_c = input_c;
packet.target_system = target_system;
packet.target_component = target_component;
packet.save_position = save_position;
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MOUNT_CONTROL, (const char *)&packet, 15, 21);
#endif
}
 
#endif
 
// MESSAGE MOUNT_CONTROL UNPACKING
 
 
/**
* @brief Get field target_system from mount_control message
*
* @return System ID
*/
static inline uint8_t mavlink_msg_mount_control_get_target_system(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 12);
}
 
/**
* @brief Get field target_component from mount_control message
*
* @return Component ID
*/
static inline uint8_t mavlink_msg_mount_control_get_target_component(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 13);
}
 
/**
* @brief Get field input_a from mount_control message
*
* @return pitch(deg*100) or lat, depending on mount mode
*/
static inline int32_t mavlink_msg_mount_control_get_input_a(const mavlink_message_t* msg)
{
return _MAV_RETURN_int32_t(msg, 0);
}
 
/**
* @brief Get field input_b from mount_control message
*
* @return roll(deg*100) or lon depending on mount mode
*/
static inline int32_t mavlink_msg_mount_control_get_input_b(const mavlink_message_t* msg)
{
return _MAV_RETURN_int32_t(msg, 4);
}
 
/**
* @brief Get field input_c from mount_control message
*
* @return yaw(deg*100) or alt (in cm) depending on mount mode
*/
static inline int32_t mavlink_msg_mount_control_get_input_c(const mavlink_message_t* msg)
{
return _MAV_RETURN_int32_t(msg, 8);
}
 
/**
* @brief Get field save_position from mount_control message
*
* @return if "1" it will save current trimmed position on EEPROM (just valid for NEUTRAL and LANDING)
*/
static inline uint8_t mavlink_msg_mount_control_get_save_position(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 14);
}
 
/**
* @brief Decode a mount_control message into a struct
*
* @param msg The message to decode
* @param mount_control C-struct to decode the message contents into
*/
static inline void mavlink_msg_mount_control_decode(const mavlink_message_t* msg, mavlink_mount_control_t* mount_control)
{
#if MAVLINK_NEED_BYTE_SWAP
mount_control->input_a = mavlink_msg_mount_control_get_input_a(msg);
mount_control->input_b = mavlink_msg_mount_control_get_input_b(msg);
mount_control->input_c = mavlink_msg_mount_control_get_input_c(msg);
mount_control->target_system = mavlink_msg_mount_control_get_target_system(msg);
mount_control->target_component = mavlink_msg_mount_control_get_target_component(msg);
mount_control->save_position = mavlink_msg_mount_control_get_save_position(msg);
#else
memcpy(mount_control, _MAV_PAYLOAD(msg), 15);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_mount_status.h
0,0 → 1,232
// MESSAGE MOUNT_STATUS PACKING
 
#define MAVLINK_MSG_ID_MOUNT_STATUS 158
 
typedef struct __mavlink_mount_status_t
{
int32_t pointing_a; ///< pitch(deg*100) or lat, depending on mount mode
int32_t pointing_b; ///< roll(deg*100) or lon depending on mount mode
int32_t pointing_c; ///< yaw(deg*100) or alt (in cm) depending on mount mode
uint8_t target_system; ///< System ID
uint8_t target_component; ///< Component ID
} mavlink_mount_status_t;
 
#define MAVLINK_MSG_ID_MOUNT_STATUS_LEN 14
#define MAVLINK_MSG_ID_158_LEN 14
 
 
 
#define MAVLINK_MESSAGE_INFO_MOUNT_STATUS { \
"MOUNT_STATUS", \
5, \
{ { "pointing_a", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_mount_status_t, pointing_a) }, \
{ "pointing_b", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_mount_status_t, pointing_b) }, \
{ "pointing_c", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_mount_status_t, pointing_c) }, \
{ "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 12, offsetof(mavlink_mount_status_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 13, offsetof(mavlink_mount_status_t, target_component) }, \
} \
}
 
 
/**
* @brief Pack a mount_status message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param target_system System ID
* @param target_component Component ID
* @param pointing_a pitch(deg*100) or lat, depending on mount mode
* @param pointing_b roll(deg*100) or lon depending on mount mode
* @param pointing_c yaw(deg*100) or alt (in cm) depending on mount mode
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_mount_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t target_system, uint8_t target_component, int32_t pointing_a, int32_t pointing_b, int32_t pointing_c)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[14];
_mav_put_int32_t(buf, 0, pointing_a);
_mav_put_int32_t(buf, 4, pointing_b);
_mav_put_int32_t(buf, 8, pointing_c);
_mav_put_uint8_t(buf, 12, target_system);
_mav_put_uint8_t(buf, 13, target_component);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 14);
#else
mavlink_mount_status_t packet;
packet.pointing_a = pointing_a;
packet.pointing_b = pointing_b;
packet.pointing_c = pointing_c;
packet.target_system = target_system;
packet.target_component = target_component;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 14);
#endif
 
msg->msgid = MAVLINK_MSG_ID_MOUNT_STATUS;
return mavlink_finalize_message(msg, system_id, component_id, 14, 134);
}
 
/**
* @brief Pack a mount_status message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param target_system System ID
* @param target_component Component ID
* @param pointing_a pitch(deg*100) or lat, depending on mount mode
* @param pointing_b roll(deg*100) or lon depending on mount mode
* @param pointing_c yaw(deg*100) or alt (in cm) depending on mount mode
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_mount_status_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,int32_t pointing_a,int32_t pointing_b,int32_t pointing_c)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[14];
_mav_put_int32_t(buf, 0, pointing_a);
_mav_put_int32_t(buf, 4, pointing_b);
_mav_put_int32_t(buf, 8, pointing_c);
_mav_put_uint8_t(buf, 12, target_system);
_mav_put_uint8_t(buf, 13, target_component);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 14);
#else
mavlink_mount_status_t packet;
packet.pointing_a = pointing_a;
packet.pointing_b = pointing_b;
packet.pointing_c = pointing_c;
packet.target_system = target_system;
packet.target_component = target_component;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 14);
#endif
 
msg->msgid = MAVLINK_MSG_ID_MOUNT_STATUS;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 14, 134);
}
 
/**
* @brief Encode a mount_status struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param mount_status C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_mount_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mount_status_t* mount_status)
{
return mavlink_msg_mount_status_pack(system_id, component_id, msg, mount_status->target_system, mount_status->target_component, mount_status->pointing_a, mount_status->pointing_b, mount_status->pointing_c);
}
 
/**
* @brief Send a mount_status message
* @param chan MAVLink channel to send the message
*
* @param target_system System ID
* @param target_component Component ID
* @param pointing_a pitch(deg*100) or lat, depending on mount mode
* @param pointing_b roll(deg*100) or lon depending on mount mode
* @param pointing_c yaw(deg*100) or alt (in cm) depending on mount mode
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_mount_status_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, int32_t pointing_a, int32_t pointing_b, int32_t pointing_c)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[14];
_mav_put_int32_t(buf, 0, pointing_a);
_mav_put_int32_t(buf, 4, pointing_b);
_mav_put_int32_t(buf, 8, pointing_c);
_mav_put_uint8_t(buf, 12, target_system);
_mav_put_uint8_t(buf, 13, target_component);
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MOUNT_STATUS, buf, 14, 134);
#else
mavlink_mount_status_t packet;
packet.pointing_a = pointing_a;
packet.pointing_b = pointing_b;
packet.pointing_c = pointing_c;
packet.target_system = target_system;
packet.target_component = target_component;
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MOUNT_STATUS, (const char *)&packet, 14, 134);
#endif
}
 
#endif
 
// MESSAGE MOUNT_STATUS UNPACKING
 
 
/**
* @brief Get field target_system from mount_status message
*
* @return System ID
*/
static inline uint8_t mavlink_msg_mount_status_get_target_system(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 12);
}
 
/**
* @brief Get field target_component from mount_status message
*
* @return Component ID
*/
static inline uint8_t mavlink_msg_mount_status_get_target_component(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 13);
}
 
/**
* @brief Get field pointing_a from mount_status message
*
* @return pitch(deg*100) or lat, depending on mount mode
*/
static inline int32_t mavlink_msg_mount_status_get_pointing_a(const mavlink_message_t* msg)
{
return _MAV_RETURN_int32_t(msg, 0);
}
 
/**
* @brief Get field pointing_b from mount_status message
*
* @return roll(deg*100) or lon depending on mount mode
*/
static inline int32_t mavlink_msg_mount_status_get_pointing_b(const mavlink_message_t* msg)
{
return _MAV_RETURN_int32_t(msg, 4);
}
 
/**
* @brief Get field pointing_c from mount_status message
*
* @return yaw(deg*100) or alt (in cm) depending on mount mode
*/
static inline int32_t mavlink_msg_mount_status_get_pointing_c(const mavlink_message_t* msg)
{
return _MAV_RETURN_int32_t(msg, 8);
}
 
/**
* @brief Decode a mount_status message into a struct
*
* @param msg The message to decode
* @param mount_status C-struct to decode the message contents into
*/
static inline void mavlink_msg_mount_status_decode(const mavlink_message_t* msg, mavlink_mount_status_t* mount_status)
{
#if MAVLINK_NEED_BYTE_SWAP
mount_status->pointing_a = mavlink_msg_mount_status_get_pointing_a(msg);
mount_status->pointing_b = mavlink_msg_mount_status_get_pointing_b(msg);
mount_status->pointing_c = mavlink_msg_mount_status_get_pointing_c(msg);
mount_status->target_system = mavlink_msg_mount_status_get_target_system(msg);
mount_status->target_component = mavlink_msg_mount_status_get_target_component(msg);
#else
memcpy(mount_status, _MAV_PAYLOAD(msg), 14);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_radio.h
0,0 → 1,276
// MESSAGE RADIO PACKING
 
#define MAVLINK_MSG_ID_RADIO 166
 
typedef struct __mavlink_radio_t
{
uint16_t rxerrors; ///< receive errors
uint16_t fixed; ///< count of error corrected packets
uint8_t rssi; ///< local signal strength
uint8_t remrssi; ///< remote signal strength
uint8_t txbuf; ///< how full the tx buffer is as a percentage
uint8_t noise; ///< background noise level
uint8_t remnoise; ///< remote background noise level
} mavlink_radio_t;
 
#define MAVLINK_MSG_ID_RADIO_LEN 9
#define MAVLINK_MSG_ID_166_LEN 9
 
 
 
#define MAVLINK_MESSAGE_INFO_RADIO { \
"RADIO", \
7, \
{ { "rxerrors", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_radio_t, rxerrors) }, \
{ "fixed", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_radio_t, fixed) }, \
{ "rssi", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_radio_t, rssi) }, \
{ "remrssi", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_radio_t, remrssi) }, \
{ "txbuf", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_radio_t, txbuf) }, \
{ "noise", NULL, MAVLINK_TYPE_UINT8_T, 0, 7, offsetof(mavlink_radio_t, noise) }, \
{ "remnoise", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_radio_t, remnoise) }, \
} \
}
 
 
/**
* @brief Pack a radio message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param rssi local signal strength
* @param remrssi remote signal strength
* @param txbuf how full the tx buffer is as a percentage
* @param noise background noise level
* @param remnoise remote background noise level
* @param rxerrors receive errors
* @param fixed count of error corrected packets
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_radio_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t rssi, uint8_t remrssi, uint8_t txbuf, uint8_t noise, uint8_t remnoise, uint16_t rxerrors, uint16_t fixed)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[9];
_mav_put_uint16_t(buf, 0, rxerrors);
_mav_put_uint16_t(buf, 2, fixed);
_mav_put_uint8_t(buf, 4, rssi);
_mav_put_uint8_t(buf, 5, remrssi);
_mav_put_uint8_t(buf, 6, txbuf);
_mav_put_uint8_t(buf, 7, noise);
_mav_put_uint8_t(buf, 8, remnoise);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 9);
#else
mavlink_radio_t packet;
packet.rxerrors = rxerrors;
packet.fixed = fixed;
packet.rssi = rssi;
packet.remrssi = remrssi;
packet.txbuf = txbuf;
packet.noise = noise;
packet.remnoise = remnoise;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 9);
#endif
 
msg->msgid = MAVLINK_MSG_ID_RADIO;
return mavlink_finalize_message(msg, system_id, component_id, 9, 21);
}
 
/**
* @brief Pack a radio message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param rssi local signal strength
* @param remrssi remote signal strength
* @param txbuf how full the tx buffer is as a percentage
* @param noise background noise level
* @param remnoise remote background noise level
* @param rxerrors receive errors
* @param fixed count of error corrected packets
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_radio_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint8_t rssi,uint8_t remrssi,uint8_t txbuf,uint8_t noise,uint8_t remnoise,uint16_t rxerrors,uint16_t fixed)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[9];
_mav_put_uint16_t(buf, 0, rxerrors);
_mav_put_uint16_t(buf, 2, fixed);
_mav_put_uint8_t(buf, 4, rssi);
_mav_put_uint8_t(buf, 5, remrssi);
_mav_put_uint8_t(buf, 6, txbuf);
_mav_put_uint8_t(buf, 7, noise);
_mav_put_uint8_t(buf, 8, remnoise);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 9);
#else
mavlink_radio_t packet;
packet.rxerrors = rxerrors;
packet.fixed = fixed;
packet.rssi = rssi;
packet.remrssi = remrssi;
packet.txbuf = txbuf;
packet.noise = noise;
packet.remnoise = remnoise;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 9);
#endif
 
msg->msgid = MAVLINK_MSG_ID_RADIO;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 9, 21);
}
 
/**
* @brief Encode a radio struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param radio C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_radio_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_radio_t* radio)
{
return mavlink_msg_radio_pack(system_id, component_id, msg, radio->rssi, radio->remrssi, radio->txbuf, radio->noise, radio->remnoise, radio->rxerrors, radio->fixed);
}
 
/**
* @brief Send a radio message
* @param chan MAVLink channel to send the message
*
* @param rssi local signal strength
* @param remrssi remote signal strength
* @param txbuf how full the tx buffer is as a percentage
* @param noise background noise level
* @param remnoise remote background noise level
* @param rxerrors receive errors
* @param fixed count of error corrected packets
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_radio_send(mavlink_channel_t chan, uint8_t rssi, uint8_t remrssi, uint8_t txbuf, uint8_t noise, uint8_t remnoise, uint16_t rxerrors, uint16_t fixed)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[9];
_mav_put_uint16_t(buf, 0, rxerrors);
_mav_put_uint16_t(buf, 2, fixed);
_mav_put_uint8_t(buf, 4, rssi);
_mav_put_uint8_t(buf, 5, remrssi);
_mav_put_uint8_t(buf, 6, txbuf);
_mav_put_uint8_t(buf, 7, noise);
_mav_put_uint8_t(buf, 8, remnoise);
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RADIO, buf, 9, 21);
#else
mavlink_radio_t packet;
packet.rxerrors = rxerrors;
packet.fixed = fixed;
packet.rssi = rssi;
packet.remrssi = remrssi;
packet.txbuf = txbuf;
packet.noise = noise;
packet.remnoise = remnoise;
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RADIO, (const char *)&packet, 9, 21);
#endif
}
 
#endif
 
// MESSAGE RADIO UNPACKING
 
 
/**
* @brief Get field rssi from radio message
*
* @return local signal strength
*/
static inline uint8_t mavlink_msg_radio_get_rssi(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 4);
}
 
/**
* @brief Get field remrssi from radio message
*
* @return remote signal strength
*/
static inline uint8_t mavlink_msg_radio_get_remrssi(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 5);
}
 
/**
* @brief Get field txbuf from radio message
*
* @return how full the tx buffer is as a percentage
*/
static inline uint8_t mavlink_msg_radio_get_txbuf(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 6);
}
 
/**
* @brief Get field noise from radio message
*
* @return background noise level
*/
static inline uint8_t mavlink_msg_radio_get_noise(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 7);
}
 
/**
* @brief Get field remnoise from radio message
*
* @return remote background noise level
*/
static inline uint8_t mavlink_msg_radio_get_remnoise(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 8);
}
 
/**
* @brief Get field rxerrors from radio message
*
* @return receive errors
*/
static inline uint16_t mavlink_msg_radio_get_rxerrors(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 0);
}
 
/**
* @brief Get field fixed from radio message
*
* @return count of error corrected packets
*/
static inline uint16_t mavlink_msg_radio_get_fixed(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 2);
}
 
/**
* @brief Decode a radio message into a struct
*
* @param msg The message to decode
* @param radio C-struct to decode the message contents into
*/
static inline void mavlink_msg_radio_decode(const mavlink_message_t* msg, mavlink_radio_t* radio)
{
#if MAVLINK_NEED_BYTE_SWAP
radio->rxerrors = mavlink_msg_radio_get_rxerrors(msg);
radio->fixed = mavlink_msg_radio_get_fixed(msg);
radio->rssi = mavlink_msg_radio_get_rssi(msg);
radio->remrssi = mavlink_msg_radio_get_remrssi(msg);
radio->txbuf = mavlink_msg_radio_get_txbuf(msg);
radio->noise = mavlink_msg_radio_get_noise(msg);
radio->remnoise = mavlink_msg_radio_get_remnoise(msg);
#else
memcpy(radio, _MAV_PAYLOAD(msg), 9);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_sensor_offsets.h
0,0 → 1,386
// MESSAGE SENSOR_OFFSETS PACKING
 
#define MAVLINK_MSG_ID_SENSOR_OFFSETS 150
 
typedef struct __mavlink_sensor_offsets_t
{
float mag_declination; ///< magnetic declination (radians)
int32_t raw_press; ///< raw pressure from barometer
int32_t raw_temp; ///< raw temperature from barometer
float gyro_cal_x; ///< gyro X calibration
float gyro_cal_y; ///< gyro Y calibration
float gyro_cal_z; ///< gyro Z calibration
float accel_cal_x; ///< accel X calibration
float accel_cal_y; ///< accel Y calibration
float accel_cal_z; ///< accel Z calibration
int16_t mag_ofs_x; ///< magnetometer X offset
int16_t mag_ofs_y; ///< magnetometer Y offset
int16_t mag_ofs_z; ///< magnetometer Z offset
} mavlink_sensor_offsets_t;
 
#define MAVLINK_MSG_ID_SENSOR_OFFSETS_LEN 42
#define MAVLINK_MSG_ID_150_LEN 42
 
 
 
#define MAVLINK_MESSAGE_INFO_SENSOR_OFFSETS { \
"SENSOR_OFFSETS", \
12, \
{ { "mag_declination", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_sensor_offsets_t, mag_declination) }, \
{ "raw_press", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_sensor_offsets_t, raw_press) }, \
{ "raw_temp", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_sensor_offsets_t, raw_temp) }, \
{ "gyro_cal_x", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_sensor_offsets_t, gyro_cal_x) }, \
{ "gyro_cal_y", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_sensor_offsets_t, gyro_cal_y) }, \
{ "gyro_cal_z", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_sensor_offsets_t, gyro_cal_z) }, \
{ "accel_cal_x", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_sensor_offsets_t, accel_cal_x) }, \
{ "accel_cal_y", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_sensor_offsets_t, accel_cal_y) }, \
{ "accel_cal_z", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_sensor_offsets_t, accel_cal_z) }, \
{ "mag_ofs_x", NULL, MAVLINK_TYPE_INT16_T, 0, 36, offsetof(mavlink_sensor_offsets_t, mag_ofs_x) }, \
{ "mag_ofs_y", NULL, MAVLINK_TYPE_INT16_T, 0, 38, offsetof(mavlink_sensor_offsets_t, mag_ofs_y) }, \
{ "mag_ofs_z", NULL, MAVLINK_TYPE_INT16_T, 0, 40, offsetof(mavlink_sensor_offsets_t, mag_ofs_z) }, \
} \
}
 
 
/**
* @brief Pack a sensor_offsets message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param mag_ofs_x magnetometer X offset
* @param mag_ofs_y magnetometer Y offset
* @param mag_ofs_z magnetometer Z offset
* @param mag_declination magnetic declination (radians)
* @param raw_press raw pressure from barometer
* @param raw_temp raw temperature from barometer
* @param gyro_cal_x gyro X calibration
* @param gyro_cal_y gyro Y calibration
* @param gyro_cal_z gyro Z calibration
* @param accel_cal_x accel X calibration
* @param accel_cal_y accel Y calibration
* @param accel_cal_z accel Z calibration
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_sensor_offsets_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
int16_t mag_ofs_x, int16_t mag_ofs_y, int16_t mag_ofs_z, float mag_declination, int32_t raw_press, int32_t raw_temp, float gyro_cal_x, float gyro_cal_y, float gyro_cal_z, float accel_cal_x, float accel_cal_y, float accel_cal_z)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[42];
_mav_put_float(buf, 0, mag_declination);
_mav_put_int32_t(buf, 4, raw_press);
_mav_put_int32_t(buf, 8, raw_temp);
_mav_put_float(buf, 12, gyro_cal_x);
_mav_put_float(buf, 16, gyro_cal_y);
_mav_put_float(buf, 20, gyro_cal_z);
_mav_put_float(buf, 24, accel_cal_x);
_mav_put_float(buf, 28, accel_cal_y);
_mav_put_float(buf, 32, accel_cal_z);
_mav_put_int16_t(buf, 36, mag_ofs_x);
_mav_put_int16_t(buf, 38, mag_ofs_y);
_mav_put_int16_t(buf, 40, mag_ofs_z);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 42);
#else
mavlink_sensor_offsets_t packet;
packet.mag_declination = mag_declination;
packet.raw_press = raw_press;
packet.raw_temp = raw_temp;
packet.gyro_cal_x = gyro_cal_x;
packet.gyro_cal_y = gyro_cal_y;
packet.gyro_cal_z = gyro_cal_z;
packet.accel_cal_x = accel_cal_x;
packet.accel_cal_y = accel_cal_y;
packet.accel_cal_z = accel_cal_z;
packet.mag_ofs_x = mag_ofs_x;
packet.mag_ofs_y = mag_ofs_y;
packet.mag_ofs_z = mag_ofs_z;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 42);
#endif
 
msg->msgid = MAVLINK_MSG_ID_SENSOR_OFFSETS;
return mavlink_finalize_message(msg, system_id, component_id, 42, 134);
}
 
/**
* @brief Pack a sensor_offsets message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param mag_ofs_x magnetometer X offset
* @param mag_ofs_y magnetometer Y offset
* @param mag_ofs_z magnetometer Z offset
* @param mag_declination magnetic declination (radians)
* @param raw_press raw pressure from barometer
* @param raw_temp raw temperature from barometer
* @param gyro_cal_x gyro X calibration
* @param gyro_cal_y gyro Y calibration
* @param gyro_cal_z gyro Z calibration
* @param accel_cal_x accel X calibration
* @param accel_cal_y accel Y calibration
* @param accel_cal_z accel Z calibration
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_sensor_offsets_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
int16_t mag_ofs_x,int16_t mag_ofs_y,int16_t mag_ofs_z,float mag_declination,int32_t raw_press,int32_t raw_temp,float gyro_cal_x,float gyro_cal_y,float gyro_cal_z,float accel_cal_x,float accel_cal_y,float accel_cal_z)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[42];
_mav_put_float(buf, 0, mag_declination);
_mav_put_int32_t(buf, 4, raw_press);
_mav_put_int32_t(buf, 8, raw_temp);
_mav_put_float(buf, 12, gyro_cal_x);
_mav_put_float(buf, 16, gyro_cal_y);
_mav_put_float(buf, 20, gyro_cal_z);
_mav_put_float(buf, 24, accel_cal_x);
_mav_put_float(buf, 28, accel_cal_y);
_mav_put_float(buf, 32, accel_cal_z);
_mav_put_int16_t(buf, 36, mag_ofs_x);
_mav_put_int16_t(buf, 38, mag_ofs_y);
_mav_put_int16_t(buf, 40, mag_ofs_z);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 42);
#else
mavlink_sensor_offsets_t packet;
packet.mag_declination = mag_declination;
packet.raw_press = raw_press;
packet.raw_temp = raw_temp;
packet.gyro_cal_x = gyro_cal_x;
packet.gyro_cal_y = gyro_cal_y;
packet.gyro_cal_z = gyro_cal_z;
packet.accel_cal_x = accel_cal_x;
packet.accel_cal_y = accel_cal_y;
packet.accel_cal_z = accel_cal_z;
packet.mag_ofs_x = mag_ofs_x;
packet.mag_ofs_y = mag_ofs_y;
packet.mag_ofs_z = mag_ofs_z;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 42);
#endif
 
msg->msgid = MAVLINK_MSG_ID_SENSOR_OFFSETS;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 42, 134);
}
 
/**
* @brief Encode a sensor_offsets struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param sensor_offsets C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_sensor_offsets_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_sensor_offsets_t* sensor_offsets)
{
return mavlink_msg_sensor_offsets_pack(system_id, component_id, msg, sensor_offsets->mag_ofs_x, sensor_offsets->mag_ofs_y, sensor_offsets->mag_ofs_z, sensor_offsets->mag_declination, sensor_offsets->raw_press, sensor_offsets->raw_temp, sensor_offsets->gyro_cal_x, sensor_offsets->gyro_cal_y, sensor_offsets->gyro_cal_z, sensor_offsets->accel_cal_x, sensor_offsets->accel_cal_y, sensor_offsets->accel_cal_z);
}
 
/**
* @brief Send a sensor_offsets message
* @param chan MAVLink channel to send the message
*
* @param mag_ofs_x magnetometer X offset
* @param mag_ofs_y magnetometer Y offset
* @param mag_ofs_z magnetometer Z offset
* @param mag_declination magnetic declination (radians)
* @param raw_press raw pressure from barometer
* @param raw_temp raw temperature from barometer
* @param gyro_cal_x gyro X calibration
* @param gyro_cal_y gyro Y calibration
* @param gyro_cal_z gyro Z calibration
* @param accel_cal_x accel X calibration
* @param accel_cal_y accel Y calibration
* @param accel_cal_z accel Z calibration
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_sensor_offsets_send(mavlink_channel_t chan, int16_t mag_ofs_x, int16_t mag_ofs_y, int16_t mag_ofs_z, float mag_declination, int32_t raw_press, int32_t raw_temp, float gyro_cal_x, float gyro_cal_y, float gyro_cal_z, float accel_cal_x, float accel_cal_y, float accel_cal_z)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[42];
_mav_put_float(buf, 0, mag_declination);
_mav_put_int32_t(buf, 4, raw_press);
_mav_put_int32_t(buf, 8, raw_temp);
_mav_put_float(buf, 12, gyro_cal_x);
_mav_put_float(buf, 16, gyro_cal_y);
_mav_put_float(buf, 20, gyro_cal_z);
_mav_put_float(buf, 24, accel_cal_x);
_mav_put_float(buf, 28, accel_cal_y);
_mav_put_float(buf, 32, accel_cal_z);
_mav_put_int16_t(buf, 36, mag_ofs_x);
_mav_put_int16_t(buf, 38, mag_ofs_y);
_mav_put_int16_t(buf, 40, mag_ofs_z);
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SENSOR_OFFSETS, buf, 42, 134);
#else
mavlink_sensor_offsets_t packet;
packet.mag_declination = mag_declination;
packet.raw_press = raw_press;
packet.raw_temp = raw_temp;
packet.gyro_cal_x = gyro_cal_x;
packet.gyro_cal_y = gyro_cal_y;
packet.gyro_cal_z = gyro_cal_z;
packet.accel_cal_x = accel_cal_x;
packet.accel_cal_y = accel_cal_y;
packet.accel_cal_z = accel_cal_z;
packet.mag_ofs_x = mag_ofs_x;
packet.mag_ofs_y = mag_ofs_y;
packet.mag_ofs_z = mag_ofs_z;
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SENSOR_OFFSETS, (const char *)&packet, 42, 134);
#endif
}
 
#endif
 
// MESSAGE SENSOR_OFFSETS UNPACKING
 
 
/**
* @brief Get field mag_ofs_x from sensor_offsets message
*
* @return magnetometer X offset
*/
static inline int16_t mavlink_msg_sensor_offsets_get_mag_ofs_x(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 36);
}
 
/**
* @brief Get field mag_ofs_y from sensor_offsets message
*
* @return magnetometer Y offset
*/
static inline int16_t mavlink_msg_sensor_offsets_get_mag_ofs_y(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 38);
}
 
/**
* @brief Get field mag_ofs_z from sensor_offsets message
*
* @return magnetometer Z offset
*/
static inline int16_t mavlink_msg_sensor_offsets_get_mag_ofs_z(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 40);
}
 
/**
* @brief Get field mag_declination from sensor_offsets message
*
* @return magnetic declination (radians)
*/
static inline float mavlink_msg_sensor_offsets_get_mag_declination(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 0);
}
 
/**
* @brief Get field raw_press from sensor_offsets message
*
* @return raw pressure from barometer
*/
static inline int32_t mavlink_msg_sensor_offsets_get_raw_press(const mavlink_message_t* msg)
{
return _MAV_RETURN_int32_t(msg, 4);
}
 
/**
* @brief Get field raw_temp from sensor_offsets message
*
* @return raw temperature from barometer
*/
static inline int32_t mavlink_msg_sensor_offsets_get_raw_temp(const mavlink_message_t* msg)
{
return _MAV_RETURN_int32_t(msg, 8);
}
 
/**
* @brief Get field gyro_cal_x from sensor_offsets message
*
* @return gyro X calibration
*/
static inline float mavlink_msg_sensor_offsets_get_gyro_cal_x(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 12);
}
 
/**
* @brief Get field gyro_cal_y from sensor_offsets message
*
* @return gyro Y calibration
*/
static inline float mavlink_msg_sensor_offsets_get_gyro_cal_y(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 16);
}
 
/**
* @brief Get field gyro_cal_z from sensor_offsets message
*
* @return gyro Z calibration
*/
static inline float mavlink_msg_sensor_offsets_get_gyro_cal_z(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 20);
}
 
/**
* @brief Get field accel_cal_x from sensor_offsets message
*
* @return accel X calibration
*/
static inline float mavlink_msg_sensor_offsets_get_accel_cal_x(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 24);
}
 
/**
* @brief Get field accel_cal_y from sensor_offsets message
*
* @return accel Y calibration
*/
static inline float mavlink_msg_sensor_offsets_get_accel_cal_y(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 28);
}
 
/**
* @brief Get field accel_cal_z from sensor_offsets message
*
* @return accel Z calibration
*/
static inline float mavlink_msg_sensor_offsets_get_accel_cal_z(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 32);
}
 
/**
* @brief Decode a sensor_offsets message into a struct
*
* @param msg The message to decode
* @param sensor_offsets C-struct to decode the message contents into
*/
static inline void mavlink_msg_sensor_offsets_decode(const mavlink_message_t* msg, mavlink_sensor_offsets_t* sensor_offsets)
{
#if MAVLINK_NEED_BYTE_SWAP
sensor_offsets->mag_declination = mavlink_msg_sensor_offsets_get_mag_declination(msg);
sensor_offsets->raw_press = mavlink_msg_sensor_offsets_get_raw_press(msg);
sensor_offsets->raw_temp = mavlink_msg_sensor_offsets_get_raw_temp(msg);
sensor_offsets->gyro_cal_x = mavlink_msg_sensor_offsets_get_gyro_cal_x(msg);
sensor_offsets->gyro_cal_y = mavlink_msg_sensor_offsets_get_gyro_cal_y(msg);
sensor_offsets->gyro_cal_z = mavlink_msg_sensor_offsets_get_gyro_cal_z(msg);
sensor_offsets->accel_cal_x = mavlink_msg_sensor_offsets_get_accel_cal_x(msg);
sensor_offsets->accel_cal_y = mavlink_msg_sensor_offsets_get_accel_cal_y(msg);
sensor_offsets->accel_cal_z = mavlink_msg_sensor_offsets_get_accel_cal_z(msg);
sensor_offsets->mag_ofs_x = mavlink_msg_sensor_offsets_get_mag_ofs_x(msg);
sensor_offsets->mag_ofs_y = mavlink_msg_sensor_offsets_get_mag_ofs_y(msg);
sensor_offsets->mag_ofs_z = mavlink_msg_sensor_offsets_get_mag_ofs_z(msg);
#else
memcpy(sensor_offsets, _MAV_PAYLOAD(msg), 42);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_set_mag_offsets.h
0,0 → 1,232
// MESSAGE SET_MAG_OFFSETS PACKING
 
#define MAVLINK_MSG_ID_SET_MAG_OFFSETS 151
 
typedef struct __mavlink_set_mag_offsets_t
{
int16_t mag_ofs_x; ///< magnetometer X offset
int16_t mag_ofs_y; ///< magnetometer Y offset
int16_t mag_ofs_z; ///< magnetometer Z offset
uint8_t target_system; ///< System ID
uint8_t target_component; ///< Component ID
} mavlink_set_mag_offsets_t;
 
#define MAVLINK_MSG_ID_SET_MAG_OFFSETS_LEN 8
#define MAVLINK_MSG_ID_151_LEN 8
 
 
 
#define MAVLINK_MESSAGE_INFO_SET_MAG_OFFSETS { \
"SET_MAG_OFFSETS", \
5, \
{ { "mag_ofs_x", NULL, MAVLINK_TYPE_INT16_T, 0, 0, offsetof(mavlink_set_mag_offsets_t, mag_ofs_x) }, \
{ "mag_ofs_y", NULL, MAVLINK_TYPE_INT16_T, 0, 2, offsetof(mavlink_set_mag_offsets_t, mag_ofs_y) }, \
{ "mag_ofs_z", NULL, MAVLINK_TYPE_INT16_T, 0, 4, offsetof(mavlink_set_mag_offsets_t, mag_ofs_z) }, \
{ "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_set_mag_offsets_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 7, offsetof(mavlink_set_mag_offsets_t, target_component) }, \
} \
}
 
 
/**
* @brief Pack a set_mag_offsets message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param target_system System ID
* @param target_component Component ID
* @param mag_ofs_x magnetometer X offset
* @param mag_ofs_y magnetometer Y offset
* @param mag_ofs_z magnetometer Z offset
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_set_mag_offsets_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t target_system, uint8_t target_component, int16_t mag_ofs_x, int16_t mag_ofs_y, int16_t mag_ofs_z)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[8];
_mav_put_int16_t(buf, 0, mag_ofs_x);
_mav_put_int16_t(buf, 2, mag_ofs_y);
_mav_put_int16_t(buf, 4, mag_ofs_z);
_mav_put_uint8_t(buf, 6, target_system);
_mav_put_uint8_t(buf, 7, target_component);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 8);
#else
mavlink_set_mag_offsets_t packet;
packet.mag_ofs_x = mag_ofs_x;
packet.mag_ofs_y = mag_ofs_y;
packet.mag_ofs_z = mag_ofs_z;
packet.target_system = target_system;
packet.target_component = target_component;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 8);
#endif
 
msg->msgid = MAVLINK_MSG_ID_SET_MAG_OFFSETS;
return mavlink_finalize_message(msg, system_id, component_id, 8, 219);
}
 
/**
* @brief Pack a set_mag_offsets message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param target_system System ID
* @param target_component Component ID
* @param mag_ofs_x magnetometer X offset
* @param mag_ofs_y magnetometer Y offset
* @param mag_ofs_z magnetometer Z offset
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_set_mag_offsets_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,int16_t mag_ofs_x,int16_t mag_ofs_y,int16_t mag_ofs_z)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[8];
_mav_put_int16_t(buf, 0, mag_ofs_x);
_mav_put_int16_t(buf, 2, mag_ofs_y);
_mav_put_int16_t(buf, 4, mag_ofs_z);
_mav_put_uint8_t(buf, 6, target_system);
_mav_put_uint8_t(buf, 7, target_component);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 8);
#else
mavlink_set_mag_offsets_t packet;
packet.mag_ofs_x = mag_ofs_x;
packet.mag_ofs_y = mag_ofs_y;
packet.mag_ofs_z = mag_ofs_z;
packet.target_system = target_system;
packet.target_component = target_component;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 8);
#endif
 
msg->msgid = MAVLINK_MSG_ID_SET_MAG_OFFSETS;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 8, 219);
}
 
/**
* @brief Encode a set_mag_offsets struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param set_mag_offsets C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_set_mag_offsets_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_mag_offsets_t* set_mag_offsets)
{
return mavlink_msg_set_mag_offsets_pack(system_id, component_id, msg, set_mag_offsets->target_system, set_mag_offsets->target_component, set_mag_offsets->mag_ofs_x, set_mag_offsets->mag_ofs_y, set_mag_offsets->mag_ofs_z);
}
 
/**
* @brief Send a set_mag_offsets message
* @param chan MAVLink channel to send the message
*
* @param target_system System ID
* @param target_component Component ID
* @param mag_ofs_x magnetometer X offset
* @param mag_ofs_y magnetometer Y offset
* @param mag_ofs_z magnetometer Z offset
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_set_mag_offsets_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, int16_t mag_ofs_x, int16_t mag_ofs_y, int16_t mag_ofs_z)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[8];
_mav_put_int16_t(buf, 0, mag_ofs_x);
_mav_put_int16_t(buf, 2, mag_ofs_y);
_mav_put_int16_t(buf, 4, mag_ofs_z);
_mav_put_uint8_t(buf, 6, target_system);
_mav_put_uint8_t(buf, 7, target_component);
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_MAG_OFFSETS, buf, 8, 219);
#else
mavlink_set_mag_offsets_t packet;
packet.mag_ofs_x = mag_ofs_x;
packet.mag_ofs_y = mag_ofs_y;
packet.mag_ofs_z = mag_ofs_z;
packet.target_system = target_system;
packet.target_component = target_component;
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_MAG_OFFSETS, (const char *)&packet, 8, 219);
#endif
}
 
#endif
 
// MESSAGE SET_MAG_OFFSETS UNPACKING
 
 
/**
* @brief Get field target_system from set_mag_offsets message
*
* @return System ID
*/
static inline uint8_t mavlink_msg_set_mag_offsets_get_target_system(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 6);
}
 
/**
* @brief Get field target_component from set_mag_offsets message
*
* @return Component ID
*/
static inline uint8_t mavlink_msg_set_mag_offsets_get_target_component(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 7);
}
 
/**
* @brief Get field mag_ofs_x from set_mag_offsets message
*
* @return magnetometer X offset
*/
static inline int16_t mavlink_msg_set_mag_offsets_get_mag_ofs_x(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 0);
}
 
/**
* @brief Get field mag_ofs_y from set_mag_offsets message
*
* @return magnetometer Y offset
*/
static inline int16_t mavlink_msg_set_mag_offsets_get_mag_ofs_y(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 2);
}
 
/**
* @brief Get field mag_ofs_z from set_mag_offsets message
*
* @return magnetometer Z offset
*/
static inline int16_t mavlink_msg_set_mag_offsets_get_mag_ofs_z(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 4);
}
 
/**
* @brief Decode a set_mag_offsets message into a struct
*
* @param msg The message to decode
* @param set_mag_offsets C-struct to decode the message contents into
*/
static inline void mavlink_msg_set_mag_offsets_decode(const mavlink_message_t* msg, mavlink_set_mag_offsets_t* set_mag_offsets)
{
#if MAVLINK_NEED_BYTE_SWAP
set_mag_offsets->mag_ofs_x = mavlink_msg_set_mag_offsets_get_mag_ofs_x(msg);
set_mag_offsets->mag_ofs_y = mavlink_msg_set_mag_offsets_get_mag_ofs_y(msg);
set_mag_offsets->mag_ofs_z = mavlink_msg_set_mag_offsets_get_mag_ofs_z(msg);
set_mag_offsets->target_system = mavlink_msg_set_mag_offsets_get_target_system(msg);
set_mag_offsets->target_component = mavlink_msg_set_mag_offsets_get_target_component(msg);
#else
memcpy(set_mag_offsets, _MAV_PAYLOAD(msg), 8);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v1.0/ardupilotmega/mavlink_msg_simstate.h
0,0 → 1,320
// MESSAGE SIMSTATE PACKING
 
#define MAVLINK_MSG_ID_SIMSTATE 164
 
typedef struct __mavlink_simstate_t
{
float roll; ///< Roll angle (rad)
float pitch; ///< Pitch angle (rad)
float yaw; ///< Yaw angle (rad)
float xacc; ///< X acceleration m/s/s
float yacc; ///< Y acceleration m/s/s
float zacc; ///< Z acceleration m/s/s
float xgyro; ///< Angular speed around X axis rad/s
float ygyro; ///< Angular speed around Y axis rad/s
float zgyro; ///< Angular speed around Z axis rad/s
} mavlink_simstate_t;
 
#define MAVLINK_MSG_ID_SIMSTATE_LEN 36
#define MAVLINK_MSG_ID_164_LEN 36
 
 
 
#define MAVLINK_MESSAGE_INFO_SIMSTATE { \
"SIMSTATE", \
9, \
{ { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_simstate_t, roll) }, \
{ "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_simstate_t, pitch) }, \
{ "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_simstate_t, yaw) }, \
{ "xacc", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_simstate_t, xacc) }, \
{ "yacc", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_simstate_t, yacc) }, \
{ "zacc", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_simstate_t, zacc) }, \
{ "xgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_simstate_t, xgyro) }, \
{ "ygyro", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_simstate_t, ygyro) }, \
{ "zgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_simstate_t, zgyro) }, \
} \
}
 
 
/**
* @brief Pack a simstate message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param roll Roll angle (rad)
* @param pitch Pitch angle (rad)
* @param yaw Yaw angle (rad)
* @param xacc X acceleration m/s/s
* @param yacc Y acceleration m/s/s
* @param zacc Z acceleration m/s/s
* @param xgyro Angular speed around X axis rad/s
* @param ygyro Angular speed around Y axis rad/s
* @param zgyro Angular speed around Z axis rad/s
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_simstate_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
float roll, float pitch, float yaw, float xacc, float yacc, float zacc, float xgyro, float ygyro, float zgyro)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[36];
_mav_put_float(buf, 0, roll);
_mav_put_float(buf, 4, pitch);
_mav_put_float(buf, 8, yaw);
_mav_put_float(buf, 12, xacc);
_mav_put_float(buf, 16, yacc);
_mav_put_float(buf, 20, zacc);
_mav_put_float(buf, 24, xgyro);
_mav_put_float(buf, 28, ygyro);
_mav_put_float(buf, 32, zgyro);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 36);
#else
mavlink_simstate_t packet;
packet.roll = roll;
packet.pitch = pitch;
packet.yaw = yaw;
packet.xacc = xacc;
packet.yacc = yacc;
packet.zacc = zacc;
packet.xgyro = xgyro;
packet.ygyro = ygyro;
packet.zgyro = zgyro;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 36);
#endif
 
msg->msgid = MAVLINK_MSG_ID_SIMSTATE;
return mavlink_finalize_message(msg, system_id, component_id, 36, 42);
}
 
/**
* @brief Pack a simstate message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param roll Roll angle (rad)
* @param pitch Pitch angle (rad)
* @param yaw Yaw angle (rad)
* @param xacc X acceleration m/s/s
* @param yacc Y acceleration m/s/s
* @param zacc Z acceleration m/s/s
* @param xgyro Angular speed around X axis rad/s
* @param ygyro Angular speed around Y axis rad/s
* @param zgyro Angular speed around Z axis rad/s
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_simstate_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
float roll,float pitch,float yaw,float xacc,float yacc,float zacc,float xgyro,float ygyro,float zgyro)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[36];
_mav_put_float(buf, 0, roll);
_mav_put_float(buf, 4, pitch);
_mav_put_float(buf, 8, yaw);
_mav_put_float(buf, 12, xacc);
_mav_put_float(buf, 16, yacc);
_mav_put_float(buf, 20, zacc);
_mav_put_float(buf, 24, xgyro);
_mav_put_float(buf, 28, ygyro);
_mav_put_float(buf, 32, zgyro);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 36);
#else
mavlink_simstate_t packet;
packet.roll = roll;
packet.pitch = pitch;
packet.yaw = yaw;
packet.xacc = xacc;
packet.yacc = yacc;
packet.zacc = zacc;
packet.xgyro = xgyro;
packet.ygyro = ygyro;
packet.zgyro = zgyro;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 36);
#endif
 
msg->msgid = MAVLINK_MSG_ID_SIMSTATE;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 36, 42);
}
 
/**
* @brief Encode a simstate struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param simstate C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_simstate_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_simstate_t* simstate)
{
return mavlink_msg_simstate_pack(system_id, component_id, msg, simstate->roll, simstate->pitch, simstate->yaw, simstate->xacc, simstate->yacc, simstate->zacc, simstate->xgyro, simstate->ygyro, simstate->zgyro);
}
 
/**
* @brief Send a simstate message
* @param chan MAVLink channel to send the message
*
* @param roll Roll angle (rad)
* @param pitch Pitch angle (rad)
* @param yaw Yaw angle (rad)
* @param xacc X acceleration m/s/s
* @param yacc Y acceleration m/s/s
* @param zacc Z acceleration m/s/s
* @param xgyro Angular speed around X axis rad/s
* @param ygyro Angular speed around Y axis rad/s
* @param zgyro Angular speed around Z axis rad/s
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_simstate_send(mavlink_channel_t chan, float roll, float pitch, float yaw, float xacc, float yacc, float zacc, float xgyro, float ygyro, float zgyro)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[36];
_mav_put_float(buf, 0, roll);
_mav_put_float(buf, 4, pitch);
_mav_put_float(buf, 8, yaw);
_mav_put_float(buf, 12, xacc);
_mav_put_float(buf, 16, yacc);
_mav_put_float(buf, 20, zacc);
_mav_put_float(buf, 24, xgyro);
_mav_put_float(buf, 28, ygyro);
_mav_put_float(buf, 32, zgyro);
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SIMSTATE, buf, 36, 42);
#else
mavlink_simstate_t packet;
packet.roll = roll;
packet.pitch = pitch;
packet.yaw = yaw;
packet.xacc = xacc;
packet.yacc = yacc;
packet.zacc = zacc;
packet.xgyro = xgyro;
packet.ygyro = ygyro;
packet.zgyro = zgyro;
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SIMSTATE, (const char *)&packet, 36, 42);
#endif
}
 
#endif
 
// MESSAGE SIMSTATE UNPACKING
 
 
/**
* @brief Get field roll from simstate message
*
* @return Roll angle (rad)
*/
static inline float mavlink_msg_simstate_get_roll(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 0);
}
 
/**
* @brief Get field pitch from simstate message
*
* @return Pitch angle (rad)
*/
static inline float mavlink_msg_simstate_get_pitch(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 4);
}
 
/**
* @brief Get field yaw from simstate message
*
* @return Yaw angle (rad)
*/
static inline float mavlink_msg_simstate_get_yaw(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 8);
}
 
/**
* @brief Get field xacc from simstate message
*
* @return X acceleration m/s/s
*/
static inline float mavlink_msg_simstate_get_xacc(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 12);
}
 
/**
* @brief Get field yacc from simstate message
*
* @return Y acceleration m/s/s
*/
static inline float mavlink_msg_simstate_get_yacc(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 16);
}
 
/**
* @brief Get field zacc from simstate message
*
* @return Z acceleration m/s/s
*/
static inline float mavlink_msg_simstate_get_zacc(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 20);
}
 
/**
* @brief Get field xgyro from simstate message
*
* @return Angular speed around X axis rad/s
*/
static inline float mavlink_msg_simstate_get_xgyro(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 24);
}
 
/**
* @brief Get field ygyro from simstate message
*
* @return Angular speed around Y axis rad/s
*/
static inline float mavlink_msg_simstate_get_ygyro(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 28);
}
 
/**
* @brief Get field zgyro from simstate message
*
* @return Angular speed around Z axis rad/s
*/
static inline float mavlink_msg_simstate_get_zgyro(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 32);
}
 
/**
* @brief Decode a simstate message into a struct
*
* @param msg The message to decode
* @param simstate C-struct to decode the message contents into
*/
static inline void mavlink_msg_simstate_decode(const mavlink_message_t* msg, mavlink_simstate_t* simstate)
{
#if MAVLINK_NEED_BYTE_SWAP
simstate->roll = mavlink_msg_simstate_get_roll(msg);
simstate->pitch = mavlink_msg_simstate_get_pitch(msg);
simstate->yaw = mavlink_msg_simstate_get_yaw(msg);
simstate->xacc = mavlink_msg_simstate_get_xacc(msg);
simstate->yacc = mavlink_msg_simstate_get_yacc(msg);
simstate->zacc = mavlink_msg_simstate_get_zacc(msg);
simstate->xgyro = mavlink_msg_simstate_get_xgyro(msg);
simstate->ygyro = mavlink_msg_simstate_get_ygyro(msg);
simstate->zgyro = mavlink_msg_simstate_get_zgyro(msg);
#else
memcpy(simstate, _MAV_PAYLOAD(msg), 36);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v1.0/ardupilotmega/testsuite.h
0,0 → 1,908
/** @file
* @brief MAVLink comm protocol testsuite generated from ardupilotmega.xml
* @see http://qgroundcontrol.org/mavlink/
*/
#ifndef ARDUPILOTMEGA_TESTSUITE_H
#define ARDUPILOTMEGA_TESTSUITE_H
 
#ifdef __cplusplus
extern "C" {
#endif
 
#ifndef MAVLINK_TEST_ALL
#define MAVLINK_TEST_ALL
static void mavlink_test_common(uint8_t, uint8_t, mavlink_message_t *last_msg);
static void mavlink_test_ardupilotmega(uint8_t, uint8_t, mavlink_message_t *last_msg);
 
static void mavlink_test_all(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_test_common(system_id, component_id, last_msg);
mavlink_test_ardupilotmega(system_id, component_id, last_msg);
}
#endif
 
#include "../common/testsuite.h"
 
 
static void mavlink_test_sensor_offsets(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_sensor_offsets_t packet_in = {
17.0,
963497672,
963497880,
101.0,
129.0,
157.0,
185.0,
213.0,
241.0,
19107,
19211,
19315,
};
mavlink_sensor_offsets_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.mag_declination = packet_in.mag_declination;
packet1.raw_press = packet_in.raw_press;
packet1.raw_temp = packet_in.raw_temp;
packet1.gyro_cal_x = packet_in.gyro_cal_x;
packet1.gyro_cal_y = packet_in.gyro_cal_y;
packet1.gyro_cal_z = packet_in.gyro_cal_z;
packet1.accel_cal_x = packet_in.accel_cal_x;
packet1.accel_cal_y = packet_in.accel_cal_y;
packet1.accel_cal_z = packet_in.accel_cal_z;
packet1.mag_ofs_x = packet_in.mag_ofs_x;
packet1.mag_ofs_y = packet_in.mag_ofs_y;
packet1.mag_ofs_z = packet_in.mag_ofs_z;
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_sensor_offsets_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_sensor_offsets_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_sensor_offsets_pack(system_id, component_id, &msg , packet1.mag_ofs_x , packet1.mag_ofs_y , packet1.mag_ofs_z , packet1.mag_declination , packet1.raw_press , packet1.raw_temp , packet1.gyro_cal_x , packet1.gyro_cal_y , packet1.gyro_cal_z , packet1.accel_cal_x , packet1.accel_cal_y , packet1.accel_cal_z );
mavlink_msg_sensor_offsets_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_sensor_offsets_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.mag_ofs_x , packet1.mag_ofs_y , packet1.mag_ofs_z , packet1.mag_declination , packet1.raw_press , packet1.raw_temp , packet1.gyro_cal_x , packet1.gyro_cal_y , packet1.gyro_cal_z , packet1.accel_cal_x , packet1.accel_cal_y , packet1.accel_cal_z );
mavlink_msg_sensor_offsets_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_sensor_offsets_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_sensor_offsets_send(MAVLINK_COMM_1 , packet1.mag_ofs_x , packet1.mag_ofs_y , packet1.mag_ofs_z , packet1.mag_declination , packet1.raw_press , packet1.raw_temp , packet1.gyro_cal_x , packet1.gyro_cal_y , packet1.gyro_cal_z , packet1.accel_cal_x , packet1.accel_cal_y , packet1.accel_cal_z );
mavlink_msg_sensor_offsets_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_set_mag_offsets(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_set_mag_offsets_t packet_in = {
17235,
17339,
17443,
151,
218,
};
mavlink_set_mag_offsets_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.mag_ofs_x = packet_in.mag_ofs_x;
packet1.mag_ofs_y = packet_in.mag_ofs_y;
packet1.mag_ofs_z = packet_in.mag_ofs_z;
packet1.target_system = packet_in.target_system;
packet1.target_component = packet_in.target_component;
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_set_mag_offsets_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_set_mag_offsets_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_set_mag_offsets_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.mag_ofs_x , packet1.mag_ofs_y , packet1.mag_ofs_z );
mavlink_msg_set_mag_offsets_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_set_mag_offsets_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.mag_ofs_x , packet1.mag_ofs_y , packet1.mag_ofs_z );
mavlink_msg_set_mag_offsets_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_set_mag_offsets_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_set_mag_offsets_send(MAVLINK_COMM_1 , packet1.target_system , packet1.target_component , packet1.mag_ofs_x , packet1.mag_ofs_y , packet1.mag_ofs_z );
mavlink_msg_set_mag_offsets_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_meminfo(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_meminfo_t packet_in = {
17235,
17339,
};
mavlink_meminfo_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.brkval = packet_in.brkval;
packet1.freemem = packet_in.freemem;
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_meminfo_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_meminfo_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_meminfo_pack(system_id, component_id, &msg , packet1.brkval , packet1.freemem );
mavlink_msg_meminfo_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_meminfo_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.brkval , packet1.freemem );
mavlink_msg_meminfo_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_meminfo_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_meminfo_send(MAVLINK_COMM_1 , packet1.brkval , packet1.freemem );
mavlink_msg_meminfo_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_ap_adc(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_ap_adc_t packet_in = {
17235,
17339,
17443,
17547,
17651,
17755,
};
mavlink_ap_adc_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.adc1 = packet_in.adc1;
packet1.adc2 = packet_in.adc2;
packet1.adc3 = packet_in.adc3;
packet1.adc4 = packet_in.adc4;
packet1.adc5 = packet_in.adc5;
packet1.adc6 = packet_in.adc6;
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_ap_adc_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_ap_adc_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_ap_adc_pack(system_id, component_id, &msg , packet1.adc1 , packet1.adc2 , packet1.adc3 , packet1.adc4 , packet1.adc5 , packet1.adc6 );
mavlink_msg_ap_adc_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_ap_adc_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.adc1 , packet1.adc2 , packet1.adc3 , packet1.adc4 , packet1.adc5 , packet1.adc6 );
mavlink_msg_ap_adc_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_ap_adc_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_ap_adc_send(MAVLINK_COMM_1 , packet1.adc1 , packet1.adc2 , packet1.adc3 , packet1.adc4 , packet1.adc5 , packet1.adc6 );
mavlink_msg_ap_adc_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_digicam_configure(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_digicam_configure_t packet_in = {
17.0,
17443,
151,
218,
29,
96,
163,
230,
41,
108,
175,
};
mavlink_digicam_configure_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.extra_value = packet_in.extra_value;
packet1.shutter_speed = packet_in.shutter_speed;
packet1.target_system = packet_in.target_system;
packet1.target_component = packet_in.target_component;
packet1.mode = packet_in.mode;
packet1.aperture = packet_in.aperture;
packet1.iso = packet_in.iso;
packet1.exposure_type = packet_in.exposure_type;
packet1.command_id = packet_in.command_id;
packet1.engine_cut_off = packet_in.engine_cut_off;
packet1.extra_param = packet_in.extra_param;
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_digicam_configure_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_digicam_configure_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_digicam_configure_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.mode , packet1.shutter_speed , packet1.aperture , packet1.iso , packet1.exposure_type , packet1.command_id , packet1.engine_cut_off , packet1.extra_param , packet1.extra_value );
mavlink_msg_digicam_configure_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_digicam_configure_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.mode , packet1.shutter_speed , packet1.aperture , packet1.iso , packet1.exposure_type , packet1.command_id , packet1.engine_cut_off , packet1.extra_param , packet1.extra_value );
mavlink_msg_digicam_configure_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_digicam_configure_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_digicam_configure_send(MAVLINK_COMM_1 , packet1.target_system , packet1.target_component , packet1.mode , packet1.shutter_speed , packet1.aperture , packet1.iso , packet1.exposure_type , packet1.command_id , packet1.engine_cut_off , packet1.extra_param , packet1.extra_value );
mavlink_msg_digicam_configure_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_digicam_control(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_digicam_control_t packet_in = {
17.0,
17,
84,
151,
218,
29,
96,
163,
230,
41,
};
mavlink_digicam_control_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.extra_value = packet_in.extra_value;
packet1.target_system = packet_in.target_system;
packet1.target_component = packet_in.target_component;
packet1.session = packet_in.session;
packet1.zoom_pos = packet_in.zoom_pos;
packet1.zoom_step = packet_in.zoom_step;
packet1.focus_lock = packet_in.focus_lock;
packet1.shot = packet_in.shot;
packet1.command_id = packet_in.command_id;
packet1.extra_param = packet_in.extra_param;
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_digicam_control_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_digicam_control_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_digicam_control_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.session , packet1.zoom_pos , packet1.zoom_step , packet1.focus_lock , packet1.shot , packet1.command_id , packet1.extra_param , packet1.extra_value );
mavlink_msg_digicam_control_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_digicam_control_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.session , packet1.zoom_pos , packet1.zoom_step , packet1.focus_lock , packet1.shot , packet1.command_id , packet1.extra_param , packet1.extra_value );
mavlink_msg_digicam_control_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_digicam_control_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_digicam_control_send(MAVLINK_COMM_1 , packet1.target_system , packet1.target_component , packet1.session , packet1.zoom_pos , packet1.zoom_step , packet1.focus_lock , packet1.shot , packet1.command_id , packet1.extra_param , packet1.extra_value );
mavlink_msg_digicam_control_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_mount_configure(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_mount_configure_t packet_in = {
5,
72,
139,
206,
17,
84,
};
mavlink_mount_configure_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.target_system = packet_in.target_system;
packet1.target_component = packet_in.target_component;
packet1.mount_mode = packet_in.mount_mode;
packet1.stab_roll = packet_in.stab_roll;
packet1.stab_pitch = packet_in.stab_pitch;
packet1.stab_yaw = packet_in.stab_yaw;
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_mount_configure_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_mount_configure_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_mount_configure_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.mount_mode , packet1.stab_roll , packet1.stab_pitch , packet1.stab_yaw );
mavlink_msg_mount_configure_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_mount_configure_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.mount_mode , packet1.stab_roll , packet1.stab_pitch , packet1.stab_yaw );
mavlink_msg_mount_configure_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_mount_configure_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_mount_configure_send(MAVLINK_COMM_1 , packet1.target_system , packet1.target_component , packet1.mount_mode , packet1.stab_roll , packet1.stab_pitch , packet1.stab_yaw );
mavlink_msg_mount_configure_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_mount_control(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_mount_control_t packet_in = {
963497464,
963497672,
963497880,
41,
108,
175,
};
mavlink_mount_control_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.input_a = packet_in.input_a;
packet1.input_b = packet_in.input_b;
packet1.input_c = packet_in.input_c;
packet1.target_system = packet_in.target_system;
packet1.target_component = packet_in.target_component;
packet1.save_position = packet_in.save_position;
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_mount_control_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_mount_control_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_mount_control_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.input_a , packet1.input_b , packet1.input_c , packet1.save_position );
mavlink_msg_mount_control_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_mount_control_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.input_a , packet1.input_b , packet1.input_c , packet1.save_position );
mavlink_msg_mount_control_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_mount_control_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_mount_control_send(MAVLINK_COMM_1 , packet1.target_system , packet1.target_component , packet1.input_a , packet1.input_b , packet1.input_c , packet1.save_position );
mavlink_msg_mount_control_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_mount_status(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_mount_status_t packet_in = {
963497464,
963497672,
963497880,
41,
108,
};
mavlink_mount_status_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.pointing_a = packet_in.pointing_a;
packet1.pointing_b = packet_in.pointing_b;
packet1.pointing_c = packet_in.pointing_c;
packet1.target_system = packet_in.target_system;
packet1.target_component = packet_in.target_component;
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_mount_status_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_mount_status_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_mount_status_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.pointing_a , packet1.pointing_b , packet1.pointing_c );
mavlink_msg_mount_status_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_mount_status_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.pointing_a , packet1.pointing_b , packet1.pointing_c );
mavlink_msg_mount_status_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_mount_status_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_mount_status_send(MAVLINK_COMM_1 , packet1.target_system , packet1.target_component , packet1.pointing_a , packet1.pointing_b , packet1.pointing_c );
mavlink_msg_mount_status_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_fence_point(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_fence_point_t packet_in = {
17.0,
45.0,
29,
96,
163,
230,
};
mavlink_fence_point_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.lat = packet_in.lat;
packet1.lng = packet_in.lng;
packet1.target_system = packet_in.target_system;
packet1.target_component = packet_in.target_component;
packet1.idx = packet_in.idx;
packet1.count = packet_in.count;
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_fence_point_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_fence_point_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_fence_point_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.idx , packet1.count , packet1.lat , packet1.lng );
mavlink_msg_fence_point_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_fence_point_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.idx , packet1.count , packet1.lat , packet1.lng );
mavlink_msg_fence_point_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_fence_point_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_fence_point_send(MAVLINK_COMM_1 , packet1.target_system , packet1.target_component , packet1.idx , packet1.count , packet1.lat , packet1.lng );
mavlink_msg_fence_point_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_fence_fetch_point(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_fence_fetch_point_t packet_in = {
5,
72,
139,
};
mavlink_fence_fetch_point_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.target_system = packet_in.target_system;
packet1.target_component = packet_in.target_component;
packet1.idx = packet_in.idx;
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_fence_fetch_point_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_fence_fetch_point_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_fence_fetch_point_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.idx );
mavlink_msg_fence_fetch_point_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_fence_fetch_point_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.idx );
mavlink_msg_fence_fetch_point_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_fence_fetch_point_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_fence_fetch_point_send(MAVLINK_COMM_1 , packet1.target_system , packet1.target_component , packet1.idx );
mavlink_msg_fence_fetch_point_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_fence_status(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_fence_status_t packet_in = {
963497464,
17443,
151,
218,
};
mavlink_fence_status_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.breach_time = packet_in.breach_time;
packet1.breach_count = packet_in.breach_count;
packet1.breach_status = packet_in.breach_status;
packet1.breach_type = packet_in.breach_type;
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_fence_status_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_fence_status_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_fence_status_pack(system_id, component_id, &msg , packet1.breach_status , packet1.breach_count , packet1.breach_type , packet1.breach_time );
mavlink_msg_fence_status_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_fence_status_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.breach_status , packet1.breach_count , packet1.breach_type , packet1.breach_time );
mavlink_msg_fence_status_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_fence_status_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_fence_status_send(MAVLINK_COMM_1 , packet1.breach_status , packet1.breach_count , packet1.breach_type , packet1.breach_time );
mavlink_msg_fence_status_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_ahrs(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_ahrs_t packet_in = {
17.0,
45.0,
73.0,
101.0,
129.0,
157.0,
185.0,
};
mavlink_ahrs_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.omegaIx = packet_in.omegaIx;
packet1.omegaIy = packet_in.omegaIy;
packet1.omegaIz = packet_in.omegaIz;
packet1.accel_weight = packet_in.accel_weight;
packet1.renorm_val = packet_in.renorm_val;
packet1.error_rp = packet_in.error_rp;
packet1.error_yaw = packet_in.error_yaw;
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_ahrs_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_ahrs_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_ahrs_pack(system_id, component_id, &msg , packet1.omegaIx , packet1.omegaIy , packet1.omegaIz , packet1.accel_weight , packet1.renorm_val , packet1.error_rp , packet1.error_yaw );
mavlink_msg_ahrs_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_ahrs_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.omegaIx , packet1.omegaIy , packet1.omegaIz , packet1.accel_weight , packet1.renorm_val , packet1.error_rp , packet1.error_yaw );
mavlink_msg_ahrs_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_ahrs_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_ahrs_send(MAVLINK_COMM_1 , packet1.omegaIx , packet1.omegaIy , packet1.omegaIz , packet1.accel_weight , packet1.renorm_val , packet1.error_rp , packet1.error_yaw );
mavlink_msg_ahrs_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_simstate(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_simstate_t packet_in = {
17.0,
45.0,
73.0,
101.0,
129.0,
157.0,
185.0,
213.0,
241.0,
};
mavlink_simstate_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.roll = packet_in.roll;
packet1.pitch = packet_in.pitch;
packet1.yaw = packet_in.yaw;
packet1.xacc = packet_in.xacc;
packet1.yacc = packet_in.yacc;
packet1.zacc = packet_in.zacc;
packet1.xgyro = packet_in.xgyro;
packet1.ygyro = packet_in.ygyro;
packet1.zgyro = packet_in.zgyro;
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_simstate_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_simstate_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_simstate_pack(system_id, component_id, &msg , packet1.roll , packet1.pitch , packet1.yaw , packet1.xacc , packet1.yacc , packet1.zacc , packet1.xgyro , packet1.ygyro , packet1.zgyro );
mavlink_msg_simstate_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_simstate_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.roll , packet1.pitch , packet1.yaw , packet1.xacc , packet1.yacc , packet1.zacc , packet1.xgyro , packet1.ygyro , packet1.zgyro );
mavlink_msg_simstate_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_simstate_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_simstate_send(MAVLINK_COMM_1 , packet1.roll , packet1.pitch , packet1.yaw , packet1.xacc , packet1.yacc , packet1.zacc , packet1.xgyro , packet1.ygyro , packet1.zgyro );
mavlink_msg_simstate_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_hwstatus(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_hwstatus_t packet_in = {
17235,
139,
};
mavlink_hwstatus_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.Vcc = packet_in.Vcc;
packet1.I2Cerr = packet_in.I2Cerr;
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_hwstatus_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_hwstatus_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_hwstatus_pack(system_id, component_id, &msg , packet1.Vcc , packet1.I2Cerr );
mavlink_msg_hwstatus_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_hwstatus_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.Vcc , packet1.I2Cerr );
mavlink_msg_hwstatus_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_hwstatus_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_hwstatus_send(MAVLINK_COMM_1 , packet1.Vcc , packet1.I2Cerr );
mavlink_msg_hwstatus_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_radio(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_radio_t packet_in = {
17235,
17339,
17,
84,
151,
218,
29,
};
mavlink_radio_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.rxerrors = packet_in.rxerrors;
packet1.fixed = packet_in.fixed;
packet1.rssi = packet_in.rssi;
packet1.remrssi = packet_in.remrssi;
packet1.txbuf = packet_in.txbuf;
packet1.noise = packet_in.noise;
packet1.remnoise = packet_in.remnoise;
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_radio_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_radio_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_radio_pack(system_id, component_id, &msg , packet1.rssi , packet1.remrssi , packet1.txbuf , packet1.noise , packet1.remnoise , packet1.rxerrors , packet1.fixed );
mavlink_msg_radio_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_radio_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.rssi , packet1.remrssi , packet1.txbuf , packet1.noise , packet1.remnoise , packet1.rxerrors , packet1.fixed );
mavlink_msg_radio_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_radio_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_radio_send(MAVLINK_COMM_1 , packet1.rssi , packet1.remrssi , packet1.txbuf , packet1.noise , packet1.remnoise , packet1.rxerrors , packet1.fixed );
mavlink_msg_radio_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_ardupilotmega(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_test_sensor_offsets(system_id, component_id, last_msg);
mavlink_test_set_mag_offsets(system_id, component_id, last_msg);
mavlink_test_meminfo(system_id, component_id, last_msg);
mavlink_test_ap_adc(system_id, component_id, last_msg);
mavlink_test_digicam_configure(system_id, component_id, last_msg);
mavlink_test_digicam_control(system_id, component_id, last_msg);
mavlink_test_mount_configure(system_id, component_id, last_msg);
mavlink_test_mount_control(system_id, component_id, last_msg);
mavlink_test_mount_status(system_id, component_id, last_msg);
mavlink_test_fence_point(system_id, component_id, last_msg);
mavlink_test_fence_fetch_point(system_id, component_id, last_msg);
mavlink_test_fence_status(system_id, component_id, last_msg);
mavlink_test_ahrs(system_id, component_id, last_msg);
mavlink_test_simstate(system_id, component_id, last_msg);
mavlink_test_hwstatus(system_id, component_id, last_msg);
mavlink_test_radio(system_id, component_id, last_msg);
}
 
#ifdef __cplusplus
}
#endif // __cplusplus
#endif // ARDUPILOTMEGA_TESTSUITE_H
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v1.0/ardupilotmega/version.h
0,0 → 1,12
/** @file
* @brief MAVLink comm protocol built from ardupilotmega.xml
* @see http://pixhawk.ethz.ch/software/mavlink
*/
#ifndef MAVLINK_VERSION_H
#define MAVLINK_VERSION_H
 
#define MAVLINK_BUILD_DATE "Mon Apr 30 11:40:12 2012"
#define MAVLINK_WIRE_PROTOCOL_VERSION "1.0"
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 101
#endif // MAVLINK_VERSION_H
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v1.0/checksum.h
0,0 → 1,89
#ifdef __cplusplus
extern "C" {
#endif
 
#ifndef _CHECKSUM_H_
#define _CHECKSUM_H_
 
 
/**
*
* CALCULATE THE CHECKSUM
*
*/
 
#define X25_INIT_CRC 0xffff
#define X25_VALIDATE_CRC 0xf0b8
 
/**
* @brief Accumulate the X.25 CRC by adding one char at a time.
*
* The checksum function adds the hash of one char at a time to the
* 16 bit checksum (uint16_t).
*
* @param data new char to hash
* @param crcAccum the already accumulated checksum
**/
static inline void crc_accumulate(uint8_t data, uint16_t *crcAccum)
{
/*Accumulate one byte of data into the CRC*/
uint8_t tmp;
 
tmp = data ^ (uint8_t)(*crcAccum &0xff);
tmp ^= (tmp<<4);
*crcAccum = (*crcAccum>>8) ^ (tmp<<8) ^ (tmp <<3) ^ (tmp>>4);
}
 
/**
* @brief Initiliaze the buffer for the X.25 CRC
*
* @param crcAccum the 16 bit X.25 CRC
*/
static inline void crc_init(uint16_t* crcAccum)
{
*crcAccum = X25_INIT_CRC;
}
 
 
/**
* @brief Calculates the X.25 checksum on a byte buffer
*
* @param pBuffer buffer containing the byte array to hash
* @param length length of the byte array
* @return the checksum over the buffer bytes
**/
static inline uint16_t crc_calculate(const uint8_t* pBuffer, uint16_t length)
{
uint16_t crcTmp;
crc_init(&crcTmp);
while (length--) {
crc_accumulate(*pBuffer++, &crcTmp);
}
return crcTmp;
}
 
/**
* @brief Accumulate the X.25 CRC by adding an array of bytes
*
* The checksum function adds the hash of one char at a time to the
* 16 bit checksum (uint16_t).
*
* @param data new bytes to hash
* @param crcAccum the already accumulated checksum
**/
static inline void crc_accumulate_buffer(uint16_t *crcAccum, const char *pBuffer, uint8_t length)
{
const uint8_t *p = (const uint8_t *)pBuffer;
while (length--) {
crc_accumulate(*p++, crcAccum);
}
}
 
 
 
 
#endif /* _CHECKSUM_H_ */
 
#ifdef __cplusplus
}
#endif
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v1.0/common/common.h
0,0 → 1,446
/** @file
* @brief MAVLink comm protocol generated from common.xml
* @see http://qgroundcontrol.org/mavlink/
*/
#ifndef COMMON_H
#define COMMON_H
 
#ifdef __cplusplus
extern "C" {
#endif
 
// MESSAGE LENGTHS AND CRCS
 
#ifndef MAVLINK_MESSAGE_LENGTHS
#define MAVLINK_MESSAGE_LENGTHS {9, 31, 12, 0, 14, 28, 3, 32, 0, 0, 0, 6, 0, 0, 0, 0, 0, 0, 0, 0, 20, 2, 25, 23, 30, 101, 22, 26, 16, 14, 28, 32, 28, 28, 22, 22, 21, 6, 6, 37, 4, 4, 2, 2, 4, 2, 2, 3, 13, 12, 19, 17, 15, 15, 27, 25, 18, 18, 20, 20, 9, 54, 26, 0, 36, 0, 6, 4, 0, 21, 18, 0, 0, 0, 20, 0, 33, 3, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 28, 56, 42, 33, 0, 0, 0, 0, 0, 0, 0, 26, 32, 32, 20, 32, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 36, 30, 18, 18, 51, 9, 0}
#endif
 
#ifndef MAVLINK_MESSAGE_CRCS
#define MAVLINK_MESSAGE_CRCS {50, 124, 137, 0, 237, 217, 104, 119, 0, 0, 0, 89, 0, 0, 0, 0, 0, 0, 0, 0, 214, 159, 220, 168, 24, 23, 170, 144, 67, 115, 39, 246, 185, 104, 237, 244, 222, 212, 9, 254, 230, 28, 28, 132, 221, 232, 11, 153, 41, 39, 214, 223, 141, 33, 15, 3, 100, 24, 239, 238, 30, 200, 183, 0, 130, 0, 148, 21, 0, 52, 124, 0, 0, 0, 20, 0, 152, 143, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 231, 183, 63, 54, 0, 0, 0, 0, 0, 0, 0, 175, 102, 158, 208, 56, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 204, 49, 170, 44, 83, 46, 0}
#endif
 
#ifndef MAVLINK_MESSAGE_INFO
#define MAVLINK_MESSAGE_INFO {MAVLINK_MESSAGE_INFO_HEARTBEAT, MAVLINK_MESSAGE_INFO_SYS_STATUS, MAVLINK_MESSAGE_INFO_SYSTEM_TIME, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_PING, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL_ACK, MAVLINK_MESSAGE_INFO_AUTH_KEY, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_SET_MODE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_READ, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_LIST, MAVLINK_MESSAGE_INFO_PARAM_VALUE, MAVLINK_MESSAGE_INFO_PARAM_SET, MAVLINK_MESSAGE_INFO_GPS_RAW_INT, MAVLINK_MESSAGE_INFO_GPS_STATUS, MAVLINK_MESSAGE_INFO_SCALED_IMU, MAVLINK_MESSAGE_INFO_RAW_IMU, MAVLINK_MESSAGE_INFO_RAW_PRESSURE, MAVLINK_MESSAGE_INFO_SCALED_PRESSURE, MAVLINK_MESSAGE_INFO_ATTITUDE, MAVLINK_MESSAGE_INFO_ATTITUDE_QUATERNION, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_INT, MAVLINK_MESSAGE_INFO_RC_CHANNELS_SCALED, MAVLINK_MESSAGE_INFO_RC_CHANNELS_RAW, MAVLINK_MESSAGE_INFO_SERVO_OUTPUT_RAW, MAVLINK_MESSAGE_INFO_MISSION_REQUEST_PARTIAL_LIST, MAVLINK_MESSAGE_INFO_MISSION_WRITE_PARTIAL_LIST, MAVLINK_MESSAGE_INFO_MISSION_ITEM, MAVLINK_MESSAGE_INFO_MISSION_REQUEST, MAVLINK_MESSAGE_INFO_MISSION_SET_CURRENT, MAVLINK_MESSAGE_INFO_MISSION_CURRENT, MAVLINK_MESSAGE_INFO_MISSION_REQUEST_LIST, MAVLINK_MESSAGE_INFO_MISSION_COUNT, MAVLINK_MESSAGE_INFO_MISSION_CLEAR_ALL, MAVLINK_MESSAGE_INFO_MISSION_ITEM_REACHED, MAVLINK_MESSAGE_INFO_MISSION_ACK, MAVLINK_MESSAGE_INFO_SET_GPS_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_GPS_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_SET_LOCAL_POSITION_SETPOINT, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_SETPOINT, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_SETPOINT_INT, MAVLINK_MESSAGE_INFO_SET_GLOBAL_POSITION_SETPOINT_INT, MAVLINK_MESSAGE_INFO_SAFETY_SET_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SAFETY_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SET_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_SET_ROLL_PITCH_YAW_SPEED_THRUST, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_SET_QUAD_MOTORS_SETPOINT, MAVLINK_MESSAGE_INFO_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_NAV_CONTROLLER_OUTPUT, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_STATE_CORRECTION, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_REQUEST_DATA_STREAM, MAVLINK_MESSAGE_INFO_DATA_STREAM, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_MANUAL_CONTROL, MAVLINK_MESSAGE_INFO_RC_CHANNELS_OVERRIDE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_VFR_HUD, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_COMMAND_LONG, MAVLINK_MESSAGE_INFO_COMMAND_ACK, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET, MAVLINK_MESSAGE_INFO_HIL_STATE, MAVLINK_MESSAGE_INFO_HIL_CONTROLS, MAVLINK_MESSAGE_INFO_HIL_RC_INPUTS_RAW, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_OPTICAL_FLOW, MAVLINK_MESSAGE_INFO_GLOBAL_VISION_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_VISION_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_VISION_SPEED_ESTIMATE, MAVLINK_MESSAGE_INFO_VICON_POSITION_ESTIMATE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_MEMORY_VECT, MAVLINK_MESSAGE_INFO_DEBUG_VECT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_FLOAT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_INT, MAVLINK_MESSAGE_INFO_STATUSTEXT, MAVLINK_MESSAGE_INFO_DEBUG, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}}
#endif
 
#include "../protocol.h"
 
#define MAVLINK_ENABLED_COMMON
 
// ENUM DEFINITIONS
 
 
/** @brief Micro air vehicle / autopilot classes. This identifies the individual model. */
#ifndef HAVE_ENUM_MAV_AUTOPILOT
#define HAVE_ENUM_MAV_AUTOPILOT
enum MAV_AUTOPILOT
{
MAV_AUTOPILOT_GENERIC=0, /* Generic autopilot, full support for everything | */
MAV_AUTOPILOT_PIXHAWK=1, /* PIXHAWK autopilot, http://pixhawk.ethz.ch | */
MAV_AUTOPILOT_SLUGS=2, /* SLUGS autopilot, http://slugsuav.soe.ucsc.edu | */
MAV_AUTOPILOT_ARDUPILOTMEGA=3, /* ArduPilotMega / ArduCopter, http://diydrones.com | */
MAV_AUTOPILOT_OPENPILOT=4, /* OpenPilot, http://openpilot.org | */
MAV_AUTOPILOT_GENERIC_WAYPOINTS_ONLY=5, /* Generic autopilot only supporting simple waypoints | */
MAV_AUTOPILOT_GENERIC_WAYPOINTS_AND_SIMPLE_NAVIGATION_ONLY=6, /* Generic autopilot supporting waypoints and other simple navigation commands | */
MAV_AUTOPILOT_GENERIC_MISSION_FULL=7, /* Generic autopilot supporting the full mission command set | */
MAV_AUTOPILOT_INVALID=8, /* No valid autopilot, e.g. a GCS or other MAVLink component | */
MAV_AUTOPILOT_PPZ=9, /* PPZ UAV - http://nongnu.org/paparazzi | */
MAV_AUTOPILOT_UDB=10, /* UAV Dev Board | */
MAV_AUTOPILOT_FP=11, /* FlexiPilot | */
MAV_AUTOPILOT_ENUM_END=12, /* | */
};
#endif
 
/** @brief */
#ifndef HAVE_ENUM_MAV_TYPE
#define HAVE_ENUM_MAV_TYPE
enum MAV_TYPE
{
MAV_TYPE_GENERIC=0, /* Generic micro air vehicle. | */
MAV_TYPE_FIXED_WING=1, /* Fixed wing aircraft. | */
MAV_TYPE_QUADROTOR=2, /* Quadrotor | */
MAV_TYPE_COAXIAL=3, /* Coaxial helicopter | */
MAV_TYPE_HELICOPTER=4, /* Normal helicopter with tail rotor. | */
MAV_TYPE_ANTENNA_TRACKER=5, /* Ground installation | */
MAV_TYPE_GCS=6, /* Operator control unit / ground control station | */
MAV_TYPE_AIRSHIP=7, /* Airship, controlled | */
MAV_TYPE_FREE_BALLOON=8, /* Free balloon, uncontrolled | */
MAV_TYPE_ROCKET=9, /* Rocket | */
MAV_TYPE_GROUND_ROVER=10, /* Ground rover | */
MAV_TYPE_SURFACE_BOAT=11, /* Surface vessel, boat, ship | */
MAV_TYPE_SUBMARINE=12, /* Submarine | */
MAV_TYPE_HEXAROTOR=13, /* Hexarotor | */
MAV_TYPE_OCTOROTOR=14, /* Octorotor | */
MAV_TYPE_TRICOPTER=15, /* Octorotor | */
MAV_TYPE_FLAPPING_WING=16, /* Flapping wing | */
MAV_TYPE_ENUM_END=17, /* | */
};
#endif
 
/** @brief These flags encode the MAV mode. */
#ifndef HAVE_ENUM_MAV_MODE_FLAG
#define HAVE_ENUM_MAV_MODE_FLAG
enum MAV_MODE_FLAG
{
MAV_MODE_FLAG_CUSTOM_MODE_ENABLED=1, /* 0b00000001 Reserved for future use. | */
MAV_MODE_FLAG_TEST_ENABLED=2, /* 0b00000010 system has a test mode enabled. This flag is intended for temporary system tests and should not be used for stable implementations. | */
MAV_MODE_FLAG_AUTO_ENABLED=4, /* 0b00000100 autonomous mode enabled, system finds its own goal positions. Guided flag can be set or not, depends on the actual implementation. | */
MAV_MODE_FLAG_GUIDED_ENABLED=8, /* 0b00001000 guided mode enabled, system flies MISSIONs / mission items. | */
MAV_MODE_FLAG_STABILIZE_ENABLED=16, /* 0b00010000 system stabilizes electronically its attitude (and optionally position). It needs however further control inputs to move around. | */
MAV_MODE_FLAG_HIL_ENABLED=32, /* 0b00100000 hardware in the loop simulation. All motors / actuators are blocked, but internal software is full operational. | */
MAV_MODE_FLAG_MANUAL_INPUT_ENABLED=64, /* 0b01000000 remote control input is enabled. | */
MAV_MODE_FLAG_SAFETY_ARMED=128, /* 0b10000000 MAV safety set to armed. Motors are enabled / running / can start. Ready to fly. | */
MAV_MODE_FLAG_ENUM_END=129, /* | */
};
#endif
 
/** @brief These values encode the bit positions of the decode position. These values can be used to read the value of a flag bit by combining the base_mode variable with AND with the flag position value. The result will be either 0 or 1, depending on if the flag is set or not. */
#ifndef HAVE_ENUM_MAV_MODE_FLAG_DECODE_POSITION
#define HAVE_ENUM_MAV_MODE_FLAG_DECODE_POSITION
enum MAV_MODE_FLAG_DECODE_POSITION
{
MAV_MODE_FLAG_DECODE_POSITION_CUSTOM_MODE=1, /* Eighth bit: 00000001 | */
MAV_MODE_FLAG_DECODE_POSITION_TEST=2, /* Seventh bit: 00000010 | */
MAV_MODE_FLAG_DECODE_POSITION_AUTO=4, /* Sixt bit: 00000100 | */
MAV_MODE_FLAG_DECODE_POSITION_GUIDED=8, /* Fifth bit: 00001000 | */
MAV_MODE_FLAG_DECODE_POSITION_STABILIZE=16, /* Fourth bit: 00010000 | */
MAV_MODE_FLAG_DECODE_POSITION_HIL=32, /* Third bit: 00100000 | */
MAV_MODE_FLAG_DECODE_POSITION_MANUAL=64, /* Second bit: 01000000 | */
MAV_MODE_FLAG_DECODE_POSITION_SAFETY=128, /* First bit: 10000000 | */
MAV_MODE_FLAG_DECODE_POSITION_ENUM_END=129, /* | */
};
#endif
 
/** @brief Override command, pauses current mission execution and moves immediately to a position */
#ifndef HAVE_ENUM_MAV_GOTO
#define HAVE_ENUM_MAV_GOTO
enum MAV_GOTO
{
MAV_GOTO_DO_HOLD=0, /* Hold at the current position. | */
MAV_GOTO_DO_CONTINUE=1, /* Continue with the next item in mission execution. | */
MAV_GOTO_HOLD_AT_CURRENT_POSITION=2, /* Hold at the current position of the system | */
MAV_GOTO_HOLD_AT_SPECIFIED_POSITION=3, /* Hold at the position specified in the parameters of the DO_HOLD action | */
MAV_GOTO_ENUM_END=4, /* | */
};
#endif
 
/** @brief These defines are predefined OR-combined mode flags. There is no need to use values from this enum, but it
simplifies the use of the mode flags. Note that manual input is enabled in all modes as a safety override. */
#ifndef HAVE_ENUM_MAV_MODE
#define HAVE_ENUM_MAV_MODE
enum MAV_MODE
{
MAV_MODE_PREFLIGHT=0, /* System is not ready to fly, booting, calibrating, etc. No flag is set. | */
MAV_MODE_MANUAL_DISARMED=64, /* System is allowed to be active, under manual (RC) control, no stabilization | */
MAV_MODE_TEST_DISARMED=66, /* UNDEFINED mode. This solely depends on the autopilot - use with caution, intended for developers only. | */
MAV_MODE_STABILIZE_DISARMED=80, /* System is allowed to be active, under assisted RC control. | */
MAV_MODE_GUIDED_DISARMED=88, /* System is allowed to be active, under autonomous control, manual setpoint | */
MAV_MODE_AUTO_DISARMED=92, /* System is allowed to be active, under autonomous control and navigation (the trajectory is decided onboard and not pre-programmed by MISSIONs) | */
MAV_MODE_MANUAL_ARMED=192, /* System is allowed to be active, under manual (RC) control, no stabilization | */
MAV_MODE_TEST_ARMED=194, /* UNDEFINED mode. This solely depends on the autopilot - use with caution, intended for developers only. | */
MAV_MODE_STABILIZE_ARMED=208, /* System is allowed to be active, under assisted RC control. | */
MAV_MODE_GUIDED_ARMED=216, /* System is allowed to be active, under autonomous control, manual setpoint | */
MAV_MODE_AUTO_ARMED=220, /* System is allowed to be active, under autonomous control and navigation (the trajectory is decided onboard and not pre-programmed by MISSIONs) | */
MAV_MODE_ENUM_END=221, /* | */
};
#endif
 
/** @brief */
#ifndef HAVE_ENUM_MAV_STATE
#define HAVE_ENUM_MAV_STATE
enum MAV_STATE
{
MAV_STATE_UNINIT=0, /* Uninitialized system, state is unknown. | */
MAV_STATE_BOOT=1, /* System is booting up. | */
MAV_STATE_CALIBRATING=2, /* System is calibrating and not flight-ready. | */
MAV_STATE_STANDBY=3, /* System is grounded and on standby. It can be launched any time. | */
MAV_STATE_ACTIVE=4, /* System is active and might be already airborne. Motors are engaged. | */
MAV_STATE_CRITICAL=5, /* System is in a non-normal flight mode. It can however still navigate. | */
MAV_STATE_EMERGENCY=6, /* System is in a non-normal flight mode. It lost control over parts or over the whole airframe. It is in mayday and going down. | */
MAV_STATE_POWEROFF=7, /* System just initialized its power-down sequence, will shut down now. | */
MAV_STATE_ENUM_END=8, /* | */
};
#endif
 
/** @brief */
#ifndef HAVE_ENUM_MAV_COMPONENT
#define HAVE_ENUM_MAV_COMPONENT
enum MAV_COMPONENT
{
MAV_COMP_ID_ALL=0, /* | */
MAV_COMP_ID_CAMERA=100, /* | */
MAV_COMP_ID_SERVO1=140, /* | */
MAV_COMP_ID_SERVO2=141, /* | */
MAV_COMP_ID_SERVO3=142, /* | */
MAV_COMP_ID_SERVO4=143, /* | */
MAV_COMP_ID_SERVO5=144, /* | */
MAV_COMP_ID_SERVO6=145, /* | */
MAV_COMP_ID_SERVO7=146, /* | */
MAV_COMP_ID_SERVO8=147, /* | */
MAV_COMP_ID_SERVO9=148, /* | */
MAV_COMP_ID_SERVO10=149, /* | */
MAV_COMP_ID_SERVO11=150, /* | */
MAV_COMP_ID_SERVO12=151, /* | */
MAV_COMP_ID_SERVO13=152, /* | */
MAV_COMP_ID_SERVO14=153, /* | */
MAV_COMP_ID_MAPPER=180, /* | */
MAV_COMP_ID_MISSIONPLANNER=190, /* | */
MAV_COMP_ID_PATHPLANNER=195, /* | */
MAV_COMP_ID_IMU=200, /* | */
MAV_COMP_ID_IMU_2=201, /* | */
MAV_COMP_ID_IMU_3=202, /* | */
MAV_COMP_ID_GPS=220, /* | */
MAV_COMP_ID_UDP_BRIDGE=240, /* | */
MAV_COMP_ID_UART_BRIDGE=241, /* | */
MAV_COMP_ID_SYSTEM_CONTROL=250, /* | */
MAV_COMPONENT_ENUM_END=251, /* | */
};
#endif
 
/** @brief */
#ifndef HAVE_ENUM_MAV_FRAME
#define HAVE_ENUM_MAV_FRAME
enum MAV_FRAME
{
MAV_FRAME_GLOBAL=0, /* Global coordinate frame, WGS84 coordinate system. First value / x: latitude, second value / y: longitude, third value / z: positive altitude over mean sea level (MSL) | */
MAV_FRAME_LOCAL_NED=1, /* Local coordinate frame, Z-up (x: north, y: east, z: down). | */
MAV_FRAME_MISSION=2, /* NOT a coordinate frame, indicates a mission command. | */
MAV_FRAME_GLOBAL_RELATIVE_ALT=3, /* Global coordinate frame, WGS84 coordinate system, relative altitude over ground with respect to the home position. First value / x: latitude, second value / y: longitude, third value / z: positive altitude with 0 being at the altitude of the home location. | */
MAV_FRAME_LOCAL_ENU=4, /* Local coordinate frame, Z-down (x: east, y: north, z: up) | */
MAV_FRAME_ENUM_END=5, /* | */
};
#endif
 
/** @brief */
#ifndef HAVE_ENUM_MAVLINK_DATA_STREAM_TYPE
#define HAVE_ENUM_MAVLINK_DATA_STREAM_TYPE
enum MAVLINK_DATA_STREAM_TYPE
{
MAVLINK_DATA_STREAM_IMG_JPEG=1, /* | */
MAVLINK_DATA_STREAM_IMG_BMP=2, /* | */
MAVLINK_DATA_STREAM_IMG_RAW8U=3, /* | */
MAVLINK_DATA_STREAM_IMG_RAW32U=4, /* | */
MAVLINK_DATA_STREAM_IMG_PGM=5, /* | */
MAVLINK_DATA_STREAM_IMG_PNG=6, /* | */
MAVLINK_DATA_STREAM_TYPE_ENUM_END=7, /* | */
};
#endif
 
/** @brief Data stream IDs. A data stream is not a fixed set of messages, but rather a
recommendation to the autopilot software. Individual autopilots may or may not obey
the recommended messages. */
#ifndef HAVE_ENUM_MAV_DATA_STREAM
#define HAVE_ENUM_MAV_DATA_STREAM
enum MAV_DATA_STREAM
{
MAV_DATA_STREAM_ALL=0, /* Enable all data streams | */
MAV_DATA_STREAM_RAW_SENSORS=1, /* Enable IMU_RAW, GPS_RAW, GPS_STATUS packets. | */
MAV_DATA_STREAM_EXTENDED_STATUS=2, /* Enable GPS_STATUS, CONTROL_STATUS, AUX_STATUS | */
MAV_DATA_STREAM_RC_CHANNELS=3, /* Enable RC_CHANNELS_SCALED, RC_CHANNELS_RAW, SERVO_OUTPUT_RAW | */
MAV_DATA_STREAM_RAW_CONTROLLER=4, /* Enable ATTITUDE_CONTROLLER_OUTPUT, POSITION_CONTROLLER_OUTPUT, NAV_CONTROLLER_OUTPUT. | */
MAV_DATA_STREAM_POSITION=6, /* Enable LOCAL_POSITION, GLOBAL_POSITION/GLOBAL_POSITION_INT messages. | */
MAV_DATA_STREAM_EXTRA1=10, /* Dependent on the autopilot | */
MAV_DATA_STREAM_EXTRA2=11, /* Dependent on the autopilot | */
MAV_DATA_STREAM_EXTRA3=12, /* Dependent on the autopilot | */
MAV_DATA_STREAM_ENUM_END=13, /* | */
};
#endif
 
/** @brief The ROI (region of interest) for the vehicle. This can be
be used by the vehicle for camera/vehicle attitude alignment (see
MAV_CMD_NAV_ROI). */
#ifndef HAVE_ENUM_MAV_ROI
#define HAVE_ENUM_MAV_ROI
enum MAV_ROI
{
MAV_ROI_NONE=0, /* No region of interest. | */
MAV_ROI_WPNEXT=1, /* Point toward next MISSION. | */
MAV_ROI_WPINDEX=2, /* Point toward given MISSION. | */
MAV_ROI_LOCATION=3, /* Point toward fixed location. | */
MAV_ROI_TARGET=4, /* Point toward of given id. | */
MAV_ROI_ENUM_END=5, /* | */
};
#endif
 
/** @brief ACK / NACK / ERROR values as a result of MAV_CMDs and for mission item transmission. */
#ifndef HAVE_ENUM_MAV_CMD_ACK
#define HAVE_ENUM_MAV_CMD_ACK
enum MAV_CMD_ACK
{
MAV_CMD_ACK_OK=1, /* Command / mission item is ok. | */
MAV_CMD_ACK_ERR_FAIL=2, /* Generic error message if none of the other reasons fails or if no detailed error reporting is implemented. | */
MAV_CMD_ACK_ERR_ACCESS_DENIED=3, /* The system is refusing to accept this command from this source / communication partner. | */
MAV_CMD_ACK_ERR_NOT_SUPPORTED=4, /* Command or mission item is not supported, other commands would be accepted. | */
MAV_CMD_ACK_ERR_COORDINATE_FRAME_NOT_SUPPORTED=5, /* The coordinate frame of this command / mission item is not supported. | */
MAV_CMD_ACK_ERR_COORDINATES_OUT_OF_RANGE=6, /* The coordinate frame of this command is ok, but he coordinate values exceed the safety limits of this system. This is a generic error, please use the more specific error messages below if possible. | */
MAV_CMD_ACK_ERR_X_LAT_OUT_OF_RANGE=7, /* The X or latitude value is out of range. | */
MAV_CMD_ACK_ERR_Y_LON_OUT_OF_RANGE=8, /* The Y or longitude value is out of range. | */
MAV_CMD_ACK_ERR_Z_ALT_OUT_OF_RANGE=9, /* The Z or altitude value is out of range. | */
MAV_CMD_ACK_ENUM_END=10, /* | */
};
#endif
 
/** @brief type of a mavlink parameter */
#ifndef HAVE_ENUM_MAV_VAR
#define HAVE_ENUM_MAV_VAR
enum MAV_VAR
{
MAV_VAR_FLOAT=0, /* 32 bit float | */
MAV_VAR_UINT8=1, /* 8 bit unsigned integer | */
MAV_VAR_INT8=2, /* 8 bit signed integer | */
MAV_VAR_UINT16=3, /* 16 bit unsigned integer | */
MAV_VAR_INT16=4, /* 16 bit signed integer | */
MAV_VAR_UINT32=5, /* 32 bit unsigned integer | */
MAV_VAR_INT32=6, /* 32 bit signed integer | */
MAV_VAR_ENUM_END=7, /* | */
};
#endif
 
/** @brief result from a mavlink command */
#ifndef HAVE_ENUM_MAV_RESULT
#define HAVE_ENUM_MAV_RESULT
enum MAV_RESULT
{
MAV_RESULT_ACCEPTED=0, /* Command ACCEPTED and EXECUTED | */
MAV_RESULT_TEMPORARILY_REJECTED=1, /* Command TEMPORARY REJECTED/DENIED | */
MAV_RESULT_DENIED=2, /* Command PERMANENTLY DENIED | */
MAV_RESULT_UNSUPPORTED=3, /* Command UNKNOWN/UNSUPPORTED | */
MAV_RESULT_FAILED=4, /* Command executed, but failed | */
MAV_RESULT_ENUM_END=5, /* | */
};
#endif
 
/** @brief result in a mavlink mission ack */
#ifndef HAVE_ENUM_MAV_MISSION_RESULT
#define HAVE_ENUM_MAV_MISSION_RESULT
enum MAV_MISSION_RESULT
{
MAV_MISSION_ACCEPTED=0, /* mission accepted OK | */
MAV_MISSION_ERROR=1, /* generic error / not accepting mission commands at all right now | */
MAV_MISSION_UNSUPPORTED_FRAME=2, /* coordinate frame is not supported | */
MAV_MISSION_UNSUPPORTED=3, /* command is not supported | */
MAV_MISSION_NO_SPACE=4, /* mission item exceeds storage space | */
MAV_MISSION_INVALID=5, /* one of the parameters has an invalid value | */
MAV_MISSION_INVALID_PARAM1=6, /* param1 has an invalid value | */
MAV_MISSION_INVALID_PARAM2=7, /* param2 has an invalid value | */
MAV_MISSION_INVALID_PARAM3=8, /* param3 has an invalid value | */
MAV_MISSION_INVALID_PARAM4=9, /* param4 has an invalid value | */
MAV_MISSION_INVALID_PARAM5_X=10, /* x/param5 has an invalid value | */
MAV_MISSION_INVALID_PARAM6_Y=11, /* y/param6 has an invalid value | */
MAV_MISSION_INVALID_PARAM7=12, /* param7 has an invalid value | */
MAV_MISSION_INVALID_SEQUENCE=13, /* received waypoint out of sequence | */
MAV_MISSION_DENIED=14, /* not accepting any mission commands from this communication partner | */
MAV_MISSION_RESULT_ENUM_END=15, /* | */
};
#endif
 
/** @brief Indicates the severity level, generally used for status messages to indicate their relative urgency. Based on RFC-5424 using expanded definitions at: http://www.kiwisyslog.com/kb/info:-syslog-message-levels/. */
#ifndef HAVE_ENUM_MAV_SEVERITY
#define HAVE_ENUM_MAV_SEVERITY
enum MAV_SEVERITY
{
MAV_SEVERITY_EMERGENCY=0, /* System is unusable. This is a "panic" condition. | */
MAV_SEVERITY_ALERT=1, /* Action should be taken immediately. Indicates error in non-critical systems. | */
MAV_SEVERITY_CRITICAL=2, /* Action must be taken immediately. Indicates failure in a primary system. | */
MAV_SEVERITY_ERROR=3, /* Indicates an error in secondary/redundant systems. | */
MAV_SEVERITY_WARNING=4, /* Indicates about a possible future error if this is not resolved within a given timeframe. Example would be a low battery warning. | */
MAV_SEVERITY_NOTICE=5, /* An unusual event has occured, though not an error condition. This should be investigated for the root cause. | */
MAV_SEVERITY_INFO=6, /* Normal operational messages. Useful for logging. No action is required for these messages. | */
MAV_SEVERITY_DEBUG=7, /* Useful non-operational messages that can assist in debugging. These should not occur during normal operation. | */
MAV_SEVERITY_ENUM_END=8, /* | */
};
#endif
 
 
 
// MAVLINK VERSION
 
#ifndef MAVLINK_VERSION
#define MAVLINK_VERSION 3
#endif
 
#if (MAVLINK_VERSION == 0)
#undef MAVLINK_VERSION
#define MAVLINK_VERSION 3
#endif
 
// MESSAGE DEFINITIONS
#include "./mavlink_msg_heartbeat.h"
#include "./mavlink_msg_sys_status.h"
#include "./mavlink_msg_system_time.h"
#include "./mavlink_msg_ping.h"
#include "./mavlink_msg_change_operator_control.h"
#include "./mavlink_msg_change_operator_control_ack.h"
#include "./mavlink_msg_auth_key.h"
#include "./mavlink_msg_set_mode.h"
#include "./mavlink_msg_param_request_read.h"
#include "./mavlink_msg_param_request_list.h"
#include "./mavlink_msg_param_value.h"
#include "./mavlink_msg_param_set.h"
#include "./mavlink_msg_gps_raw_int.h"
#include "./mavlink_msg_gps_status.h"
#include "./mavlink_msg_scaled_imu.h"
#include "./mavlink_msg_raw_imu.h"
#include "./mavlink_msg_raw_pressure.h"
#include "./mavlink_msg_scaled_pressure.h"
#include "./mavlink_msg_attitude.h"
#include "./mavlink_msg_attitude_quaternion.h"
#include "./mavlink_msg_local_position_ned.h"
#include "./mavlink_msg_global_position_int.h"
#include "./mavlink_msg_rc_channels_scaled.h"
#include "./mavlink_msg_rc_channels_raw.h"
#include "./mavlink_msg_servo_output_raw.h"
#include "./mavlink_msg_mission_request_partial_list.h"
#include "./mavlink_msg_mission_write_partial_list.h"
#include "./mavlink_msg_mission_item.h"
#include "./mavlink_msg_mission_request.h"
#include "./mavlink_msg_mission_set_current.h"
#include "./mavlink_msg_mission_current.h"
#include "./mavlink_msg_mission_request_list.h"
#include "./mavlink_msg_mission_count.h"
#include "./mavlink_msg_mission_clear_all.h"
#include "./mavlink_msg_mission_item_reached.h"
#include "./mavlink_msg_mission_ack.h"
#include "./mavlink_msg_set_gps_global_origin.h"
#include "./mavlink_msg_gps_global_origin.h"
#include "./mavlink_msg_set_local_position_setpoint.h"
#include "./mavlink_msg_local_position_setpoint.h"
#include "./mavlink_msg_global_position_setpoint_int.h"
#include "./mavlink_msg_set_global_position_setpoint_int.h"
#include "./mavlink_msg_safety_set_allowed_area.h"
#include "./mavlink_msg_safety_allowed_area.h"
#include "./mavlink_msg_set_roll_pitch_yaw_thrust.h"
#include "./mavlink_msg_set_roll_pitch_yaw_speed_thrust.h"
#include "./mavlink_msg_roll_pitch_yaw_thrust_setpoint.h"
#include "./mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint.h"
#include "./mavlink_msg_set_quad_motors_setpoint.h"
#include "./mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust.h"
#include "./mavlink_msg_nav_controller_output.h"
#include "./mavlink_msg_state_correction.h"
#include "./mavlink_msg_request_data_stream.h"
#include "./mavlink_msg_data_stream.h"
#include "./mavlink_msg_manual_control.h"
#include "./mavlink_msg_rc_channels_override.h"
#include "./mavlink_msg_vfr_hud.h"
#include "./mavlink_msg_command_long.h"
#include "./mavlink_msg_command_ack.h"
#include "./mavlink_msg_local_position_ned_system_global_offset.h"
#include "./mavlink_msg_hil_state.h"
#include "./mavlink_msg_hil_controls.h"
#include "./mavlink_msg_hil_rc_inputs_raw.h"
#include "./mavlink_msg_optical_flow.h"
#include "./mavlink_msg_global_vision_position_estimate.h"
#include "./mavlink_msg_vision_position_estimate.h"
#include "./mavlink_msg_vision_speed_estimate.h"
#include "./mavlink_msg_vicon_position_estimate.h"
#include "./mavlink_msg_memory_vect.h"
#include "./mavlink_msg_debug_vect.h"
#include "./mavlink_msg_named_value_float.h"
#include "./mavlink_msg_named_value_int.h"
#include "./mavlink_msg_statustext.h"
#include "./mavlink_msg_debug.h"
 
#ifdef __cplusplus
}
#endif // __cplusplus
#endif // COMMON_H
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v1.0/common/mavlink.h
0,0 → 1,27
/** @file
* @brief MAVLink comm protocol built from common.xml
* @see http://pixhawk.ethz.ch/software/mavlink
*/
#ifndef MAVLINK_H
#define MAVLINK_H
 
#ifndef MAVLINK_STX
#define MAVLINK_STX 254
#endif
 
#ifndef MAVLINK_ENDIAN
#define MAVLINK_ENDIAN MAVLINK_LITTLE_ENDIAN
#endif
 
#ifndef MAVLINK_ALIGNED_FIELDS
#define MAVLINK_ALIGNED_FIELDS 1
#endif
 
#ifndef MAVLINK_CRC_EXTRA
#define MAVLINK_CRC_EXTRA 1
#endif
 
#include "version.h"
#include "common.h"
 
#endif // MAVLINK_H
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v1.0/common/mavlink_msg_attitude.h
0,0 → 1,276
// MESSAGE ATTITUDE PACKING
 
#define MAVLINK_MSG_ID_ATTITUDE 30
 
typedef struct __mavlink_attitude_t
{
uint32_t time_boot_ms; ///< Timestamp (milliseconds since system boot)
float roll; ///< Roll angle (rad)
float pitch; ///< Pitch angle (rad)
float yaw; ///< Yaw angle (rad)
float rollspeed; ///< Roll angular speed (rad/s)
float pitchspeed; ///< Pitch angular speed (rad/s)
float yawspeed; ///< Yaw angular speed (rad/s)
} mavlink_attitude_t;
 
#define MAVLINK_MSG_ID_ATTITUDE_LEN 28
#define MAVLINK_MSG_ID_30_LEN 28
 
 
 
#define MAVLINK_MESSAGE_INFO_ATTITUDE { \
"ATTITUDE", \
7, \
{ { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_attitude_t, time_boot_ms) }, \
{ "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_attitude_t, roll) }, \
{ "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_attitude_t, pitch) }, \
{ "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_attitude_t, yaw) }, \
{ "rollspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_attitude_t, rollspeed) }, \
{ "pitchspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_attitude_t, pitchspeed) }, \
{ "yawspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_attitude_t, yawspeed) }, \
} \
}
 
 
/**
* @brief Pack a attitude message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param time_boot_ms Timestamp (milliseconds since system boot)
* @param roll Roll angle (rad)
* @param pitch Pitch angle (rad)
* @param yaw Yaw angle (rad)
* @param rollspeed Roll angular speed (rad/s)
* @param pitchspeed Pitch angular speed (rad/s)
* @param yawspeed Yaw angular speed (rad/s)
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_attitude_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint32_t time_boot_ms, float roll, float pitch, float yaw, float rollspeed, float pitchspeed, float yawspeed)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[28];
_mav_put_uint32_t(buf, 0, time_boot_ms);
_mav_put_float(buf, 4, roll);
_mav_put_float(buf, 8, pitch);
_mav_put_float(buf, 12, yaw);
_mav_put_float(buf, 16, rollspeed);
_mav_put_float(buf, 20, pitchspeed);
_mav_put_float(buf, 24, yawspeed);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 28);
#else
mavlink_attitude_t packet;
packet.time_boot_ms = time_boot_ms;
packet.roll = roll;
packet.pitch = pitch;
packet.yaw = yaw;
packet.rollspeed = rollspeed;
packet.pitchspeed = pitchspeed;
packet.yawspeed = yawspeed;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 28);
#endif
 
msg->msgid = MAVLINK_MSG_ID_ATTITUDE;
return mavlink_finalize_message(msg, system_id, component_id, 28, 39);
}
 
/**
* @brief Pack a attitude message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param time_boot_ms Timestamp (milliseconds since system boot)
* @param roll Roll angle (rad)
* @param pitch Pitch angle (rad)
* @param yaw Yaw angle (rad)
* @param rollspeed Roll angular speed (rad/s)
* @param pitchspeed Pitch angular speed (rad/s)
* @param yawspeed Yaw angular speed (rad/s)
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_attitude_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint32_t time_boot_ms,float roll,float pitch,float yaw,float rollspeed,float pitchspeed,float yawspeed)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[28];
_mav_put_uint32_t(buf, 0, time_boot_ms);
_mav_put_float(buf, 4, roll);
_mav_put_float(buf, 8, pitch);
_mav_put_float(buf, 12, yaw);
_mav_put_float(buf, 16, rollspeed);
_mav_put_float(buf, 20, pitchspeed);
_mav_put_float(buf, 24, yawspeed);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 28);
#else
mavlink_attitude_t packet;
packet.time_boot_ms = time_boot_ms;
packet.roll = roll;
packet.pitch = pitch;
packet.yaw = yaw;
packet.rollspeed = rollspeed;
packet.pitchspeed = pitchspeed;
packet.yawspeed = yawspeed;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 28);
#endif
 
msg->msgid = MAVLINK_MSG_ID_ATTITUDE;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 28, 39);
}
 
/**
* @brief Encode a attitude struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param attitude C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_attitude_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_attitude_t* attitude)
{
return mavlink_msg_attitude_pack(system_id, component_id, msg, attitude->time_boot_ms, attitude->roll, attitude->pitch, attitude->yaw, attitude->rollspeed, attitude->pitchspeed, attitude->yawspeed);
}
 
/**
* @brief Send a attitude message
* @param chan MAVLink channel to send the message
*
* @param time_boot_ms Timestamp (milliseconds since system boot)
* @param roll Roll angle (rad)
* @param pitch Pitch angle (rad)
* @param yaw Yaw angle (rad)
* @param rollspeed Roll angular speed (rad/s)
* @param pitchspeed Pitch angular speed (rad/s)
* @param yawspeed Yaw angular speed (rad/s)
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_attitude_send(mavlink_channel_t chan, uint32_t time_boot_ms, float roll, float pitch, float yaw, float rollspeed, float pitchspeed, float yawspeed)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[28];
_mav_put_uint32_t(buf, 0, time_boot_ms);
_mav_put_float(buf, 4, roll);
_mav_put_float(buf, 8, pitch);
_mav_put_float(buf, 12, yaw);
_mav_put_float(buf, 16, rollspeed);
_mav_put_float(buf, 20, pitchspeed);
_mav_put_float(buf, 24, yawspeed);
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE, buf, 28, 39);
#else
mavlink_attitude_t packet;
packet.time_boot_ms = time_boot_ms;
packet.roll = roll;
packet.pitch = pitch;
packet.yaw = yaw;
packet.rollspeed = rollspeed;
packet.pitchspeed = pitchspeed;
packet.yawspeed = yawspeed;
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE, (const char *)&packet, 28, 39);
#endif
}
 
#endif
 
// MESSAGE ATTITUDE UNPACKING
 
 
/**
* @brief Get field time_boot_ms from attitude message
*
* @return Timestamp (milliseconds since system boot)
*/
static inline uint32_t mavlink_msg_attitude_get_time_boot_ms(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint32_t(msg, 0);
}
 
/**
* @brief Get field roll from attitude message
*
* @return Roll angle (rad)
*/
static inline float mavlink_msg_attitude_get_roll(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 4);
}
 
/**
* @brief Get field pitch from attitude message
*
* @return Pitch angle (rad)
*/
static inline float mavlink_msg_attitude_get_pitch(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 8);
}
 
/**
* @brief Get field yaw from attitude message
*
* @return Yaw angle (rad)
*/
static inline float mavlink_msg_attitude_get_yaw(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 12);
}
 
/**
* @brief Get field rollspeed from attitude message
*
* @return Roll angular speed (rad/s)
*/
static inline float mavlink_msg_attitude_get_rollspeed(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 16);
}
 
/**
* @brief Get field pitchspeed from attitude message
*
* @return Pitch angular speed (rad/s)
*/
static inline float mavlink_msg_attitude_get_pitchspeed(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 20);
}
 
/**
* @brief Get field yawspeed from attitude message
*
* @return Yaw angular speed (rad/s)
*/
static inline float mavlink_msg_attitude_get_yawspeed(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 24);
}
 
/**
* @brief Decode a attitude message into a struct
*
* @param msg The message to decode
* @param attitude C-struct to decode the message contents into
*/
static inline void mavlink_msg_attitude_decode(const mavlink_message_t* msg, mavlink_attitude_t* attitude)
{
#if MAVLINK_NEED_BYTE_SWAP
attitude->time_boot_ms = mavlink_msg_attitude_get_time_boot_ms(msg);
attitude->roll = mavlink_msg_attitude_get_roll(msg);
attitude->pitch = mavlink_msg_attitude_get_pitch(msg);
attitude->yaw = mavlink_msg_attitude_get_yaw(msg);
attitude->rollspeed = mavlink_msg_attitude_get_rollspeed(msg);
attitude->pitchspeed = mavlink_msg_attitude_get_pitchspeed(msg);
attitude->yawspeed = mavlink_msg_attitude_get_yawspeed(msg);
#else
memcpy(attitude, _MAV_PAYLOAD(msg), 28);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v1.0/common/mavlink_msg_attitude_quaternion.h
0,0 → 1,298
// MESSAGE ATTITUDE_QUATERNION PACKING
 
#define MAVLINK_MSG_ID_ATTITUDE_QUATERNION 31
 
typedef struct __mavlink_attitude_quaternion_t
{
uint32_t time_boot_ms; ///< Timestamp (milliseconds since system boot)
float q1; ///< Quaternion component 1
float q2; ///< Quaternion component 2
float q3; ///< Quaternion component 3
float q4; ///< Quaternion component 4
float rollspeed; ///< Roll angular speed (rad/s)
float pitchspeed; ///< Pitch angular speed (rad/s)
float yawspeed; ///< Yaw angular speed (rad/s)
} mavlink_attitude_quaternion_t;
 
#define MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN 32
#define MAVLINK_MSG_ID_31_LEN 32
 
 
 
#define MAVLINK_MESSAGE_INFO_ATTITUDE_QUATERNION { \
"ATTITUDE_QUATERNION", \
8, \
{ { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_attitude_quaternion_t, time_boot_ms) }, \
{ "q1", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_attitude_quaternion_t, q1) }, \
{ "q2", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_attitude_quaternion_t, q2) }, \
{ "q3", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_attitude_quaternion_t, q3) }, \
{ "q4", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_attitude_quaternion_t, q4) }, \
{ "rollspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_attitude_quaternion_t, rollspeed) }, \
{ "pitchspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_attitude_quaternion_t, pitchspeed) }, \
{ "yawspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_attitude_quaternion_t, yawspeed) }, \
} \
}
 
 
/**
* @brief Pack a attitude_quaternion message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param time_boot_ms Timestamp (milliseconds since system boot)
* @param q1 Quaternion component 1
* @param q2 Quaternion component 2
* @param q3 Quaternion component 3
* @param q4 Quaternion component 4
* @param rollspeed Roll angular speed (rad/s)
* @param pitchspeed Pitch angular speed (rad/s)
* @param yawspeed Yaw angular speed (rad/s)
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_attitude_quaternion_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint32_t time_boot_ms, float q1, float q2, float q3, float q4, float rollspeed, float pitchspeed, float yawspeed)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[32];
_mav_put_uint32_t(buf, 0, time_boot_ms);
_mav_put_float(buf, 4, q1);
_mav_put_float(buf, 8, q2);
_mav_put_float(buf, 12, q3);
_mav_put_float(buf, 16, q4);
_mav_put_float(buf, 20, rollspeed);
_mav_put_float(buf, 24, pitchspeed);
_mav_put_float(buf, 28, yawspeed);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 32);
#else
mavlink_attitude_quaternion_t packet;
packet.time_boot_ms = time_boot_ms;
packet.q1 = q1;
packet.q2 = q2;
packet.q3 = q3;
packet.q4 = q4;
packet.rollspeed = rollspeed;
packet.pitchspeed = pitchspeed;
packet.yawspeed = yawspeed;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 32);
#endif
 
msg->msgid = MAVLINK_MSG_ID_ATTITUDE_QUATERNION;
return mavlink_finalize_message(msg, system_id, component_id, 32, 246);
}
 
/**
* @brief Pack a attitude_quaternion message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param time_boot_ms Timestamp (milliseconds since system boot)
* @param q1 Quaternion component 1
* @param q2 Quaternion component 2
* @param q3 Quaternion component 3
* @param q4 Quaternion component 4
* @param rollspeed Roll angular speed (rad/s)
* @param pitchspeed Pitch angular speed (rad/s)
* @param yawspeed Yaw angular speed (rad/s)
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_attitude_quaternion_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint32_t time_boot_ms,float q1,float q2,float q3,float q4,float rollspeed,float pitchspeed,float yawspeed)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[32];
_mav_put_uint32_t(buf, 0, time_boot_ms);
_mav_put_float(buf, 4, q1);
_mav_put_float(buf, 8, q2);
_mav_put_float(buf, 12, q3);
_mav_put_float(buf, 16, q4);
_mav_put_float(buf, 20, rollspeed);
_mav_put_float(buf, 24, pitchspeed);
_mav_put_float(buf, 28, yawspeed);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 32);
#else
mavlink_attitude_quaternion_t packet;
packet.time_boot_ms = time_boot_ms;
packet.q1 = q1;
packet.q2 = q2;
packet.q3 = q3;
packet.q4 = q4;
packet.rollspeed = rollspeed;
packet.pitchspeed = pitchspeed;
packet.yawspeed = yawspeed;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 32);
#endif
 
msg->msgid = MAVLINK_MSG_ID_ATTITUDE_QUATERNION;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 32, 246);
}
 
/**
* @brief Encode a attitude_quaternion struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param attitude_quaternion C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_attitude_quaternion_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_attitude_quaternion_t* attitude_quaternion)
{
return mavlink_msg_attitude_quaternion_pack(system_id, component_id, msg, attitude_quaternion->time_boot_ms, attitude_quaternion->q1, attitude_quaternion->q2, attitude_quaternion->q3, attitude_quaternion->q4, attitude_quaternion->rollspeed, attitude_quaternion->pitchspeed, attitude_quaternion->yawspeed);
}
 
/**
* @brief Send a attitude_quaternion message
* @param chan MAVLink channel to send the message
*
* @param time_boot_ms Timestamp (milliseconds since system boot)
* @param q1 Quaternion component 1
* @param q2 Quaternion component 2
* @param q3 Quaternion component 3
* @param q4 Quaternion component 4
* @param rollspeed Roll angular speed (rad/s)
* @param pitchspeed Pitch angular speed (rad/s)
* @param yawspeed Yaw angular speed (rad/s)
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_attitude_quaternion_send(mavlink_channel_t chan, uint32_t time_boot_ms, float q1, float q2, float q3, float q4, float rollspeed, float pitchspeed, float yawspeed)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[32];
_mav_put_uint32_t(buf, 0, time_boot_ms);
_mav_put_float(buf, 4, q1);
_mav_put_float(buf, 8, q2);
_mav_put_float(buf, 12, q3);
_mav_put_float(buf, 16, q4);
_mav_put_float(buf, 20, rollspeed);
_mav_put_float(buf, 24, pitchspeed);
_mav_put_float(buf, 28, yawspeed);
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION, buf, 32, 246);
#else
mavlink_attitude_quaternion_t packet;
packet.time_boot_ms = time_boot_ms;
packet.q1 = q1;
packet.q2 = q2;
packet.q3 = q3;
packet.q4 = q4;
packet.rollspeed = rollspeed;
packet.pitchspeed = pitchspeed;
packet.yawspeed = yawspeed;
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION, (const char *)&packet, 32, 246);
#endif
}
 
#endif
 
// MESSAGE ATTITUDE_QUATERNION UNPACKING
 
 
/**
* @brief Get field time_boot_ms from attitude_quaternion message
*
* @return Timestamp (milliseconds since system boot)
*/
static inline uint32_t mavlink_msg_attitude_quaternion_get_time_boot_ms(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint32_t(msg, 0);
}
 
/**
* @brief Get field q1 from attitude_quaternion message
*
* @return Quaternion component 1
*/
static inline float mavlink_msg_attitude_quaternion_get_q1(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 4);
}
 
/**
* @brief Get field q2 from attitude_quaternion message
*
* @return Quaternion component 2
*/
static inline float mavlink_msg_attitude_quaternion_get_q2(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 8);
}
 
/**
* @brief Get field q3 from attitude_quaternion message
*
* @return Quaternion component 3
*/
static inline float mavlink_msg_attitude_quaternion_get_q3(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 12);
}
 
/**
* @brief Get field q4 from attitude_quaternion message
*
* @return Quaternion component 4
*/
static inline float mavlink_msg_attitude_quaternion_get_q4(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 16);
}
 
/**
* @brief Get field rollspeed from attitude_quaternion message
*
* @return Roll angular speed (rad/s)
*/
static inline float mavlink_msg_attitude_quaternion_get_rollspeed(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 20);
}
 
/**
* @brief Get field pitchspeed from attitude_quaternion message
*
* @return Pitch angular speed (rad/s)
*/
static inline float mavlink_msg_attitude_quaternion_get_pitchspeed(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 24);
}
 
/**
* @brief Get field yawspeed from attitude_quaternion message
*
* @return Yaw angular speed (rad/s)
*/
static inline float mavlink_msg_attitude_quaternion_get_yawspeed(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 28);
}
 
/**
* @brief Decode a attitude_quaternion message into a struct
*
* @param msg The message to decode
* @param attitude_quaternion C-struct to decode the message contents into
*/
static inline void mavlink_msg_attitude_quaternion_decode(const mavlink_message_t* msg, mavlink_attitude_quaternion_t* attitude_quaternion)
{
#if MAVLINK_NEED_BYTE_SWAP
attitude_quaternion->time_boot_ms = mavlink_msg_attitude_quaternion_get_time_boot_ms(msg);
attitude_quaternion->q1 = mavlink_msg_attitude_quaternion_get_q1(msg);
attitude_quaternion->q2 = mavlink_msg_attitude_quaternion_get_q2(msg);
attitude_quaternion->q3 = mavlink_msg_attitude_quaternion_get_q3(msg);
attitude_quaternion->q4 = mavlink_msg_attitude_quaternion_get_q4(msg);
attitude_quaternion->rollspeed = mavlink_msg_attitude_quaternion_get_rollspeed(msg);
attitude_quaternion->pitchspeed = mavlink_msg_attitude_quaternion_get_pitchspeed(msg);
attitude_quaternion->yawspeed = mavlink_msg_attitude_quaternion_get_yawspeed(msg);
#else
memcpy(attitude_quaternion, _MAV_PAYLOAD(msg), 32);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v1.0/common/mavlink_msg_auth_key.h
0,0 → 1,144
// MESSAGE AUTH_KEY PACKING
 
#define MAVLINK_MSG_ID_AUTH_KEY 7
 
typedef struct __mavlink_auth_key_t
{
char key[32]; ///< key
} mavlink_auth_key_t;
 
#define MAVLINK_MSG_ID_AUTH_KEY_LEN 32
#define MAVLINK_MSG_ID_7_LEN 32
 
#define MAVLINK_MSG_AUTH_KEY_FIELD_KEY_LEN 32
 
#define MAVLINK_MESSAGE_INFO_AUTH_KEY { \
"AUTH_KEY", \
1, \
{ { "key", NULL, MAVLINK_TYPE_CHAR, 32, 0, offsetof(mavlink_auth_key_t, key) }, \
} \
}
 
 
/**
* @brief Pack a auth_key message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param key key
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_auth_key_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
const char *key)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[32];
 
_mav_put_char_array(buf, 0, key, 32);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 32);
#else
mavlink_auth_key_t packet;
 
mav_array_memcpy(packet.key, key, sizeof(char)*32);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 32);
#endif
 
msg->msgid = MAVLINK_MSG_ID_AUTH_KEY;
return mavlink_finalize_message(msg, system_id, component_id, 32, 119);
}
 
/**
* @brief Pack a auth_key message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param key key
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_auth_key_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
const char *key)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[32];
 
_mav_put_char_array(buf, 0, key, 32);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 32);
#else
mavlink_auth_key_t packet;
 
mav_array_memcpy(packet.key, key, sizeof(char)*32);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 32);
#endif
 
msg->msgid = MAVLINK_MSG_ID_AUTH_KEY;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 32, 119);
}
 
/**
* @brief Encode a auth_key struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param auth_key C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_auth_key_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_auth_key_t* auth_key)
{
return mavlink_msg_auth_key_pack(system_id, component_id, msg, auth_key->key);
}
 
/**
* @brief Send a auth_key message
* @param chan MAVLink channel to send the message
*
* @param key key
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_auth_key_send(mavlink_channel_t chan, const char *key)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[32];
 
_mav_put_char_array(buf, 0, key, 32);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTH_KEY, buf, 32, 119);
#else
mavlink_auth_key_t packet;
 
mav_array_memcpy(packet.key, key, sizeof(char)*32);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTH_KEY, (const char *)&packet, 32, 119);
#endif
}
 
#endif
 
// MESSAGE AUTH_KEY UNPACKING
 
 
/**
* @brief Get field key from auth_key message
*
* @return key
*/
static inline uint16_t mavlink_msg_auth_key_get_key(const mavlink_message_t* msg, char *key)
{
return _MAV_RETURN_char_array(msg, key, 32, 0);
}
 
/**
* @brief Decode a auth_key message into a struct
*
* @param msg The message to decode
* @param auth_key C-struct to decode the message contents into
*/
static inline void mavlink_msg_auth_key_decode(const mavlink_message_t* msg, mavlink_auth_key_t* auth_key)
{
#if MAVLINK_NEED_BYTE_SWAP
mavlink_msg_auth_key_get_key(msg, auth_key->key);
#else
memcpy(auth_key, _MAV_PAYLOAD(msg), 32);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v1.0/common/mavlink_msg_change_operator_control.h
0,0 → 1,204
// MESSAGE CHANGE_OPERATOR_CONTROL PACKING
 
#define MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL 5
 
typedef struct __mavlink_change_operator_control_t
{
uint8_t target_system; ///< System the GCS requests control for
uint8_t control_request; ///< 0: request control of this MAV, 1: Release control of this MAV
uint8_t version; ///< 0: key as plaintext, 1-255: future, different hashing/encryption variants. The GCS should in general use the safest mode possible initially and then gradually move down the encryption level if it gets a NACK message indicating an encryption mismatch.
char passkey[25]; ///< Password / Key, depending on version plaintext or encrypted. 25 or less characters, NULL terminated. The characters may involve A-Z, a-z, 0-9, and "!?,.-"
} mavlink_change_operator_control_t;
 
#define MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN 28
#define MAVLINK_MSG_ID_5_LEN 28
 
#define MAVLINK_MSG_CHANGE_OPERATOR_CONTROL_FIELD_PASSKEY_LEN 25
 
#define MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL { \
"CHANGE_OPERATOR_CONTROL", \
4, \
{ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_change_operator_control_t, target_system) }, \
{ "control_request", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_change_operator_control_t, control_request) }, \
{ "version", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_change_operator_control_t, version) }, \
{ "passkey", NULL, MAVLINK_TYPE_CHAR, 25, 3, offsetof(mavlink_change_operator_control_t, passkey) }, \
} \
}
 
 
/**
* @brief Pack a change_operator_control message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param target_system System the GCS requests control for
* @param control_request 0: request control of this MAV, 1: Release control of this MAV
* @param version 0: key as plaintext, 1-255: future, different hashing/encryption variants. The GCS should in general use the safest mode possible initially and then gradually move down the encryption level if it gets a NACK message indicating an encryption mismatch.
* @param passkey Password / Key, depending on version plaintext or encrypted. 25 or less characters, NULL terminated. The characters may involve A-Z, a-z, 0-9, and "!?,.-"
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_change_operator_control_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t target_system, uint8_t control_request, uint8_t version, const char *passkey)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[28];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, control_request);
_mav_put_uint8_t(buf, 2, version);
_mav_put_char_array(buf, 3, passkey, 25);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 28);
#else
mavlink_change_operator_control_t packet;
packet.target_system = target_system;
packet.control_request = control_request;
packet.version = version;
mav_array_memcpy(packet.passkey, passkey, sizeof(char)*25);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 28);
#endif
 
msg->msgid = MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL;
return mavlink_finalize_message(msg, system_id, component_id, 28, 217);
}
 
/**
* @brief Pack a change_operator_control message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param target_system System the GCS requests control for
* @param control_request 0: request control of this MAV, 1: Release control of this MAV
* @param version 0: key as plaintext, 1-255: future, different hashing/encryption variants. The GCS should in general use the safest mode possible initially and then gradually move down the encryption level if it gets a NACK message indicating an encryption mismatch.
* @param passkey Password / Key, depending on version plaintext or encrypted. 25 or less characters, NULL terminated. The characters may involve A-Z, a-z, 0-9, and "!?,.-"
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_change_operator_control_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint8_t target_system,uint8_t control_request,uint8_t version,const char *passkey)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[28];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, control_request);
_mav_put_uint8_t(buf, 2, version);
_mav_put_char_array(buf, 3, passkey, 25);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 28);
#else
mavlink_change_operator_control_t packet;
packet.target_system = target_system;
packet.control_request = control_request;
packet.version = version;
mav_array_memcpy(packet.passkey, passkey, sizeof(char)*25);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 28);
#endif
 
msg->msgid = MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 28, 217);
}
 
/**
* @brief Encode a change_operator_control struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param change_operator_control C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_change_operator_control_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_change_operator_control_t* change_operator_control)
{
return mavlink_msg_change_operator_control_pack(system_id, component_id, msg, change_operator_control->target_system, change_operator_control->control_request, change_operator_control->version, change_operator_control->passkey);
}
 
/**
* @brief Send a change_operator_control message
* @param chan MAVLink channel to send the message
*
* @param target_system System the GCS requests control for
* @param control_request 0: request control of this MAV, 1: Release control of this MAV
* @param version 0: key as plaintext, 1-255: future, different hashing/encryption variants. The GCS should in general use the safest mode possible initially and then gradually move down the encryption level if it gets a NACK message indicating an encryption mismatch.
* @param passkey Password / Key, depending on version plaintext or encrypted. 25 or less characters, NULL terminated. The characters may involve A-Z, a-z, 0-9, and "!?,.-"
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_change_operator_control_send(mavlink_channel_t chan, uint8_t target_system, uint8_t control_request, uint8_t version, const char *passkey)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[28];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, control_request);
_mav_put_uint8_t(buf, 2, version);
_mav_put_char_array(buf, 3, passkey, 25);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL, buf, 28, 217);
#else
mavlink_change_operator_control_t packet;
packet.target_system = target_system;
packet.control_request = control_request;
packet.version = version;
mav_array_memcpy(packet.passkey, passkey, sizeof(char)*25);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL, (const char *)&packet, 28, 217);
#endif
}
 
#endif
 
// MESSAGE CHANGE_OPERATOR_CONTROL UNPACKING
 
 
/**
* @brief Get field target_system from change_operator_control message
*
* @return System the GCS requests control for
*/
static inline uint8_t mavlink_msg_change_operator_control_get_target_system(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 0);
}
 
/**
* @brief Get field control_request from change_operator_control message
*
* @return 0: request control of this MAV, 1: Release control of this MAV
*/
static inline uint8_t mavlink_msg_change_operator_control_get_control_request(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 1);
}
 
/**
* @brief Get field version from change_operator_control message
*
* @return 0: key as plaintext, 1-255: future, different hashing/encryption variants. The GCS should in general use the safest mode possible initially and then gradually move down the encryption level if it gets a NACK message indicating an encryption mismatch.
*/
static inline uint8_t mavlink_msg_change_operator_control_get_version(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 2);
}
 
/**
* @brief Get field passkey from change_operator_control message
*
* @return Password / Key, depending on version plaintext or encrypted. 25 or less characters, NULL terminated. The characters may involve A-Z, a-z, 0-9, and "!?,.-"
*/
static inline uint16_t mavlink_msg_change_operator_control_get_passkey(const mavlink_message_t* msg, char *passkey)
{
return _MAV_RETURN_char_array(msg, passkey, 25, 3);
}
 
/**
* @brief Decode a change_operator_control message into a struct
*
* @param msg The message to decode
* @param change_operator_control C-struct to decode the message contents into
*/
static inline void mavlink_msg_change_operator_control_decode(const mavlink_message_t* msg, mavlink_change_operator_control_t* change_operator_control)
{
#if MAVLINK_NEED_BYTE_SWAP
change_operator_control->target_system = mavlink_msg_change_operator_control_get_target_system(msg);
change_operator_control->control_request = mavlink_msg_change_operator_control_get_control_request(msg);
change_operator_control->version = mavlink_msg_change_operator_control_get_version(msg);
mavlink_msg_change_operator_control_get_passkey(msg, change_operator_control->passkey);
#else
memcpy(change_operator_control, _MAV_PAYLOAD(msg), 28);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v1.0/common/mavlink_msg_change_operator_control_ack.h
0,0 → 1,188
// MESSAGE CHANGE_OPERATOR_CONTROL_ACK PACKING
 
#define MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK 6
 
typedef struct __mavlink_change_operator_control_ack_t
{
uint8_t gcs_system_id; ///< ID of the GCS this message
uint8_t control_request; ///< 0: request control of this MAV, 1: Release control of this MAV
uint8_t ack; ///< 0: ACK, 1: NACK: Wrong passkey, 2: NACK: Unsupported passkey encryption method, 3: NACK: Already under control
} mavlink_change_operator_control_ack_t;
 
#define MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN 3
#define MAVLINK_MSG_ID_6_LEN 3
 
 
 
#define MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL_ACK { \
"CHANGE_OPERATOR_CONTROL_ACK", \
3, \
{ { "gcs_system_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_change_operator_control_ack_t, gcs_system_id) }, \
{ "control_request", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_change_operator_control_ack_t, control_request) }, \
{ "ack", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_change_operator_control_ack_t, ack) }, \
} \
}
 
 
/**
* @brief Pack a change_operator_control_ack message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param gcs_system_id ID of the GCS this message
* @param control_request 0: request control of this MAV, 1: Release control of this MAV
* @param ack 0: ACK, 1: NACK: Wrong passkey, 2: NACK: Unsupported passkey encryption method, 3: NACK: Already under control
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_change_operator_control_ack_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t gcs_system_id, uint8_t control_request, uint8_t ack)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[3];
_mav_put_uint8_t(buf, 0, gcs_system_id);
_mav_put_uint8_t(buf, 1, control_request);
_mav_put_uint8_t(buf, 2, ack);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 3);
#else
mavlink_change_operator_control_ack_t packet;
packet.gcs_system_id = gcs_system_id;
packet.control_request = control_request;
packet.ack = ack;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 3);
#endif
 
msg->msgid = MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK;
return mavlink_finalize_message(msg, system_id, component_id, 3, 104);
}
 
/**
* @brief Pack a change_operator_control_ack message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param gcs_system_id ID of the GCS this message
* @param control_request 0: request control of this MAV, 1: Release control of this MAV
* @param ack 0: ACK, 1: NACK: Wrong passkey, 2: NACK: Unsupported passkey encryption method, 3: NACK: Already under control
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_change_operator_control_ack_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint8_t gcs_system_id,uint8_t control_request,uint8_t ack)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[3];
_mav_put_uint8_t(buf, 0, gcs_system_id);
_mav_put_uint8_t(buf, 1, control_request);
_mav_put_uint8_t(buf, 2, ack);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 3);
#else
mavlink_change_operator_control_ack_t packet;
packet.gcs_system_id = gcs_system_id;
packet.control_request = control_request;
packet.ack = ack;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 3);
#endif
 
msg->msgid = MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 3, 104);
}
 
/**
* @brief Encode a change_operator_control_ack struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param change_operator_control_ack C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_change_operator_control_ack_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_change_operator_control_ack_t* change_operator_control_ack)
{
return mavlink_msg_change_operator_control_ack_pack(system_id, component_id, msg, change_operator_control_ack->gcs_system_id, change_operator_control_ack->control_request, change_operator_control_ack->ack);
}
 
/**
* @brief Send a change_operator_control_ack message
* @param chan MAVLink channel to send the message
*
* @param gcs_system_id ID of the GCS this message
* @param control_request 0: request control of this MAV, 1: Release control of this MAV
* @param ack 0: ACK, 1: NACK: Wrong passkey, 2: NACK: Unsupported passkey encryption method, 3: NACK: Already under control
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_change_operator_control_ack_send(mavlink_channel_t chan, uint8_t gcs_system_id, uint8_t control_request, uint8_t ack)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[3];
_mav_put_uint8_t(buf, 0, gcs_system_id);
_mav_put_uint8_t(buf, 1, control_request);
_mav_put_uint8_t(buf, 2, ack);
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK, buf, 3, 104);
#else
mavlink_change_operator_control_ack_t packet;
packet.gcs_system_id = gcs_system_id;
packet.control_request = control_request;
packet.ack = ack;
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK, (const char *)&packet, 3, 104);
#endif
}
 
#endif
 
// MESSAGE CHANGE_OPERATOR_CONTROL_ACK UNPACKING
 
 
/**
* @brief Get field gcs_system_id from change_operator_control_ack message
*
* @return ID of the GCS this message
*/
static inline uint8_t mavlink_msg_change_operator_control_ack_get_gcs_system_id(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 0);
}
 
/**
* @brief Get field control_request from change_operator_control_ack message
*
* @return 0: request control of this MAV, 1: Release control of this MAV
*/
static inline uint8_t mavlink_msg_change_operator_control_ack_get_control_request(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 1);
}
 
/**
* @brief Get field ack from change_operator_control_ack message
*
* @return 0: ACK, 1: NACK: Wrong passkey, 2: NACK: Unsupported passkey encryption method, 3: NACK: Already under control
*/
static inline uint8_t mavlink_msg_change_operator_control_ack_get_ack(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 2);
}
 
/**
* @brief Decode a change_operator_control_ack message into a struct
*
* @param msg The message to decode
* @param change_operator_control_ack C-struct to decode the message contents into
*/
static inline void mavlink_msg_change_operator_control_ack_decode(const mavlink_message_t* msg, mavlink_change_operator_control_ack_t* change_operator_control_ack)
{
#if MAVLINK_NEED_BYTE_SWAP
change_operator_control_ack->gcs_system_id = mavlink_msg_change_operator_control_ack_get_gcs_system_id(msg);
change_operator_control_ack->control_request = mavlink_msg_change_operator_control_ack_get_control_request(msg);
change_operator_control_ack->ack = mavlink_msg_change_operator_control_ack_get_ack(msg);
#else
memcpy(change_operator_control_ack, _MAV_PAYLOAD(msg), 3);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v1.0/common/mavlink_msg_command_ack.h
0,0 → 1,166
// MESSAGE COMMAND_ACK PACKING
 
#define MAVLINK_MSG_ID_COMMAND_ACK 77
 
typedef struct __mavlink_command_ack_t
{
uint16_t command; ///< Command ID, as defined by MAV_CMD enum.
uint8_t result; ///< See MAV_RESULT enum
} mavlink_command_ack_t;
 
#define MAVLINK_MSG_ID_COMMAND_ACK_LEN 3
#define MAVLINK_MSG_ID_77_LEN 3
 
 
 
#define MAVLINK_MESSAGE_INFO_COMMAND_ACK { \
"COMMAND_ACK", \
2, \
{ { "command", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_command_ack_t, command) }, \
{ "result", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_command_ack_t, result) }, \
} \
}
 
 
/**
* @brief Pack a command_ack message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param command Command ID, as defined by MAV_CMD enum.
* @param result See MAV_RESULT enum
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_command_ack_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint16_t command, uint8_t result)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[3];
_mav_put_uint16_t(buf, 0, command);
_mav_put_uint8_t(buf, 2, result);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 3);
#else
mavlink_command_ack_t packet;
packet.command = command;
packet.result = result;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 3);
#endif
 
msg->msgid = MAVLINK_MSG_ID_COMMAND_ACK;
return mavlink_finalize_message(msg, system_id, component_id, 3, 143);
}
 
/**
* @brief Pack a command_ack message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param command Command ID, as defined by MAV_CMD enum.
* @param result See MAV_RESULT enum
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_command_ack_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint16_t command,uint8_t result)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[3];
_mav_put_uint16_t(buf, 0, command);
_mav_put_uint8_t(buf, 2, result);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 3);
#else
mavlink_command_ack_t packet;
packet.command = command;
packet.result = result;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 3);
#endif
 
msg->msgid = MAVLINK_MSG_ID_COMMAND_ACK;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 3, 143);
}
 
/**
* @brief Encode a command_ack struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param command_ack C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_command_ack_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_command_ack_t* command_ack)
{
return mavlink_msg_command_ack_pack(system_id, component_id, msg, command_ack->command, command_ack->result);
}
 
/**
* @brief Send a command_ack message
* @param chan MAVLink channel to send the message
*
* @param command Command ID, as defined by MAV_CMD enum.
* @param result See MAV_RESULT enum
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_command_ack_send(mavlink_channel_t chan, uint16_t command, uint8_t result)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[3];
_mav_put_uint16_t(buf, 0, command);
_mav_put_uint8_t(buf, 2, result);
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_ACK, buf, 3, 143);
#else
mavlink_command_ack_t packet;
packet.command = command;
packet.result = result;
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_ACK, (const char *)&packet, 3, 143);
#endif
}
 
#endif
 
// MESSAGE COMMAND_ACK UNPACKING
 
 
/**
* @brief Get field command from command_ack message
*
* @return Command ID, as defined by MAV_CMD enum.
*/
static inline uint16_t mavlink_msg_command_ack_get_command(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 0);
}
 
/**
* @brief Get field result from command_ack message
*
* @return See MAV_RESULT enum
*/
static inline uint8_t mavlink_msg_command_ack_get_result(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 2);
}
 
/**
* @brief Decode a command_ack message into a struct
*
* @param msg The message to decode
* @param command_ack C-struct to decode the message contents into
*/
static inline void mavlink_msg_command_ack_decode(const mavlink_message_t* msg, mavlink_command_ack_t* command_ack)
{
#if MAVLINK_NEED_BYTE_SWAP
command_ack->command = mavlink_msg_command_ack_get_command(msg);
command_ack->result = mavlink_msg_command_ack_get_result(msg);
#else
memcpy(command_ack, _MAV_PAYLOAD(msg), 3);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v1.0/common/mavlink_msg_command_long.h
0,0 → 1,364
// MESSAGE COMMAND_LONG PACKING
 
#define MAVLINK_MSG_ID_COMMAND_LONG 76
 
typedef struct __mavlink_command_long_t
{
float param1; ///< Parameter 1, as defined by MAV_CMD enum.
float param2; ///< Parameter 2, as defined by MAV_CMD enum.
float param3; ///< Parameter 3, as defined by MAV_CMD enum.
float param4; ///< Parameter 4, as defined by MAV_CMD enum.
float param5; ///< Parameter 5, as defined by MAV_CMD enum.
float param6; ///< Parameter 6, as defined by MAV_CMD enum.
float param7; ///< Parameter 7, as defined by MAV_CMD enum.
uint16_t command; ///< Command ID, as defined by MAV_CMD enum.
uint8_t target_system; ///< System which should execute the command
uint8_t target_component; ///< Component which should execute the command, 0 for all components
uint8_t confirmation; ///< 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command)
} mavlink_command_long_t;
 
#define MAVLINK_MSG_ID_COMMAND_LONG_LEN 33
#define MAVLINK_MSG_ID_76_LEN 33
 
 
 
#define MAVLINK_MESSAGE_INFO_COMMAND_LONG { \
"COMMAND_LONG", \
11, \
{ { "param1", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_command_long_t, param1) }, \
{ "param2", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_command_long_t, param2) }, \
{ "param3", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_command_long_t, param3) }, \
{ "param4", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_command_long_t, param4) }, \
{ "param5", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_command_long_t, param5) }, \
{ "param6", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_command_long_t, param6) }, \
{ "param7", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_command_long_t, param7) }, \
{ "command", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_command_long_t, command) }, \
{ "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 30, offsetof(mavlink_command_long_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 31, offsetof(mavlink_command_long_t, target_component) }, \
{ "confirmation", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_command_long_t, confirmation) }, \
} \
}
 
 
/**
* @brief Pack a command_long message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param target_system System which should execute the command
* @param target_component Component which should execute the command, 0 for all components
* @param command Command ID, as defined by MAV_CMD enum.
* @param confirmation 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command)
* @param param1 Parameter 1, as defined by MAV_CMD enum.
* @param param2 Parameter 2, as defined by MAV_CMD enum.
* @param param3 Parameter 3, as defined by MAV_CMD enum.
* @param param4 Parameter 4, as defined by MAV_CMD enum.
* @param param5 Parameter 5, as defined by MAV_CMD enum.
* @param param6 Parameter 6, as defined by MAV_CMD enum.
* @param param7 Parameter 7, as defined by MAV_CMD enum.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_command_long_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t target_system, uint8_t target_component, uint16_t command, uint8_t confirmation, float param1, float param2, float param3, float param4, float param5, float param6, float param7)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[33];
_mav_put_float(buf, 0, param1);
_mav_put_float(buf, 4, param2);
_mav_put_float(buf, 8, param3);
_mav_put_float(buf, 12, param4);
_mav_put_float(buf, 16, param5);
_mav_put_float(buf, 20, param6);
_mav_put_float(buf, 24, param7);
_mav_put_uint16_t(buf, 28, command);
_mav_put_uint8_t(buf, 30, target_system);
_mav_put_uint8_t(buf, 31, target_component);
_mav_put_uint8_t(buf, 32, confirmation);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 33);
#else
mavlink_command_long_t packet;
packet.param1 = param1;
packet.param2 = param2;
packet.param3 = param3;
packet.param4 = param4;
packet.param5 = param5;
packet.param6 = param6;
packet.param7 = param7;
packet.command = command;
packet.target_system = target_system;
packet.target_component = target_component;
packet.confirmation = confirmation;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 33);
#endif
 
msg->msgid = MAVLINK_MSG_ID_COMMAND_LONG;
return mavlink_finalize_message(msg, system_id, component_id, 33, 152);
}
 
/**
* @brief Pack a command_long message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param target_system System which should execute the command
* @param target_component Component which should execute the command, 0 for all components
* @param command Command ID, as defined by MAV_CMD enum.
* @param confirmation 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command)
* @param param1 Parameter 1, as defined by MAV_CMD enum.
* @param param2 Parameter 2, as defined by MAV_CMD enum.
* @param param3 Parameter 3, as defined by MAV_CMD enum.
* @param param4 Parameter 4, as defined by MAV_CMD enum.
* @param param5 Parameter 5, as defined by MAV_CMD enum.
* @param param6 Parameter 6, as defined by MAV_CMD enum.
* @param param7 Parameter 7, as defined by MAV_CMD enum.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_command_long_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,uint16_t command,uint8_t confirmation,float param1,float param2,float param3,float param4,float param5,float param6,float param7)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[33];
_mav_put_float(buf, 0, param1);
_mav_put_float(buf, 4, param2);
_mav_put_float(buf, 8, param3);
_mav_put_float(buf, 12, param4);
_mav_put_float(buf, 16, param5);
_mav_put_float(buf, 20, param6);
_mav_put_float(buf, 24, param7);
_mav_put_uint16_t(buf, 28, command);
_mav_put_uint8_t(buf, 30, target_system);
_mav_put_uint8_t(buf, 31, target_component);
_mav_put_uint8_t(buf, 32, confirmation);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 33);
#else
mavlink_command_long_t packet;
packet.param1 = param1;
packet.param2 = param2;
packet.param3 = param3;
packet.param4 = param4;
packet.param5 = param5;
packet.param6 = param6;
packet.param7 = param7;
packet.command = command;
packet.target_system = target_system;
packet.target_component = target_component;
packet.confirmation = confirmation;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 33);
#endif
 
msg->msgid = MAVLINK_MSG_ID_COMMAND_LONG;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 33, 152);
}
 
/**
* @brief Encode a command_long struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param command_long C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_command_long_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_command_long_t* command_long)
{
return mavlink_msg_command_long_pack(system_id, component_id, msg, command_long->target_system, command_long->target_component, command_long->command, command_long->confirmation, command_long->param1, command_long->param2, command_long->param3, command_long->param4, command_long->param5, command_long->param6, command_long->param7);
}
 
/**
* @brief Send a command_long message
* @param chan MAVLink channel to send the message
*
* @param target_system System which should execute the command
* @param target_component Component which should execute the command, 0 for all components
* @param command Command ID, as defined by MAV_CMD enum.
* @param confirmation 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command)
* @param param1 Parameter 1, as defined by MAV_CMD enum.
* @param param2 Parameter 2, as defined by MAV_CMD enum.
* @param param3 Parameter 3, as defined by MAV_CMD enum.
* @param param4 Parameter 4, as defined by MAV_CMD enum.
* @param param5 Parameter 5, as defined by MAV_CMD enum.
* @param param6 Parameter 6, as defined by MAV_CMD enum.
* @param param7 Parameter 7, as defined by MAV_CMD enum.
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_command_long_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t command, uint8_t confirmation, float param1, float param2, float param3, float param4, float param5, float param6, float param7)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[33];
_mav_put_float(buf, 0, param1);
_mav_put_float(buf, 4, param2);
_mav_put_float(buf, 8, param3);
_mav_put_float(buf, 12, param4);
_mav_put_float(buf, 16, param5);
_mav_put_float(buf, 20, param6);
_mav_put_float(buf, 24, param7);
_mav_put_uint16_t(buf, 28, command);
_mav_put_uint8_t(buf, 30, target_system);
_mav_put_uint8_t(buf, 31, target_component);
_mav_put_uint8_t(buf, 32, confirmation);
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_LONG, buf, 33, 152);
#else
mavlink_command_long_t packet;
packet.param1 = param1;
packet.param2 = param2;
packet.param3 = param3;
packet.param4 = param4;
packet.param5 = param5;
packet.param6 = param6;
packet.param7 = param7;
packet.command = command;
packet.target_system = target_system;
packet.target_component = target_component;
packet.confirmation = confirmation;
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_LONG, (const char *)&packet, 33, 152);
#endif
}
 
#endif
 
// MESSAGE COMMAND_LONG UNPACKING
 
 
/**
* @brief Get field target_system from command_long message
*
* @return System which should execute the command
*/
static inline uint8_t mavlink_msg_command_long_get_target_system(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 30);
}
 
/**
* @brief Get field target_component from command_long message
*
* @return Component which should execute the command, 0 for all components
*/
static inline uint8_t mavlink_msg_command_long_get_target_component(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 31);
}
 
/**
* @brief Get field command from command_long message
*
* @return Command ID, as defined by MAV_CMD enum.
*/
static inline uint16_t mavlink_msg_command_long_get_command(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 28);
}
 
/**
* @brief Get field confirmation from command_long message
*
* @return 0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command)
*/
static inline uint8_t mavlink_msg_command_long_get_confirmation(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 32);
}
 
/**
* @brief Get field param1 from command_long message
*
* @return Parameter 1, as defined by MAV_CMD enum.
*/
static inline float mavlink_msg_command_long_get_param1(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 0);
}
 
/**
* @brief Get field param2 from command_long message
*
* @return Parameter 2, as defined by MAV_CMD enum.
*/
static inline float mavlink_msg_command_long_get_param2(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 4);
}
 
/**
* @brief Get field param3 from command_long message
*
* @return Parameter 3, as defined by MAV_CMD enum.
*/
static inline float mavlink_msg_command_long_get_param3(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 8);
}
 
/**
* @brief Get field param4 from command_long message
*
* @return Parameter 4, as defined by MAV_CMD enum.
*/
static inline float mavlink_msg_command_long_get_param4(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 12);
}
 
/**
* @brief Get field param5 from command_long message
*
* @return Parameter 5, as defined by MAV_CMD enum.
*/
static inline float mavlink_msg_command_long_get_param5(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 16);
}
 
/**
* @brief Get field param6 from command_long message
*
* @return Parameter 6, as defined by MAV_CMD enum.
*/
static inline float mavlink_msg_command_long_get_param6(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 20);
}
 
/**
* @brief Get field param7 from command_long message
*
* @return Parameter 7, as defined by MAV_CMD enum.
*/
static inline float mavlink_msg_command_long_get_param7(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 24);
}
 
/**
* @brief Decode a command_long message into a struct
*
* @param msg The message to decode
* @param command_long C-struct to decode the message contents into
*/
static inline void mavlink_msg_command_long_decode(const mavlink_message_t* msg, mavlink_command_long_t* command_long)
{
#if MAVLINK_NEED_BYTE_SWAP
command_long->param1 = mavlink_msg_command_long_get_param1(msg);
command_long->param2 = mavlink_msg_command_long_get_param2(msg);
command_long->param3 = mavlink_msg_command_long_get_param3(msg);
command_long->param4 = mavlink_msg_command_long_get_param4(msg);
command_long->param5 = mavlink_msg_command_long_get_param5(msg);
command_long->param6 = mavlink_msg_command_long_get_param6(msg);
command_long->param7 = mavlink_msg_command_long_get_param7(msg);
command_long->command = mavlink_msg_command_long_get_command(msg);
command_long->target_system = mavlink_msg_command_long_get_target_system(msg);
command_long->target_component = mavlink_msg_command_long_get_target_component(msg);
command_long->confirmation = mavlink_msg_command_long_get_confirmation(msg);
#else
memcpy(command_long, _MAV_PAYLOAD(msg), 33);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v1.0/common/mavlink_msg_data_stream.h
0,0 → 1,188
// MESSAGE DATA_STREAM PACKING
 
#define MAVLINK_MSG_ID_DATA_STREAM 67
 
typedef struct __mavlink_data_stream_t
{
uint16_t message_rate; ///< The requested interval between two messages of this type
uint8_t stream_id; ///< The ID of the requested data stream
uint8_t on_off; ///< 1 stream is enabled, 0 stream is stopped.
} mavlink_data_stream_t;
 
#define MAVLINK_MSG_ID_DATA_STREAM_LEN 4
#define MAVLINK_MSG_ID_67_LEN 4
 
 
 
#define MAVLINK_MESSAGE_INFO_DATA_STREAM { \
"DATA_STREAM", \
3, \
{ { "message_rate", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_data_stream_t, message_rate) }, \
{ "stream_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_data_stream_t, stream_id) }, \
{ "on_off", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_data_stream_t, on_off) }, \
} \
}
 
 
/**
* @brief Pack a data_stream message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param stream_id The ID of the requested data stream
* @param message_rate The requested interval between two messages of this type
* @param on_off 1 stream is enabled, 0 stream is stopped.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_data_stream_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t stream_id, uint16_t message_rate, uint8_t on_off)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[4];
_mav_put_uint16_t(buf, 0, message_rate);
_mav_put_uint8_t(buf, 2, stream_id);
_mav_put_uint8_t(buf, 3, on_off);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 4);
#else
mavlink_data_stream_t packet;
packet.message_rate = message_rate;
packet.stream_id = stream_id;
packet.on_off = on_off;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 4);
#endif
 
msg->msgid = MAVLINK_MSG_ID_DATA_STREAM;
return mavlink_finalize_message(msg, system_id, component_id, 4, 21);
}
 
/**
* @brief Pack a data_stream message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param stream_id The ID of the requested data stream
* @param message_rate The requested interval between two messages of this type
* @param on_off 1 stream is enabled, 0 stream is stopped.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_data_stream_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint8_t stream_id,uint16_t message_rate,uint8_t on_off)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[4];
_mav_put_uint16_t(buf, 0, message_rate);
_mav_put_uint8_t(buf, 2, stream_id);
_mav_put_uint8_t(buf, 3, on_off);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 4);
#else
mavlink_data_stream_t packet;
packet.message_rate = message_rate;
packet.stream_id = stream_id;
packet.on_off = on_off;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 4);
#endif
 
msg->msgid = MAVLINK_MSG_ID_DATA_STREAM;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 4, 21);
}
 
/**
* @brief Encode a data_stream struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param data_stream C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_data_stream_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_data_stream_t* data_stream)
{
return mavlink_msg_data_stream_pack(system_id, component_id, msg, data_stream->stream_id, data_stream->message_rate, data_stream->on_off);
}
 
/**
* @brief Send a data_stream message
* @param chan MAVLink channel to send the message
*
* @param stream_id The ID of the requested data stream
* @param message_rate The requested interval between two messages of this type
* @param on_off 1 stream is enabled, 0 stream is stopped.
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_data_stream_send(mavlink_channel_t chan, uint8_t stream_id, uint16_t message_rate, uint8_t on_off)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[4];
_mav_put_uint16_t(buf, 0, message_rate);
_mav_put_uint8_t(buf, 2, stream_id);
_mav_put_uint8_t(buf, 3, on_off);
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA_STREAM, buf, 4, 21);
#else
mavlink_data_stream_t packet;
packet.message_rate = message_rate;
packet.stream_id = stream_id;
packet.on_off = on_off;
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA_STREAM, (const char *)&packet, 4, 21);
#endif
}
 
#endif
 
// MESSAGE DATA_STREAM UNPACKING
 
 
/**
* @brief Get field stream_id from data_stream message
*
* @return The ID of the requested data stream
*/
static inline uint8_t mavlink_msg_data_stream_get_stream_id(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 2);
}
 
/**
* @brief Get field message_rate from data_stream message
*
* @return The requested interval between two messages of this type
*/
static inline uint16_t mavlink_msg_data_stream_get_message_rate(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 0);
}
 
/**
* @brief Get field on_off from data_stream message
*
* @return 1 stream is enabled, 0 stream is stopped.
*/
static inline uint8_t mavlink_msg_data_stream_get_on_off(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 3);
}
 
/**
* @brief Decode a data_stream message into a struct
*
* @param msg The message to decode
* @param data_stream C-struct to decode the message contents into
*/
static inline void mavlink_msg_data_stream_decode(const mavlink_message_t* msg, mavlink_data_stream_t* data_stream)
{
#if MAVLINK_NEED_BYTE_SWAP
data_stream->message_rate = mavlink_msg_data_stream_get_message_rate(msg);
data_stream->stream_id = mavlink_msg_data_stream_get_stream_id(msg);
data_stream->on_off = mavlink_msg_data_stream_get_on_off(msg);
#else
memcpy(data_stream, _MAV_PAYLOAD(msg), 4);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v1.0/common/mavlink_msg_debug.h
0,0 → 1,188
// MESSAGE DEBUG PACKING
 
#define MAVLINK_MSG_ID_DEBUG 254
 
typedef struct __mavlink_debug_t
{
uint32_t time_boot_ms; ///< Timestamp (milliseconds since system boot)
float value; ///< DEBUG value
uint8_t ind; ///< index of debug variable
} mavlink_debug_t;
 
#define MAVLINK_MSG_ID_DEBUG_LEN 9
#define MAVLINK_MSG_ID_254_LEN 9
 
 
 
#define MAVLINK_MESSAGE_INFO_DEBUG { \
"DEBUG", \
3, \
{ { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_debug_t, time_boot_ms) }, \
{ "value", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_debug_t, value) }, \
{ "ind", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_debug_t, ind) }, \
} \
}
 
 
/**
* @brief Pack a debug message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param time_boot_ms Timestamp (milliseconds since system boot)
* @param ind index of debug variable
* @param value DEBUG value
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_debug_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint32_t time_boot_ms, uint8_t ind, float value)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[9];
_mav_put_uint32_t(buf, 0, time_boot_ms);
_mav_put_float(buf, 4, value);
_mav_put_uint8_t(buf, 8, ind);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 9);
#else
mavlink_debug_t packet;
packet.time_boot_ms = time_boot_ms;
packet.value = value;
packet.ind = ind;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 9);
#endif
 
msg->msgid = MAVLINK_MSG_ID_DEBUG;
return mavlink_finalize_message(msg, system_id, component_id, 9, 46);
}
 
/**
* @brief Pack a debug message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param time_boot_ms Timestamp (milliseconds since system boot)
* @param ind index of debug variable
* @param value DEBUG value
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_debug_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint32_t time_boot_ms,uint8_t ind,float value)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[9];
_mav_put_uint32_t(buf, 0, time_boot_ms);
_mav_put_float(buf, 4, value);
_mav_put_uint8_t(buf, 8, ind);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 9);
#else
mavlink_debug_t packet;
packet.time_boot_ms = time_boot_ms;
packet.value = value;
packet.ind = ind;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 9);
#endif
 
msg->msgid = MAVLINK_MSG_ID_DEBUG;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 9, 46);
}
 
/**
* @brief Encode a debug struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param debug C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_debug_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_debug_t* debug)
{
return mavlink_msg_debug_pack(system_id, component_id, msg, debug->time_boot_ms, debug->ind, debug->value);
}
 
/**
* @brief Send a debug message
* @param chan MAVLink channel to send the message
*
* @param time_boot_ms Timestamp (milliseconds since system boot)
* @param ind index of debug variable
* @param value DEBUG value
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_debug_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t ind, float value)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[9];
_mav_put_uint32_t(buf, 0, time_boot_ms);
_mav_put_float(buf, 4, value);
_mav_put_uint8_t(buf, 8, ind);
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG, buf, 9, 46);
#else
mavlink_debug_t packet;
packet.time_boot_ms = time_boot_ms;
packet.value = value;
packet.ind = ind;
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG, (const char *)&packet, 9, 46);
#endif
}
 
#endif
 
// MESSAGE DEBUG UNPACKING
 
 
/**
* @brief Get field time_boot_ms from debug message
*
* @return Timestamp (milliseconds since system boot)
*/
static inline uint32_t mavlink_msg_debug_get_time_boot_ms(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint32_t(msg, 0);
}
 
/**
* @brief Get field ind from debug message
*
* @return index of debug variable
*/
static inline uint8_t mavlink_msg_debug_get_ind(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 8);
}
 
/**
* @brief Get field value from debug message
*
* @return DEBUG value
*/
static inline float mavlink_msg_debug_get_value(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 4);
}
 
/**
* @brief Decode a debug message into a struct
*
* @param msg The message to decode
* @param debug C-struct to decode the message contents into
*/
static inline void mavlink_msg_debug_decode(const mavlink_message_t* msg, mavlink_debug_t* debug)
{
#if MAVLINK_NEED_BYTE_SWAP
debug->time_boot_ms = mavlink_msg_debug_get_time_boot_ms(msg);
debug->value = mavlink_msg_debug_get_value(msg);
debug->ind = mavlink_msg_debug_get_ind(msg);
#else
memcpy(debug, _MAV_PAYLOAD(msg), 9);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v1.0/common/mavlink_msg_debug_vect.h
0,0 → 1,226
// MESSAGE DEBUG_VECT PACKING
 
#define MAVLINK_MSG_ID_DEBUG_VECT 250
 
typedef struct __mavlink_debug_vect_t
{
uint64_t time_usec; ///< Timestamp
float x; ///< x
float y; ///< y
float z; ///< z
char name[10]; ///< Name
} mavlink_debug_vect_t;
 
#define MAVLINK_MSG_ID_DEBUG_VECT_LEN 30
#define MAVLINK_MSG_ID_250_LEN 30
 
#define MAVLINK_MSG_DEBUG_VECT_FIELD_NAME_LEN 10
 
#define MAVLINK_MESSAGE_INFO_DEBUG_VECT { \
"DEBUG_VECT", \
5, \
{ { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_debug_vect_t, time_usec) }, \
{ "x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_debug_vect_t, x) }, \
{ "y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_debug_vect_t, y) }, \
{ "z", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_debug_vect_t, z) }, \
{ "name", NULL, MAVLINK_TYPE_CHAR, 10, 20, offsetof(mavlink_debug_vect_t, name) }, \
} \
}
 
 
/**
* @brief Pack a debug_vect message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param name Name
* @param time_usec Timestamp
* @param x x
* @param y y
* @param z z
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_debug_vect_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
const char *name, uint64_t time_usec, float x, float y, float z)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[30];
_mav_put_uint64_t(buf, 0, time_usec);
_mav_put_float(buf, 8, x);
_mav_put_float(buf, 12, y);
_mav_put_float(buf, 16, z);
_mav_put_char_array(buf, 20, name, 10);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 30);
#else
mavlink_debug_vect_t packet;
packet.time_usec = time_usec;
packet.x = x;
packet.y = y;
packet.z = z;
mav_array_memcpy(packet.name, name, sizeof(char)*10);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 30);
#endif
 
msg->msgid = MAVLINK_MSG_ID_DEBUG_VECT;
return mavlink_finalize_message(msg, system_id, component_id, 30, 49);
}
 
/**
* @brief Pack a debug_vect message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param name Name
* @param time_usec Timestamp
* @param x x
* @param y y
* @param z z
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_debug_vect_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
const char *name,uint64_t time_usec,float x,float y,float z)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[30];
_mav_put_uint64_t(buf, 0, time_usec);
_mav_put_float(buf, 8, x);
_mav_put_float(buf, 12, y);
_mav_put_float(buf, 16, z);
_mav_put_char_array(buf, 20, name, 10);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 30);
#else
mavlink_debug_vect_t packet;
packet.time_usec = time_usec;
packet.x = x;
packet.y = y;
packet.z = z;
mav_array_memcpy(packet.name, name, sizeof(char)*10);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 30);
#endif
 
msg->msgid = MAVLINK_MSG_ID_DEBUG_VECT;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 30, 49);
}
 
/**
* @brief Encode a debug_vect struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param debug_vect C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_debug_vect_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_debug_vect_t* debug_vect)
{
return mavlink_msg_debug_vect_pack(system_id, component_id, msg, debug_vect->name, debug_vect->time_usec, debug_vect->x, debug_vect->y, debug_vect->z);
}
 
/**
* @brief Send a debug_vect message
* @param chan MAVLink channel to send the message
*
* @param name Name
* @param time_usec Timestamp
* @param x x
* @param y y
* @param z z
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_debug_vect_send(mavlink_channel_t chan, const char *name, uint64_t time_usec, float x, float y, float z)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[30];
_mav_put_uint64_t(buf, 0, time_usec);
_mav_put_float(buf, 8, x);
_mav_put_float(buf, 12, y);
_mav_put_float(buf, 16, z);
_mav_put_char_array(buf, 20, name, 10);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG_VECT, buf, 30, 49);
#else
mavlink_debug_vect_t packet;
packet.time_usec = time_usec;
packet.x = x;
packet.y = y;
packet.z = z;
mav_array_memcpy(packet.name, name, sizeof(char)*10);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG_VECT, (const char *)&packet, 30, 49);
#endif
}
 
#endif
 
// MESSAGE DEBUG_VECT UNPACKING
 
 
/**
* @brief Get field name from debug_vect message
*
* @return Name
*/
static inline uint16_t mavlink_msg_debug_vect_get_name(const mavlink_message_t* msg, char *name)
{
return _MAV_RETURN_char_array(msg, name, 10, 20);
}
 
/**
* @brief Get field time_usec from debug_vect message
*
* @return Timestamp
*/
static inline uint64_t mavlink_msg_debug_vect_get_time_usec(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint64_t(msg, 0);
}
 
/**
* @brief Get field x from debug_vect message
*
* @return x
*/
static inline float mavlink_msg_debug_vect_get_x(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 8);
}
 
/**
* @brief Get field y from debug_vect message
*
* @return y
*/
static inline float mavlink_msg_debug_vect_get_y(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 12);
}
 
/**
* @brief Get field z from debug_vect message
*
* @return z
*/
static inline float mavlink_msg_debug_vect_get_z(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 16);
}
 
/**
* @brief Decode a debug_vect message into a struct
*
* @param msg The message to decode
* @param debug_vect C-struct to decode the message contents into
*/
static inline void mavlink_msg_debug_vect_decode(const mavlink_message_t* msg, mavlink_debug_vect_t* debug_vect)
{
#if MAVLINK_NEED_BYTE_SWAP
debug_vect->time_usec = mavlink_msg_debug_vect_get_time_usec(msg);
debug_vect->x = mavlink_msg_debug_vect_get_x(msg);
debug_vect->y = mavlink_msg_debug_vect_get_y(msg);
debug_vect->z = mavlink_msg_debug_vect_get_z(msg);
mavlink_msg_debug_vect_get_name(msg, debug_vect->name);
#else
memcpy(debug_vect, _MAV_PAYLOAD(msg), 30);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v1.0/common/mavlink_msg_global_position_int.h
0,0 → 1,320
// MESSAGE GLOBAL_POSITION_INT PACKING
 
#define MAVLINK_MSG_ID_GLOBAL_POSITION_INT 33
 
typedef struct __mavlink_global_position_int_t
{
uint32_t time_boot_ms; ///< Timestamp (milliseconds since system boot)
int32_t lat; ///< Latitude, expressed as * 1E7
int32_t lon; ///< Longitude, expressed as * 1E7
int32_t alt; ///< Altitude in meters, expressed as * 1000 (millimeters), above MSL
int32_t relative_alt; ///< Altitude above ground in meters, expressed as * 1000 (millimeters)
int16_t vx; ///< Ground X Speed (Latitude), expressed as m/s * 100
int16_t vy; ///< Ground Y Speed (Longitude), expressed as m/s * 100
int16_t vz; ///< Ground Z Speed (Altitude), expressed as m/s * 100
uint16_t hdg; ///< Compass heading in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535
} mavlink_global_position_int_t;
 
#define MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN 28
#define MAVLINK_MSG_ID_33_LEN 28
 
 
 
#define MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_INT { \
"GLOBAL_POSITION_INT", \
9, \
{ { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_global_position_int_t, time_boot_ms) }, \
{ "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_global_position_int_t, lat) }, \
{ "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_global_position_int_t, lon) }, \
{ "alt", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_global_position_int_t, alt) }, \
{ "relative_alt", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_global_position_int_t, relative_alt) }, \
{ "vx", NULL, MAVLINK_TYPE_INT16_T, 0, 20, offsetof(mavlink_global_position_int_t, vx) }, \
{ "vy", NULL, MAVLINK_TYPE_INT16_T, 0, 22, offsetof(mavlink_global_position_int_t, vy) }, \
{ "vz", NULL, MAVLINK_TYPE_INT16_T, 0, 24, offsetof(mavlink_global_position_int_t, vz) }, \
{ "hdg", NULL, MAVLINK_TYPE_UINT16_T, 0, 26, offsetof(mavlink_global_position_int_t, hdg) }, \
} \
}
 
 
/**
* @brief Pack a global_position_int message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param time_boot_ms Timestamp (milliseconds since system boot)
* @param lat Latitude, expressed as * 1E7
* @param lon Longitude, expressed as * 1E7
* @param alt Altitude in meters, expressed as * 1000 (millimeters), above MSL
* @param relative_alt Altitude above ground in meters, expressed as * 1000 (millimeters)
* @param vx Ground X Speed (Latitude), expressed as m/s * 100
* @param vy Ground Y Speed (Longitude), expressed as m/s * 100
* @param vz Ground Z Speed (Altitude), expressed as m/s * 100
* @param hdg Compass heading in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_global_position_int_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint32_t time_boot_ms, int32_t lat, int32_t lon, int32_t alt, int32_t relative_alt, int16_t vx, int16_t vy, int16_t vz, uint16_t hdg)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[28];
_mav_put_uint32_t(buf, 0, time_boot_ms);
_mav_put_int32_t(buf, 4, lat);
_mav_put_int32_t(buf, 8, lon);
_mav_put_int32_t(buf, 12, alt);
_mav_put_int32_t(buf, 16, relative_alt);
_mav_put_int16_t(buf, 20, vx);
_mav_put_int16_t(buf, 22, vy);
_mav_put_int16_t(buf, 24, vz);
_mav_put_uint16_t(buf, 26, hdg);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 28);
#else
mavlink_global_position_int_t packet;
packet.time_boot_ms = time_boot_ms;
packet.lat = lat;
packet.lon = lon;
packet.alt = alt;
packet.relative_alt = relative_alt;
packet.vx = vx;
packet.vy = vy;
packet.vz = vz;
packet.hdg = hdg;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 28);
#endif
 
msg->msgid = MAVLINK_MSG_ID_GLOBAL_POSITION_INT;
return mavlink_finalize_message(msg, system_id, component_id, 28, 104);
}
 
/**
* @brief Pack a global_position_int message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param time_boot_ms Timestamp (milliseconds since system boot)
* @param lat Latitude, expressed as * 1E7
* @param lon Longitude, expressed as * 1E7
* @param alt Altitude in meters, expressed as * 1000 (millimeters), above MSL
* @param relative_alt Altitude above ground in meters, expressed as * 1000 (millimeters)
* @param vx Ground X Speed (Latitude), expressed as m/s * 100
* @param vy Ground Y Speed (Longitude), expressed as m/s * 100
* @param vz Ground Z Speed (Altitude), expressed as m/s * 100
* @param hdg Compass heading in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_global_position_int_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint32_t time_boot_ms,int32_t lat,int32_t lon,int32_t alt,int32_t relative_alt,int16_t vx,int16_t vy,int16_t vz,uint16_t hdg)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[28];
_mav_put_uint32_t(buf, 0, time_boot_ms);
_mav_put_int32_t(buf, 4, lat);
_mav_put_int32_t(buf, 8, lon);
_mav_put_int32_t(buf, 12, alt);
_mav_put_int32_t(buf, 16, relative_alt);
_mav_put_int16_t(buf, 20, vx);
_mav_put_int16_t(buf, 22, vy);
_mav_put_int16_t(buf, 24, vz);
_mav_put_uint16_t(buf, 26, hdg);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 28);
#else
mavlink_global_position_int_t packet;
packet.time_boot_ms = time_boot_ms;
packet.lat = lat;
packet.lon = lon;
packet.alt = alt;
packet.relative_alt = relative_alt;
packet.vx = vx;
packet.vy = vy;
packet.vz = vz;
packet.hdg = hdg;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 28);
#endif
 
msg->msgid = MAVLINK_MSG_ID_GLOBAL_POSITION_INT;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 28, 104);
}
 
/**
* @brief Encode a global_position_int struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param global_position_int C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_global_position_int_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_global_position_int_t* global_position_int)
{
return mavlink_msg_global_position_int_pack(system_id, component_id, msg, global_position_int->time_boot_ms, global_position_int->lat, global_position_int->lon, global_position_int->alt, global_position_int->relative_alt, global_position_int->vx, global_position_int->vy, global_position_int->vz, global_position_int->hdg);
}
 
/**
* @brief Send a global_position_int message
* @param chan MAVLink channel to send the message
*
* @param time_boot_ms Timestamp (milliseconds since system boot)
* @param lat Latitude, expressed as * 1E7
* @param lon Longitude, expressed as * 1E7
* @param alt Altitude in meters, expressed as * 1000 (millimeters), above MSL
* @param relative_alt Altitude above ground in meters, expressed as * 1000 (millimeters)
* @param vx Ground X Speed (Latitude), expressed as m/s * 100
* @param vy Ground Y Speed (Longitude), expressed as m/s * 100
* @param vz Ground Z Speed (Altitude), expressed as m/s * 100
* @param hdg Compass heading in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_global_position_int_send(mavlink_channel_t chan, uint32_t time_boot_ms, int32_t lat, int32_t lon, int32_t alt, int32_t relative_alt, int16_t vx, int16_t vy, int16_t vz, uint16_t hdg)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[28];
_mav_put_uint32_t(buf, 0, time_boot_ms);
_mav_put_int32_t(buf, 4, lat);
_mav_put_int32_t(buf, 8, lon);
_mav_put_int32_t(buf, 12, alt);
_mav_put_int32_t(buf, 16, relative_alt);
_mav_put_int16_t(buf, 20, vx);
_mav_put_int16_t(buf, 22, vy);
_mav_put_int16_t(buf, 24, vz);
_mav_put_uint16_t(buf, 26, hdg);
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT, buf, 28, 104);
#else
mavlink_global_position_int_t packet;
packet.time_boot_ms = time_boot_ms;
packet.lat = lat;
packet.lon = lon;
packet.alt = alt;
packet.relative_alt = relative_alt;
packet.vx = vx;
packet.vy = vy;
packet.vz = vz;
packet.hdg = hdg;
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT, (const char *)&packet, 28, 104);
#endif
}
 
#endif
 
// MESSAGE GLOBAL_POSITION_INT UNPACKING
 
 
/**
* @brief Get field time_boot_ms from global_position_int message
*
* @return Timestamp (milliseconds since system boot)
*/
static inline uint32_t mavlink_msg_global_position_int_get_time_boot_ms(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint32_t(msg, 0);
}
 
/**
* @brief Get field lat from global_position_int message
*
* @return Latitude, expressed as * 1E7
*/
static inline int32_t mavlink_msg_global_position_int_get_lat(const mavlink_message_t* msg)
{
return _MAV_RETURN_int32_t(msg, 4);
}
 
/**
* @brief Get field lon from global_position_int message
*
* @return Longitude, expressed as * 1E7
*/
static inline int32_t mavlink_msg_global_position_int_get_lon(const mavlink_message_t* msg)
{
return _MAV_RETURN_int32_t(msg, 8);
}
 
/**
* @brief Get field alt from global_position_int message
*
* @return Altitude in meters, expressed as * 1000 (millimeters), above MSL
*/
static inline int32_t mavlink_msg_global_position_int_get_alt(const mavlink_message_t* msg)
{
return _MAV_RETURN_int32_t(msg, 12);
}
 
/**
* @brief Get field relative_alt from global_position_int message
*
* @return Altitude above ground in meters, expressed as * 1000 (millimeters)
*/
static inline int32_t mavlink_msg_global_position_int_get_relative_alt(const mavlink_message_t* msg)
{
return _MAV_RETURN_int32_t(msg, 16);
}
 
/**
* @brief Get field vx from global_position_int message
*
* @return Ground X Speed (Latitude), expressed as m/s * 100
*/
static inline int16_t mavlink_msg_global_position_int_get_vx(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 20);
}
 
/**
* @brief Get field vy from global_position_int message
*
* @return Ground Y Speed (Longitude), expressed as m/s * 100
*/
static inline int16_t mavlink_msg_global_position_int_get_vy(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 22);
}
 
/**
* @brief Get field vz from global_position_int message
*
* @return Ground Z Speed (Altitude), expressed as m/s * 100
*/
static inline int16_t mavlink_msg_global_position_int_get_vz(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 24);
}
 
/**
* @brief Get field hdg from global_position_int message
*
* @return Compass heading in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535
*/
static inline uint16_t mavlink_msg_global_position_int_get_hdg(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 26);
}
 
/**
* @brief Decode a global_position_int message into a struct
*
* @param msg The message to decode
* @param global_position_int C-struct to decode the message contents into
*/
static inline void mavlink_msg_global_position_int_decode(const mavlink_message_t* msg, mavlink_global_position_int_t* global_position_int)
{
#if MAVLINK_NEED_BYTE_SWAP
global_position_int->time_boot_ms = mavlink_msg_global_position_int_get_time_boot_ms(msg);
global_position_int->lat = mavlink_msg_global_position_int_get_lat(msg);
global_position_int->lon = mavlink_msg_global_position_int_get_lon(msg);
global_position_int->alt = mavlink_msg_global_position_int_get_alt(msg);
global_position_int->relative_alt = mavlink_msg_global_position_int_get_relative_alt(msg);
global_position_int->vx = mavlink_msg_global_position_int_get_vx(msg);
global_position_int->vy = mavlink_msg_global_position_int_get_vy(msg);
global_position_int->vz = mavlink_msg_global_position_int_get_vz(msg);
global_position_int->hdg = mavlink_msg_global_position_int_get_hdg(msg);
#else
memcpy(global_position_int, _MAV_PAYLOAD(msg), 28);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v1.0/common/mavlink_msg_global_position_setpoint_int.h
0,0 → 1,232
// MESSAGE GLOBAL_POSITION_SETPOINT_INT PACKING
 
#define MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_INT 52
 
typedef struct __mavlink_global_position_setpoint_int_t
{
int32_t latitude; ///< WGS84 Latitude position in degrees * 1E7
int32_t longitude; ///< WGS84 Longitude position in degrees * 1E7
int32_t altitude; ///< WGS84 Altitude in meters * 1000 (positive for up)
int16_t yaw; ///< Desired yaw angle in degrees * 100
uint8_t coordinate_frame; ///< Coordinate frame - valid values are only MAV_FRAME_GLOBAL or MAV_FRAME_GLOBAL_RELATIVE_ALT
} mavlink_global_position_setpoint_int_t;
 
#define MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_INT_LEN 15
#define MAVLINK_MSG_ID_52_LEN 15
 
 
 
#define MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_SETPOINT_INT { \
"GLOBAL_POSITION_SETPOINT_INT", \
5, \
{ { "latitude", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_global_position_setpoint_int_t, latitude) }, \
{ "longitude", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_global_position_setpoint_int_t, longitude) }, \
{ "altitude", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_global_position_setpoint_int_t, altitude) }, \
{ "yaw", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_global_position_setpoint_int_t, yaw) }, \
{ "coordinate_frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 14, offsetof(mavlink_global_position_setpoint_int_t, coordinate_frame) }, \
} \
}
 
 
/**
* @brief Pack a global_position_setpoint_int message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param coordinate_frame Coordinate frame - valid values are only MAV_FRAME_GLOBAL or MAV_FRAME_GLOBAL_RELATIVE_ALT
* @param latitude WGS84 Latitude position in degrees * 1E7
* @param longitude WGS84 Longitude position in degrees * 1E7
* @param altitude WGS84 Altitude in meters * 1000 (positive for up)
* @param yaw Desired yaw angle in degrees * 100
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_global_position_setpoint_int_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t coordinate_frame, int32_t latitude, int32_t longitude, int32_t altitude, int16_t yaw)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[15];
_mav_put_int32_t(buf, 0, latitude);
_mav_put_int32_t(buf, 4, longitude);
_mav_put_int32_t(buf, 8, altitude);
_mav_put_int16_t(buf, 12, yaw);
_mav_put_uint8_t(buf, 14, coordinate_frame);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 15);
#else
mavlink_global_position_setpoint_int_t packet;
packet.latitude = latitude;
packet.longitude = longitude;
packet.altitude = altitude;
packet.yaw = yaw;
packet.coordinate_frame = coordinate_frame;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 15);
#endif
 
msg->msgid = MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_INT;
return mavlink_finalize_message(msg, system_id, component_id, 15, 141);
}
 
/**
* @brief Pack a global_position_setpoint_int message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param coordinate_frame Coordinate frame - valid values are only MAV_FRAME_GLOBAL or MAV_FRAME_GLOBAL_RELATIVE_ALT
* @param latitude WGS84 Latitude position in degrees * 1E7
* @param longitude WGS84 Longitude position in degrees * 1E7
* @param altitude WGS84 Altitude in meters * 1000 (positive for up)
* @param yaw Desired yaw angle in degrees * 100
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_global_position_setpoint_int_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint8_t coordinate_frame,int32_t latitude,int32_t longitude,int32_t altitude,int16_t yaw)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[15];
_mav_put_int32_t(buf, 0, latitude);
_mav_put_int32_t(buf, 4, longitude);
_mav_put_int32_t(buf, 8, altitude);
_mav_put_int16_t(buf, 12, yaw);
_mav_put_uint8_t(buf, 14, coordinate_frame);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 15);
#else
mavlink_global_position_setpoint_int_t packet;
packet.latitude = latitude;
packet.longitude = longitude;
packet.altitude = altitude;
packet.yaw = yaw;
packet.coordinate_frame = coordinate_frame;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 15);
#endif
 
msg->msgid = MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_INT;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 15, 141);
}
 
/**
* @brief Encode a global_position_setpoint_int struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param global_position_setpoint_int C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_global_position_setpoint_int_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_global_position_setpoint_int_t* global_position_setpoint_int)
{
return mavlink_msg_global_position_setpoint_int_pack(system_id, component_id, msg, global_position_setpoint_int->coordinate_frame, global_position_setpoint_int->latitude, global_position_setpoint_int->longitude, global_position_setpoint_int->altitude, global_position_setpoint_int->yaw);
}
 
/**
* @brief Send a global_position_setpoint_int message
* @param chan MAVLink channel to send the message
*
* @param coordinate_frame Coordinate frame - valid values are only MAV_FRAME_GLOBAL or MAV_FRAME_GLOBAL_RELATIVE_ALT
* @param latitude WGS84 Latitude position in degrees * 1E7
* @param longitude WGS84 Longitude position in degrees * 1E7
* @param altitude WGS84 Altitude in meters * 1000 (positive for up)
* @param yaw Desired yaw angle in degrees * 100
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_global_position_setpoint_int_send(mavlink_channel_t chan, uint8_t coordinate_frame, int32_t latitude, int32_t longitude, int32_t altitude, int16_t yaw)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[15];
_mav_put_int32_t(buf, 0, latitude);
_mav_put_int32_t(buf, 4, longitude);
_mav_put_int32_t(buf, 8, altitude);
_mav_put_int16_t(buf, 12, yaw);
_mav_put_uint8_t(buf, 14, coordinate_frame);
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_INT, buf, 15, 141);
#else
mavlink_global_position_setpoint_int_t packet;
packet.latitude = latitude;
packet.longitude = longitude;
packet.altitude = altitude;
packet.yaw = yaw;
packet.coordinate_frame = coordinate_frame;
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_SETPOINT_INT, (const char *)&packet, 15, 141);
#endif
}
 
#endif
 
// MESSAGE GLOBAL_POSITION_SETPOINT_INT UNPACKING
 
 
/**
* @brief Get field coordinate_frame from global_position_setpoint_int message
*
* @return Coordinate frame - valid values are only MAV_FRAME_GLOBAL or MAV_FRAME_GLOBAL_RELATIVE_ALT
*/
static inline uint8_t mavlink_msg_global_position_setpoint_int_get_coordinate_frame(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 14);
}
 
/**
* @brief Get field latitude from global_position_setpoint_int message
*
* @return WGS84 Latitude position in degrees * 1E7
*/
static inline int32_t mavlink_msg_global_position_setpoint_int_get_latitude(const mavlink_message_t* msg)
{
return _MAV_RETURN_int32_t(msg, 0);
}
 
/**
* @brief Get field longitude from global_position_setpoint_int message
*
* @return WGS84 Longitude position in degrees * 1E7
*/
static inline int32_t mavlink_msg_global_position_setpoint_int_get_longitude(const mavlink_message_t* msg)
{
return _MAV_RETURN_int32_t(msg, 4);
}
 
/**
* @brief Get field altitude from global_position_setpoint_int message
*
* @return WGS84 Altitude in meters * 1000 (positive for up)
*/
static inline int32_t mavlink_msg_global_position_setpoint_int_get_altitude(const mavlink_message_t* msg)
{
return _MAV_RETURN_int32_t(msg, 8);
}
 
/**
* @brief Get field yaw from global_position_setpoint_int message
*
* @return Desired yaw angle in degrees * 100
*/
static inline int16_t mavlink_msg_global_position_setpoint_int_get_yaw(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 12);
}
 
/**
* @brief Decode a global_position_setpoint_int message into a struct
*
* @param msg The message to decode
* @param global_position_setpoint_int C-struct to decode the message contents into
*/
static inline void mavlink_msg_global_position_setpoint_int_decode(const mavlink_message_t* msg, mavlink_global_position_setpoint_int_t* global_position_setpoint_int)
{
#if MAVLINK_NEED_BYTE_SWAP
global_position_setpoint_int->latitude = mavlink_msg_global_position_setpoint_int_get_latitude(msg);
global_position_setpoint_int->longitude = mavlink_msg_global_position_setpoint_int_get_longitude(msg);
global_position_setpoint_int->altitude = mavlink_msg_global_position_setpoint_int_get_altitude(msg);
global_position_setpoint_int->yaw = mavlink_msg_global_position_setpoint_int_get_yaw(msg);
global_position_setpoint_int->coordinate_frame = mavlink_msg_global_position_setpoint_int_get_coordinate_frame(msg);
#else
memcpy(global_position_setpoint_int, _MAV_PAYLOAD(msg), 15);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v1.0/common/mavlink_msg_global_vision_position_estimate.h
0,0 → 1,276
// MESSAGE GLOBAL_VISION_POSITION_ESTIMATE PACKING
 
#define MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE 101
 
typedef struct __mavlink_global_vision_position_estimate_t
{
uint64_t usec; ///< Timestamp (milliseconds)
float x; ///< Global X position
float y; ///< Global Y position
float z; ///< Global Z position
float roll; ///< Roll angle in rad
float pitch; ///< Pitch angle in rad
float yaw; ///< Yaw angle in rad
} mavlink_global_vision_position_estimate_t;
 
#define MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN 32
#define MAVLINK_MSG_ID_101_LEN 32
 
 
 
#define MAVLINK_MESSAGE_INFO_GLOBAL_VISION_POSITION_ESTIMATE { \
"GLOBAL_VISION_POSITION_ESTIMATE", \
7, \
{ { "usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_global_vision_position_estimate_t, usec) }, \
{ "x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_global_vision_position_estimate_t, x) }, \
{ "y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_global_vision_position_estimate_t, y) }, \
{ "z", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_global_vision_position_estimate_t, z) }, \
{ "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_global_vision_position_estimate_t, roll) }, \
{ "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_global_vision_position_estimate_t, pitch) }, \
{ "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_global_vision_position_estimate_t, yaw) }, \
} \
}
 
 
/**
* @brief Pack a global_vision_position_estimate message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param usec Timestamp (milliseconds)
* @param x Global X position
* @param y Global Y position
* @param z Global Z position
* @param roll Roll angle in rad
* @param pitch Pitch angle in rad
* @param yaw Yaw angle in rad
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_global_vision_position_estimate_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint64_t usec, float x, float y, float z, float roll, float pitch, float yaw)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[32];
_mav_put_uint64_t(buf, 0, usec);
_mav_put_float(buf, 8, x);
_mav_put_float(buf, 12, y);
_mav_put_float(buf, 16, z);
_mav_put_float(buf, 20, roll);
_mav_put_float(buf, 24, pitch);
_mav_put_float(buf, 28, yaw);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 32);
#else
mavlink_global_vision_position_estimate_t packet;
packet.usec = usec;
packet.x = x;
packet.y = y;
packet.z = z;
packet.roll = roll;
packet.pitch = pitch;
packet.yaw = yaw;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 32);
#endif
 
msg->msgid = MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE;
return mavlink_finalize_message(msg, system_id, component_id, 32, 102);
}
 
/**
* @brief Pack a global_vision_position_estimate message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param usec Timestamp (milliseconds)
* @param x Global X position
* @param y Global Y position
* @param z Global Z position
* @param roll Roll angle in rad
* @param pitch Pitch angle in rad
* @param yaw Yaw angle in rad
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_global_vision_position_estimate_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint64_t usec,float x,float y,float z,float roll,float pitch,float yaw)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[32];
_mav_put_uint64_t(buf, 0, usec);
_mav_put_float(buf, 8, x);
_mav_put_float(buf, 12, y);
_mav_put_float(buf, 16, z);
_mav_put_float(buf, 20, roll);
_mav_put_float(buf, 24, pitch);
_mav_put_float(buf, 28, yaw);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 32);
#else
mavlink_global_vision_position_estimate_t packet;
packet.usec = usec;
packet.x = x;
packet.y = y;
packet.z = z;
packet.roll = roll;
packet.pitch = pitch;
packet.yaw = yaw;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 32);
#endif
 
msg->msgid = MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 32, 102);
}
 
/**
* @brief Encode a global_vision_position_estimate struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param global_vision_position_estimate C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_global_vision_position_estimate_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_global_vision_position_estimate_t* global_vision_position_estimate)
{
return mavlink_msg_global_vision_position_estimate_pack(system_id, component_id, msg, global_vision_position_estimate->usec, global_vision_position_estimate->x, global_vision_position_estimate->y, global_vision_position_estimate->z, global_vision_position_estimate->roll, global_vision_position_estimate->pitch, global_vision_position_estimate->yaw);
}
 
/**
* @brief Send a global_vision_position_estimate message
* @param chan MAVLink channel to send the message
*
* @param usec Timestamp (milliseconds)
* @param x Global X position
* @param y Global Y position
* @param z Global Z position
* @param roll Roll angle in rad
* @param pitch Pitch angle in rad
* @param yaw Yaw angle in rad
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_global_vision_position_estimate_send(mavlink_channel_t chan, uint64_t usec, float x, float y, float z, float roll, float pitch, float yaw)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[32];
_mav_put_uint64_t(buf, 0, usec);
_mav_put_float(buf, 8, x);
_mav_put_float(buf, 12, y);
_mav_put_float(buf, 16, z);
_mav_put_float(buf, 20, roll);
_mav_put_float(buf, 24, pitch);
_mav_put_float(buf, 28, yaw);
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE, buf, 32, 102);
#else
mavlink_global_vision_position_estimate_t packet;
packet.usec = usec;
packet.x = x;
packet.y = y;
packet.z = z;
packet.roll = roll;
packet.pitch = pitch;
packet.yaw = yaw;
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE, (const char *)&packet, 32, 102);
#endif
}
 
#endif
 
// MESSAGE GLOBAL_VISION_POSITION_ESTIMATE UNPACKING
 
 
/**
* @brief Get field usec from global_vision_position_estimate message
*
* @return Timestamp (milliseconds)
*/
static inline uint64_t mavlink_msg_global_vision_position_estimate_get_usec(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint64_t(msg, 0);
}
 
/**
* @brief Get field x from global_vision_position_estimate message
*
* @return Global X position
*/
static inline float mavlink_msg_global_vision_position_estimate_get_x(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 8);
}
 
/**
* @brief Get field y from global_vision_position_estimate message
*
* @return Global Y position
*/
static inline float mavlink_msg_global_vision_position_estimate_get_y(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 12);
}
 
/**
* @brief Get field z from global_vision_position_estimate message
*
* @return Global Z position
*/
static inline float mavlink_msg_global_vision_position_estimate_get_z(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 16);
}
 
/**
* @brief Get field roll from global_vision_position_estimate message
*
* @return Roll angle in rad
*/
static inline float mavlink_msg_global_vision_position_estimate_get_roll(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 20);
}
 
/**
* @brief Get field pitch from global_vision_position_estimate message
*
* @return Pitch angle in rad
*/
static inline float mavlink_msg_global_vision_position_estimate_get_pitch(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 24);
}
 
/**
* @brief Get field yaw from global_vision_position_estimate message
*
* @return Yaw angle in rad
*/
static inline float mavlink_msg_global_vision_position_estimate_get_yaw(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 28);
}
 
/**
* @brief Decode a global_vision_position_estimate message into a struct
*
* @param msg The message to decode
* @param global_vision_position_estimate C-struct to decode the message contents into
*/
static inline void mavlink_msg_global_vision_position_estimate_decode(const mavlink_message_t* msg, mavlink_global_vision_position_estimate_t* global_vision_position_estimate)
{
#if MAVLINK_NEED_BYTE_SWAP
global_vision_position_estimate->usec = mavlink_msg_global_vision_position_estimate_get_usec(msg);
global_vision_position_estimate->x = mavlink_msg_global_vision_position_estimate_get_x(msg);
global_vision_position_estimate->y = mavlink_msg_global_vision_position_estimate_get_y(msg);
global_vision_position_estimate->z = mavlink_msg_global_vision_position_estimate_get_z(msg);
global_vision_position_estimate->roll = mavlink_msg_global_vision_position_estimate_get_roll(msg);
global_vision_position_estimate->pitch = mavlink_msg_global_vision_position_estimate_get_pitch(msg);
global_vision_position_estimate->yaw = mavlink_msg_global_vision_position_estimate_get_yaw(msg);
#else
memcpy(global_vision_position_estimate, _MAV_PAYLOAD(msg), 32);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v1.0/common/mavlink_msg_gps_global_origin.h
0,0 → 1,188
// MESSAGE GPS_GLOBAL_ORIGIN PACKING
 
#define MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN 49
 
typedef struct __mavlink_gps_global_origin_t
{
int32_t latitude; ///< Latitude (WGS84), expressed as * 1E7
int32_t longitude; ///< Longitude (WGS84), expressed as * 1E7
int32_t altitude; ///< Altitude(WGS84), expressed as * 1000
} mavlink_gps_global_origin_t;
 
#define MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN 12
#define MAVLINK_MSG_ID_49_LEN 12
 
 
 
#define MAVLINK_MESSAGE_INFO_GPS_GLOBAL_ORIGIN { \
"GPS_GLOBAL_ORIGIN", \
3, \
{ { "latitude", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_gps_global_origin_t, latitude) }, \
{ "longitude", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_gps_global_origin_t, longitude) }, \
{ "altitude", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_gps_global_origin_t, altitude) }, \
} \
}
 
 
/**
* @brief Pack a gps_global_origin message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param latitude Latitude (WGS84), expressed as * 1E7
* @param longitude Longitude (WGS84), expressed as * 1E7
* @param altitude Altitude(WGS84), expressed as * 1000
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_gps_global_origin_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
int32_t latitude, int32_t longitude, int32_t altitude)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[12];
_mav_put_int32_t(buf, 0, latitude);
_mav_put_int32_t(buf, 4, longitude);
_mav_put_int32_t(buf, 8, altitude);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 12);
#else
mavlink_gps_global_origin_t packet;
packet.latitude = latitude;
packet.longitude = longitude;
packet.altitude = altitude;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 12);
#endif
 
msg->msgid = MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN;
return mavlink_finalize_message(msg, system_id, component_id, 12, 39);
}
 
/**
* @brief Pack a gps_global_origin message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param latitude Latitude (WGS84), expressed as * 1E7
* @param longitude Longitude (WGS84), expressed as * 1E7
* @param altitude Altitude(WGS84), expressed as * 1000
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_gps_global_origin_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
int32_t latitude,int32_t longitude,int32_t altitude)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[12];
_mav_put_int32_t(buf, 0, latitude);
_mav_put_int32_t(buf, 4, longitude);
_mav_put_int32_t(buf, 8, altitude);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 12);
#else
mavlink_gps_global_origin_t packet;
packet.latitude = latitude;
packet.longitude = longitude;
packet.altitude = altitude;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 12);
#endif
 
msg->msgid = MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 12, 39);
}
 
/**
* @brief Encode a gps_global_origin struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param gps_global_origin C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_gps_global_origin_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gps_global_origin_t* gps_global_origin)
{
return mavlink_msg_gps_global_origin_pack(system_id, component_id, msg, gps_global_origin->latitude, gps_global_origin->longitude, gps_global_origin->altitude);
}
 
/**
* @brief Send a gps_global_origin message
* @param chan MAVLink channel to send the message
*
* @param latitude Latitude (WGS84), expressed as * 1E7
* @param longitude Longitude (WGS84), expressed as * 1E7
* @param altitude Altitude(WGS84), expressed as * 1000
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_gps_global_origin_send(mavlink_channel_t chan, int32_t latitude, int32_t longitude, int32_t altitude)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[12];
_mav_put_int32_t(buf, 0, latitude);
_mav_put_int32_t(buf, 4, longitude);
_mav_put_int32_t(buf, 8, altitude);
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN, buf, 12, 39);
#else
mavlink_gps_global_origin_t packet;
packet.latitude = latitude;
packet.longitude = longitude;
packet.altitude = altitude;
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN, (const char *)&packet, 12, 39);
#endif
}
 
#endif
 
// MESSAGE GPS_GLOBAL_ORIGIN UNPACKING
 
 
/**
* @brief Get field latitude from gps_global_origin message
*
* @return Latitude (WGS84), expressed as * 1E7
*/
static inline int32_t mavlink_msg_gps_global_origin_get_latitude(const mavlink_message_t* msg)
{
return _MAV_RETURN_int32_t(msg, 0);
}
 
/**
* @brief Get field longitude from gps_global_origin message
*
* @return Longitude (WGS84), expressed as * 1E7
*/
static inline int32_t mavlink_msg_gps_global_origin_get_longitude(const mavlink_message_t* msg)
{
return _MAV_RETURN_int32_t(msg, 4);
}
 
/**
* @brief Get field altitude from gps_global_origin message
*
* @return Altitude(WGS84), expressed as * 1000
*/
static inline int32_t mavlink_msg_gps_global_origin_get_altitude(const mavlink_message_t* msg)
{
return _MAV_RETURN_int32_t(msg, 8);
}
 
/**
* @brief Decode a gps_global_origin message into a struct
*
* @param msg The message to decode
* @param gps_global_origin C-struct to decode the message contents into
*/
static inline void mavlink_msg_gps_global_origin_decode(const mavlink_message_t* msg, mavlink_gps_global_origin_t* gps_global_origin)
{
#if MAVLINK_NEED_BYTE_SWAP
gps_global_origin->latitude = mavlink_msg_gps_global_origin_get_latitude(msg);
gps_global_origin->longitude = mavlink_msg_gps_global_origin_get_longitude(msg);
gps_global_origin->altitude = mavlink_msg_gps_global_origin_get_altitude(msg);
#else
memcpy(gps_global_origin, _MAV_PAYLOAD(msg), 12);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v1.0/common/mavlink_msg_gps_raw_int.h
0,0 → 1,342
// MESSAGE GPS_RAW_INT PACKING
 
#define MAVLINK_MSG_ID_GPS_RAW_INT 24
 
typedef struct __mavlink_gps_raw_int_t
{
uint64_t time_usec; ///< Timestamp (microseconds since UNIX epoch or microseconds since system boot)
int32_t lat; ///< Latitude in 1E7 degrees
int32_t lon; ///< Longitude in 1E7 degrees
int32_t alt; ///< Altitude in 1E3 meters (millimeters) above MSL
uint16_t eph; ///< GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535
uint16_t epv; ///< GPS VDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535
uint16_t vel; ///< GPS ground speed (m/s * 100). If unknown, set to: 65535
uint16_t cog; ///< Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535
uint8_t fix_type; ///< 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix.
uint8_t satellites_visible; ///< Number of satellites visible. If unknown, set to 255
} mavlink_gps_raw_int_t;
 
#define MAVLINK_MSG_ID_GPS_RAW_INT_LEN 30
#define MAVLINK_MSG_ID_24_LEN 30
 
 
 
#define MAVLINK_MESSAGE_INFO_GPS_RAW_INT { \
"GPS_RAW_INT", \
10, \
{ { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_gps_raw_int_t, time_usec) }, \
{ "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_gps_raw_int_t, lat) }, \
{ "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_gps_raw_int_t, lon) }, \
{ "alt", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_gps_raw_int_t, alt) }, \
{ "eph", NULL, MAVLINK_TYPE_UINT16_T, 0, 20, offsetof(mavlink_gps_raw_int_t, eph) }, \
{ "epv", NULL, MAVLINK_TYPE_UINT16_T, 0, 22, offsetof(mavlink_gps_raw_int_t, epv) }, \
{ "vel", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_gps_raw_int_t, vel) }, \
{ "cog", NULL, MAVLINK_TYPE_UINT16_T, 0, 26, offsetof(mavlink_gps_raw_int_t, cog) }, \
{ "fix_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 28, offsetof(mavlink_gps_raw_int_t, fix_type) }, \
{ "satellites_visible", NULL, MAVLINK_TYPE_UINT8_T, 0, 29, offsetof(mavlink_gps_raw_int_t, satellites_visible) }, \
} \
}
 
 
/**
* @brief Pack a gps_raw_int message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
* @param fix_type 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix.
* @param lat Latitude in 1E7 degrees
* @param lon Longitude in 1E7 degrees
* @param alt Altitude in 1E3 meters (millimeters) above MSL
* @param eph GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535
* @param epv GPS VDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535
* @param vel GPS ground speed (m/s * 100). If unknown, set to: 65535
* @param cog Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535
* @param satellites_visible Number of satellites visible. If unknown, set to 255
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_gps_raw_int_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint64_t time_usec, uint8_t fix_type, int32_t lat, int32_t lon, int32_t alt, uint16_t eph, uint16_t epv, uint16_t vel, uint16_t cog, uint8_t satellites_visible)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[30];
_mav_put_uint64_t(buf, 0, time_usec);
_mav_put_int32_t(buf, 8, lat);
_mav_put_int32_t(buf, 12, lon);
_mav_put_int32_t(buf, 16, alt);
_mav_put_uint16_t(buf, 20, eph);
_mav_put_uint16_t(buf, 22, epv);
_mav_put_uint16_t(buf, 24, vel);
_mav_put_uint16_t(buf, 26, cog);
_mav_put_uint8_t(buf, 28, fix_type);
_mav_put_uint8_t(buf, 29, satellites_visible);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 30);
#else
mavlink_gps_raw_int_t packet;
packet.time_usec = time_usec;
packet.lat = lat;
packet.lon = lon;
packet.alt = alt;
packet.eph = eph;
packet.epv = epv;
packet.vel = vel;
packet.cog = cog;
packet.fix_type = fix_type;
packet.satellites_visible = satellites_visible;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 30);
#endif
 
msg->msgid = MAVLINK_MSG_ID_GPS_RAW_INT;
return mavlink_finalize_message(msg, system_id, component_id, 30, 24);
}
 
/**
* @brief Pack a gps_raw_int message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
* @param fix_type 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix.
* @param lat Latitude in 1E7 degrees
* @param lon Longitude in 1E7 degrees
* @param alt Altitude in 1E3 meters (millimeters) above MSL
* @param eph GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535
* @param epv GPS VDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535
* @param vel GPS ground speed (m/s * 100). If unknown, set to: 65535
* @param cog Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535
* @param satellites_visible Number of satellites visible. If unknown, set to 255
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_gps_raw_int_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint64_t time_usec,uint8_t fix_type,int32_t lat,int32_t lon,int32_t alt,uint16_t eph,uint16_t epv,uint16_t vel,uint16_t cog,uint8_t satellites_visible)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[30];
_mav_put_uint64_t(buf, 0, time_usec);
_mav_put_int32_t(buf, 8, lat);
_mav_put_int32_t(buf, 12, lon);
_mav_put_int32_t(buf, 16, alt);
_mav_put_uint16_t(buf, 20, eph);
_mav_put_uint16_t(buf, 22, epv);
_mav_put_uint16_t(buf, 24, vel);
_mav_put_uint16_t(buf, 26, cog);
_mav_put_uint8_t(buf, 28, fix_type);
_mav_put_uint8_t(buf, 29, satellites_visible);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 30);
#else
mavlink_gps_raw_int_t packet;
packet.time_usec = time_usec;
packet.lat = lat;
packet.lon = lon;
packet.alt = alt;
packet.eph = eph;
packet.epv = epv;
packet.vel = vel;
packet.cog = cog;
packet.fix_type = fix_type;
packet.satellites_visible = satellites_visible;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 30);
#endif
 
msg->msgid = MAVLINK_MSG_ID_GPS_RAW_INT;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 30, 24);
}
 
/**
* @brief Encode a gps_raw_int struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param gps_raw_int C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_gps_raw_int_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gps_raw_int_t* gps_raw_int)
{
return mavlink_msg_gps_raw_int_pack(system_id, component_id, msg, gps_raw_int->time_usec, gps_raw_int->fix_type, gps_raw_int->lat, gps_raw_int->lon, gps_raw_int->alt, gps_raw_int->eph, gps_raw_int->epv, gps_raw_int->vel, gps_raw_int->cog, gps_raw_int->satellites_visible);
}
 
/**
* @brief Send a gps_raw_int message
* @param chan MAVLink channel to send the message
*
* @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
* @param fix_type 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix.
* @param lat Latitude in 1E7 degrees
* @param lon Longitude in 1E7 degrees
* @param alt Altitude in 1E3 meters (millimeters) above MSL
* @param eph GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535
* @param epv GPS VDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535
* @param vel GPS ground speed (m/s * 100). If unknown, set to: 65535
* @param cog Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535
* @param satellites_visible Number of satellites visible. If unknown, set to 255
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_gps_raw_int_send(mavlink_channel_t chan, uint64_t time_usec, uint8_t fix_type, int32_t lat, int32_t lon, int32_t alt, uint16_t eph, uint16_t epv, uint16_t vel, uint16_t cog, uint8_t satellites_visible)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[30];
_mav_put_uint64_t(buf, 0, time_usec);
_mav_put_int32_t(buf, 8, lat);
_mav_put_int32_t(buf, 12, lon);
_mav_put_int32_t(buf, 16, alt);
_mav_put_uint16_t(buf, 20, eph);
_mav_put_uint16_t(buf, 22, epv);
_mav_put_uint16_t(buf, 24, vel);
_mav_put_uint16_t(buf, 26, cog);
_mav_put_uint8_t(buf, 28, fix_type);
_mav_put_uint8_t(buf, 29, satellites_visible);
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RAW_INT, buf, 30, 24);
#else
mavlink_gps_raw_int_t packet;
packet.time_usec = time_usec;
packet.lat = lat;
packet.lon = lon;
packet.alt = alt;
packet.eph = eph;
packet.epv = epv;
packet.vel = vel;
packet.cog = cog;
packet.fix_type = fix_type;
packet.satellites_visible = satellites_visible;
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RAW_INT, (const char *)&packet, 30, 24);
#endif
}
 
#endif
 
// MESSAGE GPS_RAW_INT UNPACKING
 
 
/**
* @brief Get field time_usec from gps_raw_int message
*
* @return Timestamp (microseconds since UNIX epoch or microseconds since system boot)
*/
static inline uint64_t mavlink_msg_gps_raw_int_get_time_usec(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint64_t(msg, 0);
}
 
/**
* @brief Get field fix_type from gps_raw_int message
*
* @return 0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix.
*/
static inline uint8_t mavlink_msg_gps_raw_int_get_fix_type(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 28);
}
 
/**
* @brief Get field lat from gps_raw_int message
*
* @return Latitude in 1E7 degrees
*/
static inline int32_t mavlink_msg_gps_raw_int_get_lat(const mavlink_message_t* msg)
{
return _MAV_RETURN_int32_t(msg, 8);
}
 
/**
* @brief Get field lon from gps_raw_int message
*
* @return Longitude in 1E7 degrees
*/
static inline int32_t mavlink_msg_gps_raw_int_get_lon(const mavlink_message_t* msg)
{
return _MAV_RETURN_int32_t(msg, 12);
}
 
/**
* @brief Get field alt from gps_raw_int message
*
* @return Altitude in 1E3 meters (millimeters) above MSL
*/
static inline int32_t mavlink_msg_gps_raw_int_get_alt(const mavlink_message_t* msg)
{
return _MAV_RETURN_int32_t(msg, 16);
}
 
/**
* @brief Get field eph from gps_raw_int message
*
* @return GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535
*/
static inline uint16_t mavlink_msg_gps_raw_int_get_eph(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 20);
}
 
/**
* @brief Get field epv from gps_raw_int message
*
* @return GPS VDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535
*/
static inline uint16_t mavlink_msg_gps_raw_int_get_epv(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 22);
}
 
/**
* @brief Get field vel from gps_raw_int message
*
* @return GPS ground speed (m/s * 100). If unknown, set to: 65535
*/
static inline uint16_t mavlink_msg_gps_raw_int_get_vel(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 24);
}
 
/**
* @brief Get field cog from gps_raw_int message
*
* @return Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535
*/
static inline uint16_t mavlink_msg_gps_raw_int_get_cog(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 26);
}
 
/**
* @brief Get field satellites_visible from gps_raw_int message
*
* @return Number of satellites visible. If unknown, set to 255
*/
static inline uint8_t mavlink_msg_gps_raw_int_get_satellites_visible(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 29);
}
 
/**
* @brief Decode a gps_raw_int message into a struct
*
* @param msg The message to decode
* @param gps_raw_int C-struct to decode the message contents into
*/
static inline void mavlink_msg_gps_raw_int_decode(const mavlink_message_t* msg, mavlink_gps_raw_int_t* gps_raw_int)
{
#if MAVLINK_NEED_BYTE_SWAP
gps_raw_int->time_usec = mavlink_msg_gps_raw_int_get_time_usec(msg);
gps_raw_int->lat = mavlink_msg_gps_raw_int_get_lat(msg);
gps_raw_int->lon = mavlink_msg_gps_raw_int_get_lon(msg);
gps_raw_int->alt = mavlink_msg_gps_raw_int_get_alt(msg);
gps_raw_int->eph = mavlink_msg_gps_raw_int_get_eph(msg);
gps_raw_int->epv = mavlink_msg_gps_raw_int_get_epv(msg);
gps_raw_int->vel = mavlink_msg_gps_raw_int_get_vel(msg);
gps_raw_int->cog = mavlink_msg_gps_raw_int_get_cog(msg);
gps_raw_int->fix_type = mavlink_msg_gps_raw_int_get_fix_type(msg);
gps_raw_int->satellites_visible = mavlink_msg_gps_raw_int_get_satellites_visible(msg);
#else
memcpy(gps_raw_int, _MAV_PAYLOAD(msg), 30);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v1.0/common/mavlink_msg_gps_status.h
0,0 → 1,252
// MESSAGE GPS_STATUS PACKING
 
#define MAVLINK_MSG_ID_GPS_STATUS 25
 
typedef struct __mavlink_gps_status_t
{
uint8_t satellites_visible; ///< Number of satellites visible
uint8_t satellite_prn[20]; ///< Global satellite ID
uint8_t satellite_used[20]; ///< 0: Satellite not used, 1: used for localization
uint8_t satellite_elevation[20]; ///< Elevation (0: right on top of receiver, 90: on the horizon) of satellite
uint8_t satellite_azimuth[20]; ///< Direction of satellite, 0: 0 deg, 255: 360 deg.
uint8_t satellite_snr[20]; ///< Signal to noise ratio of satellite
} mavlink_gps_status_t;
 
#define MAVLINK_MSG_ID_GPS_STATUS_LEN 101
#define MAVLINK_MSG_ID_25_LEN 101
 
#define MAVLINK_MSG_GPS_STATUS_FIELD_SATELLITE_PRN_LEN 20
#define MAVLINK_MSG_GPS_STATUS_FIELD_SATELLITE_USED_LEN 20
#define MAVLINK_MSG_GPS_STATUS_FIELD_SATELLITE_ELEVATION_LEN 20
#define MAVLINK_MSG_GPS_STATUS_FIELD_SATELLITE_AZIMUTH_LEN 20
#define MAVLINK_MSG_GPS_STATUS_FIELD_SATELLITE_SNR_LEN 20
 
#define MAVLINK_MESSAGE_INFO_GPS_STATUS { \
"GPS_STATUS", \
6, \
{ { "satellites_visible", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_gps_status_t, satellites_visible) }, \
{ "satellite_prn", NULL, MAVLINK_TYPE_UINT8_T, 20, 1, offsetof(mavlink_gps_status_t, satellite_prn) }, \
{ "satellite_used", NULL, MAVLINK_TYPE_UINT8_T, 20, 21, offsetof(mavlink_gps_status_t, satellite_used) }, \
{ "satellite_elevation", NULL, MAVLINK_TYPE_UINT8_T, 20, 41, offsetof(mavlink_gps_status_t, satellite_elevation) }, \
{ "satellite_azimuth", NULL, MAVLINK_TYPE_UINT8_T, 20, 61, offsetof(mavlink_gps_status_t, satellite_azimuth) }, \
{ "satellite_snr", NULL, MAVLINK_TYPE_UINT8_T, 20, 81, offsetof(mavlink_gps_status_t, satellite_snr) }, \
} \
}
 
 
/**
* @brief Pack a gps_status message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param satellites_visible Number of satellites visible
* @param satellite_prn Global satellite ID
* @param satellite_used 0: Satellite not used, 1: used for localization
* @param satellite_elevation Elevation (0: right on top of receiver, 90: on the horizon) of satellite
* @param satellite_azimuth Direction of satellite, 0: 0 deg, 255: 360 deg.
* @param satellite_snr Signal to noise ratio of satellite
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_gps_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t satellites_visible, const uint8_t *satellite_prn, const uint8_t *satellite_used, const uint8_t *satellite_elevation, const uint8_t *satellite_azimuth, const uint8_t *satellite_snr)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[101];
_mav_put_uint8_t(buf, 0, satellites_visible);
_mav_put_uint8_t_array(buf, 1, satellite_prn, 20);
_mav_put_uint8_t_array(buf, 21, satellite_used, 20);
_mav_put_uint8_t_array(buf, 41, satellite_elevation, 20);
_mav_put_uint8_t_array(buf, 61, satellite_azimuth, 20);
_mav_put_uint8_t_array(buf, 81, satellite_snr, 20);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 101);
#else
mavlink_gps_status_t packet;
packet.satellites_visible = satellites_visible;
mav_array_memcpy(packet.satellite_prn, satellite_prn, sizeof(uint8_t)*20);
mav_array_memcpy(packet.satellite_used, satellite_used, sizeof(uint8_t)*20);
mav_array_memcpy(packet.satellite_elevation, satellite_elevation, sizeof(uint8_t)*20);
mav_array_memcpy(packet.satellite_azimuth, satellite_azimuth, sizeof(uint8_t)*20);
mav_array_memcpy(packet.satellite_snr, satellite_snr, sizeof(uint8_t)*20);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 101);
#endif
 
msg->msgid = MAVLINK_MSG_ID_GPS_STATUS;
return mavlink_finalize_message(msg, system_id, component_id, 101, 23);
}
 
/**
* @brief Pack a gps_status message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param satellites_visible Number of satellites visible
* @param satellite_prn Global satellite ID
* @param satellite_used 0: Satellite not used, 1: used for localization
* @param satellite_elevation Elevation (0: right on top of receiver, 90: on the horizon) of satellite
* @param satellite_azimuth Direction of satellite, 0: 0 deg, 255: 360 deg.
* @param satellite_snr Signal to noise ratio of satellite
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_gps_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint8_t satellites_visible,const uint8_t *satellite_prn,const uint8_t *satellite_used,const uint8_t *satellite_elevation,const uint8_t *satellite_azimuth,const uint8_t *satellite_snr)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[101];
_mav_put_uint8_t(buf, 0, satellites_visible);
_mav_put_uint8_t_array(buf, 1, satellite_prn, 20);
_mav_put_uint8_t_array(buf, 21, satellite_used, 20);
_mav_put_uint8_t_array(buf, 41, satellite_elevation, 20);
_mav_put_uint8_t_array(buf, 61, satellite_azimuth, 20);
_mav_put_uint8_t_array(buf, 81, satellite_snr, 20);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 101);
#else
mavlink_gps_status_t packet;
packet.satellites_visible = satellites_visible;
mav_array_memcpy(packet.satellite_prn, satellite_prn, sizeof(uint8_t)*20);
mav_array_memcpy(packet.satellite_used, satellite_used, sizeof(uint8_t)*20);
mav_array_memcpy(packet.satellite_elevation, satellite_elevation, sizeof(uint8_t)*20);
mav_array_memcpy(packet.satellite_azimuth, satellite_azimuth, sizeof(uint8_t)*20);
mav_array_memcpy(packet.satellite_snr, satellite_snr, sizeof(uint8_t)*20);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 101);
#endif
 
msg->msgid = MAVLINK_MSG_ID_GPS_STATUS;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 101, 23);
}
 
/**
* @brief Encode a gps_status struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param gps_status C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_gps_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gps_status_t* gps_status)
{
return mavlink_msg_gps_status_pack(system_id, component_id, msg, gps_status->satellites_visible, gps_status->satellite_prn, gps_status->satellite_used, gps_status->satellite_elevation, gps_status->satellite_azimuth, gps_status->satellite_snr);
}
 
/**
* @brief Send a gps_status message
* @param chan MAVLink channel to send the message
*
* @param satellites_visible Number of satellites visible
* @param satellite_prn Global satellite ID
* @param satellite_used 0: Satellite not used, 1: used for localization
* @param satellite_elevation Elevation (0: right on top of receiver, 90: on the horizon) of satellite
* @param satellite_azimuth Direction of satellite, 0: 0 deg, 255: 360 deg.
* @param satellite_snr Signal to noise ratio of satellite
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_gps_status_send(mavlink_channel_t chan, uint8_t satellites_visible, const uint8_t *satellite_prn, const uint8_t *satellite_used, const uint8_t *satellite_elevation, const uint8_t *satellite_azimuth, const uint8_t *satellite_snr)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[101];
_mav_put_uint8_t(buf, 0, satellites_visible);
_mav_put_uint8_t_array(buf, 1, satellite_prn, 20);
_mav_put_uint8_t_array(buf, 21, satellite_used, 20);
_mav_put_uint8_t_array(buf, 41, satellite_elevation, 20);
_mav_put_uint8_t_array(buf, 61, satellite_azimuth, 20);
_mav_put_uint8_t_array(buf, 81, satellite_snr, 20);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_STATUS, buf, 101, 23);
#else
mavlink_gps_status_t packet;
packet.satellites_visible = satellites_visible;
mav_array_memcpy(packet.satellite_prn, satellite_prn, sizeof(uint8_t)*20);
mav_array_memcpy(packet.satellite_used, satellite_used, sizeof(uint8_t)*20);
mav_array_memcpy(packet.satellite_elevation, satellite_elevation, sizeof(uint8_t)*20);
mav_array_memcpy(packet.satellite_azimuth, satellite_azimuth, sizeof(uint8_t)*20);
mav_array_memcpy(packet.satellite_snr, satellite_snr, sizeof(uint8_t)*20);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_STATUS, (const char *)&packet, 101, 23);
#endif
}
 
#endif
 
// MESSAGE GPS_STATUS UNPACKING
 
 
/**
* @brief Get field satellites_visible from gps_status message
*
* @return Number of satellites visible
*/
static inline uint8_t mavlink_msg_gps_status_get_satellites_visible(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 0);
}
 
/**
* @brief Get field satellite_prn from gps_status message
*
* @return Global satellite ID
*/
static inline uint16_t mavlink_msg_gps_status_get_satellite_prn(const mavlink_message_t* msg, uint8_t *satellite_prn)
{
return _MAV_RETURN_uint8_t_array(msg, satellite_prn, 20, 1);
}
 
/**
* @brief Get field satellite_used from gps_status message
*
* @return 0: Satellite not used, 1: used for localization
*/
static inline uint16_t mavlink_msg_gps_status_get_satellite_used(const mavlink_message_t* msg, uint8_t *satellite_used)
{
return _MAV_RETURN_uint8_t_array(msg, satellite_used, 20, 21);
}
 
/**
* @brief Get field satellite_elevation from gps_status message
*
* @return Elevation (0: right on top of receiver, 90: on the horizon) of satellite
*/
static inline uint16_t mavlink_msg_gps_status_get_satellite_elevation(const mavlink_message_t* msg, uint8_t *satellite_elevation)
{
return _MAV_RETURN_uint8_t_array(msg, satellite_elevation, 20, 41);
}
 
/**
* @brief Get field satellite_azimuth from gps_status message
*
* @return Direction of satellite, 0: 0 deg, 255: 360 deg.
*/
static inline uint16_t mavlink_msg_gps_status_get_satellite_azimuth(const mavlink_message_t* msg, uint8_t *satellite_azimuth)
{
return _MAV_RETURN_uint8_t_array(msg, satellite_azimuth, 20, 61);
}
 
/**
* @brief Get field satellite_snr from gps_status message
*
* @return Signal to noise ratio of satellite
*/
static inline uint16_t mavlink_msg_gps_status_get_satellite_snr(const mavlink_message_t* msg, uint8_t *satellite_snr)
{
return _MAV_RETURN_uint8_t_array(msg, satellite_snr, 20, 81);
}
 
/**
* @brief Decode a gps_status message into a struct
*
* @param msg The message to decode
* @param gps_status C-struct to decode the message contents into
*/
static inline void mavlink_msg_gps_status_decode(const mavlink_message_t* msg, mavlink_gps_status_t* gps_status)
{
#if MAVLINK_NEED_BYTE_SWAP
gps_status->satellites_visible = mavlink_msg_gps_status_get_satellites_visible(msg);
mavlink_msg_gps_status_get_satellite_prn(msg, gps_status->satellite_prn);
mavlink_msg_gps_status_get_satellite_used(msg, gps_status->satellite_used);
mavlink_msg_gps_status_get_satellite_elevation(msg, gps_status->satellite_elevation);
mavlink_msg_gps_status_get_satellite_azimuth(msg, gps_status->satellite_azimuth);
mavlink_msg_gps_status_get_satellite_snr(msg, gps_status->satellite_snr);
#else
memcpy(gps_status, _MAV_PAYLOAD(msg), 101);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v1.0/common/mavlink_msg_heartbeat.h
0,0 → 1,251
// MESSAGE HEARTBEAT PACKING
 
#define MAVLINK_MSG_ID_HEARTBEAT 0
 
typedef struct __mavlink_heartbeat_t
{
uint32_t custom_mode; ///< A bitfield for use for autopilot-specific flags.
uint8_t type; ///< Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM)
uint8_t autopilot; ///< Autopilot type / class. defined in MAV_AUTOPILOT ENUM
uint8_t base_mode; ///< System mode bitfield, see MAV_MODE_FLAGS ENUM in mavlink/include/mavlink_types.h
uint8_t system_status; ///< System status flag, see MAV_STATE ENUM
uint8_t mavlink_version; ///< MAVLink version, not writable by user, gets added by protocol because of magic data type: uint8_t_mavlink_version
} mavlink_heartbeat_t;
 
#define MAVLINK_MSG_ID_HEARTBEAT_LEN 9
#define MAVLINK_MSG_ID_0_LEN 9
 
 
 
#define MAVLINK_MESSAGE_INFO_HEARTBEAT { \
"HEARTBEAT", \
6, \
{ { "custom_mode", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_heartbeat_t, custom_mode) }, \
{ "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_heartbeat_t, type) }, \
{ "autopilot", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_heartbeat_t, autopilot) }, \
{ "base_mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_heartbeat_t, base_mode) }, \
{ "system_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 7, offsetof(mavlink_heartbeat_t, system_status) }, \
{ "mavlink_version", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_heartbeat_t, mavlink_version) }, \
} \
}
 
 
/**
* @brief Pack a heartbeat message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param type Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM)
* @param autopilot Autopilot type / class. defined in MAV_AUTOPILOT ENUM
* @param base_mode System mode bitfield, see MAV_MODE_FLAGS ENUM in mavlink/include/mavlink_types.h
* @param custom_mode A bitfield for use for autopilot-specific flags.
* @param system_status System status flag, see MAV_STATE ENUM
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_heartbeat_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t type, uint8_t autopilot, uint8_t base_mode, uint32_t custom_mode, uint8_t system_status)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[9];
_mav_put_uint32_t(buf, 0, custom_mode);
_mav_put_uint8_t(buf, 4, type);
_mav_put_uint8_t(buf, 5, autopilot);
_mav_put_uint8_t(buf, 6, base_mode);
_mav_put_uint8_t(buf, 7, system_status);
_mav_put_uint8_t(buf, 8, 3);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 9);
#else
mavlink_heartbeat_t packet;
packet.custom_mode = custom_mode;
packet.type = type;
packet.autopilot = autopilot;
packet.base_mode = base_mode;
packet.system_status = system_status;
packet.mavlink_version = 3;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 9);
#endif
 
msg->msgid = MAVLINK_MSG_ID_HEARTBEAT;
return mavlink_finalize_message(msg, system_id, component_id, 9, 50);
}
 
/**
* @brief Pack a heartbeat message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param type Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM)
* @param autopilot Autopilot type / class. defined in MAV_AUTOPILOT ENUM
* @param base_mode System mode bitfield, see MAV_MODE_FLAGS ENUM in mavlink/include/mavlink_types.h
* @param custom_mode A bitfield for use for autopilot-specific flags.
* @param system_status System status flag, see MAV_STATE ENUM
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_heartbeat_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint8_t type,uint8_t autopilot,uint8_t base_mode,uint32_t custom_mode,uint8_t system_status)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[9];
_mav_put_uint32_t(buf, 0, custom_mode);
_mav_put_uint8_t(buf, 4, type);
_mav_put_uint8_t(buf, 5, autopilot);
_mav_put_uint8_t(buf, 6, base_mode);
_mav_put_uint8_t(buf, 7, system_status);
_mav_put_uint8_t(buf, 8, 3);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 9);
#else
mavlink_heartbeat_t packet;
packet.custom_mode = custom_mode;
packet.type = type;
packet.autopilot = autopilot;
packet.base_mode = base_mode;
packet.system_status = system_status;
packet.mavlink_version = 3;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 9);
#endif
 
msg->msgid = MAVLINK_MSG_ID_HEARTBEAT;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 9, 50);
}
 
/**
* @brief Encode a heartbeat struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param heartbeat C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_heartbeat_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_heartbeat_t* heartbeat)
{
return mavlink_msg_heartbeat_pack(system_id, component_id, msg, heartbeat->type, heartbeat->autopilot, heartbeat->base_mode, heartbeat->custom_mode, heartbeat->system_status);
}
 
/**
* @brief Send a heartbeat message
* @param chan MAVLink channel to send the message
*
* @param type Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM)
* @param autopilot Autopilot type / class. defined in MAV_AUTOPILOT ENUM
* @param base_mode System mode bitfield, see MAV_MODE_FLAGS ENUM in mavlink/include/mavlink_types.h
* @param custom_mode A bitfield for use for autopilot-specific flags.
* @param system_status System status flag, see MAV_STATE ENUM
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_heartbeat_send(mavlink_channel_t chan, uint8_t type, uint8_t autopilot, uint8_t base_mode, uint32_t custom_mode, uint8_t system_status)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[9];
_mav_put_uint32_t(buf, 0, custom_mode);
_mav_put_uint8_t(buf, 4, type);
_mav_put_uint8_t(buf, 5, autopilot);
_mav_put_uint8_t(buf, 6, base_mode);
_mav_put_uint8_t(buf, 7, system_status);
_mav_put_uint8_t(buf, 8, 3);
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HEARTBEAT, buf, 9, 50);
#else
mavlink_heartbeat_t packet;
packet.custom_mode = custom_mode;
packet.type = type;
packet.autopilot = autopilot;
packet.base_mode = base_mode;
packet.system_status = system_status;
packet.mavlink_version = 3;
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HEARTBEAT, (const char *)&packet, 9, 50);
#endif
}
 
#endif
 
// MESSAGE HEARTBEAT UNPACKING
 
 
/**
* @brief Get field type from heartbeat message
*
* @return Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM)
*/
static inline uint8_t mavlink_msg_heartbeat_get_type(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 4);
}
 
/**
* @brief Get field autopilot from heartbeat message
*
* @return Autopilot type / class. defined in MAV_AUTOPILOT ENUM
*/
static inline uint8_t mavlink_msg_heartbeat_get_autopilot(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 5);
}
 
/**
* @brief Get field base_mode from heartbeat message
*
* @return System mode bitfield, see MAV_MODE_FLAGS ENUM in mavlink/include/mavlink_types.h
*/
static inline uint8_t mavlink_msg_heartbeat_get_base_mode(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 6);
}
 
/**
* @brief Get field custom_mode from heartbeat message
*
* @return A bitfield for use for autopilot-specific flags.
*/
static inline uint32_t mavlink_msg_heartbeat_get_custom_mode(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint32_t(msg, 0);
}
 
/**
* @brief Get field system_status from heartbeat message
*
* @return System status flag, see MAV_STATE ENUM
*/
static inline uint8_t mavlink_msg_heartbeat_get_system_status(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 7);
}
 
/**
* @brief Get field mavlink_version from heartbeat message
*
* @return MAVLink version, not writable by user, gets added by protocol because of magic data type: uint8_t_mavlink_version
*/
static inline uint8_t mavlink_msg_heartbeat_get_mavlink_version(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 8);
}
 
/**
* @brief Decode a heartbeat message into a struct
*
* @param msg The message to decode
* @param heartbeat C-struct to decode the message contents into
*/
static inline void mavlink_msg_heartbeat_decode(const mavlink_message_t* msg, mavlink_heartbeat_t* heartbeat)
{
#if MAVLINK_NEED_BYTE_SWAP
heartbeat->custom_mode = mavlink_msg_heartbeat_get_custom_mode(msg);
heartbeat->type = mavlink_msg_heartbeat_get_type(msg);
heartbeat->autopilot = mavlink_msg_heartbeat_get_autopilot(msg);
heartbeat->base_mode = mavlink_msg_heartbeat_get_base_mode(msg);
heartbeat->system_status = mavlink_msg_heartbeat_get_system_status(msg);
heartbeat->mavlink_version = mavlink_msg_heartbeat_get_mavlink_version(msg);
#else
memcpy(heartbeat, _MAV_PAYLOAD(msg), 9);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v1.0/common/mavlink_msg_hil_controls.h
0,0 → 1,364
// MESSAGE HIL_CONTROLS PACKING
 
#define MAVLINK_MSG_ID_HIL_CONTROLS 91
 
typedef struct __mavlink_hil_controls_t
{
uint64_t time_usec; ///< Timestamp (microseconds since UNIX epoch or microseconds since system boot)
float roll_ailerons; ///< Control output -1 .. 1
float pitch_elevator; ///< Control output -1 .. 1
float yaw_rudder; ///< Control output -1 .. 1
float throttle; ///< Throttle 0 .. 1
float aux1; ///< Aux 1, -1 .. 1
float aux2; ///< Aux 2, -1 .. 1
float aux3; ///< Aux 3, -1 .. 1
float aux4; ///< Aux 4, -1 .. 1
uint8_t mode; ///< System mode (MAV_MODE)
uint8_t nav_mode; ///< Navigation mode (MAV_NAV_MODE)
} mavlink_hil_controls_t;
 
#define MAVLINK_MSG_ID_HIL_CONTROLS_LEN 42
#define MAVLINK_MSG_ID_91_LEN 42
 
 
 
#define MAVLINK_MESSAGE_INFO_HIL_CONTROLS { \
"HIL_CONTROLS", \
11, \
{ { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_hil_controls_t, time_usec) }, \
{ "roll_ailerons", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_hil_controls_t, roll_ailerons) }, \
{ "pitch_elevator", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_hil_controls_t, pitch_elevator) }, \
{ "yaw_rudder", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_hil_controls_t, yaw_rudder) }, \
{ "throttle", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_hil_controls_t, throttle) }, \
{ "aux1", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_hil_controls_t, aux1) }, \
{ "aux2", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_hil_controls_t, aux2) }, \
{ "aux3", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_hil_controls_t, aux3) }, \
{ "aux4", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_hil_controls_t, aux4) }, \
{ "mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 40, offsetof(mavlink_hil_controls_t, mode) }, \
{ "nav_mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 41, offsetof(mavlink_hil_controls_t, nav_mode) }, \
} \
}
 
 
/**
* @brief Pack a hil_controls message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
* @param roll_ailerons Control output -1 .. 1
* @param pitch_elevator Control output -1 .. 1
* @param yaw_rudder Control output -1 .. 1
* @param throttle Throttle 0 .. 1
* @param aux1 Aux 1, -1 .. 1
* @param aux2 Aux 2, -1 .. 1
* @param aux3 Aux 3, -1 .. 1
* @param aux4 Aux 4, -1 .. 1
* @param mode System mode (MAV_MODE)
* @param nav_mode Navigation mode (MAV_NAV_MODE)
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_hil_controls_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint64_t time_usec, float roll_ailerons, float pitch_elevator, float yaw_rudder, float throttle, float aux1, float aux2, float aux3, float aux4, uint8_t mode, uint8_t nav_mode)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[42];
_mav_put_uint64_t(buf, 0, time_usec);
_mav_put_float(buf, 8, roll_ailerons);
_mav_put_float(buf, 12, pitch_elevator);
_mav_put_float(buf, 16, yaw_rudder);
_mav_put_float(buf, 20, throttle);
_mav_put_float(buf, 24, aux1);
_mav_put_float(buf, 28, aux2);
_mav_put_float(buf, 32, aux3);
_mav_put_float(buf, 36, aux4);
_mav_put_uint8_t(buf, 40, mode);
_mav_put_uint8_t(buf, 41, nav_mode);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 42);
#else
mavlink_hil_controls_t packet;
packet.time_usec = time_usec;
packet.roll_ailerons = roll_ailerons;
packet.pitch_elevator = pitch_elevator;
packet.yaw_rudder = yaw_rudder;
packet.throttle = throttle;
packet.aux1 = aux1;
packet.aux2 = aux2;
packet.aux3 = aux3;
packet.aux4 = aux4;
packet.mode = mode;
packet.nav_mode = nav_mode;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 42);
#endif
 
msg->msgid = MAVLINK_MSG_ID_HIL_CONTROLS;
return mavlink_finalize_message(msg, system_id, component_id, 42, 63);
}
 
/**
* @brief Pack a hil_controls message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
* @param roll_ailerons Control output -1 .. 1
* @param pitch_elevator Control output -1 .. 1
* @param yaw_rudder Control output -1 .. 1
* @param throttle Throttle 0 .. 1
* @param aux1 Aux 1, -1 .. 1
* @param aux2 Aux 2, -1 .. 1
* @param aux3 Aux 3, -1 .. 1
* @param aux4 Aux 4, -1 .. 1
* @param mode System mode (MAV_MODE)
* @param nav_mode Navigation mode (MAV_NAV_MODE)
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_hil_controls_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint64_t time_usec,float roll_ailerons,float pitch_elevator,float yaw_rudder,float throttle,float aux1,float aux2,float aux3,float aux4,uint8_t mode,uint8_t nav_mode)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[42];
_mav_put_uint64_t(buf, 0, time_usec);
_mav_put_float(buf, 8, roll_ailerons);
_mav_put_float(buf, 12, pitch_elevator);
_mav_put_float(buf, 16, yaw_rudder);
_mav_put_float(buf, 20, throttle);
_mav_put_float(buf, 24, aux1);
_mav_put_float(buf, 28, aux2);
_mav_put_float(buf, 32, aux3);
_mav_put_float(buf, 36, aux4);
_mav_put_uint8_t(buf, 40, mode);
_mav_put_uint8_t(buf, 41, nav_mode);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 42);
#else
mavlink_hil_controls_t packet;
packet.time_usec = time_usec;
packet.roll_ailerons = roll_ailerons;
packet.pitch_elevator = pitch_elevator;
packet.yaw_rudder = yaw_rudder;
packet.throttle = throttle;
packet.aux1 = aux1;
packet.aux2 = aux2;
packet.aux3 = aux3;
packet.aux4 = aux4;
packet.mode = mode;
packet.nav_mode = nav_mode;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 42);
#endif
 
msg->msgid = MAVLINK_MSG_ID_HIL_CONTROLS;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 42, 63);
}
 
/**
* @brief Encode a hil_controls struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param hil_controls C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_hil_controls_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_hil_controls_t* hil_controls)
{
return mavlink_msg_hil_controls_pack(system_id, component_id, msg, hil_controls->time_usec, hil_controls->roll_ailerons, hil_controls->pitch_elevator, hil_controls->yaw_rudder, hil_controls->throttle, hil_controls->aux1, hil_controls->aux2, hil_controls->aux3, hil_controls->aux4, hil_controls->mode, hil_controls->nav_mode);
}
 
/**
* @brief Send a hil_controls message
* @param chan MAVLink channel to send the message
*
* @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
* @param roll_ailerons Control output -1 .. 1
* @param pitch_elevator Control output -1 .. 1
* @param yaw_rudder Control output -1 .. 1
* @param throttle Throttle 0 .. 1
* @param aux1 Aux 1, -1 .. 1
* @param aux2 Aux 2, -1 .. 1
* @param aux3 Aux 3, -1 .. 1
* @param aux4 Aux 4, -1 .. 1
* @param mode System mode (MAV_MODE)
* @param nav_mode Navigation mode (MAV_NAV_MODE)
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_hil_controls_send(mavlink_channel_t chan, uint64_t time_usec, float roll_ailerons, float pitch_elevator, float yaw_rudder, float throttle, float aux1, float aux2, float aux3, float aux4, uint8_t mode, uint8_t nav_mode)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[42];
_mav_put_uint64_t(buf, 0, time_usec);
_mav_put_float(buf, 8, roll_ailerons);
_mav_put_float(buf, 12, pitch_elevator);
_mav_put_float(buf, 16, yaw_rudder);
_mav_put_float(buf, 20, throttle);
_mav_put_float(buf, 24, aux1);
_mav_put_float(buf, 28, aux2);
_mav_put_float(buf, 32, aux3);
_mav_put_float(buf, 36, aux4);
_mav_put_uint8_t(buf, 40, mode);
_mav_put_uint8_t(buf, 41, nav_mode);
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_CONTROLS, buf, 42, 63);
#else
mavlink_hil_controls_t packet;
packet.time_usec = time_usec;
packet.roll_ailerons = roll_ailerons;
packet.pitch_elevator = pitch_elevator;
packet.yaw_rudder = yaw_rudder;
packet.throttle = throttle;
packet.aux1 = aux1;
packet.aux2 = aux2;
packet.aux3 = aux3;
packet.aux4 = aux4;
packet.mode = mode;
packet.nav_mode = nav_mode;
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_CONTROLS, (const char *)&packet, 42, 63);
#endif
}
 
#endif
 
// MESSAGE HIL_CONTROLS UNPACKING
 
 
/**
* @brief Get field time_usec from hil_controls message
*
* @return Timestamp (microseconds since UNIX epoch or microseconds since system boot)
*/
static inline uint64_t mavlink_msg_hil_controls_get_time_usec(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint64_t(msg, 0);
}
 
/**
* @brief Get field roll_ailerons from hil_controls message
*
* @return Control output -1 .. 1
*/
static inline float mavlink_msg_hil_controls_get_roll_ailerons(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 8);
}
 
/**
* @brief Get field pitch_elevator from hil_controls message
*
* @return Control output -1 .. 1
*/
static inline float mavlink_msg_hil_controls_get_pitch_elevator(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 12);
}
 
/**
* @brief Get field yaw_rudder from hil_controls message
*
* @return Control output -1 .. 1
*/
static inline float mavlink_msg_hil_controls_get_yaw_rudder(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 16);
}
 
/**
* @brief Get field throttle from hil_controls message
*
* @return Throttle 0 .. 1
*/
static inline float mavlink_msg_hil_controls_get_throttle(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 20);
}
 
/**
* @brief Get field aux1 from hil_controls message
*
* @return Aux 1, -1 .. 1
*/
static inline float mavlink_msg_hil_controls_get_aux1(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 24);
}
 
/**
* @brief Get field aux2 from hil_controls message
*
* @return Aux 2, -1 .. 1
*/
static inline float mavlink_msg_hil_controls_get_aux2(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 28);
}
 
/**
* @brief Get field aux3 from hil_controls message
*
* @return Aux 3, -1 .. 1
*/
static inline float mavlink_msg_hil_controls_get_aux3(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 32);
}
 
/**
* @brief Get field aux4 from hil_controls message
*
* @return Aux 4, -1 .. 1
*/
static inline float mavlink_msg_hil_controls_get_aux4(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 36);
}
 
/**
* @brief Get field mode from hil_controls message
*
* @return System mode (MAV_MODE)
*/
static inline uint8_t mavlink_msg_hil_controls_get_mode(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 40);
}
 
/**
* @brief Get field nav_mode from hil_controls message
*
* @return Navigation mode (MAV_NAV_MODE)
*/
static inline uint8_t mavlink_msg_hil_controls_get_nav_mode(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 41);
}
 
/**
* @brief Decode a hil_controls message into a struct
*
* @param msg The message to decode
* @param hil_controls C-struct to decode the message contents into
*/
static inline void mavlink_msg_hil_controls_decode(const mavlink_message_t* msg, mavlink_hil_controls_t* hil_controls)
{
#if MAVLINK_NEED_BYTE_SWAP
hil_controls->time_usec = mavlink_msg_hil_controls_get_time_usec(msg);
hil_controls->roll_ailerons = mavlink_msg_hil_controls_get_roll_ailerons(msg);
hil_controls->pitch_elevator = mavlink_msg_hil_controls_get_pitch_elevator(msg);
hil_controls->yaw_rudder = mavlink_msg_hil_controls_get_yaw_rudder(msg);
hil_controls->throttle = mavlink_msg_hil_controls_get_throttle(msg);
hil_controls->aux1 = mavlink_msg_hil_controls_get_aux1(msg);
hil_controls->aux2 = mavlink_msg_hil_controls_get_aux2(msg);
hil_controls->aux3 = mavlink_msg_hil_controls_get_aux3(msg);
hil_controls->aux4 = mavlink_msg_hil_controls_get_aux4(msg);
hil_controls->mode = mavlink_msg_hil_controls_get_mode(msg);
hil_controls->nav_mode = mavlink_msg_hil_controls_get_nav_mode(msg);
#else
memcpy(hil_controls, _MAV_PAYLOAD(msg), 42);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v1.0/common/mavlink_msg_hil_rc_inputs_raw.h
0,0 → 1,430
// MESSAGE HIL_RC_INPUTS_RAW PACKING
 
#define MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW 92
 
typedef struct __mavlink_hil_rc_inputs_raw_t
{
uint64_t time_usec; ///< Timestamp (microseconds since UNIX epoch or microseconds since system boot)
uint16_t chan1_raw; ///< RC channel 1 value, in microseconds
uint16_t chan2_raw; ///< RC channel 2 value, in microseconds
uint16_t chan3_raw; ///< RC channel 3 value, in microseconds
uint16_t chan4_raw; ///< RC channel 4 value, in microseconds
uint16_t chan5_raw; ///< RC channel 5 value, in microseconds
uint16_t chan6_raw; ///< RC channel 6 value, in microseconds
uint16_t chan7_raw; ///< RC channel 7 value, in microseconds
uint16_t chan8_raw; ///< RC channel 8 value, in microseconds
uint16_t chan9_raw; ///< RC channel 9 value, in microseconds
uint16_t chan10_raw; ///< RC channel 10 value, in microseconds
uint16_t chan11_raw; ///< RC channel 11 value, in microseconds
uint16_t chan12_raw; ///< RC channel 12 value, in microseconds
uint8_t rssi; ///< Receive signal strength indicator, 0: 0%, 255: 100%
} mavlink_hil_rc_inputs_raw_t;
 
#define MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_LEN 33
#define MAVLINK_MSG_ID_92_LEN 33
 
 
 
#define MAVLINK_MESSAGE_INFO_HIL_RC_INPUTS_RAW { \
"HIL_RC_INPUTS_RAW", \
14, \
{ { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_hil_rc_inputs_raw_t, time_usec) }, \
{ "chan1_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_hil_rc_inputs_raw_t, chan1_raw) }, \
{ "chan2_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 10, offsetof(mavlink_hil_rc_inputs_raw_t, chan2_raw) }, \
{ "chan3_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_hil_rc_inputs_raw_t, chan3_raw) }, \
{ "chan4_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 14, offsetof(mavlink_hil_rc_inputs_raw_t, chan4_raw) }, \
{ "chan5_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_hil_rc_inputs_raw_t, chan5_raw) }, \
{ "chan6_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_hil_rc_inputs_raw_t, chan6_raw) }, \
{ "chan7_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 20, offsetof(mavlink_hil_rc_inputs_raw_t, chan7_raw) }, \
{ "chan8_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 22, offsetof(mavlink_hil_rc_inputs_raw_t, chan8_raw) }, \
{ "chan9_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_hil_rc_inputs_raw_t, chan9_raw) }, \
{ "chan10_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 26, offsetof(mavlink_hil_rc_inputs_raw_t, chan10_raw) }, \
{ "chan11_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_hil_rc_inputs_raw_t, chan11_raw) }, \
{ "chan12_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 30, offsetof(mavlink_hil_rc_inputs_raw_t, chan12_raw) }, \
{ "rssi", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_hil_rc_inputs_raw_t, rssi) }, \
} \
}
 
 
/**
* @brief Pack a hil_rc_inputs_raw message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
* @param chan1_raw RC channel 1 value, in microseconds
* @param chan2_raw RC channel 2 value, in microseconds
* @param chan3_raw RC channel 3 value, in microseconds
* @param chan4_raw RC channel 4 value, in microseconds
* @param chan5_raw RC channel 5 value, in microseconds
* @param chan6_raw RC channel 6 value, in microseconds
* @param chan7_raw RC channel 7 value, in microseconds
* @param chan8_raw RC channel 8 value, in microseconds
* @param chan9_raw RC channel 9 value, in microseconds
* @param chan10_raw RC channel 10 value, in microseconds
* @param chan11_raw RC channel 11 value, in microseconds
* @param chan12_raw RC channel 12 value, in microseconds
* @param rssi Receive signal strength indicator, 0: 0%, 255: 100%
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_hil_rc_inputs_raw_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint64_t time_usec, uint16_t chan1_raw, uint16_t chan2_raw, uint16_t chan3_raw, uint16_t chan4_raw, uint16_t chan5_raw, uint16_t chan6_raw, uint16_t chan7_raw, uint16_t chan8_raw, uint16_t chan9_raw, uint16_t chan10_raw, uint16_t chan11_raw, uint16_t chan12_raw, uint8_t rssi)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[33];
_mav_put_uint64_t(buf, 0, time_usec);
_mav_put_uint16_t(buf, 8, chan1_raw);
_mav_put_uint16_t(buf, 10, chan2_raw);
_mav_put_uint16_t(buf, 12, chan3_raw);
_mav_put_uint16_t(buf, 14, chan4_raw);
_mav_put_uint16_t(buf, 16, chan5_raw);
_mav_put_uint16_t(buf, 18, chan6_raw);
_mav_put_uint16_t(buf, 20, chan7_raw);
_mav_put_uint16_t(buf, 22, chan8_raw);
_mav_put_uint16_t(buf, 24, chan9_raw);
_mav_put_uint16_t(buf, 26, chan10_raw);
_mav_put_uint16_t(buf, 28, chan11_raw);
_mav_put_uint16_t(buf, 30, chan12_raw);
_mav_put_uint8_t(buf, 32, rssi);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 33);
#else
mavlink_hil_rc_inputs_raw_t packet;
packet.time_usec = time_usec;
packet.chan1_raw = chan1_raw;
packet.chan2_raw = chan2_raw;
packet.chan3_raw = chan3_raw;
packet.chan4_raw = chan4_raw;
packet.chan5_raw = chan5_raw;
packet.chan6_raw = chan6_raw;
packet.chan7_raw = chan7_raw;
packet.chan8_raw = chan8_raw;
packet.chan9_raw = chan9_raw;
packet.chan10_raw = chan10_raw;
packet.chan11_raw = chan11_raw;
packet.chan12_raw = chan12_raw;
packet.rssi = rssi;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 33);
#endif
 
msg->msgid = MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW;
return mavlink_finalize_message(msg, system_id, component_id, 33, 54);
}
 
/**
* @brief Pack a hil_rc_inputs_raw message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
* @param chan1_raw RC channel 1 value, in microseconds
* @param chan2_raw RC channel 2 value, in microseconds
* @param chan3_raw RC channel 3 value, in microseconds
* @param chan4_raw RC channel 4 value, in microseconds
* @param chan5_raw RC channel 5 value, in microseconds
* @param chan6_raw RC channel 6 value, in microseconds
* @param chan7_raw RC channel 7 value, in microseconds
* @param chan8_raw RC channel 8 value, in microseconds
* @param chan9_raw RC channel 9 value, in microseconds
* @param chan10_raw RC channel 10 value, in microseconds
* @param chan11_raw RC channel 11 value, in microseconds
* @param chan12_raw RC channel 12 value, in microseconds
* @param rssi Receive signal strength indicator, 0: 0%, 255: 100%
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_hil_rc_inputs_raw_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint64_t time_usec,uint16_t chan1_raw,uint16_t chan2_raw,uint16_t chan3_raw,uint16_t chan4_raw,uint16_t chan5_raw,uint16_t chan6_raw,uint16_t chan7_raw,uint16_t chan8_raw,uint16_t chan9_raw,uint16_t chan10_raw,uint16_t chan11_raw,uint16_t chan12_raw,uint8_t rssi)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[33];
_mav_put_uint64_t(buf, 0, time_usec);
_mav_put_uint16_t(buf, 8, chan1_raw);
_mav_put_uint16_t(buf, 10, chan2_raw);
_mav_put_uint16_t(buf, 12, chan3_raw);
_mav_put_uint16_t(buf, 14, chan4_raw);
_mav_put_uint16_t(buf, 16, chan5_raw);
_mav_put_uint16_t(buf, 18, chan6_raw);
_mav_put_uint16_t(buf, 20, chan7_raw);
_mav_put_uint16_t(buf, 22, chan8_raw);
_mav_put_uint16_t(buf, 24, chan9_raw);
_mav_put_uint16_t(buf, 26, chan10_raw);
_mav_put_uint16_t(buf, 28, chan11_raw);
_mav_put_uint16_t(buf, 30, chan12_raw);
_mav_put_uint8_t(buf, 32, rssi);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 33);
#else
mavlink_hil_rc_inputs_raw_t packet;
packet.time_usec = time_usec;
packet.chan1_raw = chan1_raw;
packet.chan2_raw = chan2_raw;
packet.chan3_raw = chan3_raw;
packet.chan4_raw = chan4_raw;
packet.chan5_raw = chan5_raw;
packet.chan6_raw = chan6_raw;
packet.chan7_raw = chan7_raw;
packet.chan8_raw = chan8_raw;
packet.chan9_raw = chan9_raw;
packet.chan10_raw = chan10_raw;
packet.chan11_raw = chan11_raw;
packet.chan12_raw = chan12_raw;
packet.rssi = rssi;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 33);
#endif
 
msg->msgid = MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 33, 54);
}
 
/**
* @brief Encode a hil_rc_inputs_raw struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param hil_rc_inputs_raw C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_hil_rc_inputs_raw_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_hil_rc_inputs_raw_t* hil_rc_inputs_raw)
{
return mavlink_msg_hil_rc_inputs_raw_pack(system_id, component_id, msg, hil_rc_inputs_raw->time_usec, hil_rc_inputs_raw->chan1_raw, hil_rc_inputs_raw->chan2_raw, hil_rc_inputs_raw->chan3_raw, hil_rc_inputs_raw->chan4_raw, hil_rc_inputs_raw->chan5_raw, hil_rc_inputs_raw->chan6_raw, hil_rc_inputs_raw->chan7_raw, hil_rc_inputs_raw->chan8_raw, hil_rc_inputs_raw->chan9_raw, hil_rc_inputs_raw->chan10_raw, hil_rc_inputs_raw->chan11_raw, hil_rc_inputs_raw->chan12_raw, hil_rc_inputs_raw->rssi);
}
 
/**
* @brief Send a hil_rc_inputs_raw message
* @param chan MAVLink channel to send the message
*
* @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
* @param chan1_raw RC channel 1 value, in microseconds
* @param chan2_raw RC channel 2 value, in microseconds
* @param chan3_raw RC channel 3 value, in microseconds
* @param chan4_raw RC channel 4 value, in microseconds
* @param chan5_raw RC channel 5 value, in microseconds
* @param chan6_raw RC channel 6 value, in microseconds
* @param chan7_raw RC channel 7 value, in microseconds
* @param chan8_raw RC channel 8 value, in microseconds
* @param chan9_raw RC channel 9 value, in microseconds
* @param chan10_raw RC channel 10 value, in microseconds
* @param chan11_raw RC channel 11 value, in microseconds
* @param chan12_raw RC channel 12 value, in microseconds
* @param rssi Receive signal strength indicator, 0: 0%, 255: 100%
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_hil_rc_inputs_raw_send(mavlink_channel_t chan, uint64_t time_usec, uint16_t chan1_raw, uint16_t chan2_raw, uint16_t chan3_raw, uint16_t chan4_raw, uint16_t chan5_raw, uint16_t chan6_raw, uint16_t chan7_raw, uint16_t chan8_raw, uint16_t chan9_raw, uint16_t chan10_raw, uint16_t chan11_raw, uint16_t chan12_raw, uint8_t rssi)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[33];
_mav_put_uint64_t(buf, 0, time_usec);
_mav_put_uint16_t(buf, 8, chan1_raw);
_mav_put_uint16_t(buf, 10, chan2_raw);
_mav_put_uint16_t(buf, 12, chan3_raw);
_mav_put_uint16_t(buf, 14, chan4_raw);
_mav_put_uint16_t(buf, 16, chan5_raw);
_mav_put_uint16_t(buf, 18, chan6_raw);
_mav_put_uint16_t(buf, 20, chan7_raw);
_mav_put_uint16_t(buf, 22, chan8_raw);
_mav_put_uint16_t(buf, 24, chan9_raw);
_mav_put_uint16_t(buf, 26, chan10_raw);
_mav_put_uint16_t(buf, 28, chan11_raw);
_mav_put_uint16_t(buf, 30, chan12_raw);
_mav_put_uint8_t(buf, 32, rssi);
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW, buf, 33, 54);
#else
mavlink_hil_rc_inputs_raw_t packet;
packet.time_usec = time_usec;
packet.chan1_raw = chan1_raw;
packet.chan2_raw = chan2_raw;
packet.chan3_raw = chan3_raw;
packet.chan4_raw = chan4_raw;
packet.chan5_raw = chan5_raw;
packet.chan6_raw = chan6_raw;
packet.chan7_raw = chan7_raw;
packet.chan8_raw = chan8_raw;
packet.chan9_raw = chan9_raw;
packet.chan10_raw = chan10_raw;
packet.chan11_raw = chan11_raw;
packet.chan12_raw = chan12_raw;
packet.rssi = rssi;
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW, (const char *)&packet, 33, 54);
#endif
}
 
#endif
 
// MESSAGE HIL_RC_INPUTS_RAW UNPACKING
 
 
/**
* @brief Get field time_usec from hil_rc_inputs_raw message
*
* @return Timestamp (microseconds since UNIX epoch or microseconds since system boot)
*/
static inline uint64_t mavlink_msg_hil_rc_inputs_raw_get_time_usec(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint64_t(msg, 0);
}
 
/**
* @brief Get field chan1_raw from hil_rc_inputs_raw message
*
* @return RC channel 1 value, in microseconds
*/
static inline uint16_t mavlink_msg_hil_rc_inputs_raw_get_chan1_raw(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 8);
}
 
/**
* @brief Get field chan2_raw from hil_rc_inputs_raw message
*
* @return RC channel 2 value, in microseconds
*/
static inline uint16_t mavlink_msg_hil_rc_inputs_raw_get_chan2_raw(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 10);
}
 
/**
* @brief Get field chan3_raw from hil_rc_inputs_raw message
*
* @return RC channel 3 value, in microseconds
*/
static inline uint16_t mavlink_msg_hil_rc_inputs_raw_get_chan3_raw(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 12);
}
 
/**
* @brief Get field chan4_raw from hil_rc_inputs_raw message
*
* @return RC channel 4 value, in microseconds
*/
static inline uint16_t mavlink_msg_hil_rc_inputs_raw_get_chan4_raw(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 14);
}
 
/**
* @brief Get field chan5_raw from hil_rc_inputs_raw message
*
* @return RC channel 5 value, in microseconds
*/
static inline uint16_t mavlink_msg_hil_rc_inputs_raw_get_chan5_raw(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 16);
}
 
/**
* @brief Get field chan6_raw from hil_rc_inputs_raw message
*
* @return RC channel 6 value, in microseconds
*/
static inline uint16_t mavlink_msg_hil_rc_inputs_raw_get_chan6_raw(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 18);
}
 
/**
* @brief Get field chan7_raw from hil_rc_inputs_raw message
*
* @return RC channel 7 value, in microseconds
*/
static inline uint16_t mavlink_msg_hil_rc_inputs_raw_get_chan7_raw(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 20);
}
 
/**
* @brief Get field chan8_raw from hil_rc_inputs_raw message
*
* @return RC channel 8 value, in microseconds
*/
static inline uint16_t mavlink_msg_hil_rc_inputs_raw_get_chan8_raw(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 22);
}
 
/**
* @brief Get field chan9_raw from hil_rc_inputs_raw message
*
* @return RC channel 9 value, in microseconds
*/
static inline uint16_t mavlink_msg_hil_rc_inputs_raw_get_chan9_raw(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 24);
}
 
/**
* @brief Get field chan10_raw from hil_rc_inputs_raw message
*
* @return RC channel 10 value, in microseconds
*/
static inline uint16_t mavlink_msg_hil_rc_inputs_raw_get_chan10_raw(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 26);
}
 
/**
* @brief Get field chan11_raw from hil_rc_inputs_raw message
*
* @return RC channel 11 value, in microseconds
*/
static inline uint16_t mavlink_msg_hil_rc_inputs_raw_get_chan11_raw(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 28);
}
 
/**
* @brief Get field chan12_raw from hil_rc_inputs_raw message
*
* @return RC channel 12 value, in microseconds
*/
static inline uint16_t mavlink_msg_hil_rc_inputs_raw_get_chan12_raw(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 30);
}
 
/**
* @brief Get field rssi from hil_rc_inputs_raw message
*
* @return Receive signal strength indicator, 0: 0%, 255: 100%
*/
static inline uint8_t mavlink_msg_hil_rc_inputs_raw_get_rssi(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 32);
}
 
/**
* @brief Decode a hil_rc_inputs_raw message into a struct
*
* @param msg The message to decode
* @param hil_rc_inputs_raw C-struct to decode the message contents into
*/
static inline void mavlink_msg_hil_rc_inputs_raw_decode(const mavlink_message_t* msg, mavlink_hil_rc_inputs_raw_t* hil_rc_inputs_raw)
{
#if MAVLINK_NEED_BYTE_SWAP
hil_rc_inputs_raw->time_usec = mavlink_msg_hil_rc_inputs_raw_get_time_usec(msg);
hil_rc_inputs_raw->chan1_raw = mavlink_msg_hil_rc_inputs_raw_get_chan1_raw(msg);
hil_rc_inputs_raw->chan2_raw = mavlink_msg_hil_rc_inputs_raw_get_chan2_raw(msg);
hil_rc_inputs_raw->chan3_raw = mavlink_msg_hil_rc_inputs_raw_get_chan3_raw(msg);
hil_rc_inputs_raw->chan4_raw = mavlink_msg_hil_rc_inputs_raw_get_chan4_raw(msg);
hil_rc_inputs_raw->chan5_raw = mavlink_msg_hil_rc_inputs_raw_get_chan5_raw(msg);
hil_rc_inputs_raw->chan6_raw = mavlink_msg_hil_rc_inputs_raw_get_chan6_raw(msg);
hil_rc_inputs_raw->chan7_raw = mavlink_msg_hil_rc_inputs_raw_get_chan7_raw(msg);
hil_rc_inputs_raw->chan8_raw = mavlink_msg_hil_rc_inputs_raw_get_chan8_raw(msg);
hil_rc_inputs_raw->chan9_raw = mavlink_msg_hil_rc_inputs_raw_get_chan9_raw(msg);
hil_rc_inputs_raw->chan10_raw = mavlink_msg_hil_rc_inputs_raw_get_chan10_raw(msg);
hil_rc_inputs_raw->chan11_raw = mavlink_msg_hil_rc_inputs_raw_get_chan11_raw(msg);
hil_rc_inputs_raw->chan12_raw = mavlink_msg_hil_rc_inputs_raw_get_chan12_raw(msg);
hil_rc_inputs_raw->rssi = mavlink_msg_hil_rc_inputs_raw_get_rssi(msg);
#else
memcpy(hil_rc_inputs_raw, _MAV_PAYLOAD(msg), 33);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v1.0/common/mavlink_msg_hil_state.h
0,0 → 1,474
// MESSAGE HIL_STATE PACKING
 
#define MAVLINK_MSG_ID_HIL_STATE 90
 
typedef struct __mavlink_hil_state_t
{
uint64_t time_usec; ///< Timestamp (microseconds since UNIX epoch or microseconds since system boot)
float roll; ///< Roll angle (rad)
float pitch; ///< Pitch angle (rad)
float yaw; ///< Yaw angle (rad)
float rollspeed; ///< Roll angular speed (rad/s)
float pitchspeed; ///< Pitch angular speed (rad/s)
float yawspeed; ///< Yaw angular speed (rad/s)
int32_t lat; ///< Latitude, expressed as * 1E7
int32_t lon; ///< Longitude, expressed as * 1E7
int32_t alt; ///< Altitude in meters, expressed as * 1000 (millimeters)
int16_t vx; ///< Ground X Speed (Latitude), expressed as m/s * 100
int16_t vy; ///< Ground Y Speed (Longitude), expressed as m/s * 100
int16_t vz; ///< Ground Z Speed (Altitude), expressed as m/s * 100
int16_t xacc; ///< X acceleration (mg)
int16_t yacc; ///< Y acceleration (mg)
int16_t zacc; ///< Z acceleration (mg)
} mavlink_hil_state_t;
 
#define MAVLINK_MSG_ID_HIL_STATE_LEN 56
#define MAVLINK_MSG_ID_90_LEN 56
 
 
 
#define MAVLINK_MESSAGE_INFO_HIL_STATE { \
"HIL_STATE", \
16, \
{ { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_hil_state_t, time_usec) }, \
{ "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_hil_state_t, roll) }, \
{ "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_hil_state_t, pitch) }, \
{ "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_hil_state_t, yaw) }, \
{ "rollspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_hil_state_t, rollspeed) }, \
{ "pitchspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_hil_state_t, pitchspeed) }, \
{ "yawspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_hil_state_t, yawspeed) }, \
{ "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 32, offsetof(mavlink_hil_state_t, lat) }, \
{ "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 36, offsetof(mavlink_hil_state_t, lon) }, \
{ "alt", NULL, MAVLINK_TYPE_INT32_T, 0, 40, offsetof(mavlink_hil_state_t, alt) }, \
{ "vx", NULL, MAVLINK_TYPE_INT16_T, 0, 44, offsetof(mavlink_hil_state_t, vx) }, \
{ "vy", NULL, MAVLINK_TYPE_INT16_T, 0, 46, offsetof(mavlink_hil_state_t, vy) }, \
{ "vz", NULL, MAVLINK_TYPE_INT16_T, 0, 48, offsetof(mavlink_hil_state_t, vz) }, \
{ "xacc", NULL, MAVLINK_TYPE_INT16_T, 0, 50, offsetof(mavlink_hil_state_t, xacc) }, \
{ "yacc", NULL, MAVLINK_TYPE_INT16_T, 0, 52, offsetof(mavlink_hil_state_t, yacc) }, \
{ "zacc", NULL, MAVLINK_TYPE_INT16_T, 0, 54, offsetof(mavlink_hil_state_t, zacc) }, \
} \
}
 
 
/**
* @brief Pack a hil_state message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
* @param roll Roll angle (rad)
* @param pitch Pitch angle (rad)
* @param yaw Yaw angle (rad)
* @param rollspeed Roll angular speed (rad/s)
* @param pitchspeed Pitch angular speed (rad/s)
* @param yawspeed Yaw angular speed (rad/s)
* @param lat Latitude, expressed as * 1E7
* @param lon Longitude, expressed as * 1E7
* @param alt Altitude in meters, expressed as * 1000 (millimeters)
* @param vx Ground X Speed (Latitude), expressed as m/s * 100
* @param vy Ground Y Speed (Longitude), expressed as m/s * 100
* @param vz Ground Z Speed (Altitude), expressed as m/s * 100
* @param xacc X acceleration (mg)
* @param yacc Y acceleration (mg)
* @param zacc Z acceleration (mg)
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_hil_state_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint64_t time_usec, float roll, float pitch, float yaw, float rollspeed, float pitchspeed, float yawspeed, int32_t lat, int32_t lon, int32_t alt, int16_t vx, int16_t vy, int16_t vz, int16_t xacc, int16_t yacc, int16_t zacc)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[56];
_mav_put_uint64_t(buf, 0, time_usec);
_mav_put_float(buf, 8, roll);
_mav_put_float(buf, 12, pitch);
_mav_put_float(buf, 16, yaw);
_mav_put_float(buf, 20, rollspeed);
_mav_put_float(buf, 24, pitchspeed);
_mav_put_float(buf, 28, yawspeed);
_mav_put_int32_t(buf, 32, lat);
_mav_put_int32_t(buf, 36, lon);
_mav_put_int32_t(buf, 40, alt);
_mav_put_int16_t(buf, 44, vx);
_mav_put_int16_t(buf, 46, vy);
_mav_put_int16_t(buf, 48, vz);
_mav_put_int16_t(buf, 50, xacc);
_mav_put_int16_t(buf, 52, yacc);
_mav_put_int16_t(buf, 54, zacc);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 56);
#else
mavlink_hil_state_t packet;
packet.time_usec = time_usec;
packet.roll = roll;
packet.pitch = pitch;
packet.yaw = yaw;
packet.rollspeed = rollspeed;
packet.pitchspeed = pitchspeed;
packet.yawspeed = yawspeed;
packet.lat = lat;
packet.lon = lon;
packet.alt = alt;
packet.vx = vx;
packet.vy = vy;
packet.vz = vz;
packet.xacc = xacc;
packet.yacc = yacc;
packet.zacc = zacc;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 56);
#endif
 
msg->msgid = MAVLINK_MSG_ID_HIL_STATE;
return mavlink_finalize_message(msg, system_id, component_id, 56, 183);
}
 
/**
* @brief Pack a hil_state message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
* @param roll Roll angle (rad)
* @param pitch Pitch angle (rad)
* @param yaw Yaw angle (rad)
* @param rollspeed Roll angular speed (rad/s)
* @param pitchspeed Pitch angular speed (rad/s)
* @param yawspeed Yaw angular speed (rad/s)
* @param lat Latitude, expressed as * 1E7
* @param lon Longitude, expressed as * 1E7
* @param alt Altitude in meters, expressed as * 1000 (millimeters)
* @param vx Ground X Speed (Latitude), expressed as m/s * 100
* @param vy Ground Y Speed (Longitude), expressed as m/s * 100
* @param vz Ground Z Speed (Altitude), expressed as m/s * 100
* @param xacc X acceleration (mg)
* @param yacc Y acceleration (mg)
* @param zacc Z acceleration (mg)
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_hil_state_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint64_t time_usec,float roll,float pitch,float yaw,float rollspeed,float pitchspeed,float yawspeed,int32_t lat,int32_t lon,int32_t alt,int16_t vx,int16_t vy,int16_t vz,int16_t xacc,int16_t yacc,int16_t zacc)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[56];
_mav_put_uint64_t(buf, 0, time_usec);
_mav_put_float(buf, 8, roll);
_mav_put_float(buf, 12, pitch);
_mav_put_float(buf, 16, yaw);
_mav_put_float(buf, 20, rollspeed);
_mav_put_float(buf, 24, pitchspeed);
_mav_put_float(buf, 28, yawspeed);
_mav_put_int32_t(buf, 32, lat);
_mav_put_int32_t(buf, 36, lon);
_mav_put_int32_t(buf, 40, alt);
_mav_put_int16_t(buf, 44, vx);
_mav_put_int16_t(buf, 46, vy);
_mav_put_int16_t(buf, 48, vz);
_mav_put_int16_t(buf, 50, xacc);
_mav_put_int16_t(buf, 52, yacc);
_mav_put_int16_t(buf, 54, zacc);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 56);
#else
mavlink_hil_state_t packet;
packet.time_usec = time_usec;
packet.roll = roll;
packet.pitch = pitch;
packet.yaw = yaw;
packet.rollspeed = rollspeed;
packet.pitchspeed = pitchspeed;
packet.yawspeed = yawspeed;
packet.lat = lat;
packet.lon = lon;
packet.alt = alt;
packet.vx = vx;
packet.vy = vy;
packet.vz = vz;
packet.xacc = xacc;
packet.yacc = yacc;
packet.zacc = zacc;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 56);
#endif
 
msg->msgid = MAVLINK_MSG_ID_HIL_STATE;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 56, 183);
}
 
/**
* @brief Encode a hil_state struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param hil_state C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_hil_state_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_hil_state_t* hil_state)
{
return mavlink_msg_hil_state_pack(system_id, component_id, msg, hil_state->time_usec, hil_state->roll, hil_state->pitch, hil_state->yaw, hil_state->rollspeed, hil_state->pitchspeed, hil_state->yawspeed, hil_state->lat, hil_state->lon, hil_state->alt, hil_state->vx, hil_state->vy, hil_state->vz, hil_state->xacc, hil_state->yacc, hil_state->zacc);
}
 
/**
* @brief Send a hil_state message
* @param chan MAVLink channel to send the message
*
* @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
* @param roll Roll angle (rad)
* @param pitch Pitch angle (rad)
* @param yaw Yaw angle (rad)
* @param rollspeed Roll angular speed (rad/s)
* @param pitchspeed Pitch angular speed (rad/s)
* @param yawspeed Yaw angular speed (rad/s)
* @param lat Latitude, expressed as * 1E7
* @param lon Longitude, expressed as * 1E7
* @param alt Altitude in meters, expressed as * 1000 (millimeters)
* @param vx Ground X Speed (Latitude), expressed as m/s * 100
* @param vy Ground Y Speed (Longitude), expressed as m/s * 100
* @param vz Ground Z Speed (Altitude), expressed as m/s * 100
* @param xacc X acceleration (mg)
* @param yacc Y acceleration (mg)
* @param zacc Z acceleration (mg)
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_hil_state_send(mavlink_channel_t chan, uint64_t time_usec, float roll, float pitch, float yaw, float rollspeed, float pitchspeed, float yawspeed, int32_t lat, int32_t lon, int32_t alt, int16_t vx, int16_t vy, int16_t vz, int16_t xacc, int16_t yacc, int16_t zacc)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[56];
_mav_put_uint64_t(buf, 0, time_usec);
_mav_put_float(buf, 8, roll);
_mav_put_float(buf, 12, pitch);
_mav_put_float(buf, 16, yaw);
_mav_put_float(buf, 20, rollspeed);
_mav_put_float(buf, 24, pitchspeed);
_mav_put_float(buf, 28, yawspeed);
_mav_put_int32_t(buf, 32, lat);
_mav_put_int32_t(buf, 36, lon);
_mav_put_int32_t(buf, 40, alt);
_mav_put_int16_t(buf, 44, vx);
_mav_put_int16_t(buf, 46, vy);
_mav_put_int16_t(buf, 48, vz);
_mav_put_int16_t(buf, 50, xacc);
_mav_put_int16_t(buf, 52, yacc);
_mav_put_int16_t(buf, 54, zacc);
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_STATE, buf, 56, 183);
#else
mavlink_hil_state_t packet;
packet.time_usec = time_usec;
packet.roll = roll;
packet.pitch = pitch;
packet.yaw = yaw;
packet.rollspeed = rollspeed;
packet.pitchspeed = pitchspeed;
packet.yawspeed = yawspeed;
packet.lat = lat;
packet.lon = lon;
packet.alt = alt;
packet.vx = vx;
packet.vy = vy;
packet.vz = vz;
packet.xacc = xacc;
packet.yacc = yacc;
packet.zacc = zacc;
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_STATE, (const char *)&packet, 56, 183);
#endif
}
 
#endif
 
// MESSAGE HIL_STATE UNPACKING
 
 
/**
* @brief Get field time_usec from hil_state message
*
* @return Timestamp (microseconds since UNIX epoch or microseconds since system boot)
*/
static inline uint64_t mavlink_msg_hil_state_get_time_usec(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint64_t(msg, 0);
}
 
/**
* @brief Get field roll from hil_state message
*
* @return Roll angle (rad)
*/
static inline float mavlink_msg_hil_state_get_roll(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 8);
}
 
/**
* @brief Get field pitch from hil_state message
*
* @return Pitch angle (rad)
*/
static inline float mavlink_msg_hil_state_get_pitch(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 12);
}
 
/**
* @brief Get field yaw from hil_state message
*
* @return Yaw angle (rad)
*/
static inline float mavlink_msg_hil_state_get_yaw(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 16);
}
 
/**
* @brief Get field rollspeed from hil_state message
*
* @return Roll angular speed (rad/s)
*/
static inline float mavlink_msg_hil_state_get_rollspeed(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 20);
}
 
/**
* @brief Get field pitchspeed from hil_state message
*
* @return Pitch angular speed (rad/s)
*/
static inline float mavlink_msg_hil_state_get_pitchspeed(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 24);
}
 
/**
* @brief Get field yawspeed from hil_state message
*
* @return Yaw angular speed (rad/s)
*/
static inline float mavlink_msg_hil_state_get_yawspeed(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 28);
}
 
/**
* @brief Get field lat from hil_state message
*
* @return Latitude, expressed as * 1E7
*/
static inline int32_t mavlink_msg_hil_state_get_lat(const mavlink_message_t* msg)
{
return _MAV_RETURN_int32_t(msg, 32);
}
 
/**
* @brief Get field lon from hil_state message
*
* @return Longitude, expressed as * 1E7
*/
static inline int32_t mavlink_msg_hil_state_get_lon(const mavlink_message_t* msg)
{
return _MAV_RETURN_int32_t(msg, 36);
}
 
/**
* @brief Get field alt from hil_state message
*
* @return Altitude in meters, expressed as * 1000 (millimeters)
*/
static inline int32_t mavlink_msg_hil_state_get_alt(const mavlink_message_t* msg)
{
return _MAV_RETURN_int32_t(msg, 40);
}
 
/**
* @brief Get field vx from hil_state message
*
* @return Ground X Speed (Latitude), expressed as m/s * 100
*/
static inline int16_t mavlink_msg_hil_state_get_vx(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 44);
}
 
/**
* @brief Get field vy from hil_state message
*
* @return Ground Y Speed (Longitude), expressed as m/s * 100
*/
static inline int16_t mavlink_msg_hil_state_get_vy(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 46);
}
 
/**
* @brief Get field vz from hil_state message
*
* @return Ground Z Speed (Altitude), expressed as m/s * 100
*/
static inline int16_t mavlink_msg_hil_state_get_vz(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 48);
}
 
/**
* @brief Get field xacc from hil_state message
*
* @return X acceleration (mg)
*/
static inline int16_t mavlink_msg_hil_state_get_xacc(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 50);
}
 
/**
* @brief Get field yacc from hil_state message
*
* @return Y acceleration (mg)
*/
static inline int16_t mavlink_msg_hil_state_get_yacc(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 52);
}
 
/**
* @brief Get field zacc from hil_state message
*
* @return Z acceleration (mg)
*/
static inline int16_t mavlink_msg_hil_state_get_zacc(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 54);
}
 
/**
* @brief Decode a hil_state message into a struct
*
* @param msg The message to decode
* @param hil_state C-struct to decode the message contents into
*/
static inline void mavlink_msg_hil_state_decode(const mavlink_message_t* msg, mavlink_hil_state_t* hil_state)
{
#if MAVLINK_NEED_BYTE_SWAP
hil_state->time_usec = mavlink_msg_hil_state_get_time_usec(msg);
hil_state->roll = mavlink_msg_hil_state_get_roll(msg);
hil_state->pitch = mavlink_msg_hil_state_get_pitch(msg);
hil_state->yaw = mavlink_msg_hil_state_get_yaw(msg);
hil_state->rollspeed = mavlink_msg_hil_state_get_rollspeed(msg);
hil_state->pitchspeed = mavlink_msg_hil_state_get_pitchspeed(msg);
hil_state->yawspeed = mavlink_msg_hil_state_get_yawspeed(msg);
hil_state->lat = mavlink_msg_hil_state_get_lat(msg);
hil_state->lon = mavlink_msg_hil_state_get_lon(msg);
hil_state->alt = mavlink_msg_hil_state_get_alt(msg);
hil_state->vx = mavlink_msg_hil_state_get_vx(msg);
hil_state->vy = mavlink_msg_hil_state_get_vy(msg);
hil_state->vz = mavlink_msg_hil_state_get_vz(msg);
hil_state->xacc = mavlink_msg_hil_state_get_xacc(msg);
hil_state->yacc = mavlink_msg_hil_state_get_yacc(msg);
hil_state->zacc = mavlink_msg_hil_state_get_zacc(msg);
#else
memcpy(hil_state, _MAV_PAYLOAD(msg), 56);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v1.0/common/mavlink_msg_local_position_ned.h
0,0 → 1,276
// MESSAGE LOCAL_POSITION_NED PACKING
 
#define MAVLINK_MSG_ID_LOCAL_POSITION_NED 32
 
typedef struct __mavlink_local_position_ned_t
{
uint32_t time_boot_ms; ///< Timestamp (milliseconds since system boot)
float x; ///< X Position
float y; ///< Y Position
float z; ///< Z Position
float vx; ///< X Speed
float vy; ///< Y Speed
float vz; ///< Z Speed
} mavlink_local_position_ned_t;
 
#define MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN 28
#define MAVLINK_MSG_ID_32_LEN 28
 
 
 
#define MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED { \
"LOCAL_POSITION_NED", \
7, \
{ { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_local_position_ned_t, time_boot_ms) }, \
{ "x", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_local_position_ned_t, x) }, \
{ "y", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_local_position_ned_t, y) }, \
{ "z", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_local_position_ned_t, z) }, \
{ "vx", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_local_position_ned_t, vx) }, \
{ "vy", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_local_position_ned_t, vy) }, \
{ "vz", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_local_position_ned_t, vz) }, \
} \
}
 
 
/**
* @brief Pack a local_position_ned message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param time_boot_ms Timestamp (milliseconds since system boot)
* @param x X Position
* @param y Y Position
* @param z Z Position
* @param vx X Speed
* @param vy Y Speed
* @param vz Z Speed
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_local_position_ned_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint32_t time_boot_ms, float x, float y, float z, float vx, float vy, float vz)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[28];
_mav_put_uint32_t(buf, 0, time_boot_ms);
_mav_put_float(buf, 4, x);
_mav_put_float(buf, 8, y);
_mav_put_float(buf, 12, z);
_mav_put_float(buf, 16, vx);
_mav_put_float(buf, 20, vy);
_mav_put_float(buf, 24, vz);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 28);
#else
mavlink_local_position_ned_t packet;
packet.time_boot_ms = time_boot_ms;
packet.x = x;
packet.y = y;
packet.z = z;
packet.vx = vx;
packet.vy = vy;
packet.vz = vz;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 28);
#endif
 
msg->msgid = MAVLINK_MSG_ID_LOCAL_POSITION_NED;
return mavlink_finalize_message(msg, system_id, component_id, 28, 185);
}
 
/**
* @brief Pack a local_position_ned message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param time_boot_ms Timestamp (milliseconds since system boot)
* @param x X Position
* @param y Y Position
* @param z Z Position
* @param vx X Speed
* @param vy Y Speed
* @param vz Z Speed
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_local_position_ned_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint32_t time_boot_ms,float x,float y,float z,float vx,float vy,float vz)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[28];
_mav_put_uint32_t(buf, 0, time_boot_ms);
_mav_put_float(buf, 4, x);
_mav_put_float(buf, 8, y);
_mav_put_float(buf, 12, z);
_mav_put_float(buf, 16, vx);
_mav_put_float(buf, 20, vy);
_mav_put_float(buf, 24, vz);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 28);
#else
mavlink_local_position_ned_t packet;
packet.time_boot_ms = time_boot_ms;
packet.x = x;
packet.y = y;
packet.z = z;
packet.vx = vx;
packet.vy = vy;
packet.vz = vz;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 28);
#endif
 
msg->msgid = MAVLINK_MSG_ID_LOCAL_POSITION_NED;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 28, 185);
}
 
/**
* @brief Encode a local_position_ned struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param local_position_ned C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_local_position_ned_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_local_position_ned_t* local_position_ned)
{
return mavlink_msg_local_position_ned_pack(system_id, component_id, msg, local_position_ned->time_boot_ms, local_position_ned->x, local_position_ned->y, local_position_ned->z, local_position_ned->vx, local_position_ned->vy, local_position_ned->vz);
}
 
/**
* @brief Send a local_position_ned message
* @param chan MAVLink channel to send the message
*
* @param time_boot_ms Timestamp (milliseconds since system boot)
* @param x X Position
* @param y Y Position
* @param z Z Position
* @param vx X Speed
* @param vy Y Speed
* @param vz Z Speed
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_local_position_ned_send(mavlink_channel_t chan, uint32_t time_boot_ms, float x, float y, float z, float vx, float vy, float vz)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[28];
_mav_put_uint32_t(buf, 0, time_boot_ms);
_mav_put_float(buf, 4, x);
_mav_put_float(buf, 8, y);
_mav_put_float(buf, 12, z);
_mav_put_float(buf, 16, vx);
_mav_put_float(buf, 20, vy);
_mav_put_float(buf, 24, vz);
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED, buf, 28, 185);
#else
mavlink_local_position_ned_t packet;
packet.time_boot_ms = time_boot_ms;
packet.x = x;
packet.y = y;
packet.z = z;
packet.vx = vx;
packet.vy = vy;
packet.vz = vz;
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED, (const char *)&packet, 28, 185);
#endif
}
 
#endif
 
// MESSAGE LOCAL_POSITION_NED UNPACKING
 
 
/**
* @brief Get field time_boot_ms from local_position_ned message
*
* @return Timestamp (milliseconds since system boot)
*/
static inline uint32_t mavlink_msg_local_position_ned_get_time_boot_ms(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint32_t(msg, 0);
}
 
/**
* @brief Get field x from local_position_ned message
*
* @return X Position
*/
static inline float mavlink_msg_local_position_ned_get_x(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 4);
}
 
/**
* @brief Get field y from local_position_ned message
*
* @return Y Position
*/
static inline float mavlink_msg_local_position_ned_get_y(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 8);
}
 
/**
* @brief Get field z from local_position_ned message
*
* @return Z Position
*/
static inline float mavlink_msg_local_position_ned_get_z(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 12);
}
 
/**
* @brief Get field vx from local_position_ned message
*
* @return X Speed
*/
static inline float mavlink_msg_local_position_ned_get_vx(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 16);
}
 
/**
* @brief Get field vy from local_position_ned message
*
* @return Y Speed
*/
static inline float mavlink_msg_local_position_ned_get_vy(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 20);
}
 
/**
* @brief Get field vz from local_position_ned message
*
* @return Z Speed
*/
static inline float mavlink_msg_local_position_ned_get_vz(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 24);
}
 
/**
* @brief Decode a local_position_ned message into a struct
*
* @param msg The message to decode
* @param local_position_ned C-struct to decode the message contents into
*/
static inline void mavlink_msg_local_position_ned_decode(const mavlink_message_t* msg, mavlink_local_position_ned_t* local_position_ned)
{
#if MAVLINK_NEED_BYTE_SWAP
local_position_ned->time_boot_ms = mavlink_msg_local_position_ned_get_time_boot_ms(msg);
local_position_ned->x = mavlink_msg_local_position_ned_get_x(msg);
local_position_ned->y = mavlink_msg_local_position_ned_get_y(msg);
local_position_ned->z = mavlink_msg_local_position_ned_get_z(msg);
local_position_ned->vx = mavlink_msg_local_position_ned_get_vx(msg);
local_position_ned->vy = mavlink_msg_local_position_ned_get_vy(msg);
local_position_ned->vz = mavlink_msg_local_position_ned_get_vz(msg);
#else
memcpy(local_position_ned, _MAV_PAYLOAD(msg), 28);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v1.0/common/mavlink_msg_local_position_ned_system_global_offset.h
0,0 → 1,276
// MESSAGE LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET PACKING
 
#define MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET 89
 
typedef struct __mavlink_local_position_ned_system_global_offset_t
{
uint32_t time_boot_ms; ///< Timestamp (milliseconds since system boot)
float x; ///< X Position
float y; ///< Y Position
float z; ///< Z Position
float roll; ///< Roll
float pitch; ///< Pitch
float yaw; ///< Yaw
} mavlink_local_position_ned_system_global_offset_t;
 
#define MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN 28
#define MAVLINK_MSG_ID_89_LEN 28
 
 
 
#define MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET { \
"LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET", \
7, \
{ { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_local_position_ned_system_global_offset_t, time_boot_ms) }, \
{ "x", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_local_position_ned_system_global_offset_t, x) }, \
{ "y", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_local_position_ned_system_global_offset_t, y) }, \
{ "z", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_local_position_ned_system_global_offset_t, z) }, \
{ "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_local_position_ned_system_global_offset_t, roll) }, \
{ "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_local_position_ned_system_global_offset_t, pitch) }, \
{ "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_local_position_ned_system_global_offset_t, yaw) }, \
} \
}
 
 
/**
* @brief Pack a local_position_ned_system_global_offset message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param time_boot_ms Timestamp (milliseconds since system boot)
* @param x X Position
* @param y Y Position
* @param z Z Position
* @param roll Roll
* @param pitch Pitch
* @param yaw Yaw
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_local_position_ned_system_global_offset_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint32_t time_boot_ms, float x, float y, float z, float roll, float pitch, float yaw)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[28];
_mav_put_uint32_t(buf, 0, time_boot_ms);
_mav_put_float(buf, 4, x);
_mav_put_float(buf, 8, y);
_mav_put_float(buf, 12, z);
_mav_put_float(buf, 16, roll);
_mav_put_float(buf, 20, pitch);
_mav_put_float(buf, 24, yaw);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 28);
#else
mavlink_local_position_ned_system_global_offset_t packet;
packet.time_boot_ms = time_boot_ms;
packet.x = x;
packet.y = y;
packet.z = z;
packet.roll = roll;
packet.pitch = pitch;
packet.yaw = yaw;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 28);
#endif
 
msg->msgid = MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET;
return mavlink_finalize_message(msg, system_id, component_id, 28, 231);
}
 
/**
* @brief Pack a local_position_ned_system_global_offset message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param time_boot_ms Timestamp (milliseconds since system boot)
* @param x X Position
* @param y Y Position
* @param z Z Position
* @param roll Roll
* @param pitch Pitch
* @param yaw Yaw
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_local_position_ned_system_global_offset_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint32_t time_boot_ms,float x,float y,float z,float roll,float pitch,float yaw)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[28];
_mav_put_uint32_t(buf, 0, time_boot_ms);
_mav_put_float(buf, 4, x);
_mav_put_float(buf, 8, y);
_mav_put_float(buf, 12, z);
_mav_put_float(buf, 16, roll);
_mav_put_float(buf, 20, pitch);
_mav_put_float(buf, 24, yaw);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 28);
#else
mavlink_local_position_ned_system_global_offset_t packet;
packet.time_boot_ms = time_boot_ms;
packet.x = x;
packet.y = y;
packet.z = z;
packet.roll = roll;
packet.pitch = pitch;
packet.yaw = yaw;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 28);
#endif
 
msg->msgid = MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 28, 231);
}
 
/**
* @brief Encode a local_position_ned_system_global_offset struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param local_position_ned_system_global_offset C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_local_position_ned_system_global_offset_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_local_position_ned_system_global_offset_t* local_position_ned_system_global_offset)
{
return mavlink_msg_local_position_ned_system_global_offset_pack(system_id, component_id, msg, local_position_ned_system_global_offset->time_boot_ms, local_position_ned_system_global_offset->x, local_position_ned_system_global_offset->y, local_position_ned_system_global_offset->z, local_position_ned_system_global_offset->roll, local_position_ned_system_global_offset->pitch, local_position_ned_system_global_offset->yaw);
}
 
/**
* @brief Send a local_position_ned_system_global_offset message
* @param chan MAVLink channel to send the message
*
* @param time_boot_ms Timestamp (milliseconds since system boot)
* @param x X Position
* @param y Y Position
* @param z Z Position
* @param roll Roll
* @param pitch Pitch
* @param yaw Yaw
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_local_position_ned_system_global_offset_send(mavlink_channel_t chan, uint32_t time_boot_ms, float x, float y, float z, float roll, float pitch, float yaw)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[28];
_mav_put_uint32_t(buf, 0, time_boot_ms);
_mav_put_float(buf, 4, x);
_mav_put_float(buf, 8, y);
_mav_put_float(buf, 12, z);
_mav_put_float(buf, 16, roll);
_mav_put_float(buf, 20, pitch);
_mav_put_float(buf, 24, yaw);
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET, buf, 28, 231);
#else
mavlink_local_position_ned_system_global_offset_t packet;
packet.time_boot_ms = time_boot_ms;
packet.x = x;
packet.y = y;
packet.z = z;
packet.roll = roll;
packet.pitch = pitch;
packet.yaw = yaw;
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET, (const char *)&packet, 28, 231);
#endif
}
 
#endif
 
// MESSAGE LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET UNPACKING
 
 
/**
* @brief Get field time_boot_ms from local_position_ned_system_global_offset message
*
* @return Timestamp (milliseconds since system boot)
*/
static inline uint32_t mavlink_msg_local_position_ned_system_global_offset_get_time_boot_ms(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint32_t(msg, 0);
}
 
/**
* @brief Get field x from local_position_ned_system_global_offset message
*
* @return X Position
*/
static inline float mavlink_msg_local_position_ned_system_global_offset_get_x(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 4);
}
 
/**
* @brief Get field y from local_position_ned_system_global_offset message
*
* @return Y Position
*/
static inline float mavlink_msg_local_position_ned_system_global_offset_get_y(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 8);
}
 
/**
* @brief Get field z from local_position_ned_system_global_offset message
*
* @return Z Position
*/
static inline float mavlink_msg_local_position_ned_system_global_offset_get_z(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 12);
}
 
/**
* @brief Get field roll from local_position_ned_system_global_offset message
*
* @return Roll
*/
static inline float mavlink_msg_local_position_ned_system_global_offset_get_roll(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 16);
}
 
/**
* @brief Get field pitch from local_position_ned_system_global_offset message
*
* @return Pitch
*/
static inline float mavlink_msg_local_position_ned_system_global_offset_get_pitch(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 20);
}
 
/**
* @brief Get field yaw from local_position_ned_system_global_offset message
*
* @return Yaw
*/
static inline float mavlink_msg_local_position_ned_system_global_offset_get_yaw(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 24);
}
 
/**
* @brief Decode a local_position_ned_system_global_offset message into a struct
*
* @param msg The message to decode
* @param local_position_ned_system_global_offset C-struct to decode the message contents into
*/
static inline void mavlink_msg_local_position_ned_system_global_offset_decode(const mavlink_message_t* msg, mavlink_local_position_ned_system_global_offset_t* local_position_ned_system_global_offset)
{
#if MAVLINK_NEED_BYTE_SWAP
local_position_ned_system_global_offset->time_boot_ms = mavlink_msg_local_position_ned_system_global_offset_get_time_boot_ms(msg);
local_position_ned_system_global_offset->x = mavlink_msg_local_position_ned_system_global_offset_get_x(msg);
local_position_ned_system_global_offset->y = mavlink_msg_local_position_ned_system_global_offset_get_y(msg);
local_position_ned_system_global_offset->z = mavlink_msg_local_position_ned_system_global_offset_get_z(msg);
local_position_ned_system_global_offset->roll = mavlink_msg_local_position_ned_system_global_offset_get_roll(msg);
local_position_ned_system_global_offset->pitch = mavlink_msg_local_position_ned_system_global_offset_get_pitch(msg);
local_position_ned_system_global_offset->yaw = mavlink_msg_local_position_ned_system_global_offset_get_yaw(msg);
#else
memcpy(local_position_ned_system_global_offset, _MAV_PAYLOAD(msg), 28);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v1.0/common/mavlink_msg_local_position_setpoint.h
0,0 → 1,232
// MESSAGE LOCAL_POSITION_SETPOINT PACKING
 
#define MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT 51
 
typedef struct __mavlink_local_position_setpoint_t
{
float x; ///< x position
float y; ///< y position
float z; ///< z position
float yaw; ///< Desired yaw angle
uint8_t coordinate_frame; ///< Coordinate frame - valid values are only MAV_FRAME_LOCAL_NED or MAV_FRAME_LOCAL_ENU
} mavlink_local_position_setpoint_t;
 
#define MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT_LEN 17
#define MAVLINK_MSG_ID_51_LEN 17
 
 
 
#define MAVLINK_MESSAGE_INFO_LOCAL_POSITION_SETPOINT { \
"LOCAL_POSITION_SETPOINT", \
5, \
{ { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_local_position_setpoint_t, x) }, \
{ "y", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_local_position_setpoint_t, y) }, \
{ "z", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_local_position_setpoint_t, z) }, \
{ "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_local_position_setpoint_t, yaw) }, \
{ "coordinate_frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 16, offsetof(mavlink_local_position_setpoint_t, coordinate_frame) }, \
} \
}
 
 
/**
* @brief Pack a local_position_setpoint message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param coordinate_frame Coordinate frame - valid values are only MAV_FRAME_LOCAL_NED or MAV_FRAME_LOCAL_ENU
* @param x x position
* @param y y position
* @param z z position
* @param yaw Desired yaw angle
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_local_position_setpoint_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t coordinate_frame, float x, float y, float z, float yaw)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[17];
_mav_put_float(buf, 0, x);
_mav_put_float(buf, 4, y);
_mav_put_float(buf, 8, z);
_mav_put_float(buf, 12, yaw);
_mav_put_uint8_t(buf, 16, coordinate_frame);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 17);
#else
mavlink_local_position_setpoint_t packet;
packet.x = x;
packet.y = y;
packet.z = z;
packet.yaw = yaw;
packet.coordinate_frame = coordinate_frame;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 17);
#endif
 
msg->msgid = MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT;
return mavlink_finalize_message(msg, system_id, component_id, 17, 223);
}
 
/**
* @brief Pack a local_position_setpoint message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param coordinate_frame Coordinate frame - valid values are only MAV_FRAME_LOCAL_NED or MAV_FRAME_LOCAL_ENU
* @param x x position
* @param y y position
* @param z z position
* @param yaw Desired yaw angle
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_local_position_setpoint_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint8_t coordinate_frame,float x,float y,float z,float yaw)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[17];
_mav_put_float(buf, 0, x);
_mav_put_float(buf, 4, y);
_mav_put_float(buf, 8, z);
_mav_put_float(buf, 12, yaw);
_mav_put_uint8_t(buf, 16, coordinate_frame);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 17);
#else
mavlink_local_position_setpoint_t packet;
packet.x = x;
packet.y = y;
packet.z = z;
packet.yaw = yaw;
packet.coordinate_frame = coordinate_frame;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 17);
#endif
 
msg->msgid = MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 17, 223);
}
 
/**
* @brief Encode a local_position_setpoint struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param local_position_setpoint C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_local_position_setpoint_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_local_position_setpoint_t* local_position_setpoint)
{
return mavlink_msg_local_position_setpoint_pack(system_id, component_id, msg, local_position_setpoint->coordinate_frame, local_position_setpoint->x, local_position_setpoint->y, local_position_setpoint->z, local_position_setpoint->yaw);
}
 
/**
* @brief Send a local_position_setpoint message
* @param chan MAVLink channel to send the message
*
* @param coordinate_frame Coordinate frame - valid values are only MAV_FRAME_LOCAL_NED or MAV_FRAME_LOCAL_ENU
* @param x x position
* @param y y position
* @param z z position
* @param yaw Desired yaw angle
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_local_position_setpoint_send(mavlink_channel_t chan, uint8_t coordinate_frame, float x, float y, float z, float yaw)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[17];
_mav_put_float(buf, 0, x);
_mav_put_float(buf, 4, y);
_mav_put_float(buf, 8, z);
_mav_put_float(buf, 12, yaw);
_mav_put_uint8_t(buf, 16, coordinate_frame);
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT, buf, 17, 223);
#else
mavlink_local_position_setpoint_t packet;
packet.x = x;
packet.y = y;
packet.z = z;
packet.yaw = yaw;
packet.coordinate_frame = coordinate_frame;
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_SETPOINT, (const char *)&packet, 17, 223);
#endif
}
 
#endif
 
// MESSAGE LOCAL_POSITION_SETPOINT UNPACKING
 
 
/**
* @brief Get field coordinate_frame from local_position_setpoint message
*
* @return Coordinate frame - valid values are only MAV_FRAME_LOCAL_NED or MAV_FRAME_LOCAL_ENU
*/
static inline uint8_t mavlink_msg_local_position_setpoint_get_coordinate_frame(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 16);
}
 
/**
* @brief Get field x from local_position_setpoint message
*
* @return x position
*/
static inline float mavlink_msg_local_position_setpoint_get_x(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 0);
}
 
/**
* @brief Get field y from local_position_setpoint message
*
* @return y position
*/
static inline float mavlink_msg_local_position_setpoint_get_y(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 4);
}
 
/**
* @brief Get field z from local_position_setpoint message
*
* @return z position
*/
static inline float mavlink_msg_local_position_setpoint_get_z(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 8);
}
 
/**
* @brief Get field yaw from local_position_setpoint message
*
* @return Desired yaw angle
*/
static inline float mavlink_msg_local_position_setpoint_get_yaw(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 12);
}
 
/**
* @brief Decode a local_position_setpoint message into a struct
*
* @param msg The message to decode
* @param local_position_setpoint C-struct to decode the message contents into
*/
static inline void mavlink_msg_local_position_setpoint_decode(const mavlink_message_t* msg, mavlink_local_position_setpoint_t* local_position_setpoint)
{
#if MAVLINK_NEED_BYTE_SWAP
local_position_setpoint->x = mavlink_msg_local_position_setpoint_get_x(msg);
local_position_setpoint->y = mavlink_msg_local_position_setpoint_get_y(msg);
local_position_setpoint->z = mavlink_msg_local_position_setpoint_get_z(msg);
local_position_setpoint->yaw = mavlink_msg_local_position_setpoint_get_yaw(msg);
local_position_setpoint->coordinate_frame = mavlink_msg_local_position_setpoint_get_coordinate_frame(msg);
#else
memcpy(local_position_setpoint, _MAV_PAYLOAD(msg), 17);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v1.0/common/mavlink_msg_manual_control.h
0,0 → 1,320
// MESSAGE MANUAL_CONTROL PACKING
 
#define MAVLINK_MSG_ID_MANUAL_CONTROL 69
 
typedef struct __mavlink_manual_control_t
{
float roll; ///< roll
float pitch; ///< pitch
float yaw; ///< yaw
float thrust; ///< thrust
uint8_t target; ///< The system to be controlled
uint8_t roll_manual; ///< roll control enabled auto:0, manual:1
uint8_t pitch_manual; ///< pitch auto:0, manual:1
uint8_t yaw_manual; ///< yaw auto:0, manual:1
uint8_t thrust_manual; ///< thrust auto:0, manual:1
} mavlink_manual_control_t;
 
#define MAVLINK_MSG_ID_MANUAL_CONTROL_LEN 21
#define MAVLINK_MSG_ID_69_LEN 21
 
 
 
#define MAVLINK_MESSAGE_INFO_MANUAL_CONTROL { \
"MANUAL_CONTROL", \
9, \
{ { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_manual_control_t, roll) }, \
{ "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_manual_control_t, pitch) }, \
{ "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_manual_control_t, yaw) }, \
{ "thrust", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_manual_control_t, thrust) }, \
{ "target", NULL, MAVLINK_TYPE_UINT8_T, 0, 16, offsetof(mavlink_manual_control_t, target) }, \
{ "roll_manual", NULL, MAVLINK_TYPE_UINT8_T, 0, 17, offsetof(mavlink_manual_control_t, roll_manual) }, \
{ "pitch_manual", NULL, MAVLINK_TYPE_UINT8_T, 0, 18, offsetof(mavlink_manual_control_t, pitch_manual) }, \
{ "yaw_manual", NULL, MAVLINK_TYPE_UINT8_T, 0, 19, offsetof(mavlink_manual_control_t, yaw_manual) }, \
{ "thrust_manual", NULL, MAVLINK_TYPE_UINT8_T, 0, 20, offsetof(mavlink_manual_control_t, thrust_manual) }, \
} \
}
 
 
/**
* @brief Pack a manual_control message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param target The system to be controlled
* @param roll roll
* @param pitch pitch
* @param yaw yaw
* @param thrust thrust
* @param roll_manual roll control enabled auto:0, manual:1
* @param pitch_manual pitch auto:0, manual:1
* @param yaw_manual yaw auto:0, manual:1
* @param thrust_manual thrust auto:0, manual:1
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_manual_control_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t target, float roll, float pitch, float yaw, float thrust, uint8_t roll_manual, uint8_t pitch_manual, uint8_t yaw_manual, uint8_t thrust_manual)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[21];
_mav_put_float(buf, 0, roll);
_mav_put_float(buf, 4, pitch);
_mav_put_float(buf, 8, yaw);
_mav_put_float(buf, 12, thrust);
_mav_put_uint8_t(buf, 16, target);
_mav_put_uint8_t(buf, 17, roll_manual);
_mav_put_uint8_t(buf, 18, pitch_manual);
_mav_put_uint8_t(buf, 19, yaw_manual);
_mav_put_uint8_t(buf, 20, thrust_manual);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 21);
#else
mavlink_manual_control_t packet;
packet.roll = roll;
packet.pitch = pitch;
packet.yaw = yaw;
packet.thrust = thrust;
packet.target = target;
packet.roll_manual = roll_manual;
packet.pitch_manual = pitch_manual;
packet.yaw_manual = yaw_manual;
packet.thrust_manual = thrust_manual;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 21);
#endif
 
msg->msgid = MAVLINK_MSG_ID_MANUAL_CONTROL;
return mavlink_finalize_message(msg, system_id, component_id, 21, 52);
}
 
/**
* @brief Pack a manual_control message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param target The system to be controlled
* @param roll roll
* @param pitch pitch
* @param yaw yaw
* @param thrust thrust
* @param roll_manual roll control enabled auto:0, manual:1
* @param pitch_manual pitch auto:0, manual:1
* @param yaw_manual yaw auto:0, manual:1
* @param thrust_manual thrust auto:0, manual:1
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_manual_control_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint8_t target,float roll,float pitch,float yaw,float thrust,uint8_t roll_manual,uint8_t pitch_manual,uint8_t yaw_manual,uint8_t thrust_manual)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[21];
_mav_put_float(buf, 0, roll);
_mav_put_float(buf, 4, pitch);
_mav_put_float(buf, 8, yaw);
_mav_put_float(buf, 12, thrust);
_mav_put_uint8_t(buf, 16, target);
_mav_put_uint8_t(buf, 17, roll_manual);
_mav_put_uint8_t(buf, 18, pitch_manual);
_mav_put_uint8_t(buf, 19, yaw_manual);
_mav_put_uint8_t(buf, 20, thrust_manual);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 21);
#else
mavlink_manual_control_t packet;
packet.roll = roll;
packet.pitch = pitch;
packet.yaw = yaw;
packet.thrust = thrust;
packet.target = target;
packet.roll_manual = roll_manual;
packet.pitch_manual = pitch_manual;
packet.yaw_manual = yaw_manual;
packet.thrust_manual = thrust_manual;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 21);
#endif
 
msg->msgid = MAVLINK_MSG_ID_MANUAL_CONTROL;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 21, 52);
}
 
/**
* @brief Encode a manual_control struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param manual_control C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_manual_control_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_manual_control_t* manual_control)
{
return mavlink_msg_manual_control_pack(system_id, component_id, msg, manual_control->target, manual_control->roll, manual_control->pitch, manual_control->yaw, manual_control->thrust, manual_control->roll_manual, manual_control->pitch_manual, manual_control->yaw_manual, manual_control->thrust_manual);
}
 
/**
* @brief Send a manual_control message
* @param chan MAVLink channel to send the message
*
* @param target The system to be controlled
* @param roll roll
* @param pitch pitch
* @param yaw yaw
* @param thrust thrust
* @param roll_manual roll control enabled auto:0, manual:1
* @param pitch_manual pitch auto:0, manual:1
* @param yaw_manual yaw auto:0, manual:1
* @param thrust_manual thrust auto:0, manual:1
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_manual_control_send(mavlink_channel_t chan, uint8_t target, float roll, float pitch, float yaw, float thrust, uint8_t roll_manual, uint8_t pitch_manual, uint8_t yaw_manual, uint8_t thrust_manual)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[21];
_mav_put_float(buf, 0, roll);
_mav_put_float(buf, 4, pitch);
_mav_put_float(buf, 8, yaw);
_mav_put_float(buf, 12, thrust);
_mav_put_uint8_t(buf, 16, target);
_mav_put_uint8_t(buf, 17, roll_manual);
_mav_put_uint8_t(buf, 18, pitch_manual);
_mav_put_uint8_t(buf, 19, yaw_manual);
_mav_put_uint8_t(buf, 20, thrust_manual);
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MANUAL_CONTROL, buf, 21, 52);
#else
mavlink_manual_control_t packet;
packet.roll = roll;
packet.pitch = pitch;
packet.yaw = yaw;
packet.thrust = thrust;
packet.target = target;
packet.roll_manual = roll_manual;
packet.pitch_manual = pitch_manual;
packet.yaw_manual = yaw_manual;
packet.thrust_manual = thrust_manual;
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MANUAL_CONTROL, (const char *)&packet, 21, 52);
#endif
}
 
#endif
 
// MESSAGE MANUAL_CONTROL UNPACKING
 
 
/**
* @brief Get field target from manual_control message
*
* @return The system to be controlled
*/
static inline uint8_t mavlink_msg_manual_control_get_target(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 16);
}
 
/**
* @brief Get field roll from manual_control message
*
* @return roll
*/
static inline float mavlink_msg_manual_control_get_roll(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 0);
}
 
/**
* @brief Get field pitch from manual_control message
*
* @return pitch
*/
static inline float mavlink_msg_manual_control_get_pitch(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 4);
}
 
/**
* @brief Get field yaw from manual_control message
*
* @return yaw
*/
static inline float mavlink_msg_manual_control_get_yaw(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 8);
}
 
/**
* @brief Get field thrust from manual_control message
*
* @return thrust
*/
static inline float mavlink_msg_manual_control_get_thrust(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 12);
}
 
/**
* @brief Get field roll_manual from manual_control message
*
* @return roll control enabled auto:0, manual:1
*/
static inline uint8_t mavlink_msg_manual_control_get_roll_manual(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 17);
}
 
/**
* @brief Get field pitch_manual from manual_control message
*
* @return pitch auto:0, manual:1
*/
static inline uint8_t mavlink_msg_manual_control_get_pitch_manual(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 18);
}
 
/**
* @brief Get field yaw_manual from manual_control message
*
* @return yaw auto:0, manual:1
*/
static inline uint8_t mavlink_msg_manual_control_get_yaw_manual(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 19);
}
 
/**
* @brief Get field thrust_manual from manual_control message
*
* @return thrust auto:0, manual:1
*/
static inline uint8_t mavlink_msg_manual_control_get_thrust_manual(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 20);
}
 
/**
* @brief Decode a manual_control message into a struct
*
* @param msg The message to decode
* @param manual_control C-struct to decode the message contents into
*/
static inline void mavlink_msg_manual_control_decode(const mavlink_message_t* msg, mavlink_manual_control_t* manual_control)
{
#if MAVLINK_NEED_BYTE_SWAP
manual_control->roll = mavlink_msg_manual_control_get_roll(msg);
manual_control->pitch = mavlink_msg_manual_control_get_pitch(msg);
manual_control->yaw = mavlink_msg_manual_control_get_yaw(msg);
manual_control->thrust = mavlink_msg_manual_control_get_thrust(msg);
manual_control->target = mavlink_msg_manual_control_get_target(msg);
manual_control->roll_manual = mavlink_msg_manual_control_get_roll_manual(msg);
manual_control->pitch_manual = mavlink_msg_manual_control_get_pitch_manual(msg);
manual_control->yaw_manual = mavlink_msg_manual_control_get_yaw_manual(msg);
manual_control->thrust_manual = mavlink_msg_manual_control_get_thrust_manual(msg);
#else
memcpy(manual_control, _MAV_PAYLOAD(msg), 21);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v1.0/common/mavlink_msg_memory_vect.h
0,0 → 1,204
// MESSAGE MEMORY_VECT PACKING
 
#define MAVLINK_MSG_ID_MEMORY_VECT 249
 
typedef struct __mavlink_memory_vect_t
{
uint16_t address; ///< Starting address of the debug variables
uint8_t ver; ///< Version code of the type variable. 0=unknown, type ignored and assumed int16_t. 1=as below
uint8_t type; ///< Type code of the memory variables. for ver = 1: 0=16 x int16_t, 1=16 x uint16_t, 2=16 x Q15, 3=16 x 1Q14
int8_t value[32]; ///< Memory contents at specified address
} mavlink_memory_vect_t;
 
#define MAVLINK_MSG_ID_MEMORY_VECT_LEN 36
#define MAVLINK_MSG_ID_249_LEN 36
 
#define MAVLINK_MSG_MEMORY_VECT_FIELD_VALUE_LEN 32
 
#define MAVLINK_MESSAGE_INFO_MEMORY_VECT { \
"MEMORY_VECT", \
4, \
{ { "address", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_memory_vect_t, address) }, \
{ "ver", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_memory_vect_t, ver) }, \
{ "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_memory_vect_t, type) }, \
{ "value", NULL, MAVLINK_TYPE_INT8_T, 32, 4, offsetof(mavlink_memory_vect_t, value) }, \
} \
}
 
 
/**
* @brief Pack a memory_vect message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param address Starting address of the debug variables
* @param ver Version code of the type variable. 0=unknown, type ignored and assumed int16_t. 1=as below
* @param type Type code of the memory variables. for ver = 1: 0=16 x int16_t, 1=16 x uint16_t, 2=16 x Q15, 3=16 x 1Q14
* @param value Memory contents at specified address
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_memory_vect_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint16_t address, uint8_t ver, uint8_t type, const int8_t *value)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[36];
_mav_put_uint16_t(buf, 0, address);
_mav_put_uint8_t(buf, 2, ver);
_mav_put_uint8_t(buf, 3, type);
_mav_put_int8_t_array(buf, 4, value, 32);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 36);
#else
mavlink_memory_vect_t packet;
packet.address = address;
packet.ver = ver;
packet.type = type;
mav_array_memcpy(packet.value, value, sizeof(int8_t)*32);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 36);
#endif
 
msg->msgid = MAVLINK_MSG_ID_MEMORY_VECT;
return mavlink_finalize_message(msg, system_id, component_id, 36, 204);
}
 
/**
* @brief Pack a memory_vect message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param address Starting address of the debug variables
* @param ver Version code of the type variable. 0=unknown, type ignored and assumed int16_t. 1=as below
* @param type Type code of the memory variables. for ver = 1: 0=16 x int16_t, 1=16 x uint16_t, 2=16 x Q15, 3=16 x 1Q14
* @param value Memory contents at specified address
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_memory_vect_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint16_t address,uint8_t ver,uint8_t type,const int8_t *value)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[36];
_mav_put_uint16_t(buf, 0, address);
_mav_put_uint8_t(buf, 2, ver);
_mav_put_uint8_t(buf, 3, type);
_mav_put_int8_t_array(buf, 4, value, 32);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 36);
#else
mavlink_memory_vect_t packet;
packet.address = address;
packet.ver = ver;
packet.type = type;
mav_array_memcpy(packet.value, value, sizeof(int8_t)*32);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 36);
#endif
 
msg->msgid = MAVLINK_MSG_ID_MEMORY_VECT;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 36, 204);
}
 
/**
* @brief Encode a memory_vect struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param memory_vect C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_memory_vect_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_memory_vect_t* memory_vect)
{
return mavlink_msg_memory_vect_pack(system_id, component_id, msg, memory_vect->address, memory_vect->ver, memory_vect->type, memory_vect->value);
}
 
/**
* @brief Send a memory_vect message
* @param chan MAVLink channel to send the message
*
* @param address Starting address of the debug variables
* @param ver Version code of the type variable. 0=unknown, type ignored and assumed int16_t. 1=as below
* @param type Type code of the memory variables. for ver = 1: 0=16 x int16_t, 1=16 x uint16_t, 2=16 x Q15, 3=16 x 1Q14
* @param value Memory contents at specified address
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_memory_vect_send(mavlink_channel_t chan, uint16_t address, uint8_t ver, uint8_t type, const int8_t *value)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[36];
_mav_put_uint16_t(buf, 0, address);
_mav_put_uint8_t(buf, 2, ver);
_mav_put_uint8_t(buf, 3, type);
_mav_put_int8_t_array(buf, 4, value, 32);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MEMORY_VECT, buf, 36, 204);
#else
mavlink_memory_vect_t packet;
packet.address = address;
packet.ver = ver;
packet.type = type;
mav_array_memcpy(packet.value, value, sizeof(int8_t)*32);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MEMORY_VECT, (const char *)&packet, 36, 204);
#endif
}
 
#endif
 
// MESSAGE MEMORY_VECT UNPACKING
 
 
/**
* @brief Get field address from memory_vect message
*
* @return Starting address of the debug variables
*/
static inline uint16_t mavlink_msg_memory_vect_get_address(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 0);
}
 
/**
* @brief Get field ver from memory_vect message
*
* @return Version code of the type variable. 0=unknown, type ignored and assumed int16_t. 1=as below
*/
static inline uint8_t mavlink_msg_memory_vect_get_ver(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 2);
}
 
/**
* @brief Get field type from memory_vect message
*
* @return Type code of the memory variables. for ver = 1: 0=16 x int16_t, 1=16 x uint16_t, 2=16 x Q15, 3=16 x 1Q14
*/
static inline uint8_t mavlink_msg_memory_vect_get_type(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 3);
}
 
/**
* @brief Get field value from memory_vect message
*
* @return Memory contents at specified address
*/
static inline uint16_t mavlink_msg_memory_vect_get_value(const mavlink_message_t* msg, int8_t *value)
{
return _MAV_RETURN_int8_t_array(msg, value, 32, 4);
}
 
/**
* @brief Decode a memory_vect message into a struct
*
* @param msg The message to decode
* @param memory_vect C-struct to decode the message contents into
*/
static inline void mavlink_msg_memory_vect_decode(const mavlink_message_t* msg, mavlink_memory_vect_t* memory_vect)
{
#if MAVLINK_NEED_BYTE_SWAP
memory_vect->address = mavlink_msg_memory_vect_get_address(msg);
memory_vect->ver = mavlink_msg_memory_vect_get_ver(msg);
memory_vect->type = mavlink_msg_memory_vect_get_type(msg);
mavlink_msg_memory_vect_get_value(msg, memory_vect->value);
#else
memcpy(memory_vect, _MAV_PAYLOAD(msg), 36);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v1.0/common/mavlink_msg_mission_ack.h
0,0 → 1,188
// MESSAGE MISSION_ACK PACKING
 
#define MAVLINK_MSG_ID_MISSION_ACK 47
 
typedef struct __mavlink_mission_ack_t
{
uint8_t target_system; ///< System ID
uint8_t target_component; ///< Component ID
uint8_t type; ///< See MAV_MISSION_RESULT enum
} mavlink_mission_ack_t;
 
#define MAVLINK_MSG_ID_MISSION_ACK_LEN 3
#define MAVLINK_MSG_ID_47_LEN 3
 
 
 
#define MAVLINK_MESSAGE_INFO_MISSION_ACK { \
"MISSION_ACK", \
3, \
{ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_mission_ack_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_mission_ack_t, target_component) }, \
{ "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_mission_ack_t, type) }, \
} \
}
 
 
/**
* @brief Pack a mission_ack message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param target_system System ID
* @param target_component Component ID
* @param type See MAV_MISSION_RESULT enum
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_mission_ack_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t target_system, uint8_t target_component, uint8_t type)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[3];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
_mav_put_uint8_t(buf, 2, type);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 3);
#else
mavlink_mission_ack_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
packet.type = type;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 3);
#endif
 
msg->msgid = MAVLINK_MSG_ID_MISSION_ACK;
return mavlink_finalize_message(msg, system_id, component_id, 3, 153);
}
 
/**
* @brief Pack a mission_ack message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param target_system System ID
* @param target_component Component ID
* @param type See MAV_MISSION_RESULT enum
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_mission_ack_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 type)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[3];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
_mav_put_uint8_t(buf, 2, type);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 3);
#else
mavlink_mission_ack_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
packet.type = type;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 3);
#endif
 
msg->msgid = MAVLINK_MSG_ID_MISSION_ACK;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 3, 153);
}
 
/**
* @brief Encode a mission_ack struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param mission_ack C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_mission_ack_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mission_ack_t* mission_ack)
{
return mavlink_msg_mission_ack_pack(system_id, component_id, msg, mission_ack->target_system, mission_ack->target_component, mission_ack->type);
}
 
/**
* @brief Send a mission_ack message
* @param chan MAVLink channel to send the message
*
* @param target_system System ID
* @param target_component Component ID
* @param type See MAV_MISSION_RESULT enum
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_mission_ack_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t type)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[3];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
_mav_put_uint8_t(buf, 2, type);
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ACK, buf, 3, 153);
#else
mavlink_mission_ack_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
packet.type = type;
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ACK, (const char *)&packet, 3, 153);
#endif
}
 
#endif
 
// MESSAGE MISSION_ACK UNPACKING
 
 
/**
* @brief Get field target_system from mission_ack message
*
* @return System ID
*/
static inline uint8_t mavlink_msg_mission_ack_get_target_system(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 0);
}
 
/**
* @brief Get field target_component from mission_ack message
*
* @return Component ID
*/
static inline uint8_t mavlink_msg_mission_ack_get_target_component(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 1);
}
 
/**
* @brief Get field type from mission_ack message
*
* @return See MAV_MISSION_RESULT enum
*/
static inline uint8_t mavlink_msg_mission_ack_get_type(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 2);
}
 
/**
* @brief Decode a mission_ack message into a struct
*
* @param msg The message to decode
* @param mission_ack C-struct to decode the message contents into
*/
static inline void mavlink_msg_mission_ack_decode(const mavlink_message_t* msg, mavlink_mission_ack_t* mission_ack)
{
#if MAVLINK_NEED_BYTE_SWAP
mission_ack->target_system = mavlink_msg_mission_ack_get_target_system(msg);
mission_ack->target_component = mavlink_msg_mission_ack_get_target_component(msg);
mission_ack->type = mavlink_msg_mission_ack_get_type(msg);
#else
memcpy(mission_ack, _MAV_PAYLOAD(msg), 3);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v1.0/common/mavlink_msg_mission_clear_all.h
0,0 → 1,166
// MESSAGE MISSION_CLEAR_ALL PACKING
 
#define MAVLINK_MSG_ID_MISSION_CLEAR_ALL 45
 
typedef struct __mavlink_mission_clear_all_t
{
uint8_t target_system; ///< System ID
uint8_t target_component; ///< Component ID
} mavlink_mission_clear_all_t;
 
#define MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN 2
#define MAVLINK_MSG_ID_45_LEN 2
 
 
 
#define MAVLINK_MESSAGE_INFO_MISSION_CLEAR_ALL { \
"MISSION_CLEAR_ALL", \
2, \
{ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_mission_clear_all_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_mission_clear_all_t, target_component) }, \
} \
}
 
 
/**
* @brief Pack a mission_clear_all message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param target_system System ID
* @param target_component Component ID
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_mission_clear_all_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t target_system, uint8_t target_component)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[2];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 2);
#else
mavlink_mission_clear_all_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 2);
#endif
 
msg->msgid = MAVLINK_MSG_ID_MISSION_CLEAR_ALL;
return mavlink_finalize_message(msg, system_id, component_id, 2, 232);
}
 
/**
* @brief Pack a mission_clear_all message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param target_system System ID
* @param target_component Component ID
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_mission_clear_all_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)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[2];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 2);
#else
mavlink_mission_clear_all_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 2);
#endif
 
msg->msgid = MAVLINK_MSG_ID_MISSION_CLEAR_ALL;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 2, 232);
}
 
/**
* @brief Encode a mission_clear_all struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param mission_clear_all C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_mission_clear_all_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mission_clear_all_t* mission_clear_all)
{
return mavlink_msg_mission_clear_all_pack(system_id, component_id, msg, mission_clear_all->target_system, mission_clear_all->target_component);
}
 
/**
* @brief Send a mission_clear_all message
* @param chan MAVLink channel to send the message
*
* @param target_system System ID
* @param target_component Component ID
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_mission_clear_all_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[2];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_CLEAR_ALL, buf, 2, 232);
#else
mavlink_mission_clear_all_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_CLEAR_ALL, (const char *)&packet, 2, 232);
#endif
}
 
#endif
 
// MESSAGE MISSION_CLEAR_ALL UNPACKING
 
 
/**
* @brief Get field target_system from mission_clear_all message
*
* @return System ID
*/
static inline uint8_t mavlink_msg_mission_clear_all_get_target_system(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 0);
}
 
/**
* @brief Get field target_component from mission_clear_all message
*
* @return Component ID
*/
static inline uint8_t mavlink_msg_mission_clear_all_get_target_component(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 1);
}
 
/**
* @brief Decode a mission_clear_all message into a struct
*
* @param msg The message to decode
* @param mission_clear_all C-struct to decode the message contents into
*/
static inline void mavlink_msg_mission_clear_all_decode(const mavlink_message_t* msg, mavlink_mission_clear_all_t* mission_clear_all)
{
#if MAVLINK_NEED_BYTE_SWAP
mission_clear_all->target_system = mavlink_msg_mission_clear_all_get_target_system(msg);
mission_clear_all->target_component = mavlink_msg_mission_clear_all_get_target_component(msg);
#else
memcpy(mission_clear_all, _MAV_PAYLOAD(msg), 2);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v1.0/common/mavlink_msg_mission_count.h
0,0 → 1,188
// MESSAGE MISSION_COUNT PACKING
 
#define MAVLINK_MSG_ID_MISSION_COUNT 44
 
typedef struct __mavlink_mission_count_t
{
uint16_t count; ///< Number of mission items in the sequence
uint8_t target_system; ///< System ID
uint8_t target_component; ///< Component ID
} mavlink_mission_count_t;
 
#define MAVLINK_MSG_ID_MISSION_COUNT_LEN 4
#define MAVLINK_MSG_ID_44_LEN 4
 
 
 
#define MAVLINK_MESSAGE_INFO_MISSION_COUNT { \
"MISSION_COUNT", \
3, \
{ { "count", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_mission_count_t, count) }, \
{ "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_mission_count_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_mission_count_t, target_component) }, \
} \
}
 
 
/**
* @brief Pack a mission_count message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param target_system System ID
* @param target_component Component ID
* @param count Number of mission items in the sequence
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_mission_count_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t target_system, uint8_t target_component, uint16_t count)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[4];
_mav_put_uint16_t(buf, 0, count);
_mav_put_uint8_t(buf, 2, target_system);
_mav_put_uint8_t(buf, 3, target_component);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 4);
#else
mavlink_mission_count_t packet;
packet.count = count;
packet.target_system = target_system;
packet.target_component = target_component;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 4);
#endif
 
msg->msgid = MAVLINK_MSG_ID_MISSION_COUNT;
return mavlink_finalize_message(msg, system_id, component_id, 4, 221);
}
 
/**
* @brief Pack a mission_count message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param target_system System ID
* @param target_component Component ID
* @param count Number of mission items in the sequence
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_mission_count_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,uint16_t count)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[4];
_mav_put_uint16_t(buf, 0, count);
_mav_put_uint8_t(buf, 2, target_system);
_mav_put_uint8_t(buf, 3, target_component);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 4);
#else
mavlink_mission_count_t packet;
packet.count = count;
packet.target_system = target_system;
packet.target_component = target_component;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 4);
#endif
 
msg->msgid = MAVLINK_MSG_ID_MISSION_COUNT;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 4, 221);
}
 
/**
* @brief Encode a mission_count struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param mission_count C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_mission_count_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mission_count_t* mission_count)
{
return mavlink_msg_mission_count_pack(system_id, component_id, msg, mission_count->target_system, mission_count->target_component, mission_count->count);
}
 
/**
* @brief Send a mission_count message
* @param chan MAVLink channel to send the message
*
* @param target_system System ID
* @param target_component Component ID
* @param count Number of mission items in the sequence
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_mission_count_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t count)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[4];
_mav_put_uint16_t(buf, 0, count);
_mav_put_uint8_t(buf, 2, target_system);
_mav_put_uint8_t(buf, 3, target_component);
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_COUNT, buf, 4, 221);
#else
mavlink_mission_count_t packet;
packet.count = count;
packet.target_system = target_system;
packet.target_component = target_component;
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_COUNT, (const char *)&packet, 4, 221);
#endif
}
 
#endif
 
// MESSAGE MISSION_COUNT UNPACKING
 
 
/**
* @brief Get field target_system from mission_count message
*
* @return System ID
*/
static inline uint8_t mavlink_msg_mission_count_get_target_system(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 2);
}
 
/**
* @brief Get field target_component from mission_count message
*
* @return Component ID
*/
static inline uint8_t mavlink_msg_mission_count_get_target_component(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 3);
}
 
/**
* @brief Get field count from mission_count message
*
* @return Number of mission items in the sequence
*/
static inline uint16_t mavlink_msg_mission_count_get_count(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 0);
}
 
/**
* @brief Decode a mission_count message into a struct
*
* @param msg The message to decode
* @param mission_count C-struct to decode the message contents into
*/
static inline void mavlink_msg_mission_count_decode(const mavlink_message_t* msg, mavlink_mission_count_t* mission_count)
{
#if MAVLINK_NEED_BYTE_SWAP
mission_count->count = mavlink_msg_mission_count_get_count(msg);
mission_count->target_system = mavlink_msg_mission_count_get_target_system(msg);
mission_count->target_component = mavlink_msg_mission_count_get_target_component(msg);
#else
memcpy(mission_count, _MAV_PAYLOAD(msg), 4);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v1.0/common/mavlink_msg_mission_current.h
0,0 → 1,144
// MESSAGE MISSION_CURRENT PACKING
 
#define MAVLINK_MSG_ID_MISSION_CURRENT 42
 
typedef struct __mavlink_mission_current_t
{
uint16_t seq; ///< Sequence
} mavlink_mission_current_t;
 
#define MAVLINK_MSG_ID_MISSION_CURRENT_LEN 2
#define MAVLINK_MSG_ID_42_LEN 2
 
 
 
#define MAVLINK_MESSAGE_INFO_MISSION_CURRENT { \
"MISSION_CURRENT", \
1, \
{ { "seq", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_mission_current_t, seq) }, \
} \
}
 
 
/**
* @brief Pack a mission_current message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param seq Sequence
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_mission_current_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint16_t seq)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[2];
_mav_put_uint16_t(buf, 0, seq);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 2);
#else
mavlink_mission_current_t packet;
packet.seq = seq;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 2);
#endif
 
msg->msgid = MAVLINK_MSG_ID_MISSION_CURRENT;
return mavlink_finalize_message(msg, system_id, component_id, 2, 28);
}
 
/**
* @brief Pack a mission_current message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param seq Sequence
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_mission_current_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint16_t seq)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[2];
_mav_put_uint16_t(buf, 0, seq);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 2);
#else
mavlink_mission_current_t packet;
packet.seq = seq;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 2);
#endif
 
msg->msgid = MAVLINK_MSG_ID_MISSION_CURRENT;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 2, 28);
}
 
/**
* @brief Encode a mission_current struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param mission_current C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_mission_current_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mission_current_t* mission_current)
{
return mavlink_msg_mission_current_pack(system_id, component_id, msg, mission_current->seq);
}
 
/**
* @brief Send a mission_current message
* @param chan MAVLink channel to send the message
*
* @param seq Sequence
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_mission_current_send(mavlink_channel_t chan, uint16_t seq)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[2];
_mav_put_uint16_t(buf, 0, seq);
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_CURRENT, buf, 2, 28);
#else
mavlink_mission_current_t packet;
packet.seq = seq;
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_CURRENT, (const char *)&packet, 2, 28);
#endif
}
 
#endif
 
// MESSAGE MISSION_CURRENT UNPACKING
 
 
/**
* @brief Get field seq from mission_current message
*
* @return Sequence
*/
static inline uint16_t mavlink_msg_mission_current_get_seq(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 0);
}
 
/**
* @brief Decode a mission_current message into a struct
*
* @param msg The message to decode
* @param mission_current C-struct to decode the message contents into
*/
static inline void mavlink_msg_mission_current_decode(const mavlink_message_t* msg, mavlink_mission_current_t* mission_current)
{
#if MAVLINK_NEED_BYTE_SWAP
mission_current->seq = mavlink_msg_mission_current_get_seq(msg);
#else
memcpy(mission_current, _MAV_PAYLOAD(msg), 2);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v1.0/common/mavlink_msg_mission_item.h
0,0 → 1,430
// MESSAGE MISSION_ITEM PACKING
 
#define MAVLINK_MSG_ID_MISSION_ITEM 39
 
typedef struct __mavlink_mission_item_t
{
float param1; ///< PARAM1 / For NAV command MISSIONs: Radius in which the MISSION is accepted as reached, in meters
float param2; ///< PARAM2 / For NAV command MISSIONs: Time that the MAV should stay inside the PARAM1 radius before advancing, in milliseconds
float param3; ///< PARAM3 / For LOITER command MISSIONs: Orbit to circle around the MISSION, in meters. If positive the orbit direction should be clockwise, if negative the orbit direction should be counter-clockwise.
float param4; ///< PARAM4 / For NAV and LOITER command MISSIONs: Yaw orientation in degrees, [0..360] 0 = NORTH
float x; ///< PARAM5 / local: x position, global: latitude
float y; ///< PARAM6 / y position: global: longitude
float z; ///< PARAM7 / z position: global: altitude
uint16_t seq; ///< Sequence
uint16_t command; ///< The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs
uint8_t target_system; ///< System ID
uint8_t target_component; ///< Component ID
uint8_t frame; ///< The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h
uint8_t current; ///< false:0, true:1
uint8_t autocontinue; ///< autocontinue to next wp
} mavlink_mission_item_t;
 
#define MAVLINK_MSG_ID_MISSION_ITEM_LEN 37
#define MAVLINK_MSG_ID_39_LEN 37
 
 
 
#define MAVLINK_MESSAGE_INFO_MISSION_ITEM { \
"MISSION_ITEM", \
14, \
{ { "param1", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_mission_item_t, param1) }, \
{ "param2", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_mission_item_t, param2) }, \
{ "param3", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_mission_item_t, param3) }, \
{ "param4", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_mission_item_t, param4) }, \
{ "x", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_mission_item_t, x) }, \
{ "y", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_mission_item_t, y) }, \
{ "z", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_mission_item_t, z) }, \
{ "seq", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_mission_item_t, seq) }, \
{ "command", NULL, MAVLINK_TYPE_UINT16_T, 0, 30, offsetof(mavlink_mission_item_t, command) }, \
{ "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_mission_item_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_mission_item_t, target_component) }, \
{ "frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_mission_item_t, frame) }, \
{ "current", NULL, MAVLINK_TYPE_UINT8_T, 0, 35, offsetof(mavlink_mission_item_t, current) }, \
{ "autocontinue", NULL, MAVLINK_TYPE_UINT8_T, 0, 36, offsetof(mavlink_mission_item_t, autocontinue) }, \
} \
}
 
 
/**
* @brief Pack a mission_item message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param target_system System ID
* @param target_component Component ID
* @param seq Sequence
* @param frame The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h
* @param command The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs
* @param current false:0, true:1
* @param autocontinue autocontinue to next wp
* @param param1 PARAM1 / For NAV command MISSIONs: Radius in which the MISSION is accepted as reached, in meters
* @param param2 PARAM2 / For NAV command MISSIONs: Time that the MAV should stay inside the PARAM1 radius before advancing, in milliseconds
* @param param3 PARAM3 / For LOITER command MISSIONs: Orbit to circle around the MISSION, in meters. If positive the orbit direction should be clockwise, if negative the orbit direction should be counter-clockwise.
* @param param4 PARAM4 / For NAV and LOITER command MISSIONs: Yaw orientation in degrees, [0..360] 0 = NORTH
* @param x PARAM5 / local: x position, global: latitude
* @param y PARAM6 / y position: global: longitude
* @param z PARAM7 / z position: global: altitude
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_mission_item_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t target_system, uint8_t target_component, uint16_t seq, uint8_t frame, uint16_t command, uint8_t current, uint8_t autocontinue, float param1, float param2, float param3, float param4, float x, float y, float z)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[37];
_mav_put_float(buf, 0, param1);
_mav_put_float(buf, 4, param2);
_mav_put_float(buf, 8, param3);
_mav_put_float(buf, 12, param4);
_mav_put_float(buf, 16, x);
_mav_put_float(buf, 20, y);
_mav_put_float(buf, 24, z);
_mav_put_uint16_t(buf, 28, seq);
_mav_put_uint16_t(buf, 30, command);
_mav_put_uint8_t(buf, 32, target_system);
_mav_put_uint8_t(buf, 33, target_component);
_mav_put_uint8_t(buf, 34, frame);
_mav_put_uint8_t(buf, 35, current);
_mav_put_uint8_t(buf, 36, autocontinue);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 37);
#else
mavlink_mission_item_t packet;
packet.param1 = param1;
packet.param2 = param2;
packet.param3 = param3;
packet.param4 = param4;
packet.x = x;
packet.y = y;
packet.z = z;
packet.seq = seq;
packet.command = command;
packet.target_system = target_system;
packet.target_component = target_component;
packet.frame = frame;
packet.current = current;
packet.autocontinue = autocontinue;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 37);
#endif
 
msg->msgid = MAVLINK_MSG_ID_MISSION_ITEM;
return mavlink_finalize_message(msg, system_id, component_id, 37, 254);
}
 
/**
* @brief Pack a mission_item message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param target_system System ID
* @param target_component Component ID
* @param seq Sequence
* @param frame The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h
* @param command The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs
* @param current false:0, true:1
* @param autocontinue autocontinue to next wp
* @param param1 PARAM1 / For NAV command MISSIONs: Radius in which the MISSION is accepted as reached, in meters
* @param param2 PARAM2 / For NAV command MISSIONs: Time that the MAV should stay inside the PARAM1 radius before advancing, in milliseconds
* @param param3 PARAM3 / For LOITER command MISSIONs: Orbit to circle around the MISSION, in meters. If positive the orbit direction should be clockwise, if negative the orbit direction should be counter-clockwise.
* @param param4 PARAM4 / For NAV and LOITER command MISSIONs: Yaw orientation in degrees, [0..360] 0 = NORTH
* @param x PARAM5 / local: x position, global: latitude
* @param y PARAM6 / y position: global: longitude
* @param z PARAM7 / z position: global: altitude
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_mission_item_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,uint16_t seq,uint8_t frame,uint16_t command,uint8_t current,uint8_t autocontinue,float param1,float param2,float param3,float param4,float x,float y,float z)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[37];
_mav_put_float(buf, 0, param1);
_mav_put_float(buf, 4, param2);
_mav_put_float(buf, 8, param3);
_mav_put_float(buf, 12, param4);
_mav_put_float(buf, 16, x);
_mav_put_float(buf, 20, y);
_mav_put_float(buf, 24, z);
_mav_put_uint16_t(buf, 28, seq);
_mav_put_uint16_t(buf, 30, command);
_mav_put_uint8_t(buf, 32, target_system);
_mav_put_uint8_t(buf, 33, target_component);
_mav_put_uint8_t(buf, 34, frame);
_mav_put_uint8_t(buf, 35, current);
_mav_put_uint8_t(buf, 36, autocontinue);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 37);
#else
mavlink_mission_item_t packet;
packet.param1 = param1;
packet.param2 = param2;
packet.param3 = param3;
packet.param4 = param4;
packet.x = x;
packet.y = y;
packet.z = z;
packet.seq = seq;
packet.command = command;
packet.target_system = target_system;
packet.target_component = target_component;
packet.frame = frame;
packet.current = current;
packet.autocontinue = autocontinue;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 37);
#endif
 
msg->msgid = MAVLINK_MSG_ID_MISSION_ITEM;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 37, 254);
}
 
/**
* @brief Encode a mission_item struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param mission_item C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_mission_item_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mission_item_t* mission_item)
{
return mavlink_msg_mission_item_pack(system_id, component_id, msg, mission_item->target_system, mission_item->target_component, mission_item->seq, mission_item->frame, mission_item->command, mission_item->current, mission_item->autocontinue, mission_item->param1, mission_item->param2, mission_item->param3, mission_item->param4, mission_item->x, mission_item->y, mission_item->z);
}
 
/**
* @brief Send a mission_item message
* @param chan MAVLink channel to send the message
*
* @param target_system System ID
* @param target_component Component ID
* @param seq Sequence
* @param frame The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h
* @param command The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs
* @param current false:0, true:1
* @param autocontinue autocontinue to next wp
* @param param1 PARAM1 / For NAV command MISSIONs: Radius in which the MISSION is accepted as reached, in meters
* @param param2 PARAM2 / For NAV command MISSIONs: Time that the MAV should stay inside the PARAM1 radius before advancing, in milliseconds
* @param param3 PARAM3 / For LOITER command MISSIONs: Orbit to circle around the MISSION, in meters. If positive the orbit direction should be clockwise, if negative the orbit direction should be counter-clockwise.
* @param param4 PARAM4 / For NAV and LOITER command MISSIONs: Yaw orientation in degrees, [0..360] 0 = NORTH
* @param x PARAM5 / local: x position, global: latitude
* @param y PARAM6 / y position: global: longitude
* @param z PARAM7 / z position: global: altitude
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_mission_item_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t seq, uint8_t frame, uint16_t command, uint8_t current, uint8_t autocontinue, float param1, float param2, float param3, float param4, float x, float y, float z)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[37];
_mav_put_float(buf, 0, param1);
_mav_put_float(buf, 4, param2);
_mav_put_float(buf, 8, param3);
_mav_put_float(buf, 12, param4);
_mav_put_float(buf, 16, x);
_mav_put_float(buf, 20, y);
_mav_put_float(buf, 24, z);
_mav_put_uint16_t(buf, 28, seq);
_mav_put_uint16_t(buf, 30, command);
_mav_put_uint8_t(buf, 32, target_system);
_mav_put_uint8_t(buf, 33, target_component);
_mav_put_uint8_t(buf, 34, frame);
_mav_put_uint8_t(buf, 35, current);
_mav_put_uint8_t(buf, 36, autocontinue);
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM, buf, 37, 254);
#else
mavlink_mission_item_t packet;
packet.param1 = param1;
packet.param2 = param2;
packet.param3 = param3;
packet.param4 = param4;
packet.x = x;
packet.y = y;
packet.z = z;
packet.seq = seq;
packet.command = command;
packet.target_system = target_system;
packet.target_component = target_component;
packet.frame = frame;
packet.current = current;
packet.autocontinue = autocontinue;
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM, (const char *)&packet, 37, 254);
#endif
}
 
#endif
 
// MESSAGE MISSION_ITEM UNPACKING
 
 
/**
* @brief Get field target_system from mission_item message
*
* @return System ID
*/
static inline uint8_t mavlink_msg_mission_item_get_target_system(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 32);
}
 
/**
* @brief Get field target_component from mission_item message
*
* @return Component ID
*/
static inline uint8_t mavlink_msg_mission_item_get_target_component(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 33);
}
 
/**
* @brief Get field seq from mission_item message
*
* @return Sequence
*/
static inline uint16_t mavlink_msg_mission_item_get_seq(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 28);
}
 
/**
* @brief Get field frame from mission_item message
*
* @return The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h
*/
static inline uint8_t mavlink_msg_mission_item_get_frame(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 34);
}
 
/**
* @brief Get field command from mission_item message
*
* @return The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs
*/
static inline uint16_t mavlink_msg_mission_item_get_command(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 30);
}
 
/**
* @brief Get field current from mission_item message
*
* @return false:0, true:1
*/
static inline uint8_t mavlink_msg_mission_item_get_current(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 35);
}
 
/**
* @brief Get field autocontinue from mission_item message
*
* @return autocontinue to next wp
*/
static inline uint8_t mavlink_msg_mission_item_get_autocontinue(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 36);
}
 
/**
* @brief Get field param1 from mission_item message
*
* @return PARAM1 / For NAV command MISSIONs: Radius in which the MISSION is accepted as reached, in meters
*/
static inline float mavlink_msg_mission_item_get_param1(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 0);
}
 
/**
* @brief Get field param2 from mission_item message
*
* @return PARAM2 / For NAV command MISSIONs: Time that the MAV should stay inside the PARAM1 radius before advancing, in milliseconds
*/
static inline float mavlink_msg_mission_item_get_param2(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 4);
}
 
/**
* @brief Get field param3 from mission_item message
*
* @return PARAM3 / For LOITER command MISSIONs: Orbit to circle around the MISSION, in meters. If positive the orbit direction should be clockwise, if negative the orbit direction should be counter-clockwise.
*/
static inline float mavlink_msg_mission_item_get_param3(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 8);
}
 
/**
* @brief Get field param4 from mission_item message
*
* @return PARAM4 / For NAV and LOITER command MISSIONs: Yaw orientation in degrees, [0..360] 0 = NORTH
*/
static inline float mavlink_msg_mission_item_get_param4(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 12);
}
 
/**
* @brief Get field x from mission_item message
*
* @return PARAM5 / local: x position, global: latitude
*/
static inline float mavlink_msg_mission_item_get_x(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 16);
}
 
/**
* @brief Get field y from mission_item message
*
* @return PARAM6 / y position: global: longitude
*/
static inline float mavlink_msg_mission_item_get_y(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 20);
}
 
/**
* @brief Get field z from mission_item message
*
* @return PARAM7 / z position: global: altitude
*/
static inline float mavlink_msg_mission_item_get_z(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 24);
}
 
/**
* @brief Decode a mission_item message into a struct
*
* @param msg The message to decode
* @param mission_item C-struct to decode the message contents into
*/
static inline void mavlink_msg_mission_item_decode(const mavlink_message_t* msg, mavlink_mission_item_t* mission_item)
{
#if MAVLINK_NEED_BYTE_SWAP
mission_item->param1 = mavlink_msg_mission_item_get_param1(msg);
mission_item->param2 = mavlink_msg_mission_item_get_param2(msg);
mission_item->param3 = mavlink_msg_mission_item_get_param3(msg);
mission_item->param4 = mavlink_msg_mission_item_get_param4(msg);
mission_item->x = mavlink_msg_mission_item_get_x(msg);
mission_item->y = mavlink_msg_mission_item_get_y(msg);
mission_item->z = mavlink_msg_mission_item_get_z(msg);
mission_item->seq = mavlink_msg_mission_item_get_seq(msg);
mission_item->command = mavlink_msg_mission_item_get_command(msg);
mission_item->target_system = mavlink_msg_mission_item_get_target_system(msg);
mission_item->target_component = mavlink_msg_mission_item_get_target_component(msg);
mission_item->frame = mavlink_msg_mission_item_get_frame(msg);
mission_item->current = mavlink_msg_mission_item_get_current(msg);
mission_item->autocontinue = mavlink_msg_mission_item_get_autocontinue(msg);
#else
memcpy(mission_item, _MAV_PAYLOAD(msg), 37);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v1.0/common/mavlink_msg_mission_item_reached.h
0,0 → 1,144
// MESSAGE MISSION_ITEM_REACHED PACKING
 
#define MAVLINK_MSG_ID_MISSION_ITEM_REACHED 46
 
typedef struct __mavlink_mission_item_reached_t
{
uint16_t seq; ///< Sequence
} mavlink_mission_item_reached_t;
 
#define MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN 2
#define MAVLINK_MSG_ID_46_LEN 2
 
 
 
#define MAVLINK_MESSAGE_INFO_MISSION_ITEM_REACHED { \
"MISSION_ITEM_REACHED", \
1, \
{ { "seq", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_mission_item_reached_t, seq) }, \
} \
}
 
 
/**
* @brief Pack a mission_item_reached message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param seq Sequence
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_mission_item_reached_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint16_t seq)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[2];
_mav_put_uint16_t(buf, 0, seq);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 2);
#else
mavlink_mission_item_reached_t packet;
packet.seq = seq;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 2);
#endif
 
msg->msgid = MAVLINK_MSG_ID_MISSION_ITEM_REACHED;
return mavlink_finalize_message(msg, system_id, component_id, 2, 11);
}
 
/**
* @brief Pack a mission_item_reached message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param seq Sequence
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_mission_item_reached_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint16_t seq)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[2];
_mav_put_uint16_t(buf, 0, seq);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 2);
#else
mavlink_mission_item_reached_t packet;
packet.seq = seq;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 2);
#endif
 
msg->msgid = MAVLINK_MSG_ID_MISSION_ITEM_REACHED;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 2, 11);
}
 
/**
* @brief Encode a mission_item_reached struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param mission_item_reached C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_mission_item_reached_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mission_item_reached_t* mission_item_reached)
{
return mavlink_msg_mission_item_reached_pack(system_id, component_id, msg, mission_item_reached->seq);
}
 
/**
* @brief Send a mission_item_reached message
* @param chan MAVLink channel to send the message
*
* @param seq Sequence
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_mission_item_reached_send(mavlink_channel_t chan, uint16_t seq)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[2];
_mav_put_uint16_t(buf, 0, seq);
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM_REACHED, buf, 2, 11);
#else
mavlink_mission_item_reached_t packet;
packet.seq = seq;
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM_REACHED, (const char *)&packet, 2, 11);
#endif
}
 
#endif
 
// MESSAGE MISSION_ITEM_REACHED UNPACKING
 
 
/**
* @brief Get field seq from mission_item_reached message
*
* @return Sequence
*/
static inline uint16_t mavlink_msg_mission_item_reached_get_seq(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 0);
}
 
/**
* @brief Decode a mission_item_reached message into a struct
*
* @param msg The message to decode
* @param mission_item_reached C-struct to decode the message contents into
*/
static inline void mavlink_msg_mission_item_reached_decode(const mavlink_message_t* msg, mavlink_mission_item_reached_t* mission_item_reached)
{
#if MAVLINK_NEED_BYTE_SWAP
mission_item_reached->seq = mavlink_msg_mission_item_reached_get_seq(msg);
#else
memcpy(mission_item_reached, _MAV_PAYLOAD(msg), 2);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v1.0/common/mavlink_msg_mission_request.h
0,0 → 1,188
// MESSAGE MISSION_REQUEST PACKING
 
#define MAVLINK_MSG_ID_MISSION_REQUEST 40
 
typedef struct __mavlink_mission_request_t
{
uint16_t seq; ///< Sequence
uint8_t target_system; ///< System ID
uint8_t target_component; ///< Component ID
} mavlink_mission_request_t;
 
#define MAVLINK_MSG_ID_MISSION_REQUEST_LEN 4
#define MAVLINK_MSG_ID_40_LEN 4
 
 
 
#define MAVLINK_MESSAGE_INFO_MISSION_REQUEST { \
"MISSION_REQUEST", \
3, \
{ { "seq", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_mission_request_t, seq) }, \
{ "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_mission_request_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_mission_request_t, target_component) }, \
} \
}
 
 
/**
* @brief Pack a mission_request message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param target_system System ID
* @param target_component Component ID
* @param seq Sequence
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_mission_request_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t target_system, uint8_t target_component, uint16_t seq)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[4];
_mav_put_uint16_t(buf, 0, seq);
_mav_put_uint8_t(buf, 2, target_system);
_mav_put_uint8_t(buf, 3, target_component);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 4);
#else
mavlink_mission_request_t packet;
packet.seq = seq;
packet.target_system = target_system;
packet.target_component = target_component;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 4);
#endif
 
msg->msgid = MAVLINK_MSG_ID_MISSION_REQUEST;
return mavlink_finalize_message(msg, system_id, component_id, 4, 230);
}
 
/**
* @brief Pack a mission_request message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param target_system System ID
* @param target_component Component ID
* @param seq Sequence
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_mission_request_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,uint16_t seq)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[4];
_mav_put_uint16_t(buf, 0, seq);
_mav_put_uint8_t(buf, 2, target_system);
_mav_put_uint8_t(buf, 3, target_component);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 4);
#else
mavlink_mission_request_t packet;
packet.seq = seq;
packet.target_system = target_system;
packet.target_component = target_component;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 4);
#endif
 
msg->msgid = MAVLINK_MSG_ID_MISSION_REQUEST;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 4, 230);
}
 
/**
* @brief Encode a mission_request struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param mission_request C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_mission_request_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mission_request_t* mission_request)
{
return mavlink_msg_mission_request_pack(system_id, component_id, msg, mission_request->target_system, mission_request->target_component, mission_request->seq);
}
 
/**
* @brief Send a mission_request message
* @param chan MAVLink channel to send the message
*
* @param target_system System ID
* @param target_component Component ID
* @param seq Sequence
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_mission_request_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t seq)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[4];
_mav_put_uint16_t(buf, 0, seq);
_mav_put_uint8_t(buf, 2, target_system);
_mav_put_uint8_t(buf, 3, target_component);
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST, buf, 4, 230);
#else
mavlink_mission_request_t packet;
packet.seq = seq;
packet.target_system = target_system;
packet.target_component = target_component;
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST, (const char *)&packet, 4, 230);
#endif
}
 
#endif
 
// MESSAGE MISSION_REQUEST UNPACKING
 
 
/**
* @brief Get field target_system from mission_request message
*
* @return System ID
*/
static inline uint8_t mavlink_msg_mission_request_get_target_system(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 2);
}
 
/**
* @brief Get field target_component from mission_request message
*
* @return Component ID
*/
static inline uint8_t mavlink_msg_mission_request_get_target_component(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 3);
}
 
/**
* @brief Get field seq from mission_request message
*
* @return Sequence
*/
static inline uint16_t mavlink_msg_mission_request_get_seq(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 0);
}
 
/**
* @brief Decode a mission_request message into a struct
*
* @param msg The message to decode
* @param mission_request C-struct to decode the message contents into
*/
static inline void mavlink_msg_mission_request_decode(const mavlink_message_t* msg, mavlink_mission_request_t* mission_request)
{
#if MAVLINK_NEED_BYTE_SWAP
mission_request->seq = mavlink_msg_mission_request_get_seq(msg);
mission_request->target_system = mavlink_msg_mission_request_get_target_system(msg);
mission_request->target_component = mavlink_msg_mission_request_get_target_component(msg);
#else
memcpy(mission_request, _MAV_PAYLOAD(msg), 4);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v1.0/common/mavlink_msg_mission_request_list.h
0,0 → 1,166
// MESSAGE MISSION_REQUEST_LIST PACKING
 
#define MAVLINK_MSG_ID_MISSION_REQUEST_LIST 43
 
typedef struct __mavlink_mission_request_list_t
{
uint8_t target_system; ///< System ID
uint8_t target_component; ///< Component ID
} mavlink_mission_request_list_t;
 
#define MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN 2
#define MAVLINK_MSG_ID_43_LEN 2
 
 
 
#define MAVLINK_MESSAGE_INFO_MISSION_REQUEST_LIST { \
"MISSION_REQUEST_LIST", \
2, \
{ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_mission_request_list_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_mission_request_list_t, target_component) }, \
} \
}
 
 
/**
* @brief Pack a mission_request_list message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param target_system System ID
* @param target_component Component ID
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_mission_request_list_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t target_system, uint8_t target_component)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[2];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 2);
#else
mavlink_mission_request_list_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 2);
#endif
 
msg->msgid = MAVLINK_MSG_ID_MISSION_REQUEST_LIST;
return mavlink_finalize_message(msg, system_id, component_id, 2, 132);
}
 
/**
* @brief Pack a mission_request_list message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param target_system System ID
* @param target_component Component ID
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_mission_request_list_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)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[2];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 2);
#else
mavlink_mission_request_list_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 2);
#endif
 
msg->msgid = MAVLINK_MSG_ID_MISSION_REQUEST_LIST;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 2, 132);
}
 
/**
* @brief Encode a mission_request_list struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param mission_request_list C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_mission_request_list_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mission_request_list_t* mission_request_list)
{
return mavlink_msg_mission_request_list_pack(system_id, component_id, msg, mission_request_list->target_system, mission_request_list->target_component);
}
 
/**
* @brief Send a mission_request_list message
* @param chan MAVLink channel to send the message
*
* @param target_system System ID
* @param target_component Component ID
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_mission_request_list_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[2];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_LIST, buf, 2, 132);
#else
mavlink_mission_request_list_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_LIST, (const char *)&packet, 2, 132);
#endif
}
 
#endif
 
// MESSAGE MISSION_REQUEST_LIST UNPACKING
 
 
/**
* @brief Get field target_system from mission_request_list message
*
* @return System ID
*/
static inline uint8_t mavlink_msg_mission_request_list_get_target_system(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 0);
}
 
/**
* @brief Get field target_component from mission_request_list message
*
* @return Component ID
*/
static inline uint8_t mavlink_msg_mission_request_list_get_target_component(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 1);
}
 
/**
* @brief Decode a mission_request_list message into a struct
*
* @param msg The message to decode
* @param mission_request_list C-struct to decode the message contents into
*/
static inline void mavlink_msg_mission_request_list_decode(const mavlink_message_t* msg, mavlink_mission_request_list_t* mission_request_list)
{
#if MAVLINK_NEED_BYTE_SWAP
mission_request_list->target_system = mavlink_msg_mission_request_list_get_target_system(msg);
mission_request_list->target_component = mavlink_msg_mission_request_list_get_target_component(msg);
#else
memcpy(mission_request_list, _MAV_PAYLOAD(msg), 2);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v1.0/common/mavlink_msg_mission_request_partial_list.h
0,0 → 1,210
// MESSAGE MISSION_REQUEST_PARTIAL_LIST PACKING
 
#define MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST 37
 
typedef struct __mavlink_mission_request_partial_list_t
{
int16_t start_index; ///< Start index, 0 by default
int16_t end_index; ///< End index, -1 by default (-1: send list to end). Else a valid index of the list
uint8_t target_system; ///< System ID
uint8_t target_component; ///< Component ID
} mavlink_mission_request_partial_list_t;
 
#define MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN 6
#define MAVLINK_MSG_ID_37_LEN 6
 
 
 
#define MAVLINK_MESSAGE_INFO_MISSION_REQUEST_PARTIAL_LIST { \
"MISSION_REQUEST_PARTIAL_LIST", \
4, \
{ { "start_index", NULL, MAVLINK_TYPE_INT16_T, 0, 0, offsetof(mavlink_mission_request_partial_list_t, start_index) }, \
{ "end_index", NULL, MAVLINK_TYPE_INT16_T, 0, 2, offsetof(mavlink_mission_request_partial_list_t, end_index) }, \
{ "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_mission_request_partial_list_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_mission_request_partial_list_t, target_component) }, \
} \
}
 
 
/**
* @brief Pack a mission_request_partial_list message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param target_system System ID
* @param target_component Component ID
* @param start_index Start index, 0 by default
* @param end_index End index, -1 by default (-1: send list to end). Else a valid index of the list
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_mission_request_partial_list_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t target_system, uint8_t target_component, int16_t start_index, int16_t end_index)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[6];
_mav_put_int16_t(buf, 0, start_index);
_mav_put_int16_t(buf, 2, end_index);
_mav_put_uint8_t(buf, 4, target_system);
_mav_put_uint8_t(buf, 5, target_component);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 6);
#else
mavlink_mission_request_partial_list_t packet;
packet.start_index = start_index;
packet.end_index = end_index;
packet.target_system = target_system;
packet.target_component = target_component;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 6);
#endif
 
msg->msgid = MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST;
return mavlink_finalize_message(msg, system_id, component_id, 6, 212);
}
 
/**
* @brief Pack a mission_request_partial_list message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param target_system System ID
* @param target_component Component ID
* @param start_index Start index, 0 by default
* @param end_index End index, -1 by default (-1: send list to end). Else a valid index of the list
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_mission_request_partial_list_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,int16_t start_index,int16_t end_index)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[6];
_mav_put_int16_t(buf, 0, start_index);
_mav_put_int16_t(buf, 2, end_index);
_mav_put_uint8_t(buf, 4, target_system);
_mav_put_uint8_t(buf, 5, target_component);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 6);
#else
mavlink_mission_request_partial_list_t packet;
packet.start_index = start_index;
packet.end_index = end_index;
packet.target_system = target_system;
packet.target_component = target_component;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 6);
#endif
 
msg->msgid = MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 6, 212);
}
 
/**
* @brief Encode a mission_request_partial_list struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param mission_request_partial_list C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_mission_request_partial_list_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mission_request_partial_list_t* mission_request_partial_list)
{
return mavlink_msg_mission_request_partial_list_pack(system_id, component_id, msg, mission_request_partial_list->target_system, mission_request_partial_list->target_component, mission_request_partial_list->start_index, mission_request_partial_list->end_index);
}
 
/**
* @brief Send a mission_request_partial_list message
* @param chan MAVLink channel to send the message
*
* @param target_system System ID
* @param target_component Component ID
* @param start_index Start index, 0 by default
* @param end_index End index, -1 by default (-1: send list to end). Else a valid index of the list
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_mission_request_partial_list_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, int16_t start_index, int16_t end_index)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[6];
_mav_put_int16_t(buf, 0, start_index);
_mav_put_int16_t(buf, 2, end_index);
_mav_put_uint8_t(buf, 4, target_system);
_mav_put_uint8_t(buf, 5, target_component);
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST, buf, 6, 212);
#else
mavlink_mission_request_partial_list_t packet;
packet.start_index = start_index;
packet.end_index = end_index;
packet.target_system = target_system;
packet.target_component = target_component;
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST, (const char *)&packet, 6, 212);
#endif
}
 
#endif
 
// MESSAGE MISSION_REQUEST_PARTIAL_LIST UNPACKING
 
 
/**
* @brief Get field target_system from mission_request_partial_list message
*
* @return System ID
*/
static inline uint8_t mavlink_msg_mission_request_partial_list_get_target_system(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 4);
}
 
/**
* @brief Get field target_component from mission_request_partial_list message
*
* @return Component ID
*/
static inline uint8_t mavlink_msg_mission_request_partial_list_get_target_component(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 5);
}
 
/**
* @brief Get field start_index from mission_request_partial_list message
*
* @return Start index, 0 by default
*/
static inline int16_t mavlink_msg_mission_request_partial_list_get_start_index(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 0);
}
 
/**
* @brief Get field end_index from mission_request_partial_list message
*
* @return End index, -1 by default (-1: send list to end). Else a valid index of the list
*/
static inline int16_t mavlink_msg_mission_request_partial_list_get_end_index(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 2);
}
 
/**
* @brief Decode a mission_request_partial_list message into a struct
*
* @param msg The message to decode
* @param mission_request_partial_list C-struct to decode the message contents into
*/
static inline void mavlink_msg_mission_request_partial_list_decode(const mavlink_message_t* msg, mavlink_mission_request_partial_list_t* mission_request_partial_list)
{
#if MAVLINK_NEED_BYTE_SWAP
mission_request_partial_list->start_index = mavlink_msg_mission_request_partial_list_get_start_index(msg);
mission_request_partial_list->end_index = mavlink_msg_mission_request_partial_list_get_end_index(msg);
mission_request_partial_list->target_system = mavlink_msg_mission_request_partial_list_get_target_system(msg);
mission_request_partial_list->target_component = mavlink_msg_mission_request_partial_list_get_target_component(msg);
#else
memcpy(mission_request_partial_list, _MAV_PAYLOAD(msg), 6);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v1.0/common/mavlink_msg_mission_set_current.h
0,0 → 1,188
// MESSAGE MISSION_SET_CURRENT PACKING
 
#define MAVLINK_MSG_ID_MISSION_SET_CURRENT 41
 
typedef struct __mavlink_mission_set_current_t
{
uint16_t seq; ///< Sequence
uint8_t target_system; ///< System ID
uint8_t target_component; ///< Component ID
} mavlink_mission_set_current_t;
 
#define MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN 4
#define MAVLINK_MSG_ID_41_LEN 4
 
 
 
#define MAVLINK_MESSAGE_INFO_MISSION_SET_CURRENT { \
"MISSION_SET_CURRENT", \
3, \
{ { "seq", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_mission_set_current_t, seq) }, \
{ "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_mission_set_current_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_mission_set_current_t, target_component) }, \
} \
}
 
 
/**
* @brief Pack a mission_set_current message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param target_system System ID
* @param target_component Component ID
* @param seq Sequence
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_mission_set_current_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t target_system, uint8_t target_component, uint16_t seq)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[4];
_mav_put_uint16_t(buf, 0, seq);
_mav_put_uint8_t(buf, 2, target_system);
_mav_put_uint8_t(buf, 3, target_component);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 4);
#else
mavlink_mission_set_current_t packet;
packet.seq = seq;
packet.target_system = target_system;
packet.target_component = target_component;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 4);
#endif
 
msg->msgid = MAVLINK_MSG_ID_MISSION_SET_CURRENT;
return mavlink_finalize_message(msg, system_id, component_id, 4, 28);
}
 
/**
* @brief Pack a mission_set_current message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param target_system System ID
* @param target_component Component ID
* @param seq Sequence
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_mission_set_current_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,uint16_t seq)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[4];
_mav_put_uint16_t(buf, 0, seq);
_mav_put_uint8_t(buf, 2, target_system);
_mav_put_uint8_t(buf, 3, target_component);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 4);
#else
mavlink_mission_set_current_t packet;
packet.seq = seq;
packet.target_system = target_system;
packet.target_component = target_component;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 4);
#endif
 
msg->msgid = MAVLINK_MSG_ID_MISSION_SET_CURRENT;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 4, 28);
}
 
/**
* @brief Encode a mission_set_current struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param mission_set_current C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_mission_set_current_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mission_set_current_t* mission_set_current)
{
return mavlink_msg_mission_set_current_pack(system_id, component_id, msg, mission_set_current->target_system, mission_set_current->target_component, mission_set_current->seq);
}
 
/**
* @brief Send a mission_set_current message
* @param chan MAVLink channel to send the message
*
* @param target_system System ID
* @param target_component Component ID
* @param seq Sequence
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_mission_set_current_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t seq)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[4];
_mav_put_uint16_t(buf, 0, seq);
_mav_put_uint8_t(buf, 2, target_system);
_mav_put_uint8_t(buf, 3, target_component);
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_SET_CURRENT, buf, 4, 28);
#else
mavlink_mission_set_current_t packet;
packet.seq = seq;
packet.target_system = target_system;
packet.target_component = target_component;
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_SET_CURRENT, (const char *)&packet, 4, 28);
#endif
}
 
#endif
 
// MESSAGE MISSION_SET_CURRENT UNPACKING
 
 
/**
* @brief Get field target_system from mission_set_current message
*
* @return System ID
*/
static inline uint8_t mavlink_msg_mission_set_current_get_target_system(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 2);
}
 
/**
* @brief Get field target_component from mission_set_current message
*
* @return Component ID
*/
static inline uint8_t mavlink_msg_mission_set_current_get_target_component(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 3);
}
 
/**
* @brief Get field seq from mission_set_current message
*
* @return Sequence
*/
static inline uint16_t mavlink_msg_mission_set_current_get_seq(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 0);
}
 
/**
* @brief Decode a mission_set_current message into a struct
*
* @param msg The message to decode
* @param mission_set_current C-struct to decode the message contents into
*/
static inline void mavlink_msg_mission_set_current_decode(const mavlink_message_t* msg, mavlink_mission_set_current_t* mission_set_current)
{
#if MAVLINK_NEED_BYTE_SWAP
mission_set_current->seq = mavlink_msg_mission_set_current_get_seq(msg);
mission_set_current->target_system = mavlink_msg_mission_set_current_get_target_system(msg);
mission_set_current->target_component = mavlink_msg_mission_set_current_get_target_component(msg);
#else
memcpy(mission_set_current, _MAV_PAYLOAD(msg), 4);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v1.0/common/mavlink_msg_mission_write_partial_list.h
0,0 → 1,210
// MESSAGE MISSION_WRITE_PARTIAL_LIST PACKING
 
#define MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST 38
 
typedef struct __mavlink_mission_write_partial_list_t
{
int16_t start_index; ///< Start index, 0 by default and smaller / equal to the largest index of the current onboard list.
int16_t end_index; ///< End index, equal or greater than start index.
uint8_t target_system; ///< System ID
uint8_t target_component; ///< Component ID
} mavlink_mission_write_partial_list_t;
 
#define MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN 6
#define MAVLINK_MSG_ID_38_LEN 6
 
 
 
#define MAVLINK_MESSAGE_INFO_MISSION_WRITE_PARTIAL_LIST { \
"MISSION_WRITE_PARTIAL_LIST", \
4, \
{ { "start_index", NULL, MAVLINK_TYPE_INT16_T, 0, 0, offsetof(mavlink_mission_write_partial_list_t, start_index) }, \
{ "end_index", NULL, MAVLINK_TYPE_INT16_T, 0, 2, offsetof(mavlink_mission_write_partial_list_t, end_index) }, \
{ "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_mission_write_partial_list_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_mission_write_partial_list_t, target_component) }, \
} \
}
 
 
/**
* @brief Pack a mission_write_partial_list message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param target_system System ID
* @param target_component Component ID
* @param start_index Start index, 0 by default and smaller / equal to the largest index of the current onboard list.
* @param end_index End index, equal or greater than start index.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_mission_write_partial_list_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t target_system, uint8_t target_component, int16_t start_index, int16_t end_index)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[6];
_mav_put_int16_t(buf, 0, start_index);
_mav_put_int16_t(buf, 2, end_index);
_mav_put_uint8_t(buf, 4, target_system);
_mav_put_uint8_t(buf, 5, target_component);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 6);
#else
mavlink_mission_write_partial_list_t packet;
packet.start_index = start_index;
packet.end_index = end_index;
packet.target_system = target_system;
packet.target_component = target_component;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 6);
#endif
 
msg->msgid = MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST;
return mavlink_finalize_message(msg, system_id, component_id, 6, 9);
}
 
/**
* @brief Pack a mission_write_partial_list message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param target_system System ID
* @param target_component Component ID
* @param start_index Start index, 0 by default and smaller / equal to the largest index of the current onboard list.
* @param end_index End index, equal or greater than start index.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_mission_write_partial_list_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,int16_t start_index,int16_t end_index)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[6];
_mav_put_int16_t(buf, 0, start_index);
_mav_put_int16_t(buf, 2, end_index);
_mav_put_uint8_t(buf, 4, target_system);
_mav_put_uint8_t(buf, 5, target_component);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 6);
#else
mavlink_mission_write_partial_list_t packet;
packet.start_index = start_index;
packet.end_index = end_index;
packet.target_system = target_system;
packet.target_component = target_component;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 6);
#endif
 
msg->msgid = MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 6, 9);
}
 
/**
* @brief Encode a mission_write_partial_list struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param mission_write_partial_list C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_mission_write_partial_list_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mission_write_partial_list_t* mission_write_partial_list)
{
return mavlink_msg_mission_write_partial_list_pack(system_id, component_id, msg, mission_write_partial_list->target_system, mission_write_partial_list->target_component, mission_write_partial_list->start_index, mission_write_partial_list->end_index);
}
 
/**
* @brief Send a mission_write_partial_list message
* @param chan MAVLink channel to send the message
*
* @param target_system System ID
* @param target_component Component ID
* @param start_index Start index, 0 by default and smaller / equal to the largest index of the current onboard list.
* @param end_index End index, equal or greater than start index.
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_mission_write_partial_list_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, int16_t start_index, int16_t end_index)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[6];
_mav_put_int16_t(buf, 0, start_index);
_mav_put_int16_t(buf, 2, end_index);
_mav_put_uint8_t(buf, 4, target_system);
_mav_put_uint8_t(buf, 5, target_component);
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST, buf, 6, 9);
#else
mavlink_mission_write_partial_list_t packet;
packet.start_index = start_index;
packet.end_index = end_index;
packet.target_system = target_system;
packet.target_component = target_component;
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST, (const char *)&packet, 6, 9);
#endif
}
 
#endif
 
// MESSAGE MISSION_WRITE_PARTIAL_LIST UNPACKING
 
 
/**
* @brief Get field target_system from mission_write_partial_list message
*
* @return System ID
*/
static inline uint8_t mavlink_msg_mission_write_partial_list_get_target_system(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 4);
}
 
/**
* @brief Get field target_component from mission_write_partial_list message
*
* @return Component ID
*/
static inline uint8_t mavlink_msg_mission_write_partial_list_get_target_component(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 5);
}
 
/**
* @brief Get field start_index from mission_write_partial_list message
*
* @return Start index, 0 by default and smaller / equal to the largest index of the current onboard list.
*/
static inline int16_t mavlink_msg_mission_write_partial_list_get_start_index(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 0);
}
 
/**
* @brief Get field end_index from mission_write_partial_list message
*
* @return End index, equal or greater than start index.
*/
static inline int16_t mavlink_msg_mission_write_partial_list_get_end_index(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 2);
}
 
/**
* @brief Decode a mission_write_partial_list message into a struct
*
* @param msg The message to decode
* @param mission_write_partial_list C-struct to decode the message contents into
*/
static inline void mavlink_msg_mission_write_partial_list_decode(const mavlink_message_t* msg, mavlink_mission_write_partial_list_t* mission_write_partial_list)
{
#if MAVLINK_NEED_BYTE_SWAP
mission_write_partial_list->start_index = mavlink_msg_mission_write_partial_list_get_start_index(msg);
mission_write_partial_list->end_index = mavlink_msg_mission_write_partial_list_get_end_index(msg);
mission_write_partial_list->target_system = mavlink_msg_mission_write_partial_list_get_target_system(msg);
mission_write_partial_list->target_component = mavlink_msg_mission_write_partial_list_get_target_component(msg);
#else
memcpy(mission_write_partial_list, _MAV_PAYLOAD(msg), 6);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v1.0/common/mavlink_msg_named_value_float.h
0,0 → 1,182
// MESSAGE NAMED_VALUE_FLOAT PACKING
 
#define MAVLINK_MSG_ID_NAMED_VALUE_FLOAT 251
 
typedef struct __mavlink_named_value_float_t
{
uint32_t time_boot_ms; ///< Timestamp (milliseconds since system boot)
float value; ///< Floating point value
char name[10]; ///< Name of the debug variable
} mavlink_named_value_float_t;
 
#define MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN 18
#define MAVLINK_MSG_ID_251_LEN 18
 
#define MAVLINK_MSG_NAMED_VALUE_FLOAT_FIELD_NAME_LEN 10
 
#define MAVLINK_MESSAGE_INFO_NAMED_VALUE_FLOAT { \
"NAMED_VALUE_FLOAT", \
3, \
{ { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_named_value_float_t, time_boot_ms) }, \
{ "value", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_named_value_float_t, value) }, \
{ "name", NULL, MAVLINK_TYPE_CHAR, 10, 8, offsetof(mavlink_named_value_float_t, name) }, \
} \
}
 
 
/**
* @brief Pack a named_value_float message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param time_boot_ms Timestamp (milliseconds since system boot)
* @param name Name of the debug variable
* @param value Floating point value
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_named_value_float_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint32_t time_boot_ms, const char *name, float value)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[18];
_mav_put_uint32_t(buf, 0, time_boot_ms);
_mav_put_float(buf, 4, value);
_mav_put_char_array(buf, 8, name, 10);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 18);
#else
mavlink_named_value_float_t packet;
packet.time_boot_ms = time_boot_ms;
packet.value = value;
mav_array_memcpy(packet.name, name, sizeof(char)*10);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 18);
#endif
 
msg->msgid = MAVLINK_MSG_ID_NAMED_VALUE_FLOAT;
return mavlink_finalize_message(msg, system_id, component_id, 18, 170);
}
 
/**
* @brief Pack a named_value_float message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param time_boot_ms Timestamp (milliseconds since system boot)
* @param name Name of the debug variable
* @param value Floating point value
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_named_value_float_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint32_t time_boot_ms,const char *name,float value)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[18];
_mav_put_uint32_t(buf, 0, time_boot_ms);
_mav_put_float(buf, 4, value);
_mav_put_char_array(buf, 8, name, 10);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 18);
#else
mavlink_named_value_float_t packet;
packet.time_boot_ms = time_boot_ms;
packet.value = value;
mav_array_memcpy(packet.name, name, sizeof(char)*10);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 18);
#endif
 
msg->msgid = MAVLINK_MSG_ID_NAMED_VALUE_FLOAT;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 18, 170);
}
 
/**
* @brief Encode a named_value_float struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param named_value_float C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_named_value_float_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_named_value_float_t* named_value_float)
{
return mavlink_msg_named_value_float_pack(system_id, component_id, msg, named_value_float->time_boot_ms, named_value_float->name, named_value_float->value);
}
 
/**
* @brief Send a named_value_float message
* @param chan MAVLink channel to send the message
*
* @param time_boot_ms Timestamp (milliseconds since system boot)
* @param name Name of the debug variable
* @param value Floating point value
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_named_value_float_send(mavlink_channel_t chan, uint32_t time_boot_ms, const char *name, float value)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[18];
_mav_put_uint32_t(buf, 0, time_boot_ms);
_mav_put_float(buf, 4, value);
_mav_put_char_array(buf, 8, name, 10);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT, buf, 18, 170);
#else
mavlink_named_value_float_t packet;
packet.time_boot_ms = time_boot_ms;
packet.value = value;
mav_array_memcpy(packet.name, name, sizeof(char)*10);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT, (const char *)&packet, 18, 170);
#endif
}
 
#endif
 
// MESSAGE NAMED_VALUE_FLOAT UNPACKING
 
 
/**
* @brief Get field time_boot_ms from named_value_float message
*
* @return Timestamp (milliseconds since system boot)
*/
static inline uint32_t mavlink_msg_named_value_float_get_time_boot_ms(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint32_t(msg, 0);
}
 
/**
* @brief Get field name from named_value_float message
*
* @return Name of the debug variable
*/
static inline uint16_t mavlink_msg_named_value_float_get_name(const mavlink_message_t* msg, char *name)
{
return _MAV_RETURN_char_array(msg, name, 10, 8);
}
 
/**
* @brief Get field value from named_value_float message
*
* @return Floating point value
*/
static inline float mavlink_msg_named_value_float_get_value(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 4);
}
 
/**
* @brief Decode a named_value_float message into a struct
*
* @param msg The message to decode
* @param named_value_float C-struct to decode the message contents into
*/
static inline void mavlink_msg_named_value_float_decode(const mavlink_message_t* msg, mavlink_named_value_float_t* named_value_float)
{
#if MAVLINK_NEED_BYTE_SWAP
named_value_float->time_boot_ms = mavlink_msg_named_value_float_get_time_boot_ms(msg);
named_value_float->value = mavlink_msg_named_value_float_get_value(msg);
mavlink_msg_named_value_float_get_name(msg, named_value_float->name);
#else
memcpy(named_value_float, _MAV_PAYLOAD(msg), 18);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v1.0/common/mavlink_msg_named_value_int.h
0,0 → 1,182
// MESSAGE NAMED_VALUE_INT PACKING
 
#define MAVLINK_MSG_ID_NAMED_VALUE_INT 252
 
typedef struct __mavlink_named_value_int_t
{
uint32_t time_boot_ms; ///< Timestamp (milliseconds since system boot)
int32_t value; ///< Signed integer value
char name[10]; ///< Name of the debug variable
} mavlink_named_value_int_t;
 
#define MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN 18
#define MAVLINK_MSG_ID_252_LEN 18
 
#define MAVLINK_MSG_NAMED_VALUE_INT_FIELD_NAME_LEN 10
 
#define MAVLINK_MESSAGE_INFO_NAMED_VALUE_INT { \
"NAMED_VALUE_INT", \
3, \
{ { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_named_value_int_t, time_boot_ms) }, \
{ "value", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_named_value_int_t, value) }, \
{ "name", NULL, MAVLINK_TYPE_CHAR, 10, 8, offsetof(mavlink_named_value_int_t, name) }, \
} \
}
 
 
/**
* @brief Pack a named_value_int message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param time_boot_ms Timestamp (milliseconds since system boot)
* @param name Name of the debug variable
* @param value Signed integer value
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_named_value_int_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint32_t time_boot_ms, const char *name, int32_t value)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[18];
_mav_put_uint32_t(buf, 0, time_boot_ms);
_mav_put_int32_t(buf, 4, value);
_mav_put_char_array(buf, 8, name, 10);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 18);
#else
mavlink_named_value_int_t packet;
packet.time_boot_ms = time_boot_ms;
packet.value = value;
mav_array_memcpy(packet.name, name, sizeof(char)*10);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 18);
#endif
 
msg->msgid = MAVLINK_MSG_ID_NAMED_VALUE_INT;
return mavlink_finalize_message(msg, system_id, component_id, 18, 44);
}
 
/**
* @brief Pack a named_value_int message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param time_boot_ms Timestamp (milliseconds since system boot)
* @param name Name of the debug variable
* @param value Signed integer value
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_named_value_int_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint32_t time_boot_ms,const char *name,int32_t value)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[18];
_mav_put_uint32_t(buf, 0, time_boot_ms);
_mav_put_int32_t(buf, 4, value);
_mav_put_char_array(buf, 8, name, 10);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 18);
#else
mavlink_named_value_int_t packet;
packet.time_boot_ms = time_boot_ms;
packet.value = value;
mav_array_memcpy(packet.name, name, sizeof(char)*10);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 18);
#endif
 
msg->msgid = MAVLINK_MSG_ID_NAMED_VALUE_INT;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 18, 44);
}
 
/**
* @brief Encode a named_value_int struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param named_value_int C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_named_value_int_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_named_value_int_t* named_value_int)
{
return mavlink_msg_named_value_int_pack(system_id, component_id, msg, named_value_int->time_boot_ms, named_value_int->name, named_value_int->value);
}
 
/**
* @brief Send a named_value_int message
* @param chan MAVLink channel to send the message
*
* @param time_boot_ms Timestamp (milliseconds since system boot)
* @param name Name of the debug variable
* @param value Signed integer value
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_named_value_int_send(mavlink_channel_t chan, uint32_t time_boot_ms, const char *name, int32_t value)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[18];
_mav_put_uint32_t(buf, 0, time_boot_ms);
_mav_put_int32_t(buf, 4, value);
_mav_put_char_array(buf, 8, name, 10);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAMED_VALUE_INT, buf, 18, 44);
#else
mavlink_named_value_int_t packet;
packet.time_boot_ms = time_boot_ms;
packet.value = value;
mav_array_memcpy(packet.name, name, sizeof(char)*10);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAMED_VALUE_INT, (const char *)&packet, 18, 44);
#endif
}
 
#endif
 
// MESSAGE NAMED_VALUE_INT UNPACKING
 
 
/**
* @brief Get field time_boot_ms from named_value_int message
*
* @return Timestamp (milliseconds since system boot)
*/
static inline uint32_t mavlink_msg_named_value_int_get_time_boot_ms(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint32_t(msg, 0);
}
 
/**
* @brief Get field name from named_value_int message
*
* @return Name of the debug variable
*/
static inline uint16_t mavlink_msg_named_value_int_get_name(const mavlink_message_t* msg, char *name)
{
return _MAV_RETURN_char_array(msg, name, 10, 8);
}
 
/**
* @brief Get field value from named_value_int message
*
* @return Signed integer value
*/
static inline int32_t mavlink_msg_named_value_int_get_value(const mavlink_message_t* msg)
{
return _MAV_RETURN_int32_t(msg, 4);
}
 
/**
* @brief Decode a named_value_int message into a struct
*
* @param msg The message to decode
* @param named_value_int C-struct to decode the message contents into
*/
static inline void mavlink_msg_named_value_int_decode(const mavlink_message_t* msg, mavlink_named_value_int_t* named_value_int)
{
#if MAVLINK_NEED_BYTE_SWAP
named_value_int->time_boot_ms = mavlink_msg_named_value_int_get_time_boot_ms(msg);
named_value_int->value = mavlink_msg_named_value_int_get_value(msg);
mavlink_msg_named_value_int_get_name(msg, named_value_int->name);
#else
memcpy(named_value_int, _MAV_PAYLOAD(msg), 18);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v1.0/common/mavlink_msg_nav_controller_output.h
0,0 → 1,298
// MESSAGE NAV_CONTROLLER_OUTPUT PACKING
 
#define MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT 62
 
typedef struct __mavlink_nav_controller_output_t
{
float nav_roll; ///< Current desired roll in degrees
float nav_pitch; ///< Current desired pitch in degrees
float alt_error; ///< Current altitude error in meters
float aspd_error; ///< Current airspeed error in meters/second
float xtrack_error; ///< Current crosstrack error on x-y plane in meters
int16_t nav_bearing; ///< Current desired heading in degrees
int16_t target_bearing; ///< Bearing to current MISSION/target in degrees
uint16_t wp_dist; ///< Distance to active MISSION in meters
} mavlink_nav_controller_output_t;
 
#define MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN 26
#define MAVLINK_MSG_ID_62_LEN 26
 
 
 
#define MAVLINK_MESSAGE_INFO_NAV_CONTROLLER_OUTPUT { \
"NAV_CONTROLLER_OUTPUT", \
8, \
{ { "nav_roll", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_nav_controller_output_t, nav_roll) }, \
{ "nav_pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_nav_controller_output_t, nav_pitch) }, \
{ "alt_error", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_nav_controller_output_t, alt_error) }, \
{ "aspd_error", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_nav_controller_output_t, aspd_error) }, \
{ "xtrack_error", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_nav_controller_output_t, xtrack_error) }, \
{ "nav_bearing", NULL, MAVLINK_TYPE_INT16_T, 0, 20, offsetof(mavlink_nav_controller_output_t, nav_bearing) }, \
{ "target_bearing", NULL, MAVLINK_TYPE_INT16_T, 0, 22, offsetof(mavlink_nav_controller_output_t, target_bearing) }, \
{ "wp_dist", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_nav_controller_output_t, wp_dist) }, \
} \
}
 
 
/**
* @brief Pack a nav_controller_output message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param nav_roll Current desired roll in degrees
* @param nav_pitch Current desired pitch in degrees
* @param nav_bearing Current desired heading in degrees
* @param target_bearing Bearing to current MISSION/target in degrees
* @param wp_dist Distance to active MISSION in meters
* @param alt_error Current altitude error in meters
* @param aspd_error Current airspeed error in meters/second
* @param xtrack_error Current crosstrack error on x-y plane in meters
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_nav_controller_output_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
float nav_roll, float nav_pitch, int16_t nav_bearing, int16_t target_bearing, uint16_t wp_dist, float alt_error, float aspd_error, float xtrack_error)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[26];
_mav_put_float(buf, 0, nav_roll);
_mav_put_float(buf, 4, nav_pitch);
_mav_put_float(buf, 8, alt_error);
_mav_put_float(buf, 12, aspd_error);
_mav_put_float(buf, 16, xtrack_error);
_mav_put_int16_t(buf, 20, nav_bearing);
_mav_put_int16_t(buf, 22, target_bearing);
_mav_put_uint16_t(buf, 24, wp_dist);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 26);
#else
mavlink_nav_controller_output_t packet;
packet.nav_roll = nav_roll;
packet.nav_pitch = nav_pitch;
packet.alt_error = alt_error;
packet.aspd_error = aspd_error;
packet.xtrack_error = xtrack_error;
packet.nav_bearing = nav_bearing;
packet.target_bearing = target_bearing;
packet.wp_dist = wp_dist;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 26);
#endif
 
msg->msgid = MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT;
return mavlink_finalize_message(msg, system_id, component_id, 26, 183);
}
 
/**
* @brief Pack a nav_controller_output message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param nav_roll Current desired roll in degrees
* @param nav_pitch Current desired pitch in degrees
* @param nav_bearing Current desired heading in degrees
* @param target_bearing Bearing to current MISSION/target in degrees
* @param wp_dist Distance to active MISSION in meters
* @param alt_error Current altitude error in meters
* @param aspd_error Current airspeed error in meters/second
* @param xtrack_error Current crosstrack error on x-y plane in meters
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_nav_controller_output_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
float nav_roll,float nav_pitch,int16_t nav_bearing,int16_t target_bearing,uint16_t wp_dist,float alt_error,float aspd_error,float xtrack_error)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[26];
_mav_put_float(buf, 0, nav_roll);
_mav_put_float(buf, 4, nav_pitch);
_mav_put_float(buf, 8, alt_error);
_mav_put_float(buf, 12, aspd_error);
_mav_put_float(buf, 16, xtrack_error);
_mav_put_int16_t(buf, 20, nav_bearing);
_mav_put_int16_t(buf, 22, target_bearing);
_mav_put_uint16_t(buf, 24, wp_dist);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 26);
#else
mavlink_nav_controller_output_t packet;
packet.nav_roll = nav_roll;
packet.nav_pitch = nav_pitch;
packet.alt_error = alt_error;
packet.aspd_error = aspd_error;
packet.xtrack_error = xtrack_error;
packet.nav_bearing = nav_bearing;
packet.target_bearing = target_bearing;
packet.wp_dist = wp_dist;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 26);
#endif
 
msg->msgid = MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 26, 183);
}
 
/**
* @brief Encode a nav_controller_output struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param nav_controller_output C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_nav_controller_output_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_nav_controller_output_t* nav_controller_output)
{
return mavlink_msg_nav_controller_output_pack(system_id, component_id, msg, nav_controller_output->nav_roll, nav_controller_output->nav_pitch, nav_controller_output->nav_bearing, nav_controller_output->target_bearing, nav_controller_output->wp_dist, nav_controller_output->alt_error, nav_controller_output->aspd_error, nav_controller_output->xtrack_error);
}
 
/**
* @brief Send a nav_controller_output message
* @param chan MAVLink channel to send the message
*
* @param nav_roll Current desired roll in degrees
* @param nav_pitch Current desired pitch in degrees
* @param nav_bearing Current desired heading in degrees
* @param target_bearing Bearing to current MISSION/target in degrees
* @param wp_dist Distance to active MISSION in meters
* @param alt_error Current altitude error in meters
* @param aspd_error Current airspeed error in meters/second
* @param xtrack_error Current crosstrack error on x-y plane in meters
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_nav_controller_output_send(mavlink_channel_t chan, float nav_roll, float nav_pitch, int16_t nav_bearing, int16_t target_bearing, uint16_t wp_dist, float alt_error, float aspd_error, float xtrack_error)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[26];
_mav_put_float(buf, 0, nav_roll);
_mav_put_float(buf, 4, nav_pitch);
_mav_put_float(buf, 8, alt_error);
_mav_put_float(buf, 12, aspd_error);
_mav_put_float(buf, 16, xtrack_error);
_mav_put_int16_t(buf, 20, nav_bearing);
_mav_put_int16_t(buf, 22, target_bearing);
_mav_put_uint16_t(buf, 24, wp_dist);
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT, buf, 26, 183);
#else
mavlink_nav_controller_output_t packet;
packet.nav_roll = nav_roll;
packet.nav_pitch = nav_pitch;
packet.alt_error = alt_error;
packet.aspd_error = aspd_error;
packet.xtrack_error = xtrack_error;
packet.nav_bearing = nav_bearing;
packet.target_bearing = target_bearing;
packet.wp_dist = wp_dist;
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT, (const char *)&packet, 26, 183);
#endif
}
 
#endif
 
// MESSAGE NAV_CONTROLLER_OUTPUT UNPACKING
 
 
/**
* @brief Get field nav_roll from nav_controller_output message
*
* @return Current desired roll in degrees
*/
static inline float mavlink_msg_nav_controller_output_get_nav_roll(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 0);
}
 
/**
* @brief Get field nav_pitch from nav_controller_output message
*
* @return Current desired pitch in degrees
*/
static inline float mavlink_msg_nav_controller_output_get_nav_pitch(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 4);
}
 
/**
* @brief Get field nav_bearing from nav_controller_output message
*
* @return Current desired heading in degrees
*/
static inline int16_t mavlink_msg_nav_controller_output_get_nav_bearing(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 20);
}
 
/**
* @brief Get field target_bearing from nav_controller_output message
*
* @return Bearing to current MISSION/target in degrees
*/
static inline int16_t mavlink_msg_nav_controller_output_get_target_bearing(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 22);
}
 
/**
* @brief Get field wp_dist from nav_controller_output message
*
* @return Distance to active MISSION in meters
*/
static inline uint16_t mavlink_msg_nav_controller_output_get_wp_dist(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 24);
}
 
/**
* @brief Get field alt_error from nav_controller_output message
*
* @return Current altitude error in meters
*/
static inline float mavlink_msg_nav_controller_output_get_alt_error(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 8);
}
 
/**
* @brief Get field aspd_error from nav_controller_output message
*
* @return Current airspeed error in meters/second
*/
static inline float mavlink_msg_nav_controller_output_get_aspd_error(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 12);
}
 
/**
* @brief Get field xtrack_error from nav_controller_output message
*
* @return Current crosstrack error on x-y plane in meters
*/
static inline float mavlink_msg_nav_controller_output_get_xtrack_error(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 16);
}
 
/**
* @brief Decode a nav_controller_output message into a struct
*
* @param msg The message to decode
* @param nav_controller_output C-struct to decode the message contents into
*/
static inline void mavlink_msg_nav_controller_output_decode(const mavlink_message_t* msg, mavlink_nav_controller_output_t* nav_controller_output)
{
#if MAVLINK_NEED_BYTE_SWAP
nav_controller_output->nav_roll = mavlink_msg_nav_controller_output_get_nav_roll(msg);
nav_controller_output->nav_pitch = mavlink_msg_nav_controller_output_get_nav_pitch(msg);
nav_controller_output->alt_error = mavlink_msg_nav_controller_output_get_alt_error(msg);
nav_controller_output->aspd_error = mavlink_msg_nav_controller_output_get_aspd_error(msg);
nav_controller_output->xtrack_error = mavlink_msg_nav_controller_output_get_xtrack_error(msg);
nav_controller_output->nav_bearing = mavlink_msg_nav_controller_output_get_nav_bearing(msg);
nav_controller_output->target_bearing = mavlink_msg_nav_controller_output_get_target_bearing(msg);
nav_controller_output->wp_dist = mavlink_msg_nav_controller_output_get_wp_dist(msg);
#else
memcpy(nav_controller_output, _MAV_PAYLOAD(msg), 26);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v1.0/common/mavlink_msg_optical_flow.h
0,0 → 1,298
// MESSAGE OPTICAL_FLOW PACKING
 
#define MAVLINK_MSG_ID_OPTICAL_FLOW 100
 
typedef struct __mavlink_optical_flow_t
{
uint64_t time_usec; ///< Timestamp (UNIX)
float flow_comp_m_x; ///< Flow in meters in x-sensor direction, angular-speed compensated
float flow_comp_m_y; ///< Flow in meters in y-sensor direction, angular-speed compensated
float ground_distance; ///< Ground distance in meters. Positive value: distance known. Negative value: Unknown distance
int16_t flow_x; ///< Flow in pixels in x-sensor direction
int16_t flow_y; ///< Flow in pixels in y-sensor direction
uint8_t sensor_id; ///< Sensor ID
uint8_t quality; ///< Optical flow quality / confidence. 0: bad, 255: maximum quality
} mavlink_optical_flow_t;
 
#define MAVLINK_MSG_ID_OPTICAL_FLOW_LEN 26
#define MAVLINK_MSG_ID_100_LEN 26
 
 
 
#define MAVLINK_MESSAGE_INFO_OPTICAL_FLOW { \
"OPTICAL_FLOW", \
8, \
{ { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_optical_flow_t, time_usec) }, \
{ "flow_comp_m_x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_optical_flow_t, flow_comp_m_x) }, \
{ "flow_comp_m_y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_optical_flow_t, flow_comp_m_y) }, \
{ "ground_distance", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_optical_flow_t, ground_distance) }, \
{ "flow_x", NULL, MAVLINK_TYPE_INT16_T, 0, 20, offsetof(mavlink_optical_flow_t, flow_x) }, \
{ "flow_y", NULL, MAVLINK_TYPE_INT16_T, 0, 22, offsetof(mavlink_optical_flow_t, flow_y) }, \
{ "sensor_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 24, offsetof(mavlink_optical_flow_t, sensor_id) }, \
{ "quality", NULL, MAVLINK_TYPE_UINT8_T, 0, 25, offsetof(mavlink_optical_flow_t, quality) }, \
} \
}
 
 
/**
* @brief Pack a optical_flow message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param time_usec Timestamp (UNIX)
* @param sensor_id Sensor ID
* @param flow_x Flow in pixels in x-sensor direction
* @param flow_y Flow in pixels in y-sensor direction
* @param flow_comp_m_x Flow in meters in x-sensor direction, angular-speed compensated
* @param flow_comp_m_y Flow in meters in y-sensor direction, angular-speed compensated
* @param quality Optical flow quality / confidence. 0: bad, 255: maximum quality
* @param ground_distance Ground distance in meters. Positive value: distance known. Negative value: Unknown distance
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_optical_flow_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint64_t time_usec, uint8_t sensor_id, int16_t flow_x, int16_t flow_y, float flow_comp_m_x, float flow_comp_m_y, uint8_t quality, float ground_distance)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[26];
_mav_put_uint64_t(buf, 0, time_usec);
_mav_put_float(buf, 8, flow_comp_m_x);
_mav_put_float(buf, 12, flow_comp_m_y);
_mav_put_float(buf, 16, ground_distance);
_mav_put_int16_t(buf, 20, flow_x);
_mav_put_int16_t(buf, 22, flow_y);
_mav_put_uint8_t(buf, 24, sensor_id);
_mav_put_uint8_t(buf, 25, quality);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 26);
#else
mavlink_optical_flow_t packet;
packet.time_usec = time_usec;
packet.flow_comp_m_x = flow_comp_m_x;
packet.flow_comp_m_y = flow_comp_m_y;
packet.ground_distance = ground_distance;
packet.flow_x = flow_x;
packet.flow_y = flow_y;
packet.sensor_id = sensor_id;
packet.quality = quality;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 26);
#endif
 
msg->msgid = MAVLINK_MSG_ID_OPTICAL_FLOW;
return mavlink_finalize_message(msg, system_id, component_id, 26, 175);
}
 
/**
* @brief Pack a optical_flow message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param time_usec Timestamp (UNIX)
* @param sensor_id Sensor ID
* @param flow_x Flow in pixels in x-sensor direction
* @param flow_y Flow in pixels in y-sensor direction
* @param flow_comp_m_x Flow in meters in x-sensor direction, angular-speed compensated
* @param flow_comp_m_y Flow in meters in y-sensor direction, angular-speed compensated
* @param quality Optical flow quality / confidence. 0: bad, 255: maximum quality
* @param ground_distance Ground distance in meters. Positive value: distance known. Negative value: Unknown distance
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_optical_flow_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint64_t time_usec,uint8_t sensor_id,int16_t flow_x,int16_t flow_y,float flow_comp_m_x,float flow_comp_m_y,uint8_t quality,float ground_distance)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[26];
_mav_put_uint64_t(buf, 0, time_usec);
_mav_put_float(buf, 8, flow_comp_m_x);
_mav_put_float(buf, 12, flow_comp_m_y);
_mav_put_float(buf, 16, ground_distance);
_mav_put_int16_t(buf, 20, flow_x);
_mav_put_int16_t(buf, 22, flow_y);
_mav_put_uint8_t(buf, 24, sensor_id);
_mav_put_uint8_t(buf, 25, quality);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 26);
#else
mavlink_optical_flow_t packet;
packet.time_usec = time_usec;
packet.flow_comp_m_x = flow_comp_m_x;
packet.flow_comp_m_y = flow_comp_m_y;
packet.ground_distance = ground_distance;
packet.flow_x = flow_x;
packet.flow_y = flow_y;
packet.sensor_id = sensor_id;
packet.quality = quality;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 26);
#endif
 
msg->msgid = MAVLINK_MSG_ID_OPTICAL_FLOW;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 26, 175);
}
 
/**
* @brief Encode a optical_flow struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param optical_flow C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_optical_flow_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_optical_flow_t* optical_flow)
{
return mavlink_msg_optical_flow_pack(system_id, component_id, msg, optical_flow->time_usec, optical_flow->sensor_id, optical_flow->flow_x, optical_flow->flow_y, optical_flow->flow_comp_m_x, optical_flow->flow_comp_m_y, optical_flow->quality, optical_flow->ground_distance);
}
 
/**
* @brief Send a optical_flow message
* @param chan MAVLink channel to send the message
*
* @param time_usec Timestamp (UNIX)
* @param sensor_id Sensor ID
* @param flow_x Flow in pixels in x-sensor direction
* @param flow_y Flow in pixels in y-sensor direction
* @param flow_comp_m_x Flow in meters in x-sensor direction, angular-speed compensated
* @param flow_comp_m_y Flow in meters in y-sensor direction, angular-speed compensated
* @param quality Optical flow quality / confidence. 0: bad, 255: maximum quality
* @param ground_distance Ground distance in meters. Positive value: distance known. Negative value: Unknown distance
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_optical_flow_send(mavlink_channel_t chan, uint64_t time_usec, uint8_t sensor_id, int16_t flow_x, int16_t flow_y, float flow_comp_m_x, float flow_comp_m_y, uint8_t quality, float ground_distance)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[26];
_mav_put_uint64_t(buf, 0, time_usec);
_mav_put_float(buf, 8, flow_comp_m_x);
_mav_put_float(buf, 12, flow_comp_m_y);
_mav_put_float(buf, 16, ground_distance);
_mav_put_int16_t(buf, 20, flow_x);
_mav_put_int16_t(buf, 22, flow_y);
_mav_put_uint8_t(buf, 24, sensor_id);
_mav_put_uint8_t(buf, 25, quality);
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPTICAL_FLOW, buf, 26, 175);
#else
mavlink_optical_flow_t packet;
packet.time_usec = time_usec;
packet.flow_comp_m_x = flow_comp_m_x;
packet.flow_comp_m_y = flow_comp_m_y;
packet.ground_distance = ground_distance;
packet.flow_x = flow_x;
packet.flow_y = flow_y;
packet.sensor_id = sensor_id;
packet.quality = quality;
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPTICAL_FLOW, (const char *)&packet, 26, 175);
#endif
}
 
#endif
 
// MESSAGE OPTICAL_FLOW UNPACKING
 
 
/**
* @brief Get field time_usec from optical_flow message
*
* @return Timestamp (UNIX)
*/
static inline uint64_t mavlink_msg_optical_flow_get_time_usec(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint64_t(msg, 0);
}
 
/**
* @brief Get field sensor_id from optical_flow message
*
* @return Sensor ID
*/
static inline uint8_t mavlink_msg_optical_flow_get_sensor_id(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 24);
}
 
/**
* @brief Get field flow_x from optical_flow message
*
* @return Flow in pixels in x-sensor direction
*/
static inline int16_t mavlink_msg_optical_flow_get_flow_x(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 20);
}
 
/**
* @brief Get field flow_y from optical_flow message
*
* @return Flow in pixels in y-sensor direction
*/
static inline int16_t mavlink_msg_optical_flow_get_flow_y(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 22);
}
 
/**
* @brief Get field flow_comp_m_x from optical_flow message
*
* @return Flow in meters in x-sensor direction, angular-speed compensated
*/
static inline float mavlink_msg_optical_flow_get_flow_comp_m_x(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 8);
}
 
/**
* @brief Get field flow_comp_m_y from optical_flow message
*
* @return Flow in meters in y-sensor direction, angular-speed compensated
*/
static inline float mavlink_msg_optical_flow_get_flow_comp_m_y(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 12);
}
 
/**
* @brief Get field quality from optical_flow message
*
* @return Optical flow quality / confidence. 0: bad, 255: maximum quality
*/
static inline uint8_t mavlink_msg_optical_flow_get_quality(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 25);
}
 
/**
* @brief Get field ground_distance from optical_flow message
*
* @return Ground distance in meters. Positive value: distance known. Negative value: Unknown distance
*/
static inline float mavlink_msg_optical_flow_get_ground_distance(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 16);
}
 
/**
* @brief Decode a optical_flow message into a struct
*
* @param msg The message to decode
* @param optical_flow C-struct to decode the message contents into
*/
static inline void mavlink_msg_optical_flow_decode(const mavlink_message_t* msg, mavlink_optical_flow_t* optical_flow)
{
#if MAVLINK_NEED_BYTE_SWAP
optical_flow->time_usec = mavlink_msg_optical_flow_get_time_usec(msg);
optical_flow->flow_comp_m_x = mavlink_msg_optical_flow_get_flow_comp_m_x(msg);
optical_flow->flow_comp_m_y = mavlink_msg_optical_flow_get_flow_comp_m_y(msg);
optical_flow->ground_distance = mavlink_msg_optical_flow_get_ground_distance(msg);
optical_flow->flow_x = mavlink_msg_optical_flow_get_flow_x(msg);
optical_flow->flow_y = mavlink_msg_optical_flow_get_flow_y(msg);
optical_flow->sensor_id = mavlink_msg_optical_flow_get_sensor_id(msg);
optical_flow->quality = mavlink_msg_optical_flow_get_quality(msg);
#else
memcpy(optical_flow, _MAV_PAYLOAD(msg), 26);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v1.0/common/mavlink_msg_param_request_list.h
0,0 → 1,166
// MESSAGE PARAM_REQUEST_LIST PACKING
 
#define MAVLINK_MSG_ID_PARAM_REQUEST_LIST 21
 
typedef struct __mavlink_param_request_list_t
{
uint8_t target_system; ///< System ID
uint8_t target_component; ///< Component ID
} mavlink_param_request_list_t;
 
#define MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN 2
#define MAVLINK_MSG_ID_21_LEN 2
 
 
 
#define MAVLINK_MESSAGE_INFO_PARAM_REQUEST_LIST { \
"PARAM_REQUEST_LIST", \
2, \
{ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_param_request_list_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_param_request_list_t, target_component) }, \
} \
}
 
 
/**
* @brief Pack a param_request_list message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param target_system System ID
* @param target_component Component ID
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_param_request_list_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t target_system, uint8_t target_component)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[2];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 2);
#else
mavlink_param_request_list_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 2);
#endif
 
msg->msgid = MAVLINK_MSG_ID_PARAM_REQUEST_LIST;
return mavlink_finalize_message(msg, system_id, component_id, 2, 159);
}
 
/**
* @brief Pack a param_request_list message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param target_system System ID
* @param target_component Component ID
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_param_request_list_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)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[2];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 2);
#else
mavlink_param_request_list_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 2);
#endif
 
msg->msgid = MAVLINK_MSG_ID_PARAM_REQUEST_LIST;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 2, 159);
}
 
/**
* @brief Encode a param_request_list struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param param_request_list C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_param_request_list_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_param_request_list_t* param_request_list)
{
return mavlink_msg_param_request_list_pack(system_id, component_id, msg, param_request_list->target_system, param_request_list->target_component);
}
 
/**
* @brief Send a param_request_list message
* @param chan MAVLink channel to send the message
*
* @param target_system System ID
* @param target_component Component ID
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_param_request_list_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[2];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_REQUEST_LIST, buf, 2, 159);
#else
mavlink_param_request_list_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_REQUEST_LIST, (const char *)&packet, 2, 159);
#endif
}
 
#endif
 
// MESSAGE PARAM_REQUEST_LIST UNPACKING
 
 
/**
* @brief Get field target_system from param_request_list message
*
* @return System ID
*/
static inline uint8_t mavlink_msg_param_request_list_get_target_system(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 0);
}
 
/**
* @brief Get field target_component from param_request_list message
*
* @return Component ID
*/
static inline uint8_t mavlink_msg_param_request_list_get_target_component(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 1);
}
 
/**
* @brief Decode a param_request_list message into a struct
*
* @param msg The message to decode
* @param param_request_list C-struct to decode the message contents into
*/
static inline void mavlink_msg_param_request_list_decode(const mavlink_message_t* msg, mavlink_param_request_list_t* param_request_list)
{
#if MAVLINK_NEED_BYTE_SWAP
param_request_list->target_system = mavlink_msg_param_request_list_get_target_system(msg);
param_request_list->target_component = mavlink_msg_param_request_list_get_target_component(msg);
#else
memcpy(param_request_list, _MAV_PAYLOAD(msg), 2);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v1.0/common/mavlink_msg_param_request_read.h
0,0 → 1,204
// MESSAGE PARAM_REQUEST_READ PACKING
 
#define MAVLINK_MSG_ID_PARAM_REQUEST_READ 20
 
typedef struct __mavlink_param_request_read_t
{
int16_t param_index; ///< Parameter index. Send -1 to use the param ID field as identifier
uint8_t target_system; ///< System ID
uint8_t target_component; ///< Component ID
char param_id[16]; ///< Onboard parameter id
} mavlink_param_request_read_t;
 
#define MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN 20
#define MAVLINK_MSG_ID_20_LEN 20
 
#define MAVLINK_MSG_PARAM_REQUEST_READ_FIELD_PARAM_ID_LEN 16
 
#define MAVLINK_MESSAGE_INFO_PARAM_REQUEST_READ { \
"PARAM_REQUEST_READ", \
4, \
{ { "param_index", NULL, MAVLINK_TYPE_INT16_T, 0, 0, offsetof(mavlink_param_request_read_t, param_index) }, \
{ "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_param_request_read_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_param_request_read_t, target_component) }, \
{ "param_id", NULL, MAVLINK_TYPE_CHAR, 16, 4, offsetof(mavlink_param_request_read_t, param_id) }, \
} \
}
 
 
/**
* @brief Pack a param_request_read message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param target_system System ID
* @param target_component Component ID
* @param param_id Onboard parameter id
* @param param_index Parameter index. Send -1 to use the param ID field as identifier
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_param_request_read_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t target_system, uint8_t target_component, const char *param_id, int16_t param_index)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[20];
_mav_put_int16_t(buf, 0, param_index);
_mav_put_uint8_t(buf, 2, target_system);
_mav_put_uint8_t(buf, 3, target_component);
_mav_put_char_array(buf, 4, param_id, 16);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 20);
#else
mavlink_param_request_read_t packet;
packet.param_index = param_index;
packet.target_system = target_system;
packet.target_component = target_component;
mav_array_memcpy(packet.param_id, param_id, sizeof(char)*16);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 20);
#endif
 
msg->msgid = MAVLINK_MSG_ID_PARAM_REQUEST_READ;
return mavlink_finalize_message(msg, system_id, component_id, 20, 214);
}
 
/**
* @brief Pack a param_request_read message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param target_system System ID
* @param target_component Component ID
* @param param_id Onboard parameter id
* @param param_index Parameter index. Send -1 to use the param ID field as identifier
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_param_request_read_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,const char *param_id,int16_t param_index)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[20];
_mav_put_int16_t(buf, 0, param_index);
_mav_put_uint8_t(buf, 2, target_system);
_mav_put_uint8_t(buf, 3, target_component);
_mav_put_char_array(buf, 4, param_id, 16);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 20);
#else
mavlink_param_request_read_t packet;
packet.param_index = param_index;
packet.target_system = target_system;
packet.target_component = target_component;
mav_array_memcpy(packet.param_id, param_id, sizeof(char)*16);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 20);
#endif
 
msg->msgid = MAVLINK_MSG_ID_PARAM_REQUEST_READ;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 20, 214);
}
 
/**
* @brief Encode a param_request_read struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param param_request_read C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_param_request_read_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_param_request_read_t* param_request_read)
{
return mavlink_msg_param_request_read_pack(system_id, component_id, msg, param_request_read->target_system, param_request_read->target_component, param_request_read->param_id, param_request_read->param_index);
}
 
/**
* @brief Send a param_request_read message
* @param chan MAVLink channel to send the message
*
* @param target_system System ID
* @param target_component Component ID
* @param param_id Onboard parameter id
* @param param_index Parameter index. Send -1 to use the param ID field as identifier
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_param_request_read_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, const char *param_id, int16_t param_index)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[20];
_mav_put_int16_t(buf, 0, param_index);
_mav_put_uint8_t(buf, 2, target_system);
_mav_put_uint8_t(buf, 3, target_component);
_mav_put_char_array(buf, 4, param_id, 16);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_REQUEST_READ, buf, 20, 214);
#else
mavlink_param_request_read_t packet;
packet.param_index = param_index;
packet.target_system = target_system;
packet.target_component = target_component;
mav_array_memcpy(packet.param_id, param_id, sizeof(char)*16);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_REQUEST_READ, (const char *)&packet, 20, 214);
#endif
}
 
#endif
 
// MESSAGE PARAM_REQUEST_READ UNPACKING
 
 
/**
* @brief Get field target_system from param_request_read message
*
* @return System ID
*/
static inline uint8_t mavlink_msg_param_request_read_get_target_system(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 2);
}
 
/**
* @brief Get field target_component from param_request_read message
*
* @return Component ID
*/
static inline uint8_t mavlink_msg_param_request_read_get_target_component(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 3);
}
 
/**
* @brief Get field param_id from param_request_read message
*
* @return Onboard parameter id
*/
static inline uint16_t mavlink_msg_param_request_read_get_param_id(const mavlink_message_t* msg, char *param_id)
{
return _MAV_RETURN_char_array(msg, param_id, 16, 4);
}
 
/**
* @brief Get field param_index from param_request_read message
*
* @return Parameter index. Send -1 to use the param ID field as identifier
*/
static inline int16_t mavlink_msg_param_request_read_get_param_index(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 0);
}
 
/**
* @brief Decode a param_request_read message into a struct
*
* @param msg The message to decode
* @param param_request_read C-struct to decode the message contents into
*/
static inline void mavlink_msg_param_request_read_decode(const mavlink_message_t* msg, mavlink_param_request_read_t* param_request_read)
{
#if MAVLINK_NEED_BYTE_SWAP
param_request_read->param_index = mavlink_msg_param_request_read_get_param_index(msg);
param_request_read->target_system = mavlink_msg_param_request_read_get_target_system(msg);
param_request_read->target_component = mavlink_msg_param_request_read_get_target_component(msg);
mavlink_msg_param_request_read_get_param_id(msg, param_request_read->param_id);
#else
memcpy(param_request_read, _MAV_PAYLOAD(msg), 20);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v1.0/common/mavlink_msg_param_set.h
0,0 → 1,226
// MESSAGE PARAM_SET PACKING
 
#define MAVLINK_MSG_ID_PARAM_SET 23
 
typedef struct __mavlink_param_set_t
{
float param_value; ///< Onboard parameter value
uint8_t target_system; ///< System ID
uint8_t target_component; ///< Component ID
char param_id[16]; ///< Onboard parameter id
uint8_t param_type; ///< Onboard parameter type: see MAV_VAR enum
} mavlink_param_set_t;
 
#define MAVLINK_MSG_ID_PARAM_SET_LEN 23
#define MAVLINK_MSG_ID_23_LEN 23
 
#define MAVLINK_MSG_PARAM_SET_FIELD_PARAM_ID_LEN 16
 
#define MAVLINK_MESSAGE_INFO_PARAM_SET { \
"PARAM_SET", \
5, \
{ { "param_value", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_param_set_t, param_value) }, \
{ "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_param_set_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_param_set_t, target_component) }, \
{ "param_id", NULL, MAVLINK_TYPE_CHAR, 16, 6, offsetof(mavlink_param_set_t, param_id) }, \
{ "param_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 22, offsetof(mavlink_param_set_t, param_type) }, \
} \
}
 
 
/**
* @brief Pack a param_set message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param target_system System ID
* @param target_component Component ID
* @param param_id Onboard parameter id
* @param param_value Onboard parameter value
* @param param_type Onboard parameter type: see MAV_VAR enum
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_param_set_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t target_system, uint8_t target_component, const char *param_id, float param_value, uint8_t param_type)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[23];
_mav_put_float(buf, 0, param_value);
_mav_put_uint8_t(buf, 4, target_system);
_mav_put_uint8_t(buf, 5, target_component);
_mav_put_uint8_t(buf, 22, param_type);
_mav_put_char_array(buf, 6, param_id, 16);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 23);
#else
mavlink_param_set_t packet;
packet.param_value = param_value;
packet.target_system = target_system;
packet.target_component = target_component;
packet.param_type = param_type;
mav_array_memcpy(packet.param_id, param_id, sizeof(char)*16);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 23);
#endif
 
msg->msgid = MAVLINK_MSG_ID_PARAM_SET;
return mavlink_finalize_message(msg, system_id, component_id, 23, 168);
}
 
/**
* @brief Pack a param_set message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param target_system System ID
* @param target_component Component ID
* @param param_id Onboard parameter id
* @param param_value Onboard parameter value
* @param param_type Onboard parameter type: see MAV_VAR enum
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_param_set_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,const char *param_id,float param_value,uint8_t param_type)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[23];
_mav_put_float(buf, 0, param_value);
_mav_put_uint8_t(buf, 4, target_system);
_mav_put_uint8_t(buf, 5, target_component);
_mav_put_uint8_t(buf, 22, param_type);
_mav_put_char_array(buf, 6, param_id, 16);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 23);
#else
mavlink_param_set_t packet;
packet.param_value = param_value;
packet.target_system = target_system;
packet.target_component = target_component;
packet.param_type = param_type;
mav_array_memcpy(packet.param_id, param_id, sizeof(char)*16);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 23);
#endif
 
msg->msgid = MAVLINK_MSG_ID_PARAM_SET;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 23, 168);
}
 
/**
* @brief Encode a param_set struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param param_set C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_param_set_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_param_set_t* param_set)
{
return mavlink_msg_param_set_pack(system_id, component_id, msg, param_set->target_system, param_set->target_component, param_set->param_id, param_set->param_value, param_set->param_type);
}
 
/**
* @brief Send a param_set message
* @param chan MAVLink channel to send the message
*
* @param target_system System ID
* @param target_component Component ID
* @param param_id Onboard parameter id
* @param param_value Onboard parameter value
* @param param_type Onboard parameter type: see MAV_VAR enum
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_param_set_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, const char *param_id, float param_value, uint8_t param_type)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[23];
_mav_put_float(buf, 0, param_value);
_mav_put_uint8_t(buf, 4, target_system);
_mav_put_uint8_t(buf, 5, target_component);
_mav_put_uint8_t(buf, 22, param_type);
_mav_put_char_array(buf, 6, param_id, 16);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_SET, buf, 23, 168);
#else
mavlink_param_set_t packet;
packet.param_value = param_value;
packet.target_system = target_system;
packet.target_component = target_component;
packet.param_type = param_type;
mav_array_memcpy(packet.param_id, param_id, sizeof(char)*16);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_SET, (const char *)&packet, 23, 168);
#endif
}
 
#endif
 
// MESSAGE PARAM_SET UNPACKING
 
 
/**
* @brief Get field target_system from param_set message
*
* @return System ID
*/
static inline uint8_t mavlink_msg_param_set_get_target_system(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 4);
}
 
/**
* @brief Get field target_component from param_set message
*
* @return Component ID
*/
static inline uint8_t mavlink_msg_param_set_get_target_component(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 5);
}
 
/**
* @brief Get field param_id from param_set message
*
* @return Onboard parameter id
*/
static inline uint16_t mavlink_msg_param_set_get_param_id(const mavlink_message_t* msg, char *param_id)
{
return _MAV_RETURN_char_array(msg, param_id, 16, 6);
}
 
/**
* @brief Get field param_value from param_set message
*
* @return Onboard parameter value
*/
static inline float mavlink_msg_param_set_get_param_value(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 0);
}
 
/**
* @brief Get field param_type from param_set message
*
* @return Onboard parameter type: see MAV_VAR enum
*/
static inline uint8_t mavlink_msg_param_set_get_param_type(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 22);
}
 
/**
* @brief Decode a param_set message into a struct
*
* @param msg The message to decode
* @param param_set C-struct to decode the message contents into
*/
static inline void mavlink_msg_param_set_decode(const mavlink_message_t* msg, mavlink_param_set_t* param_set)
{
#if MAVLINK_NEED_BYTE_SWAP
param_set->param_value = mavlink_msg_param_set_get_param_value(msg);
param_set->target_system = mavlink_msg_param_set_get_target_system(msg);
param_set->target_component = mavlink_msg_param_set_get_target_component(msg);
mavlink_msg_param_set_get_param_id(msg, param_set->param_id);
param_set->param_type = mavlink_msg_param_set_get_param_type(msg);
#else
memcpy(param_set, _MAV_PAYLOAD(msg), 23);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v1.0/common/mavlink_msg_param_value.h
0,0 → 1,226
// MESSAGE PARAM_VALUE PACKING
 
#define MAVLINK_MSG_ID_PARAM_VALUE 22
 
typedef struct __mavlink_param_value_t
{
float param_value; ///< Onboard parameter value
uint16_t param_count; ///< Total number of onboard parameters
uint16_t param_index; ///< Index of this onboard parameter
char param_id[16]; ///< Onboard parameter id
uint8_t param_type; ///< Onboard parameter type: see MAV_VAR enum
} mavlink_param_value_t;
 
#define MAVLINK_MSG_ID_PARAM_VALUE_LEN 25
#define MAVLINK_MSG_ID_22_LEN 25
 
#define MAVLINK_MSG_PARAM_VALUE_FIELD_PARAM_ID_LEN 16
 
#define MAVLINK_MESSAGE_INFO_PARAM_VALUE { \
"PARAM_VALUE", \
5, \
{ { "param_value", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_param_value_t, param_value) }, \
{ "param_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_param_value_t, param_count) }, \
{ "param_index", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_param_value_t, param_index) }, \
{ "param_id", NULL, MAVLINK_TYPE_CHAR, 16, 8, offsetof(mavlink_param_value_t, param_id) }, \
{ "param_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 24, offsetof(mavlink_param_value_t, param_type) }, \
} \
}
 
 
/**
* @brief Pack a param_value message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param param_id Onboard parameter id
* @param param_value Onboard parameter value
* @param param_type Onboard parameter type: see MAV_VAR enum
* @param param_count Total number of onboard parameters
* @param param_index Index of this onboard parameter
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_param_value_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
const char *param_id, float param_value, uint8_t param_type, uint16_t param_count, uint16_t param_index)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[25];
_mav_put_float(buf, 0, param_value);
_mav_put_uint16_t(buf, 4, param_count);
_mav_put_uint16_t(buf, 6, param_index);
_mav_put_uint8_t(buf, 24, param_type);
_mav_put_char_array(buf, 8, param_id, 16);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 25);
#else
mavlink_param_value_t packet;
packet.param_value = param_value;
packet.param_count = param_count;
packet.param_index = param_index;
packet.param_type = param_type;
mav_array_memcpy(packet.param_id, param_id, sizeof(char)*16);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 25);
#endif
 
msg->msgid = MAVLINK_MSG_ID_PARAM_VALUE;
return mavlink_finalize_message(msg, system_id, component_id, 25, 220);
}
 
/**
* @brief Pack a param_value message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param param_id Onboard parameter id
* @param param_value Onboard parameter value
* @param param_type Onboard parameter type: see MAV_VAR enum
* @param param_count Total number of onboard parameters
* @param param_index Index of this onboard parameter
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_param_value_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
const char *param_id,float param_value,uint8_t param_type,uint16_t param_count,uint16_t param_index)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[25];
_mav_put_float(buf, 0, param_value);
_mav_put_uint16_t(buf, 4, param_count);
_mav_put_uint16_t(buf, 6, param_index);
_mav_put_uint8_t(buf, 24, param_type);
_mav_put_char_array(buf, 8, param_id, 16);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 25);
#else
mavlink_param_value_t packet;
packet.param_value = param_value;
packet.param_count = param_count;
packet.param_index = param_index;
packet.param_type = param_type;
mav_array_memcpy(packet.param_id, param_id, sizeof(char)*16);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 25);
#endif
 
msg->msgid = MAVLINK_MSG_ID_PARAM_VALUE;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 25, 220);
}
 
/**
* @brief Encode a param_value struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param param_value C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_param_value_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_param_value_t* param_value)
{
return mavlink_msg_param_value_pack(system_id, component_id, msg, param_value->param_id, param_value->param_value, param_value->param_type, param_value->param_count, param_value->param_index);
}
 
/**
* @brief Send a param_value message
* @param chan MAVLink channel to send the message
*
* @param param_id Onboard parameter id
* @param param_value Onboard parameter value
* @param param_type Onboard parameter type: see MAV_VAR enum
* @param param_count Total number of onboard parameters
* @param param_index Index of this onboard parameter
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_param_value_send(mavlink_channel_t chan, const char *param_id, float param_value, uint8_t param_type, uint16_t param_count, uint16_t param_index)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[25];
_mav_put_float(buf, 0, param_value);
_mav_put_uint16_t(buf, 4, param_count);
_mav_put_uint16_t(buf, 6, param_index);
_mav_put_uint8_t(buf, 24, param_type);
_mav_put_char_array(buf, 8, param_id, 16);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_VALUE, buf, 25, 220);
#else
mavlink_param_value_t packet;
packet.param_value = param_value;
packet.param_count = param_count;
packet.param_index = param_index;
packet.param_type = param_type;
mav_array_memcpy(packet.param_id, param_id, sizeof(char)*16);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_VALUE, (const char *)&packet, 25, 220);
#endif
}
 
#endif
 
// MESSAGE PARAM_VALUE UNPACKING
 
 
/**
* @brief Get field param_id from param_value message
*
* @return Onboard parameter id
*/
static inline uint16_t mavlink_msg_param_value_get_param_id(const mavlink_message_t* msg, char *param_id)
{
return _MAV_RETURN_char_array(msg, param_id, 16, 8);
}
 
/**
* @brief Get field param_value from param_value message
*
* @return Onboard parameter value
*/
static inline float mavlink_msg_param_value_get_param_value(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 0);
}
 
/**
* @brief Get field param_type from param_value message
*
* @return Onboard parameter type: see MAV_VAR enum
*/
static inline uint8_t mavlink_msg_param_value_get_param_type(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 24);
}
 
/**
* @brief Get field param_count from param_value message
*
* @return Total number of onboard parameters
*/
static inline uint16_t mavlink_msg_param_value_get_param_count(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 4);
}
 
/**
* @brief Get field param_index from param_value message
*
* @return Index of this onboard parameter
*/
static inline uint16_t mavlink_msg_param_value_get_param_index(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 6);
}
 
/**
* @brief Decode a param_value message into a struct
*
* @param msg The message to decode
* @param param_value C-struct to decode the message contents into
*/
static inline void mavlink_msg_param_value_decode(const mavlink_message_t* msg, mavlink_param_value_t* param_value)
{
#if MAVLINK_NEED_BYTE_SWAP
param_value->param_value = mavlink_msg_param_value_get_param_value(msg);
param_value->param_count = mavlink_msg_param_value_get_param_count(msg);
param_value->param_index = mavlink_msg_param_value_get_param_index(msg);
mavlink_msg_param_value_get_param_id(msg, param_value->param_id);
param_value->param_type = mavlink_msg_param_value_get_param_type(msg);
#else
memcpy(param_value, _MAV_PAYLOAD(msg), 25);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v1.0/common/mavlink_msg_ping.h
0,0 → 1,210
// MESSAGE PING PACKING
 
#define MAVLINK_MSG_ID_PING 4
 
typedef struct __mavlink_ping_t
{
uint64_t time_usec; ///< Unix timestamp in microseconds
uint32_t seq; ///< PING sequence
uint8_t target_system; ///< 0: request ping from all receiving systems, if greater than 0: message is a ping response and number is the system id of the requesting system
uint8_t target_component; ///< 0: request ping from all receiving components, if greater than 0: message is a ping response and number is the system id of the requesting system
} mavlink_ping_t;
 
#define MAVLINK_MSG_ID_PING_LEN 14
#define MAVLINK_MSG_ID_4_LEN 14
 
 
 
#define MAVLINK_MESSAGE_INFO_PING { \
"PING", \
4, \
{ { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_ping_t, time_usec) }, \
{ "seq", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_ping_t, seq) }, \
{ "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 12, offsetof(mavlink_ping_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 13, offsetof(mavlink_ping_t, target_component) }, \
} \
}
 
 
/**
* @brief Pack a ping message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param time_usec Unix timestamp in microseconds
* @param seq PING sequence
* @param target_system 0: request ping from all receiving systems, if greater than 0: message is a ping response and number is the system id of the requesting system
* @param target_component 0: request ping from all receiving components, if greater than 0: message is a ping response and number is the system id of the requesting system
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_ping_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint64_t time_usec, uint32_t seq, uint8_t target_system, uint8_t target_component)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[14];
_mav_put_uint64_t(buf, 0, time_usec);
_mav_put_uint32_t(buf, 8, seq);
_mav_put_uint8_t(buf, 12, target_system);
_mav_put_uint8_t(buf, 13, target_component);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 14);
#else
mavlink_ping_t packet;
packet.time_usec = time_usec;
packet.seq = seq;
packet.target_system = target_system;
packet.target_component = target_component;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 14);
#endif
 
msg->msgid = MAVLINK_MSG_ID_PING;
return mavlink_finalize_message(msg, system_id, component_id, 14, 237);
}
 
/**
* @brief Pack a ping message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param time_usec Unix timestamp in microseconds
* @param seq PING sequence
* @param target_system 0: request ping from all receiving systems, if greater than 0: message is a ping response and number is the system id of the requesting system
* @param target_component 0: request ping from all receiving components, if greater than 0: message is a ping response and number is the system id of the requesting system
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_ping_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint64_t time_usec,uint32_t seq,uint8_t target_system,uint8_t target_component)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[14];
_mav_put_uint64_t(buf, 0, time_usec);
_mav_put_uint32_t(buf, 8, seq);
_mav_put_uint8_t(buf, 12, target_system);
_mav_put_uint8_t(buf, 13, target_component);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 14);
#else
mavlink_ping_t packet;
packet.time_usec = time_usec;
packet.seq = seq;
packet.target_system = target_system;
packet.target_component = target_component;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 14);
#endif
 
msg->msgid = MAVLINK_MSG_ID_PING;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 14, 237);
}
 
/**
* @brief Encode a ping struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param ping C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_ping_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_ping_t* ping)
{
return mavlink_msg_ping_pack(system_id, component_id, msg, ping->time_usec, ping->seq, ping->target_system, ping->target_component);
}
 
/**
* @brief Send a ping message
* @param chan MAVLink channel to send the message
*
* @param time_usec Unix timestamp in microseconds
* @param seq PING sequence
* @param target_system 0: request ping from all receiving systems, if greater than 0: message is a ping response and number is the system id of the requesting system
* @param target_component 0: request ping from all receiving components, if greater than 0: message is a ping response and number is the system id of the requesting system
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_ping_send(mavlink_channel_t chan, uint64_t time_usec, uint32_t seq, uint8_t target_system, uint8_t target_component)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[14];
_mav_put_uint64_t(buf, 0, time_usec);
_mav_put_uint32_t(buf, 8, seq);
_mav_put_uint8_t(buf, 12, target_system);
_mav_put_uint8_t(buf, 13, target_component);
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PING, buf, 14, 237);
#else
mavlink_ping_t packet;
packet.time_usec = time_usec;
packet.seq = seq;
packet.target_system = target_system;
packet.target_component = target_component;
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PING, (const char *)&packet, 14, 237);
#endif
}
 
#endif
 
// MESSAGE PING UNPACKING
 
 
/**
* @brief Get field time_usec from ping message
*
* @return Unix timestamp in microseconds
*/
static inline uint64_t mavlink_msg_ping_get_time_usec(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint64_t(msg, 0);
}
 
/**
* @brief Get field seq from ping message
*
* @return PING sequence
*/
static inline uint32_t mavlink_msg_ping_get_seq(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint32_t(msg, 8);
}
 
/**
* @brief Get field target_system from ping message
*
* @return 0: request ping from all receiving systems, if greater than 0: message is a ping response and number is the system id of the requesting system
*/
static inline uint8_t mavlink_msg_ping_get_target_system(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 12);
}
 
/**
* @brief Get field target_component from ping message
*
* @return 0: request ping from all receiving components, if greater than 0: message is a ping response and number is the system id of the requesting system
*/
static inline uint8_t mavlink_msg_ping_get_target_component(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 13);
}
 
/**
* @brief Decode a ping message into a struct
*
* @param msg The message to decode
* @param ping C-struct to decode the message contents into
*/
static inline void mavlink_msg_ping_decode(const mavlink_message_t* msg, mavlink_ping_t* ping)
{
#if MAVLINK_NEED_BYTE_SWAP
ping->time_usec = mavlink_msg_ping_get_time_usec(msg);
ping->seq = mavlink_msg_ping_get_seq(msg);
ping->target_system = mavlink_msg_ping_get_target_system(msg);
ping->target_component = mavlink_msg_ping_get_target_component(msg);
#else
memcpy(ping, _MAV_PAYLOAD(msg), 14);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v1.0/common/mavlink_msg_raw_imu.h
0,0 → 1,342
// MESSAGE RAW_IMU PACKING
 
#define MAVLINK_MSG_ID_RAW_IMU 27
 
typedef struct __mavlink_raw_imu_t
{
uint64_t time_usec; ///< Timestamp (microseconds since UNIX epoch or microseconds since system boot)
int16_t xacc; ///< X acceleration (raw)
int16_t yacc; ///< Y acceleration (raw)
int16_t zacc; ///< Z acceleration (raw)
int16_t xgyro; ///< Angular speed around X axis (raw)
int16_t ygyro; ///< Angular speed around Y axis (raw)
int16_t zgyro; ///< Angular speed around Z axis (raw)
int16_t xmag; ///< X Magnetic field (raw)
int16_t ymag; ///< Y Magnetic field (raw)
int16_t zmag; ///< Z Magnetic field (raw)
} mavlink_raw_imu_t;
 
#define MAVLINK_MSG_ID_RAW_IMU_LEN 26
#define MAVLINK_MSG_ID_27_LEN 26
 
 
 
#define MAVLINK_MESSAGE_INFO_RAW_IMU { \
"RAW_IMU", \
10, \
{ { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_raw_imu_t, time_usec) }, \
{ "xacc", NULL, MAVLINK_TYPE_INT16_T, 0, 8, offsetof(mavlink_raw_imu_t, xacc) }, \
{ "yacc", NULL, MAVLINK_TYPE_INT16_T, 0, 10, offsetof(mavlink_raw_imu_t, yacc) }, \
{ "zacc", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_raw_imu_t, zacc) }, \
{ "xgyro", NULL, MAVLINK_TYPE_INT16_T, 0, 14, offsetof(mavlink_raw_imu_t, xgyro) }, \
{ "ygyro", NULL, MAVLINK_TYPE_INT16_T, 0, 16, offsetof(mavlink_raw_imu_t, ygyro) }, \
{ "zgyro", NULL, MAVLINK_TYPE_INT16_T, 0, 18, offsetof(mavlink_raw_imu_t, zgyro) }, \
{ "xmag", NULL, MAVLINK_TYPE_INT16_T, 0, 20, offsetof(mavlink_raw_imu_t, xmag) }, \
{ "ymag", NULL, MAVLINK_TYPE_INT16_T, 0, 22, offsetof(mavlink_raw_imu_t, ymag) }, \
{ "zmag", NULL, MAVLINK_TYPE_INT16_T, 0, 24, offsetof(mavlink_raw_imu_t, zmag) }, \
} \
}
 
 
/**
* @brief Pack a raw_imu message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
* @param xacc X acceleration (raw)
* @param yacc Y acceleration (raw)
* @param zacc Z acceleration (raw)
* @param xgyro Angular speed around X axis (raw)
* @param ygyro Angular speed around Y axis (raw)
* @param zgyro Angular speed around Z axis (raw)
* @param xmag X Magnetic field (raw)
* @param ymag Y Magnetic field (raw)
* @param zmag Z Magnetic field (raw)
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_raw_imu_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint64_t time_usec, int16_t xacc, int16_t yacc, int16_t zacc, int16_t xgyro, int16_t ygyro, int16_t zgyro, int16_t xmag, int16_t ymag, int16_t zmag)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[26];
_mav_put_uint64_t(buf, 0, time_usec);
_mav_put_int16_t(buf, 8, xacc);
_mav_put_int16_t(buf, 10, yacc);
_mav_put_int16_t(buf, 12, zacc);
_mav_put_int16_t(buf, 14, xgyro);
_mav_put_int16_t(buf, 16, ygyro);
_mav_put_int16_t(buf, 18, zgyro);
_mav_put_int16_t(buf, 20, xmag);
_mav_put_int16_t(buf, 22, ymag);
_mav_put_int16_t(buf, 24, zmag);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 26);
#else
mavlink_raw_imu_t packet;
packet.time_usec = time_usec;
packet.xacc = xacc;
packet.yacc = yacc;
packet.zacc = zacc;
packet.xgyro = xgyro;
packet.ygyro = ygyro;
packet.zgyro = zgyro;
packet.xmag = xmag;
packet.ymag = ymag;
packet.zmag = zmag;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 26);
#endif
 
msg->msgid = MAVLINK_MSG_ID_RAW_IMU;
return mavlink_finalize_message(msg, system_id, component_id, 26, 144);
}
 
/**
* @brief Pack a raw_imu message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
* @param xacc X acceleration (raw)
* @param yacc Y acceleration (raw)
* @param zacc Z acceleration (raw)
* @param xgyro Angular speed around X axis (raw)
* @param ygyro Angular speed around Y axis (raw)
* @param zgyro Angular speed around Z axis (raw)
* @param xmag X Magnetic field (raw)
* @param ymag Y Magnetic field (raw)
* @param zmag Z Magnetic field (raw)
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_raw_imu_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint64_t time_usec,int16_t xacc,int16_t yacc,int16_t zacc,int16_t xgyro,int16_t ygyro,int16_t zgyro,int16_t xmag,int16_t ymag,int16_t zmag)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[26];
_mav_put_uint64_t(buf, 0, time_usec);
_mav_put_int16_t(buf, 8, xacc);
_mav_put_int16_t(buf, 10, yacc);
_mav_put_int16_t(buf, 12, zacc);
_mav_put_int16_t(buf, 14, xgyro);
_mav_put_int16_t(buf, 16, ygyro);
_mav_put_int16_t(buf, 18, zgyro);
_mav_put_int16_t(buf, 20, xmag);
_mav_put_int16_t(buf, 22, ymag);
_mav_put_int16_t(buf, 24, zmag);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 26);
#else
mavlink_raw_imu_t packet;
packet.time_usec = time_usec;
packet.xacc = xacc;
packet.yacc = yacc;
packet.zacc = zacc;
packet.xgyro = xgyro;
packet.ygyro = ygyro;
packet.zgyro = zgyro;
packet.xmag = xmag;
packet.ymag = ymag;
packet.zmag = zmag;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 26);
#endif
 
msg->msgid = MAVLINK_MSG_ID_RAW_IMU;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 26, 144);
}
 
/**
* @brief Encode a raw_imu struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param raw_imu C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_raw_imu_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_raw_imu_t* raw_imu)
{
return mavlink_msg_raw_imu_pack(system_id, component_id, msg, raw_imu->time_usec, raw_imu->xacc, raw_imu->yacc, raw_imu->zacc, raw_imu->xgyro, raw_imu->ygyro, raw_imu->zgyro, raw_imu->xmag, raw_imu->ymag, raw_imu->zmag);
}
 
/**
* @brief Send a raw_imu message
* @param chan MAVLink channel to send the message
*
* @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
* @param xacc X acceleration (raw)
* @param yacc Y acceleration (raw)
* @param zacc Z acceleration (raw)
* @param xgyro Angular speed around X axis (raw)
* @param ygyro Angular speed around Y axis (raw)
* @param zgyro Angular speed around Z axis (raw)
* @param xmag X Magnetic field (raw)
* @param ymag Y Magnetic field (raw)
* @param zmag Z Magnetic field (raw)
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_raw_imu_send(mavlink_channel_t chan, uint64_t time_usec, int16_t xacc, int16_t yacc, int16_t zacc, int16_t xgyro, int16_t ygyro, int16_t zgyro, int16_t xmag, int16_t ymag, int16_t zmag)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[26];
_mav_put_uint64_t(buf, 0, time_usec);
_mav_put_int16_t(buf, 8, xacc);
_mav_put_int16_t(buf, 10, yacc);
_mav_put_int16_t(buf, 12, zacc);
_mav_put_int16_t(buf, 14, xgyro);
_mav_put_int16_t(buf, 16, ygyro);
_mav_put_int16_t(buf, 18, zgyro);
_mav_put_int16_t(buf, 20, xmag);
_mav_put_int16_t(buf, 22, ymag);
_mav_put_int16_t(buf, 24, zmag);
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_IMU, buf, 26, 144);
#else
mavlink_raw_imu_t packet;
packet.time_usec = time_usec;
packet.xacc = xacc;
packet.yacc = yacc;
packet.zacc = zacc;
packet.xgyro = xgyro;
packet.ygyro = ygyro;
packet.zgyro = zgyro;
packet.xmag = xmag;
packet.ymag = ymag;
packet.zmag = zmag;
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_IMU, (const char *)&packet, 26, 144);
#endif
}
 
#endif
 
// MESSAGE RAW_IMU UNPACKING
 
 
/**
* @brief Get field time_usec from raw_imu message
*
* @return Timestamp (microseconds since UNIX epoch or microseconds since system boot)
*/
static inline uint64_t mavlink_msg_raw_imu_get_time_usec(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint64_t(msg, 0);
}
 
/**
* @brief Get field xacc from raw_imu message
*
* @return X acceleration (raw)
*/
static inline int16_t mavlink_msg_raw_imu_get_xacc(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 8);
}
 
/**
* @brief Get field yacc from raw_imu message
*
* @return Y acceleration (raw)
*/
static inline int16_t mavlink_msg_raw_imu_get_yacc(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 10);
}
 
/**
* @brief Get field zacc from raw_imu message
*
* @return Z acceleration (raw)
*/
static inline int16_t mavlink_msg_raw_imu_get_zacc(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 12);
}
 
/**
* @brief Get field xgyro from raw_imu message
*
* @return Angular speed around X axis (raw)
*/
static inline int16_t mavlink_msg_raw_imu_get_xgyro(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 14);
}
 
/**
* @brief Get field ygyro from raw_imu message
*
* @return Angular speed around Y axis (raw)
*/
static inline int16_t mavlink_msg_raw_imu_get_ygyro(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 16);
}
 
/**
* @brief Get field zgyro from raw_imu message
*
* @return Angular speed around Z axis (raw)
*/
static inline int16_t mavlink_msg_raw_imu_get_zgyro(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 18);
}
 
/**
* @brief Get field xmag from raw_imu message
*
* @return X Magnetic field (raw)
*/
static inline int16_t mavlink_msg_raw_imu_get_xmag(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 20);
}
 
/**
* @brief Get field ymag from raw_imu message
*
* @return Y Magnetic field (raw)
*/
static inline int16_t mavlink_msg_raw_imu_get_ymag(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 22);
}
 
/**
* @brief Get field zmag from raw_imu message
*
* @return Z Magnetic field (raw)
*/
static inline int16_t mavlink_msg_raw_imu_get_zmag(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 24);
}
 
/**
* @brief Decode a raw_imu message into a struct
*
* @param msg The message to decode
* @param raw_imu C-struct to decode the message contents into
*/
static inline void mavlink_msg_raw_imu_decode(const mavlink_message_t* msg, mavlink_raw_imu_t* raw_imu)
{
#if MAVLINK_NEED_BYTE_SWAP
raw_imu->time_usec = mavlink_msg_raw_imu_get_time_usec(msg);
raw_imu->xacc = mavlink_msg_raw_imu_get_xacc(msg);
raw_imu->yacc = mavlink_msg_raw_imu_get_yacc(msg);
raw_imu->zacc = mavlink_msg_raw_imu_get_zacc(msg);
raw_imu->xgyro = mavlink_msg_raw_imu_get_xgyro(msg);
raw_imu->ygyro = mavlink_msg_raw_imu_get_ygyro(msg);
raw_imu->zgyro = mavlink_msg_raw_imu_get_zgyro(msg);
raw_imu->xmag = mavlink_msg_raw_imu_get_xmag(msg);
raw_imu->ymag = mavlink_msg_raw_imu_get_ymag(msg);
raw_imu->zmag = mavlink_msg_raw_imu_get_zmag(msg);
#else
memcpy(raw_imu, _MAV_PAYLOAD(msg), 26);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v1.0/common/mavlink_msg_raw_pressure.h
0,0 → 1,232
// MESSAGE RAW_PRESSURE PACKING
 
#define MAVLINK_MSG_ID_RAW_PRESSURE 28
 
typedef struct __mavlink_raw_pressure_t
{
uint64_t time_usec; ///< Timestamp (microseconds since UNIX epoch or microseconds since system boot)
int16_t press_abs; ///< Absolute pressure (raw)
int16_t press_diff1; ///< Differential pressure 1 (raw)
int16_t press_diff2; ///< Differential pressure 2 (raw)
int16_t temperature; ///< Raw Temperature measurement (raw)
} mavlink_raw_pressure_t;
 
#define MAVLINK_MSG_ID_RAW_PRESSURE_LEN 16
#define MAVLINK_MSG_ID_28_LEN 16
 
 
 
#define MAVLINK_MESSAGE_INFO_RAW_PRESSURE { \
"RAW_PRESSURE", \
5, \
{ { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_raw_pressure_t, time_usec) }, \
{ "press_abs", NULL, MAVLINK_TYPE_INT16_T, 0, 8, offsetof(mavlink_raw_pressure_t, press_abs) }, \
{ "press_diff1", NULL, MAVLINK_TYPE_INT16_T, 0, 10, offsetof(mavlink_raw_pressure_t, press_diff1) }, \
{ "press_diff2", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_raw_pressure_t, press_diff2) }, \
{ "temperature", NULL, MAVLINK_TYPE_INT16_T, 0, 14, offsetof(mavlink_raw_pressure_t, temperature) }, \
} \
}
 
 
/**
* @brief Pack a raw_pressure message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
* @param press_abs Absolute pressure (raw)
* @param press_diff1 Differential pressure 1 (raw)
* @param press_diff2 Differential pressure 2 (raw)
* @param temperature Raw Temperature measurement (raw)
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_raw_pressure_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint64_t time_usec, int16_t press_abs, int16_t press_diff1, int16_t press_diff2, int16_t temperature)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[16];
_mav_put_uint64_t(buf, 0, time_usec);
_mav_put_int16_t(buf, 8, press_abs);
_mav_put_int16_t(buf, 10, press_diff1);
_mav_put_int16_t(buf, 12, press_diff2);
_mav_put_int16_t(buf, 14, temperature);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 16);
#else
mavlink_raw_pressure_t packet;
packet.time_usec = time_usec;
packet.press_abs = press_abs;
packet.press_diff1 = press_diff1;
packet.press_diff2 = press_diff2;
packet.temperature = temperature;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 16);
#endif
 
msg->msgid = MAVLINK_MSG_ID_RAW_PRESSURE;
return mavlink_finalize_message(msg, system_id, component_id, 16, 67);
}
 
/**
* @brief Pack a raw_pressure message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
* @param press_abs Absolute pressure (raw)
* @param press_diff1 Differential pressure 1 (raw)
* @param press_diff2 Differential pressure 2 (raw)
* @param temperature Raw Temperature measurement (raw)
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_raw_pressure_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint64_t time_usec,int16_t press_abs,int16_t press_diff1,int16_t press_diff2,int16_t temperature)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[16];
_mav_put_uint64_t(buf, 0, time_usec);
_mav_put_int16_t(buf, 8, press_abs);
_mav_put_int16_t(buf, 10, press_diff1);
_mav_put_int16_t(buf, 12, press_diff2);
_mav_put_int16_t(buf, 14, temperature);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 16);
#else
mavlink_raw_pressure_t packet;
packet.time_usec = time_usec;
packet.press_abs = press_abs;
packet.press_diff1 = press_diff1;
packet.press_diff2 = press_diff2;
packet.temperature = temperature;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 16);
#endif
 
msg->msgid = MAVLINK_MSG_ID_RAW_PRESSURE;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 16, 67);
}
 
/**
* @brief Encode a raw_pressure struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param raw_pressure C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_raw_pressure_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_raw_pressure_t* raw_pressure)
{
return mavlink_msg_raw_pressure_pack(system_id, component_id, msg, raw_pressure->time_usec, raw_pressure->press_abs, raw_pressure->press_diff1, raw_pressure->press_diff2, raw_pressure->temperature);
}
 
/**
* @brief Send a raw_pressure message
* @param chan MAVLink channel to send the message
*
* @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
* @param press_abs Absolute pressure (raw)
* @param press_diff1 Differential pressure 1 (raw)
* @param press_diff2 Differential pressure 2 (raw)
* @param temperature Raw Temperature measurement (raw)
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_raw_pressure_send(mavlink_channel_t chan, uint64_t time_usec, int16_t press_abs, int16_t press_diff1, int16_t press_diff2, int16_t temperature)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[16];
_mav_put_uint64_t(buf, 0, time_usec);
_mav_put_int16_t(buf, 8, press_abs);
_mav_put_int16_t(buf, 10, press_diff1);
_mav_put_int16_t(buf, 12, press_diff2);
_mav_put_int16_t(buf, 14, temperature);
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_PRESSURE, buf, 16, 67);
#else
mavlink_raw_pressure_t packet;
packet.time_usec = time_usec;
packet.press_abs = press_abs;
packet.press_diff1 = press_diff1;
packet.press_diff2 = press_diff2;
packet.temperature = temperature;
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_PRESSURE, (const char *)&packet, 16, 67);
#endif
}
 
#endif
 
// MESSAGE RAW_PRESSURE UNPACKING
 
 
/**
* @brief Get field time_usec from raw_pressure message
*
* @return Timestamp (microseconds since UNIX epoch or microseconds since system boot)
*/
static inline uint64_t mavlink_msg_raw_pressure_get_time_usec(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint64_t(msg, 0);
}
 
/**
* @brief Get field press_abs from raw_pressure message
*
* @return Absolute pressure (raw)
*/
static inline int16_t mavlink_msg_raw_pressure_get_press_abs(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 8);
}
 
/**
* @brief Get field press_diff1 from raw_pressure message
*
* @return Differential pressure 1 (raw)
*/
static inline int16_t mavlink_msg_raw_pressure_get_press_diff1(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 10);
}
 
/**
* @brief Get field press_diff2 from raw_pressure message
*
* @return Differential pressure 2 (raw)
*/
static inline int16_t mavlink_msg_raw_pressure_get_press_diff2(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 12);
}
 
/**
* @brief Get field temperature from raw_pressure message
*
* @return Raw Temperature measurement (raw)
*/
static inline int16_t mavlink_msg_raw_pressure_get_temperature(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 14);
}
 
/**
* @brief Decode a raw_pressure message into a struct
*
* @param msg The message to decode
* @param raw_pressure C-struct to decode the message contents into
*/
static inline void mavlink_msg_raw_pressure_decode(const mavlink_message_t* msg, mavlink_raw_pressure_t* raw_pressure)
{
#if MAVLINK_NEED_BYTE_SWAP
raw_pressure->time_usec = mavlink_msg_raw_pressure_get_time_usec(msg);
raw_pressure->press_abs = mavlink_msg_raw_pressure_get_press_abs(msg);
raw_pressure->press_diff1 = mavlink_msg_raw_pressure_get_press_diff1(msg);
raw_pressure->press_diff2 = mavlink_msg_raw_pressure_get_press_diff2(msg);
raw_pressure->temperature = mavlink_msg_raw_pressure_get_temperature(msg);
#else
memcpy(raw_pressure, _MAV_PAYLOAD(msg), 16);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v1.0/common/mavlink_msg_rc_channels_override.h
0,0 → 1,342
// MESSAGE RC_CHANNELS_OVERRIDE PACKING
 
#define MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE 70
 
typedef struct __mavlink_rc_channels_override_t
{
uint16_t chan1_raw; ///< RC channel 1 value, in microseconds
uint16_t chan2_raw; ///< RC channel 2 value, in microseconds
uint16_t chan3_raw; ///< RC channel 3 value, in microseconds
uint16_t chan4_raw; ///< RC channel 4 value, in microseconds
uint16_t chan5_raw; ///< RC channel 5 value, in microseconds
uint16_t chan6_raw; ///< RC channel 6 value, in microseconds
uint16_t chan7_raw; ///< RC channel 7 value, in microseconds
uint16_t chan8_raw; ///< RC channel 8 value, in microseconds
uint8_t target_system; ///< System ID
uint8_t target_component; ///< Component ID
} mavlink_rc_channels_override_t;
 
#define MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN 18
#define MAVLINK_MSG_ID_70_LEN 18
 
 
 
#define MAVLINK_MESSAGE_INFO_RC_CHANNELS_OVERRIDE { \
"RC_CHANNELS_OVERRIDE", \
10, \
{ { "chan1_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_rc_channels_override_t, chan1_raw) }, \
{ "chan2_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_rc_channels_override_t, chan2_raw) }, \
{ "chan3_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_rc_channels_override_t, chan3_raw) }, \
{ "chan4_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_rc_channels_override_t, chan4_raw) }, \
{ "chan5_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_rc_channels_override_t, chan5_raw) }, \
{ "chan6_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 10, offsetof(mavlink_rc_channels_override_t, chan6_raw) }, \
{ "chan7_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_rc_channels_override_t, chan7_raw) }, \
{ "chan8_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 14, offsetof(mavlink_rc_channels_override_t, chan8_raw) }, \
{ "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 16, offsetof(mavlink_rc_channels_override_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 17, offsetof(mavlink_rc_channels_override_t, target_component) }, \
} \
}
 
 
/**
* @brief Pack a rc_channels_override message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param target_system System ID
* @param target_component Component ID
* @param chan1_raw RC channel 1 value, in microseconds
* @param chan2_raw RC channel 2 value, in microseconds
* @param chan3_raw RC channel 3 value, in microseconds
* @param chan4_raw RC channel 4 value, in microseconds
* @param chan5_raw RC channel 5 value, in microseconds
* @param chan6_raw RC channel 6 value, in microseconds
* @param chan7_raw RC channel 7 value, in microseconds
* @param chan8_raw RC channel 8 value, in microseconds
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_rc_channels_override_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t target_system, uint8_t target_component, uint16_t chan1_raw, uint16_t chan2_raw, uint16_t chan3_raw, uint16_t chan4_raw, uint16_t chan5_raw, uint16_t chan6_raw, uint16_t chan7_raw, uint16_t chan8_raw)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[18];
_mav_put_uint16_t(buf, 0, chan1_raw);
_mav_put_uint16_t(buf, 2, chan2_raw);
_mav_put_uint16_t(buf, 4, chan3_raw);
_mav_put_uint16_t(buf, 6, chan4_raw);
_mav_put_uint16_t(buf, 8, chan5_raw);
_mav_put_uint16_t(buf, 10, chan6_raw);
_mav_put_uint16_t(buf, 12, chan7_raw);
_mav_put_uint16_t(buf, 14, chan8_raw);
_mav_put_uint8_t(buf, 16, target_system);
_mav_put_uint8_t(buf, 17, target_component);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 18);
#else
mavlink_rc_channels_override_t packet;
packet.chan1_raw = chan1_raw;
packet.chan2_raw = chan2_raw;
packet.chan3_raw = chan3_raw;
packet.chan4_raw = chan4_raw;
packet.chan5_raw = chan5_raw;
packet.chan6_raw = chan6_raw;
packet.chan7_raw = chan7_raw;
packet.chan8_raw = chan8_raw;
packet.target_system = target_system;
packet.target_component = target_component;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 18);
#endif
 
msg->msgid = MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE;
return mavlink_finalize_message(msg, system_id, component_id, 18, 124);
}
 
/**
* @brief Pack a rc_channels_override message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param target_system System ID
* @param target_component Component ID
* @param chan1_raw RC channel 1 value, in microseconds
* @param chan2_raw RC channel 2 value, in microseconds
* @param chan3_raw RC channel 3 value, in microseconds
* @param chan4_raw RC channel 4 value, in microseconds
* @param chan5_raw RC channel 5 value, in microseconds
* @param chan6_raw RC channel 6 value, in microseconds
* @param chan7_raw RC channel 7 value, in microseconds
* @param chan8_raw RC channel 8 value, in microseconds
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_rc_channels_override_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,uint16_t chan1_raw,uint16_t chan2_raw,uint16_t chan3_raw,uint16_t chan4_raw,uint16_t chan5_raw,uint16_t chan6_raw,uint16_t chan7_raw,uint16_t chan8_raw)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[18];
_mav_put_uint16_t(buf, 0, chan1_raw);
_mav_put_uint16_t(buf, 2, chan2_raw);
_mav_put_uint16_t(buf, 4, chan3_raw);
_mav_put_uint16_t(buf, 6, chan4_raw);
_mav_put_uint16_t(buf, 8, chan5_raw);
_mav_put_uint16_t(buf, 10, chan6_raw);
_mav_put_uint16_t(buf, 12, chan7_raw);
_mav_put_uint16_t(buf, 14, chan8_raw);
_mav_put_uint8_t(buf, 16, target_system);
_mav_put_uint8_t(buf, 17, target_component);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 18);
#else
mavlink_rc_channels_override_t packet;
packet.chan1_raw = chan1_raw;
packet.chan2_raw = chan2_raw;
packet.chan3_raw = chan3_raw;
packet.chan4_raw = chan4_raw;
packet.chan5_raw = chan5_raw;
packet.chan6_raw = chan6_raw;
packet.chan7_raw = chan7_raw;
packet.chan8_raw = chan8_raw;
packet.target_system = target_system;
packet.target_component = target_component;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 18);
#endif
 
msg->msgid = MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 18, 124);
}
 
/**
* @brief Encode a rc_channels_override struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param rc_channels_override C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_rc_channels_override_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_rc_channels_override_t* rc_channels_override)
{
return mavlink_msg_rc_channels_override_pack(system_id, component_id, msg, rc_channels_override->target_system, rc_channels_override->target_component, rc_channels_override->chan1_raw, rc_channels_override->chan2_raw, rc_channels_override->chan3_raw, rc_channels_override->chan4_raw, rc_channels_override->chan5_raw, rc_channels_override->chan6_raw, rc_channels_override->chan7_raw, rc_channels_override->chan8_raw);
}
 
/**
* @brief Send a rc_channels_override message
* @param chan MAVLink channel to send the message
*
* @param target_system System ID
* @param target_component Component ID
* @param chan1_raw RC channel 1 value, in microseconds
* @param chan2_raw RC channel 2 value, in microseconds
* @param chan3_raw RC channel 3 value, in microseconds
* @param chan4_raw RC channel 4 value, in microseconds
* @param chan5_raw RC channel 5 value, in microseconds
* @param chan6_raw RC channel 6 value, in microseconds
* @param chan7_raw RC channel 7 value, in microseconds
* @param chan8_raw RC channel 8 value, in microseconds
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_rc_channels_override_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t chan1_raw, uint16_t chan2_raw, uint16_t chan3_raw, uint16_t chan4_raw, uint16_t chan5_raw, uint16_t chan6_raw, uint16_t chan7_raw, uint16_t chan8_raw)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[18];
_mav_put_uint16_t(buf, 0, chan1_raw);
_mav_put_uint16_t(buf, 2, chan2_raw);
_mav_put_uint16_t(buf, 4, chan3_raw);
_mav_put_uint16_t(buf, 6, chan4_raw);
_mav_put_uint16_t(buf, 8, chan5_raw);
_mav_put_uint16_t(buf, 10, chan6_raw);
_mav_put_uint16_t(buf, 12, chan7_raw);
_mav_put_uint16_t(buf, 14, chan8_raw);
_mav_put_uint8_t(buf, 16, target_system);
_mav_put_uint8_t(buf, 17, target_component);
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE, buf, 18, 124);
#else
mavlink_rc_channels_override_t packet;
packet.chan1_raw = chan1_raw;
packet.chan2_raw = chan2_raw;
packet.chan3_raw = chan3_raw;
packet.chan4_raw = chan4_raw;
packet.chan5_raw = chan5_raw;
packet.chan6_raw = chan6_raw;
packet.chan7_raw = chan7_raw;
packet.chan8_raw = chan8_raw;
packet.target_system = target_system;
packet.target_component = target_component;
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE, (const char *)&packet, 18, 124);
#endif
}
 
#endif
 
// MESSAGE RC_CHANNELS_OVERRIDE UNPACKING
 
 
/**
* @brief Get field target_system from rc_channels_override message
*
* @return System ID
*/
static inline uint8_t mavlink_msg_rc_channels_override_get_target_system(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 16);
}
 
/**
* @brief Get field target_component from rc_channels_override message
*
* @return Component ID
*/
static inline uint8_t mavlink_msg_rc_channels_override_get_target_component(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 17);
}
 
/**
* @brief Get field chan1_raw from rc_channels_override message
*
* @return RC channel 1 value, in microseconds
*/
static inline uint16_t mavlink_msg_rc_channels_override_get_chan1_raw(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 0);
}
 
/**
* @brief Get field chan2_raw from rc_channels_override message
*
* @return RC channel 2 value, in microseconds
*/
static inline uint16_t mavlink_msg_rc_channels_override_get_chan2_raw(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 2);
}
 
/**
* @brief Get field chan3_raw from rc_channels_override message
*
* @return RC channel 3 value, in microseconds
*/
static inline uint16_t mavlink_msg_rc_channels_override_get_chan3_raw(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 4);
}
 
/**
* @brief Get field chan4_raw from rc_channels_override message
*
* @return RC channel 4 value, in microseconds
*/
static inline uint16_t mavlink_msg_rc_channels_override_get_chan4_raw(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 6);
}
 
/**
* @brief Get field chan5_raw from rc_channels_override message
*
* @return RC channel 5 value, in microseconds
*/
static inline uint16_t mavlink_msg_rc_channels_override_get_chan5_raw(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 8);
}
 
/**
* @brief Get field chan6_raw from rc_channels_override message
*
* @return RC channel 6 value, in microseconds
*/
static inline uint16_t mavlink_msg_rc_channels_override_get_chan6_raw(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 10);
}
 
/**
* @brief Get field chan7_raw from rc_channels_override message
*
* @return RC channel 7 value, in microseconds
*/
static inline uint16_t mavlink_msg_rc_channels_override_get_chan7_raw(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 12);
}
 
/**
* @brief Get field chan8_raw from rc_channels_override message
*
* @return RC channel 8 value, in microseconds
*/
static inline uint16_t mavlink_msg_rc_channels_override_get_chan8_raw(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 14);
}
 
/**
* @brief Decode a rc_channels_override message into a struct
*
* @param msg The message to decode
* @param rc_channels_override C-struct to decode the message contents into
*/
static inline void mavlink_msg_rc_channels_override_decode(const mavlink_message_t* msg, mavlink_rc_channels_override_t* rc_channels_override)
{
#if MAVLINK_NEED_BYTE_SWAP
rc_channels_override->chan1_raw = mavlink_msg_rc_channels_override_get_chan1_raw(msg);
rc_channels_override->chan2_raw = mavlink_msg_rc_channels_override_get_chan2_raw(msg);
rc_channels_override->chan3_raw = mavlink_msg_rc_channels_override_get_chan3_raw(msg);
rc_channels_override->chan4_raw = mavlink_msg_rc_channels_override_get_chan4_raw(msg);
rc_channels_override->chan5_raw = mavlink_msg_rc_channels_override_get_chan5_raw(msg);
rc_channels_override->chan6_raw = mavlink_msg_rc_channels_override_get_chan6_raw(msg);
rc_channels_override->chan7_raw = mavlink_msg_rc_channels_override_get_chan7_raw(msg);
rc_channels_override->chan8_raw = mavlink_msg_rc_channels_override_get_chan8_raw(msg);
rc_channels_override->target_system = mavlink_msg_rc_channels_override_get_target_system(msg);
rc_channels_override->target_component = mavlink_msg_rc_channels_override_get_target_component(msg);
#else
memcpy(rc_channels_override, _MAV_PAYLOAD(msg), 18);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v1.0/common/mavlink_msg_rc_channels_raw.h
0,0 → 1,364
// MESSAGE RC_CHANNELS_RAW PACKING
 
#define MAVLINK_MSG_ID_RC_CHANNELS_RAW 35
 
typedef struct __mavlink_rc_channels_raw_t
{
uint32_t time_boot_ms; ///< Timestamp (milliseconds since system boot)
uint16_t chan1_raw; ///< RC channel 1 value, in microseconds
uint16_t chan2_raw; ///< RC channel 2 value, in microseconds
uint16_t chan3_raw; ///< RC channel 3 value, in microseconds
uint16_t chan4_raw; ///< RC channel 4 value, in microseconds
uint16_t chan5_raw; ///< RC channel 5 value, in microseconds
uint16_t chan6_raw; ///< RC channel 6 value, in microseconds
uint16_t chan7_raw; ///< RC channel 7 value, in microseconds
uint16_t chan8_raw; ///< RC channel 8 value, in microseconds
uint8_t port; ///< Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos.
uint8_t rssi; ///< Receive signal strength indicator, 0: 0%, 255: 100%
} mavlink_rc_channels_raw_t;
 
#define MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN 22
#define MAVLINK_MSG_ID_35_LEN 22
 
 
 
#define MAVLINK_MESSAGE_INFO_RC_CHANNELS_RAW { \
"RC_CHANNELS_RAW", \
11, \
{ { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_rc_channels_raw_t, time_boot_ms) }, \
{ "chan1_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_rc_channels_raw_t, chan1_raw) }, \
{ "chan2_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_rc_channels_raw_t, chan2_raw) }, \
{ "chan3_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_rc_channels_raw_t, chan3_raw) }, \
{ "chan4_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 10, offsetof(mavlink_rc_channels_raw_t, chan4_raw) }, \
{ "chan5_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_rc_channels_raw_t, chan5_raw) }, \
{ "chan6_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 14, offsetof(mavlink_rc_channels_raw_t, chan6_raw) }, \
{ "chan7_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_rc_channels_raw_t, chan7_raw) }, \
{ "chan8_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_rc_channels_raw_t, chan8_raw) }, \
{ "port", NULL, MAVLINK_TYPE_UINT8_T, 0, 20, offsetof(mavlink_rc_channels_raw_t, port) }, \
{ "rssi", NULL, MAVLINK_TYPE_UINT8_T, 0, 21, offsetof(mavlink_rc_channels_raw_t, rssi) }, \
} \
}
 
 
/**
* @brief Pack a rc_channels_raw message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param time_boot_ms Timestamp (milliseconds since system boot)
* @param port Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos.
* @param chan1_raw RC channel 1 value, in microseconds
* @param chan2_raw RC channel 2 value, in microseconds
* @param chan3_raw RC channel 3 value, in microseconds
* @param chan4_raw RC channel 4 value, in microseconds
* @param chan5_raw RC channel 5 value, in microseconds
* @param chan6_raw RC channel 6 value, in microseconds
* @param chan7_raw RC channel 7 value, in microseconds
* @param chan8_raw RC channel 8 value, in microseconds
* @param rssi Receive signal strength indicator, 0: 0%, 255: 100%
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_rc_channels_raw_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint32_t time_boot_ms, uint8_t port, uint16_t chan1_raw, uint16_t chan2_raw, uint16_t chan3_raw, uint16_t chan4_raw, uint16_t chan5_raw, uint16_t chan6_raw, uint16_t chan7_raw, uint16_t chan8_raw, uint8_t rssi)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[22];
_mav_put_uint32_t(buf, 0, time_boot_ms);
_mav_put_uint16_t(buf, 4, chan1_raw);
_mav_put_uint16_t(buf, 6, chan2_raw);
_mav_put_uint16_t(buf, 8, chan3_raw);
_mav_put_uint16_t(buf, 10, chan4_raw);
_mav_put_uint16_t(buf, 12, chan5_raw);
_mav_put_uint16_t(buf, 14, chan6_raw);
_mav_put_uint16_t(buf, 16, chan7_raw);
_mav_put_uint16_t(buf, 18, chan8_raw);
_mav_put_uint8_t(buf, 20, port);
_mav_put_uint8_t(buf, 21, rssi);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 22);
#else
mavlink_rc_channels_raw_t packet;
packet.time_boot_ms = time_boot_ms;
packet.chan1_raw = chan1_raw;
packet.chan2_raw = chan2_raw;
packet.chan3_raw = chan3_raw;
packet.chan4_raw = chan4_raw;
packet.chan5_raw = chan5_raw;
packet.chan6_raw = chan6_raw;
packet.chan7_raw = chan7_raw;
packet.chan8_raw = chan8_raw;
packet.port = port;
packet.rssi = rssi;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 22);
#endif
 
msg->msgid = MAVLINK_MSG_ID_RC_CHANNELS_RAW;
return mavlink_finalize_message(msg, system_id, component_id, 22, 244);
}
 
/**
* @brief Pack a rc_channels_raw message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param time_boot_ms Timestamp (milliseconds since system boot)
* @param port Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos.
* @param chan1_raw RC channel 1 value, in microseconds
* @param chan2_raw RC channel 2 value, in microseconds
* @param chan3_raw RC channel 3 value, in microseconds
* @param chan4_raw RC channel 4 value, in microseconds
* @param chan5_raw RC channel 5 value, in microseconds
* @param chan6_raw RC channel 6 value, in microseconds
* @param chan7_raw RC channel 7 value, in microseconds
* @param chan8_raw RC channel 8 value, in microseconds
* @param rssi Receive signal strength indicator, 0: 0%, 255: 100%
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_rc_channels_raw_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint32_t time_boot_ms,uint8_t port,uint16_t chan1_raw,uint16_t chan2_raw,uint16_t chan3_raw,uint16_t chan4_raw,uint16_t chan5_raw,uint16_t chan6_raw,uint16_t chan7_raw,uint16_t chan8_raw,uint8_t rssi)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[22];
_mav_put_uint32_t(buf, 0, time_boot_ms);
_mav_put_uint16_t(buf, 4, chan1_raw);
_mav_put_uint16_t(buf, 6, chan2_raw);
_mav_put_uint16_t(buf, 8, chan3_raw);
_mav_put_uint16_t(buf, 10, chan4_raw);
_mav_put_uint16_t(buf, 12, chan5_raw);
_mav_put_uint16_t(buf, 14, chan6_raw);
_mav_put_uint16_t(buf, 16, chan7_raw);
_mav_put_uint16_t(buf, 18, chan8_raw);
_mav_put_uint8_t(buf, 20, port);
_mav_put_uint8_t(buf, 21, rssi);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 22);
#else
mavlink_rc_channels_raw_t packet;
packet.time_boot_ms = time_boot_ms;
packet.chan1_raw = chan1_raw;
packet.chan2_raw = chan2_raw;
packet.chan3_raw = chan3_raw;
packet.chan4_raw = chan4_raw;
packet.chan5_raw = chan5_raw;
packet.chan6_raw = chan6_raw;
packet.chan7_raw = chan7_raw;
packet.chan8_raw = chan8_raw;
packet.port = port;
packet.rssi = rssi;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 22);
#endif
 
msg->msgid = MAVLINK_MSG_ID_RC_CHANNELS_RAW;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 22, 244);
}
 
/**
* @brief Encode a rc_channels_raw struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param rc_channels_raw C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_rc_channels_raw_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_rc_channels_raw_t* rc_channels_raw)
{
return mavlink_msg_rc_channels_raw_pack(system_id, component_id, msg, rc_channels_raw->time_boot_ms, rc_channels_raw->port, rc_channels_raw->chan1_raw, rc_channels_raw->chan2_raw, rc_channels_raw->chan3_raw, rc_channels_raw->chan4_raw, rc_channels_raw->chan5_raw, rc_channels_raw->chan6_raw, rc_channels_raw->chan7_raw, rc_channels_raw->chan8_raw, rc_channels_raw->rssi);
}
 
/**
* @brief Send a rc_channels_raw message
* @param chan MAVLink channel to send the message
*
* @param time_boot_ms Timestamp (milliseconds since system boot)
* @param port Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos.
* @param chan1_raw RC channel 1 value, in microseconds
* @param chan2_raw RC channel 2 value, in microseconds
* @param chan3_raw RC channel 3 value, in microseconds
* @param chan4_raw RC channel 4 value, in microseconds
* @param chan5_raw RC channel 5 value, in microseconds
* @param chan6_raw RC channel 6 value, in microseconds
* @param chan7_raw RC channel 7 value, in microseconds
* @param chan8_raw RC channel 8 value, in microseconds
* @param rssi Receive signal strength indicator, 0: 0%, 255: 100%
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_rc_channels_raw_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t port, uint16_t chan1_raw, uint16_t chan2_raw, uint16_t chan3_raw, uint16_t chan4_raw, uint16_t chan5_raw, uint16_t chan6_raw, uint16_t chan7_raw, uint16_t chan8_raw, uint8_t rssi)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[22];
_mav_put_uint32_t(buf, 0, time_boot_ms);
_mav_put_uint16_t(buf, 4, chan1_raw);
_mav_put_uint16_t(buf, 6, chan2_raw);
_mav_put_uint16_t(buf, 8, chan3_raw);
_mav_put_uint16_t(buf, 10, chan4_raw);
_mav_put_uint16_t(buf, 12, chan5_raw);
_mav_put_uint16_t(buf, 14, chan6_raw);
_mav_put_uint16_t(buf, 16, chan7_raw);
_mav_put_uint16_t(buf, 18, chan8_raw);
_mav_put_uint8_t(buf, 20, port);
_mav_put_uint8_t(buf, 21, rssi);
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_RAW, buf, 22, 244);
#else
mavlink_rc_channels_raw_t packet;
packet.time_boot_ms = time_boot_ms;
packet.chan1_raw = chan1_raw;
packet.chan2_raw = chan2_raw;
packet.chan3_raw = chan3_raw;
packet.chan4_raw = chan4_raw;
packet.chan5_raw = chan5_raw;
packet.chan6_raw = chan6_raw;
packet.chan7_raw = chan7_raw;
packet.chan8_raw = chan8_raw;
packet.port = port;
packet.rssi = rssi;
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_RAW, (const char *)&packet, 22, 244);
#endif
}
 
#endif
 
// MESSAGE RC_CHANNELS_RAW UNPACKING
 
 
/**
* @brief Get field time_boot_ms from rc_channels_raw message
*
* @return Timestamp (milliseconds since system boot)
*/
static inline uint32_t mavlink_msg_rc_channels_raw_get_time_boot_ms(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint32_t(msg, 0);
}
 
/**
* @brief Get field port from rc_channels_raw message
*
* @return Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos.
*/
static inline uint8_t mavlink_msg_rc_channels_raw_get_port(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 20);
}
 
/**
* @brief Get field chan1_raw from rc_channels_raw message
*
* @return RC channel 1 value, in microseconds
*/
static inline uint16_t mavlink_msg_rc_channels_raw_get_chan1_raw(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 4);
}
 
/**
* @brief Get field chan2_raw from rc_channels_raw message
*
* @return RC channel 2 value, in microseconds
*/
static inline uint16_t mavlink_msg_rc_channels_raw_get_chan2_raw(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 6);
}
 
/**
* @brief Get field chan3_raw from rc_channels_raw message
*
* @return RC channel 3 value, in microseconds
*/
static inline uint16_t mavlink_msg_rc_channels_raw_get_chan3_raw(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 8);
}
 
/**
* @brief Get field chan4_raw from rc_channels_raw message
*
* @return RC channel 4 value, in microseconds
*/
static inline uint16_t mavlink_msg_rc_channels_raw_get_chan4_raw(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 10);
}
 
/**
* @brief Get field chan5_raw from rc_channels_raw message
*
* @return RC channel 5 value, in microseconds
*/
static inline uint16_t mavlink_msg_rc_channels_raw_get_chan5_raw(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 12);
}
 
/**
* @brief Get field chan6_raw from rc_channels_raw message
*
* @return RC channel 6 value, in microseconds
*/
static inline uint16_t mavlink_msg_rc_channels_raw_get_chan6_raw(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 14);
}
 
/**
* @brief Get field chan7_raw from rc_channels_raw message
*
* @return RC channel 7 value, in microseconds
*/
static inline uint16_t mavlink_msg_rc_channels_raw_get_chan7_raw(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 16);
}
 
/**
* @brief Get field chan8_raw from rc_channels_raw message
*
* @return RC channel 8 value, in microseconds
*/
static inline uint16_t mavlink_msg_rc_channels_raw_get_chan8_raw(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 18);
}
 
/**
* @brief Get field rssi from rc_channels_raw message
*
* @return Receive signal strength indicator, 0: 0%, 255: 100%
*/
static inline uint8_t mavlink_msg_rc_channels_raw_get_rssi(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 21);
}
 
/**
* @brief Decode a rc_channels_raw message into a struct
*
* @param msg The message to decode
* @param rc_channels_raw C-struct to decode the message contents into
*/
static inline void mavlink_msg_rc_channels_raw_decode(const mavlink_message_t* msg, mavlink_rc_channels_raw_t* rc_channels_raw)
{
#if MAVLINK_NEED_BYTE_SWAP
rc_channels_raw->time_boot_ms = mavlink_msg_rc_channels_raw_get_time_boot_ms(msg);
rc_channels_raw->chan1_raw = mavlink_msg_rc_channels_raw_get_chan1_raw(msg);
rc_channels_raw->chan2_raw = mavlink_msg_rc_channels_raw_get_chan2_raw(msg);
rc_channels_raw->chan3_raw = mavlink_msg_rc_channels_raw_get_chan3_raw(msg);
rc_channels_raw->chan4_raw = mavlink_msg_rc_channels_raw_get_chan4_raw(msg);
rc_channels_raw->chan5_raw = mavlink_msg_rc_channels_raw_get_chan5_raw(msg);
rc_channels_raw->chan6_raw = mavlink_msg_rc_channels_raw_get_chan6_raw(msg);
rc_channels_raw->chan7_raw = mavlink_msg_rc_channels_raw_get_chan7_raw(msg);
rc_channels_raw->chan8_raw = mavlink_msg_rc_channels_raw_get_chan8_raw(msg);
rc_channels_raw->port = mavlink_msg_rc_channels_raw_get_port(msg);
rc_channels_raw->rssi = mavlink_msg_rc_channels_raw_get_rssi(msg);
#else
memcpy(rc_channels_raw, _MAV_PAYLOAD(msg), 22);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v1.0/common/mavlink_msg_rc_channels_scaled.h
0,0 → 1,364
// MESSAGE RC_CHANNELS_SCALED PACKING
 
#define MAVLINK_MSG_ID_RC_CHANNELS_SCALED 34
 
typedef struct __mavlink_rc_channels_scaled_t
{
uint32_t time_boot_ms; ///< Timestamp (milliseconds since system boot)
int16_t chan1_scaled; ///< RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
int16_t chan2_scaled; ///< RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
int16_t chan3_scaled; ///< RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
int16_t chan4_scaled; ///< RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
int16_t chan5_scaled; ///< RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
int16_t chan6_scaled; ///< RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
int16_t chan7_scaled; ///< RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
int16_t chan8_scaled; ///< RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
uint8_t port; ///< Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos.
uint8_t rssi; ///< Receive signal strength indicator, 0: 0%, 255: 100%
} mavlink_rc_channels_scaled_t;
 
#define MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN 22
#define MAVLINK_MSG_ID_34_LEN 22
 
 
 
#define MAVLINK_MESSAGE_INFO_RC_CHANNELS_SCALED { \
"RC_CHANNELS_SCALED", \
11, \
{ { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_rc_channels_scaled_t, time_boot_ms) }, \
{ "chan1_scaled", NULL, MAVLINK_TYPE_INT16_T, 0, 4, offsetof(mavlink_rc_channels_scaled_t, chan1_scaled) }, \
{ "chan2_scaled", NULL, MAVLINK_TYPE_INT16_T, 0, 6, offsetof(mavlink_rc_channels_scaled_t, chan2_scaled) }, \
{ "chan3_scaled", NULL, MAVLINK_TYPE_INT16_T, 0, 8, offsetof(mavlink_rc_channels_scaled_t, chan3_scaled) }, \
{ "chan4_scaled", NULL, MAVLINK_TYPE_INT16_T, 0, 10, offsetof(mavlink_rc_channels_scaled_t, chan4_scaled) }, \
{ "chan5_scaled", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_rc_channels_scaled_t, chan5_scaled) }, \
{ "chan6_scaled", NULL, MAVLINK_TYPE_INT16_T, 0, 14, offsetof(mavlink_rc_channels_scaled_t, chan6_scaled) }, \
{ "chan7_scaled", NULL, MAVLINK_TYPE_INT16_T, 0, 16, offsetof(mavlink_rc_channels_scaled_t, chan7_scaled) }, \
{ "chan8_scaled", NULL, MAVLINK_TYPE_INT16_T, 0, 18, offsetof(mavlink_rc_channels_scaled_t, chan8_scaled) }, \
{ "port", NULL, MAVLINK_TYPE_UINT8_T, 0, 20, offsetof(mavlink_rc_channels_scaled_t, port) }, \
{ "rssi", NULL, MAVLINK_TYPE_UINT8_T, 0, 21, offsetof(mavlink_rc_channels_scaled_t, rssi) }, \
} \
}
 
 
/**
* @brief Pack a rc_channels_scaled message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param time_boot_ms Timestamp (milliseconds since system boot)
* @param port Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos.
* @param chan1_scaled RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
* @param chan2_scaled RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
* @param chan3_scaled RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
* @param chan4_scaled RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
* @param chan5_scaled RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
* @param chan6_scaled RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
* @param chan7_scaled RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
* @param chan8_scaled RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
* @param rssi Receive signal strength indicator, 0: 0%, 255: 100%
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_rc_channels_scaled_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint32_t time_boot_ms, uint8_t port, int16_t chan1_scaled, int16_t chan2_scaled, int16_t chan3_scaled, int16_t chan4_scaled, int16_t chan5_scaled, int16_t chan6_scaled, int16_t chan7_scaled, int16_t chan8_scaled, uint8_t rssi)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[22];
_mav_put_uint32_t(buf, 0, time_boot_ms);
_mav_put_int16_t(buf, 4, chan1_scaled);
_mav_put_int16_t(buf, 6, chan2_scaled);
_mav_put_int16_t(buf, 8, chan3_scaled);
_mav_put_int16_t(buf, 10, chan4_scaled);
_mav_put_int16_t(buf, 12, chan5_scaled);
_mav_put_int16_t(buf, 14, chan6_scaled);
_mav_put_int16_t(buf, 16, chan7_scaled);
_mav_put_int16_t(buf, 18, chan8_scaled);
_mav_put_uint8_t(buf, 20, port);
_mav_put_uint8_t(buf, 21, rssi);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 22);
#else
mavlink_rc_channels_scaled_t packet;
packet.time_boot_ms = time_boot_ms;
packet.chan1_scaled = chan1_scaled;
packet.chan2_scaled = chan2_scaled;
packet.chan3_scaled = chan3_scaled;
packet.chan4_scaled = chan4_scaled;
packet.chan5_scaled = chan5_scaled;
packet.chan6_scaled = chan6_scaled;
packet.chan7_scaled = chan7_scaled;
packet.chan8_scaled = chan8_scaled;
packet.port = port;
packet.rssi = rssi;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 22);
#endif
 
msg->msgid = MAVLINK_MSG_ID_RC_CHANNELS_SCALED;
return mavlink_finalize_message(msg, system_id, component_id, 22, 237);
}
 
/**
* @brief Pack a rc_channels_scaled message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param time_boot_ms Timestamp (milliseconds since system boot)
* @param port Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos.
* @param chan1_scaled RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
* @param chan2_scaled RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
* @param chan3_scaled RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
* @param chan4_scaled RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
* @param chan5_scaled RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
* @param chan6_scaled RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
* @param chan7_scaled RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
* @param chan8_scaled RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
* @param rssi Receive signal strength indicator, 0: 0%, 255: 100%
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_rc_channels_scaled_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint32_t time_boot_ms,uint8_t port,int16_t chan1_scaled,int16_t chan2_scaled,int16_t chan3_scaled,int16_t chan4_scaled,int16_t chan5_scaled,int16_t chan6_scaled,int16_t chan7_scaled,int16_t chan8_scaled,uint8_t rssi)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[22];
_mav_put_uint32_t(buf, 0, time_boot_ms);
_mav_put_int16_t(buf, 4, chan1_scaled);
_mav_put_int16_t(buf, 6, chan2_scaled);
_mav_put_int16_t(buf, 8, chan3_scaled);
_mav_put_int16_t(buf, 10, chan4_scaled);
_mav_put_int16_t(buf, 12, chan5_scaled);
_mav_put_int16_t(buf, 14, chan6_scaled);
_mav_put_int16_t(buf, 16, chan7_scaled);
_mav_put_int16_t(buf, 18, chan8_scaled);
_mav_put_uint8_t(buf, 20, port);
_mav_put_uint8_t(buf, 21, rssi);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 22);
#else
mavlink_rc_channels_scaled_t packet;
packet.time_boot_ms = time_boot_ms;
packet.chan1_scaled = chan1_scaled;
packet.chan2_scaled = chan2_scaled;
packet.chan3_scaled = chan3_scaled;
packet.chan4_scaled = chan4_scaled;
packet.chan5_scaled = chan5_scaled;
packet.chan6_scaled = chan6_scaled;
packet.chan7_scaled = chan7_scaled;
packet.chan8_scaled = chan8_scaled;
packet.port = port;
packet.rssi = rssi;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 22);
#endif
 
msg->msgid = MAVLINK_MSG_ID_RC_CHANNELS_SCALED;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 22, 237);
}
 
/**
* @brief Encode a rc_channels_scaled struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param rc_channels_scaled C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_rc_channels_scaled_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_rc_channels_scaled_t* rc_channels_scaled)
{
return mavlink_msg_rc_channels_scaled_pack(system_id, component_id, msg, rc_channels_scaled->time_boot_ms, rc_channels_scaled->port, rc_channels_scaled->chan1_scaled, rc_channels_scaled->chan2_scaled, rc_channels_scaled->chan3_scaled, rc_channels_scaled->chan4_scaled, rc_channels_scaled->chan5_scaled, rc_channels_scaled->chan6_scaled, rc_channels_scaled->chan7_scaled, rc_channels_scaled->chan8_scaled, rc_channels_scaled->rssi);
}
 
/**
* @brief Send a rc_channels_scaled message
* @param chan MAVLink channel to send the message
*
* @param time_boot_ms Timestamp (milliseconds since system boot)
* @param port Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos.
* @param chan1_scaled RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
* @param chan2_scaled RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
* @param chan3_scaled RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
* @param chan4_scaled RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
* @param chan5_scaled RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
* @param chan6_scaled RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
* @param chan7_scaled RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
* @param chan8_scaled RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
* @param rssi Receive signal strength indicator, 0: 0%, 255: 100%
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_rc_channels_scaled_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t port, int16_t chan1_scaled, int16_t chan2_scaled, int16_t chan3_scaled, int16_t chan4_scaled, int16_t chan5_scaled, int16_t chan6_scaled, int16_t chan7_scaled, int16_t chan8_scaled, uint8_t rssi)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[22];
_mav_put_uint32_t(buf, 0, time_boot_ms);
_mav_put_int16_t(buf, 4, chan1_scaled);
_mav_put_int16_t(buf, 6, chan2_scaled);
_mav_put_int16_t(buf, 8, chan3_scaled);
_mav_put_int16_t(buf, 10, chan4_scaled);
_mav_put_int16_t(buf, 12, chan5_scaled);
_mav_put_int16_t(buf, 14, chan6_scaled);
_mav_put_int16_t(buf, 16, chan7_scaled);
_mav_put_int16_t(buf, 18, chan8_scaled);
_mav_put_uint8_t(buf, 20, port);
_mav_put_uint8_t(buf, 21, rssi);
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_SCALED, buf, 22, 237);
#else
mavlink_rc_channels_scaled_t packet;
packet.time_boot_ms = time_boot_ms;
packet.chan1_scaled = chan1_scaled;
packet.chan2_scaled = chan2_scaled;
packet.chan3_scaled = chan3_scaled;
packet.chan4_scaled = chan4_scaled;
packet.chan5_scaled = chan5_scaled;
packet.chan6_scaled = chan6_scaled;
packet.chan7_scaled = chan7_scaled;
packet.chan8_scaled = chan8_scaled;
packet.port = port;
packet.rssi = rssi;
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_SCALED, (const char *)&packet, 22, 237);
#endif
}
 
#endif
 
// MESSAGE RC_CHANNELS_SCALED UNPACKING
 
 
/**
* @brief Get field time_boot_ms from rc_channels_scaled message
*
* @return Timestamp (milliseconds since system boot)
*/
static inline uint32_t mavlink_msg_rc_channels_scaled_get_time_boot_ms(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint32_t(msg, 0);
}
 
/**
* @brief Get field port from rc_channels_scaled message
*
* @return Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos.
*/
static inline uint8_t mavlink_msg_rc_channels_scaled_get_port(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 20);
}
 
/**
* @brief Get field chan1_scaled from rc_channels_scaled message
*
* @return RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
*/
static inline int16_t mavlink_msg_rc_channels_scaled_get_chan1_scaled(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 4);
}
 
/**
* @brief Get field chan2_scaled from rc_channels_scaled message
*
* @return RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
*/
static inline int16_t mavlink_msg_rc_channels_scaled_get_chan2_scaled(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 6);
}
 
/**
* @brief Get field chan3_scaled from rc_channels_scaled message
*
* @return RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
*/
static inline int16_t mavlink_msg_rc_channels_scaled_get_chan3_scaled(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 8);
}
 
/**
* @brief Get field chan4_scaled from rc_channels_scaled message
*
* @return RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
*/
static inline int16_t mavlink_msg_rc_channels_scaled_get_chan4_scaled(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 10);
}
 
/**
* @brief Get field chan5_scaled from rc_channels_scaled message
*
* @return RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
*/
static inline int16_t mavlink_msg_rc_channels_scaled_get_chan5_scaled(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 12);
}
 
/**
* @brief Get field chan6_scaled from rc_channels_scaled message
*
* @return RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
*/
static inline int16_t mavlink_msg_rc_channels_scaled_get_chan6_scaled(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 14);
}
 
/**
* @brief Get field chan7_scaled from rc_channels_scaled message
*
* @return RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
*/
static inline int16_t mavlink_msg_rc_channels_scaled_get_chan7_scaled(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 16);
}
 
/**
* @brief Get field chan8_scaled from rc_channels_scaled message
*
* @return RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000
*/
static inline int16_t mavlink_msg_rc_channels_scaled_get_chan8_scaled(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 18);
}
 
/**
* @brief Get field rssi from rc_channels_scaled message
*
* @return Receive signal strength indicator, 0: 0%, 255: 100%
*/
static inline uint8_t mavlink_msg_rc_channels_scaled_get_rssi(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 21);
}
 
/**
* @brief Decode a rc_channels_scaled message into a struct
*
* @param msg The message to decode
* @param rc_channels_scaled C-struct to decode the message contents into
*/
static inline void mavlink_msg_rc_channels_scaled_decode(const mavlink_message_t* msg, mavlink_rc_channels_scaled_t* rc_channels_scaled)
{
#if MAVLINK_NEED_BYTE_SWAP
rc_channels_scaled->time_boot_ms = mavlink_msg_rc_channels_scaled_get_time_boot_ms(msg);
rc_channels_scaled->chan1_scaled = mavlink_msg_rc_channels_scaled_get_chan1_scaled(msg);
rc_channels_scaled->chan2_scaled = mavlink_msg_rc_channels_scaled_get_chan2_scaled(msg);
rc_channels_scaled->chan3_scaled = mavlink_msg_rc_channels_scaled_get_chan3_scaled(msg);
rc_channels_scaled->chan4_scaled = mavlink_msg_rc_channels_scaled_get_chan4_scaled(msg);
rc_channels_scaled->chan5_scaled = mavlink_msg_rc_channels_scaled_get_chan5_scaled(msg);
rc_channels_scaled->chan6_scaled = mavlink_msg_rc_channels_scaled_get_chan6_scaled(msg);
rc_channels_scaled->chan7_scaled = mavlink_msg_rc_channels_scaled_get_chan7_scaled(msg);
rc_channels_scaled->chan8_scaled = mavlink_msg_rc_channels_scaled_get_chan8_scaled(msg);
rc_channels_scaled->port = mavlink_msg_rc_channels_scaled_get_port(msg);
rc_channels_scaled->rssi = mavlink_msg_rc_channels_scaled_get_rssi(msg);
#else
memcpy(rc_channels_scaled, _MAV_PAYLOAD(msg), 22);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v1.0/common/mavlink_msg_request_data_stream.h
0,0 → 1,232
// MESSAGE REQUEST_DATA_STREAM PACKING
 
#define MAVLINK_MSG_ID_REQUEST_DATA_STREAM 66
 
typedef struct __mavlink_request_data_stream_t
{
uint16_t req_message_rate; ///< The requested interval between two messages of this type
uint8_t target_system; ///< The target requested to send the message stream.
uint8_t target_component; ///< The target requested to send the message stream.
uint8_t req_stream_id; ///< The ID of the requested data stream
uint8_t start_stop; ///< 1 to start sending, 0 to stop sending.
} mavlink_request_data_stream_t;
 
#define MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN 6
#define MAVLINK_MSG_ID_66_LEN 6
 
 
 
#define MAVLINK_MESSAGE_INFO_REQUEST_DATA_STREAM { \
"REQUEST_DATA_STREAM", \
5, \
{ { "req_message_rate", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_request_data_stream_t, req_message_rate) }, \
{ "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_request_data_stream_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_request_data_stream_t, target_component) }, \
{ "req_stream_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_request_data_stream_t, req_stream_id) }, \
{ "start_stop", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_request_data_stream_t, start_stop) }, \
} \
}
 
 
/**
* @brief Pack a request_data_stream message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param target_system The target requested to send the message stream.
* @param target_component The target requested to send the message stream.
* @param req_stream_id The ID of the requested data stream
* @param req_message_rate The requested interval between two messages of this type
* @param start_stop 1 to start sending, 0 to stop sending.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_request_data_stream_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t target_system, uint8_t target_component, uint8_t req_stream_id, uint16_t req_message_rate, uint8_t start_stop)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[6];
_mav_put_uint16_t(buf, 0, req_message_rate);
_mav_put_uint8_t(buf, 2, target_system);
_mav_put_uint8_t(buf, 3, target_component);
_mav_put_uint8_t(buf, 4, req_stream_id);
_mav_put_uint8_t(buf, 5, start_stop);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 6);
#else
mavlink_request_data_stream_t packet;
packet.req_message_rate = req_message_rate;
packet.target_system = target_system;
packet.target_component = target_component;
packet.req_stream_id = req_stream_id;
packet.start_stop = start_stop;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 6);
#endif
 
msg->msgid = MAVLINK_MSG_ID_REQUEST_DATA_STREAM;
return mavlink_finalize_message(msg, system_id, component_id, 6, 148);
}
 
/**
* @brief Pack a request_data_stream message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param target_system The target requested to send the message stream.
* @param target_component The target requested to send the message stream.
* @param req_stream_id The ID of the requested data stream
* @param req_message_rate The requested interval between two messages of this type
* @param start_stop 1 to start sending, 0 to stop sending.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_request_data_stream_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 req_stream_id,uint16_t req_message_rate,uint8_t start_stop)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[6];
_mav_put_uint16_t(buf, 0, req_message_rate);
_mav_put_uint8_t(buf, 2, target_system);
_mav_put_uint8_t(buf, 3, target_component);
_mav_put_uint8_t(buf, 4, req_stream_id);
_mav_put_uint8_t(buf, 5, start_stop);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 6);
#else
mavlink_request_data_stream_t packet;
packet.req_message_rate = req_message_rate;
packet.target_system = target_system;
packet.target_component = target_component;
packet.req_stream_id = req_stream_id;
packet.start_stop = start_stop;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 6);
#endif
 
msg->msgid = MAVLINK_MSG_ID_REQUEST_DATA_STREAM;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 6, 148);
}
 
/**
* @brief Encode a request_data_stream struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param request_data_stream C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_request_data_stream_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_request_data_stream_t* request_data_stream)
{
return mavlink_msg_request_data_stream_pack(system_id, component_id, msg, request_data_stream->target_system, request_data_stream->target_component, request_data_stream->req_stream_id, request_data_stream->req_message_rate, request_data_stream->start_stop);
}
 
/**
* @brief Send a request_data_stream message
* @param chan MAVLink channel to send the message
*
* @param target_system The target requested to send the message stream.
* @param target_component The target requested to send the message stream.
* @param req_stream_id The ID of the requested data stream
* @param req_message_rate The requested interval between two messages of this type
* @param start_stop 1 to start sending, 0 to stop sending.
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_request_data_stream_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t req_stream_id, uint16_t req_message_rate, uint8_t start_stop)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[6];
_mav_put_uint16_t(buf, 0, req_message_rate);
_mav_put_uint8_t(buf, 2, target_system);
_mav_put_uint8_t(buf, 3, target_component);
_mav_put_uint8_t(buf, 4, req_stream_id);
_mav_put_uint8_t(buf, 5, start_stop);
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_REQUEST_DATA_STREAM, buf, 6, 148);
#else
mavlink_request_data_stream_t packet;
packet.req_message_rate = req_message_rate;
packet.target_system = target_system;
packet.target_component = target_component;
packet.req_stream_id = req_stream_id;
packet.start_stop = start_stop;
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_REQUEST_DATA_STREAM, (const char *)&packet, 6, 148);
#endif
}
 
#endif
 
// MESSAGE REQUEST_DATA_STREAM UNPACKING
 
 
/**
* @brief Get field target_system from request_data_stream message
*
* @return The target requested to send the message stream.
*/
static inline uint8_t mavlink_msg_request_data_stream_get_target_system(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 2);
}
 
/**
* @brief Get field target_component from request_data_stream message
*
* @return The target requested to send the message stream.
*/
static inline uint8_t mavlink_msg_request_data_stream_get_target_component(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 3);
}
 
/**
* @brief Get field req_stream_id from request_data_stream message
*
* @return The ID of the requested data stream
*/
static inline uint8_t mavlink_msg_request_data_stream_get_req_stream_id(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 4);
}
 
/**
* @brief Get field req_message_rate from request_data_stream message
*
* @return The requested interval between two messages of this type
*/
static inline uint16_t mavlink_msg_request_data_stream_get_req_message_rate(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 0);
}
 
/**
* @brief Get field start_stop from request_data_stream message
*
* @return 1 to start sending, 0 to stop sending.
*/
static inline uint8_t mavlink_msg_request_data_stream_get_start_stop(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 5);
}
 
/**
* @brief Decode a request_data_stream message into a struct
*
* @param msg The message to decode
* @param request_data_stream C-struct to decode the message contents into
*/
static inline void mavlink_msg_request_data_stream_decode(const mavlink_message_t* msg, mavlink_request_data_stream_t* request_data_stream)
{
#if MAVLINK_NEED_BYTE_SWAP
request_data_stream->req_message_rate = mavlink_msg_request_data_stream_get_req_message_rate(msg);
request_data_stream->target_system = mavlink_msg_request_data_stream_get_target_system(msg);
request_data_stream->target_component = mavlink_msg_request_data_stream_get_target_component(msg);
request_data_stream->req_stream_id = mavlink_msg_request_data_stream_get_req_stream_id(msg);
request_data_stream->start_stop = mavlink_msg_request_data_stream_get_start_stop(msg);
#else
memcpy(request_data_stream, _MAV_PAYLOAD(msg), 6);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v1.0/common/mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint.h
0,0 → 1,232
// MESSAGE ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT PACKING
 
#define MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT 59
 
typedef struct __mavlink_roll_pitch_yaw_speed_thrust_setpoint_t
{
uint32_t time_boot_ms; ///< Timestamp in milliseconds since system boot
float roll_speed; ///< Desired roll angular speed in rad/s
float pitch_speed; ///< Desired pitch angular speed in rad/s
float yaw_speed; ///< Desired yaw angular speed in rad/s
float thrust; ///< Collective thrust, normalized to 0 .. 1
} mavlink_roll_pitch_yaw_speed_thrust_setpoint_t;
 
#define MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT_LEN 20
#define MAVLINK_MSG_ID_59_LEN 20
 
 
 
#define MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT { \
"ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT", \
5, \
{ { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_roll_pitch_yaw_speed_thrust_setpoint_t, time_boot_ms) }, \
{ "roll_speed", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_roll_pitch_yaw_speed_thrust_setpoint_t, roll_speed) }, \
{ "pitch_speed", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_roll_pitch_yaw_speed_thrust_setpoint_t, pitch_speed) }, \
{ "yaw_speed", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_roll_pitch_yaw_speed_thrust_setpoint_t, yaw_speed) }, \
{ "thrust", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_roll_pitch_yaw_speed_thrust_setpoint_t, thrust) }, \
} \
}
 
 
/**
* @brief Pack a roll_pitch_yaw_speed_thrust_setpoint message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param time_boot_ms Timestamp in milliseconds since system boot
* @param roll_speed Desired roll angular speed in rad/s
* @param pitch_speed Desired pitch angular speed in rad/s
* @param yaw_speed Desired yaw angular speed in rad/s
* @param thrust Collective thrust, normalized to 0 .. 1
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint32_t time_boot_ms, float roll_speed, float pitch_speed, float yaw_speed, float thrust)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[20];
_mav_put_uint32_t(buf, 0, time_boot_ms);
_mav_put_float(buf, 4, roll_speed);
_mav_put_float(buf, 8, pitch_speed);
_mav_put_float(buf, 12, yaw_speed);
_mav_put_float(buf, 16, thrust);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 20);
#else
mavlink_roll_pitch_yaw_speed_thrust_setpoint_t packet;
packet.time_boot_ms = time_boot_ms;
packet.roll_speed = roll_speed;
packet.pitch_speed = pitch_speed;
packet.yaw_speed = yaw_speed;
packet.thrust = thrust;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 20);
#endif
 
msg->msgid = MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT;
return mavlink_finalize_message(msg, system_id, component_id, 20, 238);
}
 
/**
* @brief Pack a roll_pitch_yaw_speed_thrust_setpoint message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param time_boot_ms Timestamp in milliseconds since system boot
* @param roll_speed Desired roll angular speed in rad/s
* @param pitch_speed Desired pitch angular speed in rad/s
* @param yaw_speed Desired yaw angular speed in rad/s
* @param thrust Collective thrust, normalized to 0 .. 1
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint32_t time_boot_ms,float roll_speed,float pitch_speed,float yaw_speed,float thrust)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[20];
_mav_put_uint32_t(buf, 0, time_boot_ms);
_mav_put_float(buf, 4, roll_speed);
_mav_put_float(buf, 8, pitch_speed);
_mav_put_float(buf, 12, yaw_speed);
_mav_put_float(buf, 16, thrust);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 20);
#else
mavlink_roll_pitch_yaw_speed_thrust_setpoint_t packet;
packet.time_boot_ms = time_boot_ms;
packet.roll_speed = roll_speed;
packet.pitch_speed = pitch_speed;
packet.yaw_speed = yaw_speed;
packet.thrust = thrust;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 20);
#endif
 
msg->msgid = MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 20, 238);
}
 
/**
* @brief Encode a roll_pitch_yaw_speed_thrust_setpoint struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param roll_pitch_yaw_speed_thrust_setpoint C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_roll_pitch_yaw_speed_thrust_setpoint_t* roll_pitch_yaw_speed_thrust_setpoint)
{
return mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_pack(system_id, component_id, msg, roll_pitch_yaw_speed_thrust_setpoint->time_boot_ms, roll_pitch_yaw_speed_thrust_setpoint->roll_speed, roll_pitch_yaw_speed_thrust_setpoint->pitch_speed, roll_pitch_yaw_speed_thrust_setpoint->yaw_speed, roll_pitch_yaw_speed_thrust_setpoint->thrust);
}
 
/**
* @brief Send a roll_pitch_yaw_speed_thrust_setpoint message
* @param chan MAVLink channel to send the message
*
* @param time_boot_ms Timestamp in milliseconds since system boot
* @param roll_speed Desired roll angular speed in rad/s
* @param pitch_speed Desired pitch angular speed in rad/s
* @param yaw_speed Desired yaw angular speed in rad/s
* @param thrust Collective thrust, normalized to 0 .. 1
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_send(mavlink_channel_t chan, uint32_t time_boot_ms, float roll_speed, float pitch_speed, float yaw_speed, float thrust)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[20];
_mav_put_uint32_t(buf, 0, time_boot_ms);
_mav_put_float(buf, 4, roll_speed);
_mav_put_float(buf, 8, pitch_speed);
_mav_put_float(buf, 12, yaw_speed);
_mav_put_float(buf, 16, thrust);
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT, buf, 20, 238);
#else
mavlink_roll_pitch_yaw_speed_thrust_setpoint_t packet;
packet.time_boot_ms = time_boot_ms;
packet.roll_speed = roll_speed;
packet.pitch_speed = pitch_speed;
packet.yaw_speed = yaw_speed;
packet.thrust = thrust;
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT, (const char *)&packet, 20, 238);
#endif
}
 
#endif
 
// MESSAGE ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT UNPACKING
 
 
/**
* @brief Get field time_boot_ms from roll_pitch_yaw_speed_thrust_setpoint message
*
* @return Timestamp in milliseconds since system boot
*/
static inline uint32_t mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_get_time_boot_ms(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint32_t(msg, 0);
}
 
/**
* @brief Get field roll_speed from roll_pitch_yaw_speed_thrust_setpoint message
*
* @return Desired roll angular speed in rad/s
*/
static inline float mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_get_roll_speed(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 4);
}
 
/**
* @brief Get field pitch_speed from roll_pitch_yaw_speed_thrust_setpoint message
*
* @return Desired pitch angular speed in rad/s
*/
static inline float mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_get_pitch_speed(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 8);
}
 
/**
* @brief Get field yaw_speed from roll_pitch_yaw_speed_thrust_setpoint message
*
* @return Desired yaw angular speed in rad/s
*/
static inline float mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_get_yaw_speed(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 12);
}
 
/**
* @brief Get field thrust from roll_pitch_yaw_speed_thrust_setpoint message
*
* @return Collective thrust, normalized to 0 .. 1
*/
static inline float mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_get_thrust(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 16);
}
 
/**
* @brief Decode a roll_pitch_yaw_speed_thrust_setpoint message into a struct
*
* @param msg The message to decode
* @param roll_pitch_yaw_speed_thrust_setpoint C-struct to decode the message contents into
*/
static inline void mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_decode(const mavlink_message_t* msg, mavlink_roll_pitch_yaw_speed_thrust_setpoint_t* roll_pitch_yaw_speed_thrust_setpoint)
{
#if MAVLINK_NEED_BYTE_SWAP
roll_pitch_yaw_speed_thrust_setpoint->time_boot_ms = mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_get_time_boot_ms(msg);
roll_pitch_yaw_speed_thrust_setpoint->roll_speed = mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_get_roll_speed(msg);
roll_pitch_yaw_speed_thrust_setpoint->pitch_speed = mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_get_pitch_speed(msg);
roll_pitch_yaw_speed_thrust_setpoint->yaw_speed = mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_get_yaw_speed(msg);
roll_pitch_yaw_speed_thrust_setpoint->thrust = mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_get_thrust(msg);
#else
memcpy(roll_pitch_yaw_speed_thrust_setpoint, _MAV_PAYLOAD(msg), 20);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v1.0/common/mavlink_msg_roll_pitch_yaw_thrust_setpoint.h
0,0 → 1,232
// MESSAGE ROLL_PITCH_YAW_THRUST_SETPOINT PACKING
 
#define MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT 58
 
typedef struct __mavlink_roll_pitch_yaw_thrust_setpoint_t
{
uint32_t time_boot_ms; ///< Timestamp in milliseconds since system boot
float roll; ///< Desired roll angle in radians
float pitch; ///< Desired pitch angle in radians
float yaw; ///< Desired yaw angle in radians
float thrust; ///< Collective thrust, normalized to 0 .. 1
} mavlink_roll_pitch_yaw_thrust_setpoint_t;
 
#define MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT_LEN 20
#define MAVLINK_MSG_ID_58_LEN 20
 
 
 
#define MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_THRUST_SETPOINT { \
"ROLL_PITCH_YAW_THRUST_SETPOINT", \
5, \
{ { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_roll_pitch_yaw_thrust_setpoint_t, time_boot_ms) }, \
{ "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_roll_pitch_yaw_thrust_setpoint_t, roll) }, \
{ "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_roll_pitch_yaw_thrust_setpoint_t, pitch) }, \
{ "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_roll_pitch_yaw_thrust_setpoint_t, yaw) }, \
{ "thrust", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_roll_pitch_yaw_thrust_setpoint_t, thrust) }, \
} \
}
 
 
/**
* @brief Pack a roll_pitch_yaw_thrust_setpoint message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param time_boot_ms Timestamp in milliseconds since system boot
* @param roll Desired roll angle in radians
* @param pitch Desired pitch angle in radians
* @param yaw Desired yaw angle in radians
* @param thrust Collective thrust, normalized to 0 .. 1
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_roll_pitch_yaw_thrust_setpoint_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint32_t time_boot_ms, float roll, float pitch, float yaw, float thrust)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[20];
_mav_put_uint32_t(buf, 0, time_boot_ms);
_mav_put_float(buf, 4, roll);
_mav_put_float(buf, 8, pitch);
_mav_put_float(buf, 12, yaw);
_mav_put_float(buf, 16, thrust);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 20);
#else
mavlink_roll_pitch_yaw_thrust_setpoint_t packet;
packet.time_boot_ms = time_boot_ms;
packet.roll = roll;
packet.pitch = pitch;
packet.yaw = yaw;
packet.thrust = thrust;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 20);
#endif
 
msg->msgid = MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT;
return mavlink_finalize_message(msg, system_id, component_id, 20, 239);
}
 
/**
* @brief Pack a roll_pitch_yaw_thrust_setpoint message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param time_boot_ms Timestamp in milliseconds since system boot
* @param roll Desired roll angle in radians
* @param pitch Desired pitch angle in radians
* @param yaw Desired yaw angle in radians
* @param thrust Collective thrust, normalized to 0 .. 1
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_roll_pitch_yaw_thrust_setpoint_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint32_t time_boot_ms,float roll,float pitch,float yaw,float thrust)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[20];
_mav_put_uint32_t(buf, 0, time_boot_ms);
_mav_put_float(buf, 4, roll);
_mav_put_float(buf, 8, pitch);
_mav_put_float(buf, 12, yaw);
_mav_put_float(buf, 16, thrust);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 20);
#else
mavlink_roll_pitch_yaw_thrust_setpoint_t packet;
packet.time_boot_ms = time_boot_ms;
packet.roll = roll;
packet.pitch = pitch;
packet.yaw = yaw;
packet.thrust = thrust;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 20);
#endif
 
msg->msgid = MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 20, 239);
}
 
/**
* @brief Encode a roll_pitch_yaw_thrust_setpoint struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param roll_pitch_yaw_thrust_setpoint C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_roll_pitch_yaw_thrust_setpoint_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_roll_pitch_yaw_thrust_setpoint_t* roll_pitch_yaw_thrust_setpoint)
{
return mavlink_msg_roll_pitch_yaw_thrust_setpoint_pack(system_id, component_id, msg, roll_pitch_yaw_thrust_setpoint->time_boot_ms, roll_pitch_yaw_thrust_setpoint->roll, roll_pitch_yaw_thrust_setpoint->pitch, roll_pitch_yaw_thrust_setpoint->yaw, roll_pitch_yaw_thrust_setpoint->thrust);
}
 
/**
* @brief Send a roll_pitch_yaw_thrust_setpoint message
* @param chan MAVLink channel to send the message
*
* @param time_boot_ms Timestamp in milliseconds since system boot
* @param roll Desired roll angle in radians
* @param pitch Desired pitch angle in radians
* @param yaw Desired yaw angle in radians
* @param thrust Collective thrust, normalized to 0 .. 1
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_roll_pitch_yaw_thrust_setpoint_send(mavlink_channel_t chan, uint32_t time_boot_ms, float roll, float pitch, float yaw, float thrust)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[20];
_mav_put_uint32_t(buf, 0, time_boot_ms);
_mav_put_float(buf, 4, roll);
_mav_put_float(buf, 8, pitch);
_mav_put_float(buf, 12, yaw);
_mav_put_float(buf, 16, thrust);
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT, buf, 20, 239);
#else
mavlink_roll_pitch_yaw_thrust_setpoint_t packet;
packet.time_boot_ms = time_boot_ms;
packet.roll = roll;
packet.pitch = pitch;
packet.yaw = yaw;
packet.thrust = thrust;
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ROLL_PITCH_YAW_THRUST_SETPOINT, (const char *)&packet, 20, 239);
#endif
}
 
#endif
 
// MESSAGE ROLL_PITCH_YAW_THRUST_SETPOINT UNPACKING
 
 
/**
* @brief Get field time_boot_ms from roll_pitch_yaw_thrust_setpoint message
*
* @return Timestamp in milliseconds since system boot
*/
static inline uint32_t mavlink_msg_roll_pitch_yaw_thrust_setpoint_get_time_boot_ms(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint32_t(msg, 0);
}
 
/**
* @brief Get field roll from roll_pitch_yaw_thrust_setpoint message
*
* @return Desired roll angle in radians
*/
static inline float mavlink_msg_roll_pitch_yaw_thrust_setpoint_get_roll(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 4);
}
 
/**
* @brief Get field pitch from roll_pitch_yaw_thrust_setpoint message
*
* @return Desired pitch angle in radians
*/
static inline float mavlink_msg_roll_pitch_yaw_thrust_setpoint_get_pitch(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 8);
}
 
/**
* @brief Get field yaw from roll_pitch_yaw_thrust_setpoint message
*
* @return Desired yaw angle in radians
*/
static inline float mavlink_msg_roll_pitch_yaw_thrust_setpoint_get_yaw(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 12);
}
 
/**
* @brief Get field thrust from roll_pitch_yaw_thrust_setpoint message
*
* @return Collective thrust, normalized to 0 .. 1
*/
static inline float mavlink_msg_roll_pitch_yaw_thrust_setpoint_get_thrust(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 16);
}
 
/**
* @brief Decode a roll_pitch_yaw_thrust_setpoint message into a struct
*
* @param msg The message to decode
* @param roll_pitch_yaw_thrust_setpoint C-struct to decode the message contents into
*/
static inline void mavlink_msg_roll_pitch_yaw_thrust_setpoint_decode(const mavlink_message_t* msg, mavlink_roll_pitch_yaw_thrust_setpoint_t* roll_pitch_yaw_thrust_setpoint)
{
#if MAVLINK_NEED_BYTE_SWAP
roll_pitch_yaw_thrust_setpoint->time_boot_ms = mavlink_msg_roll_pitch_yaw_thrust_setpoint_get_time_boot_ms(msg);
roll_pitch_yaw_thrust_setpoint->roll = mavlink_msg_roll_pitch_yaw_thrust_setpoint_get_roll(msg);
roll_pitch_yaw_thrust_setpoint->pitch = mavlink_msg_roll_pitch_yaw_thrust_setpoint_get_pitch(msg);
roll_pitch_yaw_thrust_setpoint->yaw = mavlink_msg_roll_pitch_yaw_thrust_setpoint_get_yaw(msg);
roll_pitch_yaw_thrust_setpoint->thrust = mavlink_msg_roll_pitch_yaw_thrust_setpoint_get_thrust(msg);
#else
memcpy(roll_pitch_yaw_thrust_setpoint, _MAV_PAYLOAD(msg), 20);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v1.0/common/mavlink_msg_safety_allowed_area.h
0,0 → 1,276
// MESSAGE SAFETY_ALLOWED_AREA PACKING
 
#define MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA 55
 
typedef struct __mavlink_safety_allowed_area_t
{
float p1x; ///< x position 1 / Latitude 1
float p1y; ///< y position 1 / Longitude 1
float p1z; ///< z position 1 / Altitude 1
float p2x; ///< x position 2 / Latitude 2
float p2y; ///< y position 2 / Longitude 2
float p2z; ///< z position 2 / Altitude 2
uint8_t frame; ///< Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down.
} mavlink_safety_allowed_area_t;
 
#define MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN 25
#define MAVLINK_MSG_ID_55_LEN 25
 
 
 
#define MAVLINK_MESSAGE_INFO_SAFETY_ALLOWED_AREA { \
"SAFETY_ALLOWED_AREA", \
7, \
{ { "p1x", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_safety_allowed_area_t, p1x) }, \
{ "p1y", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_safety_allowed_area_t, p1y) }, \
{ "p1z", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_safety_allowed_area_t, p1z) }, \
{ "p2x", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_safety_allowed_area_t, p2x) }, \
{ "p2y", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_safety_allowed_area_t, p2y) }, \
{ "p2z", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_safety_allowed_area_t, p2z) }, \
{ "frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 24, offsetof(mavlink_safety_allowed_area_t, frame) }, \
} \
}
 
 
/**
* @brief Pack a safety_allowed_area message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param frame Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down.
* @param p1x x position 1 / Latitude 1
* @param p1y y position 1 / Longitude 1
* @param p1z z position 1 / Altitude 1
* @param p2x x position 2 / Latitude 2
* @param p2y y position 2 / Longitude 2
* @param p2z z position 2 / Altitude 2
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_safety_allowed_area_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t frame, float p1x, float p1y, float p1z, float p2x, float p2y, float p2z)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[25];
_mav_put_float(buf, 0, p1x);
_mav_put_float(buf, 4, p1y);
_mav_put_float(buf, 8, p1z);
_mav_put_float(buf, 12, p2x);
_mav_put_float(buf, 16, p2y);
_mav_put_float(buf, 20, p2z);
_mav_put_uint8_t(buf, 24, frame);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 25);
#else
mavlink_safety_allowed_area_t packet;
packet.p1x = p1x;
packet.p1y = p1y;
packet.p1z = p1z;
packet.p2x = p2x;
packet.p2y = p2y;
packet.p2z = p2z;
packet.frame = frame;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 25);
#endif
 
msg->msgid = MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA;
return mavlink_finalize_message(msg, system_id, component_id, 25, 3);
}
 
/**
* @brief Pack a safety_allowed_area message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param frame Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down.
* @param p1x x position 1 / Latitude 1
* @param p1y y position 1 / Longitude 1
* @param p1z z position 1 / Altitude 1
* @param p2x x position 2 / Latitude 2
* @param p2y y position 2 / Longitude 2
* @param p2z z position 2 / Altitude 2
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_safety_allowed_area_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint8_t frame,float p1x,float p1y,float p1z,float p2x,float p2y,float p2z)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[25];
_mav_put_float(buf, 0, p1x);
_mav_put_float(buf, 4, p1y);
_mav_put_float(buf, 8, p1z);
_mav_put_float(buf, 12, p2x);
_mav_put_float(buf, 16, p2y);
_mav_put_float(buf, 20, p2z);
_mav_put_uint8_t(buf, 24, frame);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 25);
#else
mavlink_safety_allowed_area_t packet;
packet.p1x = p1x;
packet.p1y = p1y;
packet.p1z = p1z;
packet.p2x = p2x;
packet.p2y = p2y;
packet.p2z = p2z;
packet.frame = frame;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 25);
#endif
 
msg->msgid = MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 25, 3);
}
 
/**
* @brief Encode a safety_allowed_area struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param safety_allowed_area C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_safety_allowed_area_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_safety_allowed_area_t* safety_allowed_area)
{
return mavlink_msg_safety_allowed_area_pack(system_id, component_id, msg, safety_allowed_area->frame, safety_allowed_area->p1x, safety_allowed_area->p1y, safety_allowed_area->p1z, safety_allowed_area->p2x, safety_allowed_area->p2y, safety_allowed_area->p2z);
}
 
/**
* @brief Send a safety_allowed_area message
* @param chan MAVLink channel to send the message
*
* @param frame Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down.
* @param p1x x position 1 / Latitude 1
* @param p1y y position 1 / Longitude 1
* @param p1z z position 1 / Altitude 1
* @param p2x x position 2 / Latitude 2
* @param p2y y position 2 / Longitude 2
* @param p2z z position 2 / Altitude 2
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_safety_allowed_area_send(mavlink_channel_t chan, uint8_t frame, float p1x, float p1y, float p1z, float p2x, float p2y, float p2z)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[25];
_mav_put_float(buf, 0, p1x);
_mav_put_float(buf, 4, p1y);
_mav_put_float(buf, 8, p1z);
_mav_put_float(buf, 12, p2x);
_mav_put_float(buf, 16, p2y);
_mav_put_float(buf, 20, p2z);
_mav_put_uint8_t(buf, 24, frame);
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA, buf, 25, 3);
#else
mavlink_safety_allowed_area_t packet;
packet.p1x = p1x;
packet.p1y = p1y;
packet.p1z = p1z;
packet.p2x = p2x;
packet.p2y = p2y;
packet.p2z = p2z;
packet.frame = frame;
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA, (const char *)&packet, 25, 3);
#endif
}
 
#endif
 
// MESSAGE SAFETY_ALLOWED_AREA UNPACKING
 
 
/**
* @brief Get field frame from safety_allowed_area message
*
* @return Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down.
*/
static inline uint8_t mavlink_msg_safety_allowed_area_get_frame(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 24);
}
 
/**
* @brief Get field p1x from safety_allowed_area message
*
* @return x position 1 / Latitude 1
*/
static inline float mavlink_msg_safety_allowed_area_get_p1x(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 0);
}
 
/**
* @brief Get field p1y from safety_allowed_area message
*
* @return y position 1 / Longitude 1
*/
static inline float mavlink_msg_safety_allowed_area_get_p1y(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 4);
}
 
/**
* @brief Get field p1z from safety_allowed_area message
*
* @return z position 1 / Altitude 1
*/
static inline float mavlink_msg_safety_allowed_area_get_p1z(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 8);
}
 
/**
* @brief Get field p2x from safety_allowed_area message
*
* @return x position 2 / Latitude 2
*/
static inline float mavlink_msg_safety_allowed_area_get_p2x(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 12);
}
 
/**
* @brief Get field p2y from safety_allowed_area message
*
* @return y position 2 / Longitude 2
*/
static inline float mavlink_msg_safety_allowed_area_get_p2y(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 16);
}
 
/**
* @brief Get field p2z from safety_allowed_area message
*
* @return z position 2 / Altitude 2
*/
static inline float mavlink_msg_safety_allowed_area_get_p2z(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 20);
}
 
/**
* @brief Decode a safety_allowed_area message into a struct
*
* @param msg The message to decode
* @param safety_allowed_area C-struct to decode the message contents into
*/
static inline void mavlink_msg_safety_allowed_area_decode(const mavlink_message_t* msg, mavlink_safety_allowed_area_t* safety_allowed_area)
{
#if MAVLINK_NEED_BYTE_SWAP
safety_allowed_area->p1x = mavlink_msg_safety_allowed_area_get_p1x(msg);
safety_allowed_area->p1y = mavlink_msg_safety_allowed_area_get_p1y(msg);
safety_allowed_area->p1z = mavlink_msg_safety_allowed_area_get_p1z(msg);
safety_allowed_area->p2x = mavlink_msg_safety_allowed_area_get_p2x(msg);
safety_allowed_area->p2y = mavlink_msg_safety_allowed_area_get_p2y(msg);
safety_allowed_area->p2z = mavlink_msg_safety_allowed_area_get_p2z(msg);
safety_allowed_area->frame = mavlink_msg_safety_allowed_area_get_frame(msg);
#else
memcpy(safety_allowed_area, _MAV_PAYLOAD(msg), 25);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v1.0/common/mavlink_msg_safety_set_allowed_area.h
0,0 → 1,320
// MESSAGE SAFETY_SET_ALLOWED_AREA PACKING
 
#define MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA 54
 
typedef struct __mavlink_safety_set_allowed_area_t
{
float p1x; ///< x position 1 / Latitude 1
float p1y; ///< y position 1 / Longitude 1
float p1z; ///< z position 1 / Altitude 1
float p2x; ///< x position 2 / Latitude 2
float p2y; ///< y position 2 / Longitude 2
float p2z; ///< z position 2 / Altitude 2
uint8_t target_system; ///< System ID
uint8_t target_component; ///< Component ID
uint8_t frame; ///< Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down.
} mavlink_safety_set_allowed_area_t;
 
#define MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN 27
#define MAVLINK_MSG_ID_54_LEN 27
 
 
 
#define MAVLINK_MESSAGE_INFO_SAFETY_SET_ALLOWED_AREA { \
"SAFETY_SET_ALLOWED_AREA", \
9, \
{ { "p1x", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_safety_set_allowed_area_t, p1x) }, \
{ "p1y", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_safety_set_allowed_area_t, p1y) }, \
{ "p1z", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_safety_set_allowed_area_t, p1z) }, \
{ "p2x", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_safety_set_allowed_area_t, p2x) }, \
{ "p2y", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_safety_set_allowed_area_t, p2y) }, \
{ "p2z", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_safety_set_allowed_area_t, p2z) }, \
{ "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 24, offsetof(mavlink_safety_set_allowed_area_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 25, offsetof(mavlink_safety_set_allowed_area_t, target_component) }, \
{ "frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 26, offsetof(mavlink_safety_set_allowed_area_t, frame) }, \
} \
}
 
 
/**
* @brief Pack a safety_set_allowed_area message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param target_system System ID
* @param target_component Component ID
* @param frame Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down.
* @param p1x x position 1 / Latitude 1
* @param p1y y position 1 / Longitude 1
* @param p1z z position 1 / Altitude 1
* @param p2x x position 2 / Latitude 2
* @param p2y y position 2 / Longitude 2
* @param p2z z position 2 / Altitude 2
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_safety_set_allowed_area_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t target_system, uint8_t target_component, uint8_t frame, float p1x, float p1y, float p1z, float p2x, float p2y, float p2z)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[27];
_mav_put_float(buf, 0, p1x);
_mav_put_float(buf, 4, p1y);
_mav_put_float(buf, 8, p1z);
_mav_put_float(buf, 12, p2x);
_mav_put_float(buf, 16, p2y);
_mav_put_float(buf, 20, p2z);
_mav_put_uint8_t(buf, 24, target_system);
_mav_put_uint8_t(buf, 25, target_component);
_mav_put_uint8_t(buf, 26, frame);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 27);
#else
mavlink_safety_set_allowed_area_t packet;
packet.p1x = p1x;
packet.p1y = p1y;
packet.p1z = p1z;
packet.p2x = p2x;
packet.p2y = p2y;
packet.p2z = p2z;
packet.target_system = target_system;
packet.target_component = target_component;
packet.frame = frame;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 27);
#endif
 
msg->msgid = MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA;
return mavlink_finalize_message(msg, system_id, component_id, 27, 15);
}
 
/**
* @brief Pack a safety_set_allowed_area message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param target_system System ID
* @param target_component Component ID
* @param frame Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down.
* @param p1x x position 1 / Latitude 1
* @param p1y y position 1 / Longitude 1
* @param p1z z position 1 / Altitude 1
* @param p2x x position 2 / Latitude 2
* @param p2y y position 2 / Longitude 2
* @param p2z z position 2 / Altitude 2
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_safety_set_allowed_area_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 frame,float p1x,float p1y,float p1z,float p2x,float p2y,float p2z)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[27];
_mav_put_float(buf, 0, p1x);
_mav_put_float(buf, 4, p1y);
_mav_put_float(buf, 8, p1z);
_mav_put_float(buf, 12, p2x);
_mav_put_float(buf, 16, p2y);
_mav_put_float(buf, 20, p2z);
_mav_put_uint8_t(buf, 24, target_system);
_mav_put_uint8_t(buf, 25, target_component);
_mav_put_uint8_t(buf, 26, frame);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 27);
#else
mavlink_safety_set_allowed_area_t packet;
packet.p1x = p1x;
packet.p1y = p1y;
packet.p1z = p1z;
packet.p2x = p2x;
packet.p2y = p2y;
packet.p2z = p2z;
packet.target_system = target_system;
packet.target_component = target_component;
packet.frame = frame;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 27);
#endif
 
msg->msgid = MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 27, 15);
}
 
/**
* @brief Encode a safety_set_allowed_area struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param safety_set_allowed_area C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_safety_set_allowed_area_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_safety_set_allowed_area_t* safety_set_allowed_area)
{
return mavlink_msg_safety_set_allowed_area_pack(system_id, component_id, msg, safety_set_allowed_area->target_system, safety_set_allowed_area->target_component, safety_set_allowed_area->frame, safety_set_allowed_area->p1x, safety_set_allowed_area->p1y, safety_set_allowed_area->p1z, safety_set_allowed_area->p2x, safety_set_allowed_area->p2y, safety_set_allowed_area->p2z);
}
 
/**
* @brief Send a safety_set_allowed_area message
* @param chan MAVLink channel to send the message
*
* @param target_system System ID
* @param target_component Component ID
* @param frame Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down.
* @param p1x x position 1 / Latitude 1
* @param p1y y position 1 / Longitude 1
* @param p1z z position 1 / Altitude 1
* @param p2x x position 2 / Latitude 2
* @param p2y y position 2 / Longitude 2
* @param p2z z position 2 / Altitude 2
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_safety_set_allowed_area_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t frame, float p1x, float p1y, float p1z, float p2x, float p2y, float p2z)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[27];
_mav_put_float(buf, 0, p1x);
_mav_put_float(buf, 4, p1y);
_mav_put_float(buf, 8, p1z);
_mav_put_float(buf, 12, p2x);
_mav_put_float(buf, 16, p2y);
_mav_put_float(buf, 20, p2z);
_mav_put_uint8_t(buf, 24, target_system);
_mav_put_uint8_t(buf, 25, target_component);
_mav_put_uint8_t(buf, 26, frame);
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA, buf, 27, 15);
#else
mavlink_safety_set_allowed_area_t packet;
packet.p1x = p1x;
packet.p1y = p1y;
packet.p1z = p1z;
packet.p2x = p2x;
packet.p2y = p2y;
packet.p2z = p2z;
packet.target_system = target_system;
packet.target_component = target_component;
packet.frame = frame;
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA, (const char *)&packet, 27, 15);
#endif
}
 
#endif
 
// MESSAGE SAFETY_SET_ALLOWED_AREA UNPACKING
 
 
/**
* @brief Get field target_system from safety_set_allowed_area message
*
* @return System ID
*/
static inline uint8_t mavlink_msg_safety_set_allowed_area_get_target_system(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 24);
}
 
/**
* @brief Get field target_component from safety_set_allowed_area message
*
* @return Component ID
*/
static inline uint8_t mavlink_msg_safety_set_allowed_area_get_target_component(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 25);
}
 
/**
* @brief Get field frame from safety_set_allowed_area message
*
* @return Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down.
*/
static inline uint8_t mavlink_msg_safety_set_allowed_area_get_frame(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 26);
}
 
/**
* @brief Get field p1x from safety_set_allowed_area message
*
* @return x position 1 / Latitude 1
*/
static inline float mavlink_msg_safety_set_allowed_area_get_p1x(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 0);
}
 
/**
* @brief Get field p1y from safety_set_allowed_area message
*
* @return y position 1 / Longitude 1
*/
static inline float mavlink_msg_safety_set_allowed_area_get_p1y(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 4);
}
 
/**
* @brief Get field p1z from safety_set_allowed_area message
*
* @return z position 1 / Altitude 1
*/
static inline float mavlink_msg_safety_set_allowed_area_get_p1z(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 8);
}
 
/**
* @brief Get field p2x from safety_set_allowed_area message
*
* @return x position 2 / Latitude 2
*/
static inline float mavlink_msg_safety_set_allowed_area_get_p2x(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 12);
}
 
/**
* @brief Get field p2y from safety_set_allowed_area message
*
* @return y position 2 / Longitude 2
*/
static inline float mavlink_msg_safety_set_allowed_area_get_p2y(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 16);
}
 
/**
* @brief Get field p2z from safety_set_allowed_area message
*
* @return z position 2 / Altitude 2
*/
static inline float mavlink_msg_safety_set_allowed_area_get_p2z(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 20);
}
 
/**
* @brief Decode a safety_set_allowed_area message into a struct
*
* @param msg The message to decode
* @param safety_set_allowed_area C-struct to decode the message contents into
*/
static inline void mavlink_msg_safety_set_allowed_area_decode(const mavlink_message_t* msg, mavlink_safety_set_allowed_area_t* safety_set_allowed_area)
{
#if MAVLINK_NEED_BYTE_SWAP
safety_set_allowed_area->p1x = mavlink_msg_safety_set_allowed_area_get_p1x(msg);
safety_set_allowed_area->p1y = mavlink_msg_safety_set_allowed_area_get_p1y(msg);
safety_set_allowed_area->p1z = mavlink_msg_safety_set_allowed_area_get_p1z(msg);
safety_set_allowed_area->p2x = mavlink_msg_safety_set_allowed_area_get_p2x(msg);
safety_set_allowed_area->p2y = mavlink_msg_safety_set_allowed_area_get_p2y(msg);
safety_set_allowed_area->p2z = mavlink_msg_safety_set_allowed_area_get_p2z(msg);
safety_set_allowed_area->target_system = mavlink_msg_safety_set_allowed_area_get_target_system(msg);
safety_set_allowed_area->target_component = mavlink_msg_safety_set_allowed_area_get_target_component(msg);
safety_set_allowed_area->frame = mavlink_msg_safety_set_allowed_area_get_frame(msg);
#else
memcpy(safety_set_allowed_area, _MAV_PAYLOAD(msg), 27);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v1.0/common/mavlink_msg_scaled_imu.h
0,0 → 1,342
// MESSAGE SCALED_IMU PACKING
 
#define MAVLINK_MSG_ID_SCALED_IMU 26
 
typedef struct __mavlink_scaled_imu_t
{
uint32_t time_boot_ms; ///< Timestamp (milliseconds since system boot)
int16_t xacc; ///< X acceleration (mg)
int16_t yacc; ///< Y acceleration (mg)
int16_t zacc; ///< Z acceleration (mg)
int16_t xgyro; ///< Angular speed around X axis (millirad /sec)
int16_t ygyro; ///< Angular speed around Y axis (millirad /sec)
int16_t zgyro; ///< Angular speed around Z axis (millirad /sec)
int16_t xmag; ///< X Magnetic field (milli tesla)
int16_t ymag; ///< Y Magnetic field (milli tesla)
int16_t zmag; ///< Z Magnetic field (milli tesla)
} mavlink_scaled_imu_t;
 
#define MAVLINK_MSG_ID_SCALED_IMU_LEN 22
#define MAVLINK_MSG_ID_26_LEN 22
 
 
 
#define MAVLINK_MESSAGE_INFO_SCALED_IMU { \
"SCALED_IMU", \
10, \
{ { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_scaled_imu_t, time_boot_ms) }, \
{ "xacc", NULL, MAVLINK_TYPE_INT16_T, 0, 4, offsetof(mavlink_scaled_imu_t, xacc) }, \
{ "yacc", NULL, MAVLINK_TYPE_INT16_T, 0, 6, offsetof(mavlink_scaled_imu_t, yacc) }, \
{ "zacc", NULL, MAVLINK_TYPE_INT16_T, 0, 8, offsetof(mavlink_scaled_imu_t, zacc) }, \
{ "xgyro", NULL, MAVLINK_TYPE_INT16_T, 0, 10, offsetof(mavlink_scaled_imu_t, xgyro) }, \
{ "ygyro", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_scaled_imu_t, ygyro) }, \
{ "zgyro", NULL, MAVLINK_TYPE_INT16_T, 0, 14, offsetof(mavlink_scaled_imu_t, zgyro) }, \
{ "xmag", NULL, MAVLINK_TYPE_INT16_T, 0, 16, offsetof(mavlink_scaled_imu_t, xmag) }, \
{ "ymag", NULL, MAVLINK_TYPE_INT16_T, 0, 18, offsetof(mavlink_scaled_imu_t, ymag) }, \
{ "zmag", NULL, MAVLINK_TYPE_INT16_T, 0, 20, offsetof(mavlink_scaled_imu_t, zmag) }, \
} \
}
 
 
/**
* @brief Pack a scaled_imu message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param time_boot_ms Timestamp (milliseconds since system boot)
* @param xacc X acceleration (mg)
* @param yacc Y acceleration (mg)
* @param zacc Z acceleration (mg)
* @param xgyro Angular speed around X axis (millirad /sec)
* @param ygyro Angular speed around Y axis (millirad /sec)
* @param zgyro Angular speed around Z axis (millirad /sec)
* @param xmag X Magnetic field (milli tesla)
* @param ymag Y Magnetic field (milli tesla)
* @param zmag Z Magnetic field (milli tesla)
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_scaled_imu_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint32_t time_boot_ms, int16_t xacc, int16_t yacc, int16_t zacc, int16_t xgyro, int16_t ygyro, int16_t zgyro, int16_t xmag, int16_t ymag, int16_t zmag)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[22];
_mav_put_uint32_t(buf, 0, time_boot_ms);
_mav_put_int16_t(buf, 4, xacc);
_mav_put_int16_t(buf, 6, yacc);
_mav_put_int16_t(buf, 8, zacc);
_mav_put_int16_t(buf, 10, xgyro);
_mav_put_int16_t(buf, 12, ygyro);
_mav_put_int16_t(buf, 14, zgyro);
_mav_put_int16_t(buf, 16, xmag);
_mav_put_int16_t(buf, 18, ymag);
_mav_put_int16_t(buf, 20, zmag);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 22);
#else
mavlink_scaled_imu_t packet;
packet.time_boot_ms = time_boot_ms;
packet.xacc = xacc;
packet.yacc = yacc;
packet.zacc = zacc;
packet.xgyro = xgyro;
packet.ygyro = ygyro;
packet.zgyro = zgyro;
packet.xmag = xmag;
packet.ymag = ymag;
packet.zmag = zmag;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 22);
#endif
 
msg->msgid = MAVLINK_MSG_ID_SCALED_IMU;
return mavlink_finalize_message(msg, system_id, component_id, 22, 170);
}
 
/**
* @brief Pack a scaled_imu message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param time_boot_ms Timestamp (milliseconds since system boot)
* @param xacc X acceleration (mg)
* @param yacc Y acceleration (mg)
* @param zacc Z acceleration (mg)
* @param xgyro Angular speed around X axis (millirad /sec)
* @param ygyro Angular speed around Y axis (millirad /sec)
* @param zgyro Angular speed around Z axis (millirad /sec)
* @param xmag X Magnetic field (milli tesla)
* @param ymag Y Magnetic field (milli tesla)
* @param zmag Z Magnetic field (milli tesla)
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_scaled_imu_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint32_t time_boot_ms,int16_t xacc,int16_t yacc,int16_t zacc,int16_t xgyro,int16_t ygyro,int16_t zgyro,int16_t xmag,int16_t ymag,int16_t zmag)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[22];
_mav_put_uint32_t(buf, 0, time_boot_ms);
_mav_put_int16_t(buf, 4, xacc);
_mav_put_int16_t(buf, 6, yacc);
_mav_put_int16_t(buf, 8, zacc);
_mav_put_int16_t(buf, 10, xgyro);
_mav_put_int16_t(buf, 12, ygyro);
_mav_put_int16_t(buf, 14, zgyro);
_mav_put_int16_t(buf, 16, xmag);
_mav_put_int16_t(buf, 18, ymag);
_mav_put_int16_t(buf, 20, zmag);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 22);
#else
mavlink_scaled_imu_t packet;
packet.time_boot_ms = time_boot_ms;
packet.xacc = xacc;
packet.yacc = yacc;
packet.zacc = zacc;
packet.xgyro = xgyro;
packet.ygyro = ygyro;
packet.zgyro = zgyro;
packet.xmag = xmag;
packet.ymag = ymag;
packet.zmag = zmag;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 22);
#endif
 
msg->msgid = MAVLINK_MSG_ID_SCALED_IMU;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 22, 170);
}
 
/**
* @brief Encode a scaled_imu struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param scaled_imu C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_scaled_imu_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_scaled_imu_t* scaled_imu)
{
return mavlink_msg_scaled_imu_pack(system_id, component_id, msg, scaled_imu->time_boot_ms, scaled_imu->xacc, scaled_imu->yacc, scaled_imu->zacc, scaled_imu->xgyro, scaled_imu->ygyro, scaled_imu->zgyro, scaled_imu->xmag, scaled_imu->ymag, scaled_imu->zmag);
}
 
/**
* @brief Send a scaled_imu message
* @param chan MAVLink channel to send the message
*
* @param time_boot_ms Timestamp (milliseconds since system boot)
* @param xacc X acceleration (mg)
* @param yacc Y acceleration (mg)
* @param zacc Z acceleration (mg)
* @param xgyro Angular speed around X axis (millirad /sec)
* @param ygyro Angular speed around Y axis (millirad /sec)
* @param zgyro Angular speed around Z axis (millirad /sec)
* @param xmag X Magnetic field (milli tesla)
* @param ymag Y Magnetic field (milli tesla)
* @param zmag Z Magnetic field (milli tesla)
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_scaled_imu_send(mavlink_channel_t chan, uint32_t time_boot_ms, int16_t xacc, int16_t yacc, int16_t zacc, int16_t xgyro, int16_t ygyro, int16_t zgyro, int16_t xmag, int16_t ymag, int16_t zmag)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[22];
_mav_put_uint32_t(buf, 0, time_boot_ms);
_mav_put_int16_t(buf, 4, xacc);
_mav_put_int16_t(buf, 6, yacc);
_mav_put_int16_t(buf, 8, zacc);
_mav_put_int16_t(buf, 10, xgyro);
_mav_put_int16_t(buf, 12, ygyro);
_mav_put_int16_t(buf, 14, zgyro);
_mav_put_int16_t(buf, 16, xmag);
_mav_put_int16_t(buf, 18, ymag);
_mav_put_int16_t(buf, 20, zmag);
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU, buf, 22, 170);
#else
mavlink_scaled_imu_t packet;
packet.time_boot_ms = time_boot_ms;
packet.xacc = xacc;
packet.yacc = yacc;
packet.zacc = zacc;
packet.xgyro = xgyro;
packet.ygyro = ygyro;
packet.zgyro = zgyro;
packet.xmag = xmag;
packet.ymag = ymag;
packet.zmag = zmag;
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU, (const char *)&packet, 22, 170);
#endif
}
 
#endif
 
// MESSAGE SCALED_IMU UNPACKING
 
 
/**
* @brief Get field time_boot_ms from scaled_imu message
*
* @return Timestamp (milliseconds since system boot)
*/
static inline uint32_t mavlink_msg_scaled_imu_get_time_boot_ms(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint32_t(msg, 0);
}
 
/**
* @brief Get field xacc from scaled_imu message
*
* @return X acceleration (mg)
*/
static inline int16_t mavlink_msg_scaled_imu_get_xacc(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 4);
}
 
/**
* @brief Get field yacc from scaled_imu message
*
* @return Y acceleration (mg)
*/
static inline int16_t mavlink_msg_scaled_imu_get_yacc(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 6);
}
 
/**
* @brief Get field zacc from scaled_imu message
*
* @return Z acceleration (mg)
*/
static inline int16_t mavlink_msg_scaled_imu_get_zacc(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 8);
}
 
/**
* @brief Get field xgyro from scaled_imu message
*
* @return Angular speed around X axis (millirad /sec)
*/
static inline int16_t mavlink_msg_scaled_imu_get_xgyro(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 10);
}
 
/**
* @brief Get field ygyro from scaled_imu message
*
* @return Angular speed around Y axis (millirad /sec)
*/
static inline int16_t mavlink_msg_scaled_imu_get_ygyro(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 12);
}
 
/**
* @brief Get field zgyro from scaled_imu message
*
* @return Angular speed around Z axis (millirad /sec)
*/
static inline int16_t mavlink_msg_scaled_imu_get_zgyro(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 14);
}
 
/**
* @brief Get field xmag from scaled_imu message
*
* @return X Magnetic field (milli tesla)
*/
static inline int16_t mavlink_msg_scaled_imu_get_xmag(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 16);
}
 
/**
* @brief Get field ymag from scaled_imu message
*
* @return Y Magnetic field (milli tesla)
*/
static inline int16_t mavlink_msg_scaled_imu_get_ymag(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 18);
}
 
/**
* @brief Get field zmag from scaled_imu message
*
* @return Z Magnetic field (milli tesla)
*/
static inline int16_t mavlink_msg_scaled_imu_get_zmag(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 20);
}
 
/**
* @brief Decode a scaled_imu message into a struct
*
* @param msg The message to decode
* @param scaled_imu C-struct to decode the message contents into
*/
static inline void mavlink_msg_scaled_imu_decode(const mavlink_message_t* msg, mavlink_scaled_imu_t* scaled_imu)
{
#if MAVLINK_NEED_BYTE_SWAP
scaled_imu->time_boot_ms = mavlink_msg_scaled_imu_get_time_boot_ms(msg);
scaled_imu->xacc = mavlink_msg_scaled_imu_get_xacc(msg);
scaled_imu->yacc = mavlink_msg_scaled_imu_get_yacc(msg);
scaled_imu->zacc = mavlink_msg_scaled_imu_get_zacc(msg);
scaled_imu->xgyro = mavlink_msg_scaled_imu_get_xgyro(msg);
scaled_imu->ygyro = mavlink_msg_scaled_imu_get_ygyro(msg);
scaled_imu->zgyro = mavlink_msg_scaled_imu_get_zgyro(msg);
scaled_imu->xmag = mavlink_msg_scaled_imu_get_xmag(msg);
scaled_imu->ymag = mavlink_msg_scaled_imu_get_ymag(msg);
scaled_imu->zmag = mavlink_msg_scaled_imu_get_zmag(msg);
#else
memcpy(scaled_imu, _MAV_PAYLOAD(msg), 22);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v1.0/common/mavlink_msg_scaled_pressure.h
0,0 → 1,210
// MESSAGE SCALED_PRESSURE PACKING
 
#define MAVLINK_MSG_ID_SCALED_PRESSURE 29
 
typedef struct __mavlink_scaled_pressure_t
{
uint32_t time_boot_ms; ///< Timestamp (microseconds since UNIX epoch or microseconds since system boot)
float press_abs; ///< Absolute pressure (hectopascal)
float press_diff; ///< Differential pressure 1 (hectopascal)
int16_t temperature; ///< Temperature measurement (0.01 degrees celsius)
} mavlink_scaled_pressure_t;
 
#define MAVLINK_MSG_ID_SCALED_PRESSURE_LEN 14
#define MAVLINK_MSG_ID_29_LEN 14
 
 
 
#define MAVLINK_MESSAGE_INFO_SCALED_PRESSURE { \
"SCALED_PRESSURE", \
4, \
{ { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_scaled_pressure_t, time_boot_ms) }, \
{ "press_abs", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_scaled_pressure_t, press_abs) }, \
{ "press_diff", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_scaled_pressure_t, press_diff) }, \
{ "temperature", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_scaled_pressure_t, temperature) }, \
} \
}
 
 
/**
* @brief Pack a scaled_pressure message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param time_boot_ms Timestamp (microseconds since UNIX epoch or microseconds since system boot)
* @param press_abs Absolute pressure (hectopascal)
* @param press_diff Differential pressure 1 (hectopascal)
* @param temperature Temperature measurement (0.01 degrees celsius)
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_scaled_pressure_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint32_t time_boot_ms, float press_abs, float press_diff, int16_t temperature)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[14];
_mav_put_uint32_t(buf, 0, time_boot_ms);
_mav_put_float(buf, 4, press_abs);
_mav_put_float(buf, 8, press_diff);
_mav_put_int16_t(buf, 12, temperature);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 14);
#else
mavlink_scaled_pressure_t packet;
packet.time_boot_ms = time_boot_ms;
packet.press_abs = press_abs;
packet.press_diff = press_diff;
packet.temperature = temperature;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 14);
#endif
 
msg->msgid = MAVLINK_MSG_ID_SCALED_PRESSURE;
return mavlink_finalize_message(msg, system_id, component_id, 14, 115);
}
 
/**
* @brief Pack a scaled_pressure message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param time_boot_ms Timestamp (microseconds since UNIX epoch or microseconds since system boot)
* @param press_abs Absolute pressure (hectopascal)
* @param press_diff Differential pressure 1 (hectopascal)
* @param temperature Temperature measurement (0.01 degrees celsius)
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_scaled_pressure_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint32_t time_boot_ms,float press_abs,float press_diff,int16_t temperature)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[14];
_mav_put_uint32_t(buf, 0, time_boot_ms);
_mav_put_float(buf, 4, press_abs);
_mav_put_float(buf, 8, press_diff);
_mav_put_int16_t(buf, 12, temperature);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 14);
#else
mavlink_scaled_pressure_t packet;
packet.time_boot_ms = time_boot_ms;
packet.press_abs = press_abs;
packet.press_diff = press_diff;
packet.temperature = temperature;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 14);
#endif
 
msg->msgid = MAVLINK_MSG_ID_SCALED_PRESSURE;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 14, 115);
}
 
/**
* @brief Encode a scaled_pressure struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param scaled_pressure C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_scaled_pressure_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_scaled_pressure_t* scaled_pressure)
{
return mavlink_msg_scaled_pressure_pack(system_id, component_id, msg, scaled_pressure->time_boot_ms, scaled_pressure->press_abs, scaled_pressure->press_diff, scaled_pressure->temperature);
}
 
/**
* @brief Send a scaled_pressure message
* @param chan MAVLink channel to send the message
*
* @param time_boot_ms Timestamp (microseconds since UNIX epoch or microseconds since system boot)
* @param press_abs Absolute pressure (hectopascal)
* @param press_diff Differential pressure 1 (hectopascal)
* @param temperature Temperature measurement (0.01 degrees celsius)
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_scaled_pressure_send(mavlink_channel_t chan, uint32_t time_boot_ms, float press_abs, float press_diff, int16_t temperature)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[14];
_mav_put_uint32_t(buf, 0, time_boot_ms);
_mav_put_float(buf, 4, press_abs);
_mav_put_float(buf, 8, press_diff);
_mav_put_int16_t(buf, 12, temperature);
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_PRESSURE, buf, 14, 115);
#else
mavlink_scaled_pressure_t packet;
packet.time_boot_ms = time_boot_ms;
packet.press_abs = press_abs;
packet.press_diff = press_diff;
packet.temperature = temperature;
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_PRESSURE, (const char *)&packet, 14, 115);
#endif
}
 
#endif
 
// MESSAGE SCALED_PRESSURE UNPACKING
 
 
/**
* @brief Get field time_boot_ms from scaled_pressure message
*
* @return Timestamp (microseconds since UNIX epoch or microseconds since system boot)
*/
static inline uint32_t mavlink_msg_scaled_pressure_get_time_boot_ms(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint32_t(msg, 0);
}
 
/**
* @brief Get field press_abs from scaled_pressure message
*
* @return Absolute pressure (hectopascal)
*/
static inline float mavlink_msg_scaled_pressure_get_press_abs(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 4);
}
 
/**
* @brief Get field press_diff from scaled_pressure message
*
* @return Differential pressure 1 (hectopascal)
*/
static inline float mavlink_msg_scaled_pressure_get_press_diff(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 8);
}
 
/**
* @brief Get field temperature from scaled_pressure message
*
* @return Temperature measurement (0.01 degrees celsius)
*/
static inline int16_t mavlink_msg_scaled_pressure_get_temperature(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 12);
}
 
/**
* @brief Decode a scaled_pressure message into a struct
*
* @param msg The message to decode
* @param scaled_pressure C-struct to decode the message contents into
*/
static inline void mavlink_msg_scaled_pressure_decode(const mavlink_message_t* msg, mavlink_scaled_pressure_t* scaled_pressure)
{
#if MAVLINK_NEED_BYTE_SWAP
scaled_pressure->time_boot_ms = mavlink_msg_scaled_pressure_get_time_boot_ms(msg);
scaled_pressure->press_abs = mavlink_msg_scaled_pressure_get_press_abs(msg);
scaled_pressure->press_diff = mavlink_msg_scaled_pressure_get_press_diff(msg);
scaled_pressure->temperature = mavlink_msg_scaled_pressure_get_temperature(msg);
#else
memcpy(scaled_pressure, _MAV_PAYLOAD(msg), 14);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v1.0/common/mavlink_msg_servo_output_raw.h
0,0 → 1,342
// MESSAGE SERVO_OUTPUT_RAW PACKING
 
#define MAVLINK_MSG_ID_SERVO_OUTPUT_RAW 36
 
typedef struct __mavlink_servo_output_raw_t
{
uint32_t time_usec; ///< Timestamp (since UNIX epoch or microseconds since system boot)
uint16_t servo1_raw; ///< Servo output 1 value, in microseconds
uint16_t servo2_raw; ///< Servo output 2 value, in microseconds
uint16_t servo3_raw; ///< Servo output 3 value, in microseconds
uint16_t servo4_raw; ///< Servo output 4 value, in microseconds
uint16_t servo5_raw; ///< Servo output 5 value, in microseconds
uint16_t servo6_raw; ///< Servo output 6 value, in microseconds
uint16_t servo7_raw; ///< Servo output 7 value, in microseconds
uint16_t servo8_raw; ///< Servo output 8 value, in microseconds
uint8_t port; ///< Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos.
} mavlink_servo_output_raw_t;
 
#define MAVLINK_MSG_ID_SERVO_OUTPUT_RAW_LEN 21
#define MAVLINK_MSG_ID_36_LEN 21
 
 
 
#define MAVLINK_MESSAGE_INFO_SERVO_OUTPUT_RAW { \
"SERVO_OUTPUT_RAW", \
10, \
{ { "time_usec", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_servo_output_raw_t, time_usec) }, \
{ "servo1_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_servo_output_raw_t, servo1_raw) }, \
{ "servo2_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_servo_output_raw_t, servo2_raw) }, \
{ "servo3_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_servo_output_raw_t, servo3_raw) }, \
{ "servo4_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 10, offsetof(mavlink_servo_output_raw_t, servo4_raw) }, \
{ "servo5_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_servo_output_raw_t, servo5_raw) }, \
{ "servo6_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 14, offsetof(mavlink_servo_output_raw_t, servo6_raw) }, \
{ "servo7_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_servo_output_raw_t, servo7_raw) }, \
{ "servo8_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_servo_output_raw_t, servo8_raw) }, \
{ "port", NULL, MAVLINK_TYPE_UINT8_T, 0, 20, offsetof(mavlink_servo_output_raw_t, port) }, \
} \
}
 
 
/**
* @brief Pack a servo_output_raw message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param time_usec Timestamp (since UNIX epoch or microseconds since system boot)
* @param port Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos.
* @param servo1_raw Servo output 1 value, in microseconds
* @param servo2_raw Servo output 2 value, in microseconds
* @param servo3_raw Servo output 3 value, in microseconds
* @param servo4_raw Servo output 4 value, in microseconds
* @param servo5_raw Servo output 5 value, in microseconds
* @param servo6_raw Servo output 6 value, in microseconds
* @param servo7_raw Servo output 7 value, in microseconds
* @param servo8_raw Servo output 8 value, in microseconds
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_servo_output_raw_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint32_t time_usec, uint8_t port, uint16_t servo1_raw, uint16_t servo2_raw, uint16_t servo3_raw, uint16_t servo4_raw, uint16_t servo5_raw, uint16_t servo6_raw, uint16_t servo7_raw, uint16_t servo8_raw)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[21];
_mav_put_uint32_t(buf, 0, time_usec);
_mav_put_uint16_t(buf, 4, servo1_raw);
_mav_put_uint16_t(buf, 6, servo2_raw);
_mav_put_uint16_t(buf, 8, servo3_raw);
_mav_put_uint16_t(buf, 10, servo4_raw);
_mav_put_uint16_t(buf, 12, servo5_raw);
_mav_put_uint16_t(buf, 14, servo6_raw);
_mav_put_uint16_t(buf, 16, servo7_raw);
_mav_put_uint16_t(buf, 18, servo8_raw);
_mav_put_uint8_t(buf, 20, port);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 21);
#else
mavlink_servo_output_raw_t packet;
packet.time_usec = time_usec;
packet.servo1_raw = servo1_raw;
packet.servo2_raw = servo2_raw;
packet.servo3_raw = servo3_raw;
packet.servo4_raw = servo4_raw;
packet.servo5_raw = servo5_raw;
packet.servo6_raw = servo6_raw;
packet.servo7_raw = servo7_raw;
packet.servo8_raw = servo8_raw;
packet.port = port;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 21);
#endif
 
msg->msgid = MAVLINK_MSG_ID_SERVO_OUTPUT_RAW;
return mavlink_finalize_message(msg, system_id, component_id, 21, 222);
}
 
/**
* @brief Pack a servo_output_raw message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param time_usec Timestamp (since UNIX epoch or microseconds since system boot)
* @param port Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos.
* @param servo1_raw Servo output 1 value, in microseconds
* @param servo2_raw Servo output 2 value, in microseconds
* @param servo3_raw Servo output 3 value, in microseconds
* @param servo4_raw Servo output 4 value, in microseconds
* @param servo5_raw Servo output 5 value, in microseconds
* @param servo6_raw Servo output 6 value, in microseconds
* @param servo7_raw Servo output 7 value, in microseconds
* @param servo8_raw Servo output 8 value, in microseconds
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_servo_output_raw_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint32_t time_usec,uint8_t port,uint16_t servo1_raw,uint16_t servo2_raw,uint16_t servo3_raw,uint16_t servo4_raw,uint16_t servo5_raw,uint16_t servo6_raw,uint16_t servo7_raw,uint16_t servo8_raw)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[21];
_mav_put_uint32_t(buf, 0, time_usec);
_mav_put_uint16_t(buf, 4, servo1_raw);
_mav_put_uint16_t(buf, 6, servo2_raw);
_mav_put_uint16_t(buf, 8, servo3_raw);
_mav_put_uint16_t(buf, 10, servo4_raw);
_mav_put_uint16_t(buf, 12, servo5_raw);
_mav_put_uint16_t(buf, 14, servo6_raw);
_mav_put_uint16_t(buf, 16, servo7_raw);
_mav_put_uint16_t(buf, 18, servo8_raw);
_mav_put_uint8_t(buf, 20, port);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 21);
#else
mavlink_servo_output_raw_t packet;
packet.time_usec = time_usec;
packet.servo1_raw = servo1_raw;
packet.servo2_raw = servo2_raw;
packet.servo3_raw = servo3_raw;
packet.servo4_raw = servo4_raw;
packet.servo5_raw = servo5_raw;
packet.servo6_raw = servo6_raw;
packet.servo7_raw = servo7_raw;
packet.servo8_raw = servo8_raw;
packet.port = port;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 21);
#endif
 
msg->msgid = MAVLINK_MSG_ID_SERVO_OUTPUT_RAW;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 21, 222);
}
 
/**
* @brief Encode a servo_output_raw struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param servo_output_raw C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_servo_output_raw_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_servo_output_raw_t* servo_output_raw)
{
return mavlink_msg_servo_output_raw_pack(system_id, component_id, msg, servo_output_raw->time_usec, servo_output_raw->port, servo_output_raw->servo1_raw, servo_output_raw->servo2_raw, servo_output_raw->servo3_raw, servo_output_raw->servo4_raw, servo_output_raw->servo5_raw, servo_output_raw->servo6_raw, servo_output_raw->servo7_raw, servo_output_raw->servo8_raw);
}
 
/**
* @brief Send a servo_output_raw message
* @param chan MAVLink channel to send the message
*
* @param time_usec Timestamp (since UNIX epoch or microseconds since system boot)
* @param port Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos.
* @param servo1_raw Servo output 1 value, in microseconds
* @param servo2_raw Servo output 2 value, in microseconds
* @param servo3_raw Servo output 3 value, in microseconds
* @param servo4_raw Servo output 4 value, in microseconds
* @param servo5_raw Servo output 5 value, in microseconds
* @param servo6_raw Servo output 6 value, in microseconds
* @param servo7_raw Servo output 7 value, in microseconds
* @param servo8_raw Servo output 8 value, in microseconds
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_servo_output_raw_send(mavlink_channel_t chan, uint32_t time_usec, uint8_t port, uint16_t servo1_raw, uint16_t servo2_raw, uint16_t servo3_raw, uint16_t servo4_raw, uint16_t servo5_raw, uint16_t servo6_raw, uint16_t servo7_raw, uint16_t servo8_raw)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[21];
_mav_put_uint32_t(buf, 0, time_usec);
_mav_put_uint16_t(buf, 4, servo1_raw);
_mav_put_uint16_t(buf, 6, servo2_raw);
_mav_put_uint16_t(buf, 8, servo3_raw);
_mav_put_uint16_t(buf, 10, servo4_raw);
_mav_put_uint16_t(buf, 12, servo5_raw);
_mav_put_uint16_t(buf, 14, servo6_raw);
_mav_put_uint16_t(buf, 16, servo7_raw);
_mav_put_uint16_t(buf, 18, servo8_raw);
_mav_put_uint8_t(buf, 20, port);
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW, buf, 21, 222);
#else
mavlink_servo_output_raw_t packet;
packet.time_usec = time_usec;
packet.servo1_raw = servo1_raw;
packet.servo2_raw = servo2_raw;
packet.servo3_raw = servo3_raw;
packet.servo4_raw = servo4_raw;
packet.servo5_raw = servo5_raw;
packet.servo6_raw = servo6_raw;
packet.servo7_raw = servo7_raw;
packet.servo8_raw = servo8_raw;
packet.port = port;
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SERVO_OUTPUT_RAW, (const char *)&packet, 21, 222);
#endif
}
 
#endif
 
// MESSAGE SERVO_OUTPUT_RAW UNPACKING
 
 
/**
* @brief Get field time_usec from servo_output_raw message
*
* @return Timestamp (since UNIX epoch or microseconds since system boot)
*/
static inline uint32_t mavlink_msg_servo_output_raw_get_time_usec(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint32_t(msg, 0);
}
 
/**
* @brief Get field port from servo_output_raw message
*
* @return Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos.
*/
static inline uint8_t mavlink_msg_servo_output_raw_get_port(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 20);
}
 
/**
* @brief Get field servo1_raw from servo_output_raw message
*
* @return Servo output 1 value, in microseconds
*/
static inline uint16_t mavlink_msg_servo_output_raw_get_servo1_raw(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 4);
}
 
/**
* @brief Get field servo2_raw from servo_output_raw message
*
* @return Servo output 2 value, in microseconds
*/
static inline uint16_t mavlink_msg_servo_output_raw_get_servo2_raw(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 6);
}
 
/**
* @brief Get field servo3_raw from servo_output_raw message
*
* @return Servo output 3 value, in microseconds
*/
static inline uint16_t mavlink_msg_servo_output_raw_get_servo3_raw(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 8);
}
 
/**
* @brief Get field servo4_raw from servo_output_raw message
*
* @return Servo output 4 value, in microseconds
*/
static inline uint16_t mavlink_msg_servo_output_raw_get_servo4_raw(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 10);
}
 
/**
* @brief Get field servo5_raw from servo_output_raw message
*
* @return Servo output 5 value, in microseconds
*/
static inline uint16_t mavlink_msg_servo_output_raw_get_servo5_raw(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 12);
}
 
/**
* @brief Get field servo6_raw from servo_output_raw message
*
* @return Servo output 6 value, in microseconds
*/
static inline uint16_t mavlink_msg_servo_output_raw_get_servo6_raw(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 14);
}
 
/**
* @brief Get field servo7_raw from servo_output_raw message
*
* @return Servo output 7 value, in microseconds
*/
static inline uint16_t mavlink_msg_servo_output_raw_get_servo7_raw(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 16);
}
 
/**
* @brief Get field servo8_raw from servo_output_raw message
*
* @return Servo output 8 value, in microseconds
*/
static inline uint16_t mavlink_msg_servo_output_raw_get_servo8_raw(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 18);
}
 
/**
* @brief Decode a servo_output_raw message into a struct
*
* @param msg The message to decode
* @param servo_output_raw C-struct to decode the message contents into
*/
static inline void mavlink_msg_servo_output_raw_decode(const mavlink_message_t* msg, mavlink_servo_output_raw_t* servo_output_raw)
{
#if MAVLINK_NEED_BYTE_SWAP
servo_output_raw->time_usec = mavlink_msg_servo_output_raw_get_time_usec(msg);
servo_output_raw->servo1_raw = mavlink_msg_servo_output_raw_get_servo1_raw(msg);
servo_output_raw->servo2_raw = mavlink_msg_servo_output_raw_get_servo2_raw(msg);
servo_output_raw->servo3_raw = mavlink_msg_servo_output_raw_get_servo3_raw(msg);
servo_output_raw->servo4_raw = mavlink_msg_servo_output_raw_get_servo4_raw(msg);
servo_output_raw->servo5_raw = mavlink_msg_servo_output_raw_get_servo5_raw(msg);
servo_output_raw->servo6_raw = mavlink_msg_servo_output_raw_get_servo6_raw(msg);
servo_output_raw->servo7_raw = mavlink_msg_servo_output_raw_get_servo7_raw(msg);
servo_output_raw->servo8_raw = mavlink_msg_servo_output_raw_get_servo8_raw(msg);
servo_output_raw->port = mavlink_msg_servo_output_raw_get_port(msg);
#else
memcpy(servo_output_raw, _MAV_PAYLOAD(msg), 21);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v1.0/common/mavlink_msg_set_global_position_setpoint_int.h
0,0 → 1,232
// MESSAGE SET_GLOBAL_POSITION_SETPOINT_INT PACKING
 
#define MAVLINK_MSG_ID_SET_GLOBAL_POSITION_SETPOINT_INT 53
 
typedef struct __mavlink_set_global_position_setpoint_int_t
{
int32_t latitude; ///< WGS84 Latitude position in degrees * 1E7
int32_t longitude; ///< WGS84 Longitude position in degrees * 1E7
int32_t altitude; ///< WGS84 Altitude in meters * 1000 (positive for up)
int16_t yaw; ///< Desired yaw angle in degrees * 100
uint8_t coordinate_frame; ///< Coordinate frame - valid values are only MAV_FRAME_GLOBAL or MAV_FRAME_GLOBAL_RELATIVE_ALT
} mavlink_set_global_position_setpoint_int_t;
 
#define MAVLINK_MSG_ID_SET_GLOBAL_POSITION_SETPOINT_INT_LEN 15
#define MAVLINK_MSG_ID_53_LEN 15
 
 
 
#define MAVLINK_MESSAGE_INFO_SET_GLOBAL_POSITION_SETPOINT_INT { \
"SET_GLOBAL_POSITION_SETPOINT_INT", \
5, \
{ { "latitude", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_set_global_position_setpoint_int_t, latitude) }, \
{ "longitude", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_set_global_position_setpoint_int_t, longitude) }, \
{ "altitude", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_set_global_position_setpoint_int_t, altitude) }, \
{ "yaw", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_set_global_position_setpoint_int_t, yaw) }, \
{ "coordinate_frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 14, offsetof(mavlink_set_global_position_setpoint_int_t, coordinate_frame) }, \
} \
}
 
 
/**
* @brief Pack a set_global_position_setpoint_int message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param coordinate_frame Coordinate frame - valid values are only MAV_FRAME_GLOBAL or MAV_FRAME_GLOBAL_RELATIVE_ALT
* @param latitude WGS84 Latitude position in degrees * 1E7
* @param longitude WGS84 Longitude position in degrees * 1E7
* @param altitude WGS84 Altitude in meters * 1000 (positive for up)
* @param yaw Desired yaw angle in degrees * 100
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_set_global_position_setpoint_int_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t coordinate_frame, int32_t latitude, int32_t longitude, int32_t altitude, int16_t yaw)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[15];
_mav_put_int32_t(buf, 0, latitude);
_mav_put_int32_t(buf, 4, longitude);
_mav_put_int32_t(buf, 8, altitude);
_mav_put_int16_t(buf, 12, yaw);
_mav_put_uint8_t(buf, 14, coordinate_frame);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 15);
#else
mavlink_set_global_position_setpoint_int_t packet;
packet.latitude = latitude;
packet.longitude = longitude;
packet.altitude = altitude;
packet.yaw = yaw;
packet.coordinate_frame = coordinate_frame;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 15);
#endif
 
msg->msgid = MAVLINK_MSG_ID_SET_GLOBAL_POSITION_SETPOINT_INT;
return mavlink_finalize_message(msg, system_id, component_id, 15, 33);
}
 
/**
* @brief Pack a set_global_position_setpoint_int message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param coordinate_frame Coordinate frame - valid values are only MAV_FRAME_GLOBAL or MAV_FRAME_GLOBAL_RELATIVE_ALT
* @param latitude WGS84 Latitude position in degrees * 1E7
* @param longitude WGS84 Longitude position in degrees * 1E7
* @param altitude WGS84 Altitude in meters * 1000 (positive for up)
* @param yaw Desired yaw angle in degrees * 100
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_set_global_position_setpoint_int_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint8_t coordinate_frame,int32_t latitude,int32_t longitude,int32_t altitude,int16_t yaw)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[15];
_mav_put_int32_t(buf, 0, latitude);
_mav_put_int32_t(buf, 4, longitude);
_mav_put_int32_t(buf, 8, altitude);
_mav_put_int16_t(buf, 12, yaw);
_mav_put_uint8_t(buf, 14, coordinate_frame);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 15);
#else
mavlink_set_global_position_setpoint_int_t packet;
packet.latitude = latitude;
packet.longitude = longitude;
packet.altitude = altitude;
packet.yaw = yaw;
packet.coordinate_frame = coordinate_frame;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 15);
#endif
 
msg->msgid = MAVLINK_MSG_ID_SET_GLOBAL_POSITION_SETPOINT_INT;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 15, 33);
}
 
/**
* @brief Encode a set_global_position_setpoint_int struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param set_global_position_setpoint_int C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_set_global_position_setpoint_int_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_global_position_setpoint_int_t* set_global_position_setpoint_int)
{
return mavlink_msg_set_global_position_setpoint_int_pack(system_id, component_id, msg, set_global_position_setpoint_int->coordinate_frame, set_global_position_setpoint_int->latitude, set_global_position_setpoint_int->longitude, set_global_position_setpoint_int->altitude, set_global_position_setpoint_int->yaw);
}
 
/**
* @brief Send a set_global_position_setpoint_int message
* @param chan MAVLink channel to send the message
*
* @param coordinate_frame Coordinate frame - valid values are only MAV_FRAME_GLOBAL or MAV_FRAME_GLOBAL_RELATIVE_ALT
* @param latitude WGS84 Latitude position in degrees * 1E7
* @param longitude WGS84 Longitude position in degrees * 1E7
* @param altitude WGS84 Altitude in meters * 1000 (positive for up)
* @param yaw Desired yaw angle in degrees * 100
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_set_global_position_setpoint_int_send(mavlink_channel_t chan, uint8_t coordinate_frame, int32_t latitude, int32_t longitude, int32_t altitude, int16_t yaw)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[15];
_mav_put_int32_t(buf, 0, latitude);
_mav_put_int32_t(buf, 4, longitude);
_mav_put_int32_t(buf, 8, altitude);
_mav_put_int16_t(buf, 12, yaw);
_mav_put_uint8_t(buf, 14, coordinate_frame);
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_GLOBAL_POSITION_SETPOINT_INT, buf, 15, 33);
#else
mavlink_set_global_position_setpoint_int_t packet;
packet.latitude = latitude;
packet.longitude = longitude;
packet.altitude = altitude;
packet.yaw = yaw;
packet.coordinate_frame = coordinate_frame;
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_GLOBAL_POSITION_SETPOINT_INT, (const char *)&packet, 15, 33);
#endif
}
 
#endif
 
// MESSAGE SET_GLOBAL_POSITION_SETPOINT_INT UNPACKING
 
 
/**
* @brief Get field coordinate_frame from set_global_position_setpoint_int message
*
* @return Coordinate frame - valid values are only MAV_FRAME_GLOBAL or MAV_FRAME_GLOBAL_RELATIVE_ALT
*/
static inline uint8_t mavlink_msg_set_global_position_setpoint_int_get_coordinate_frame(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 14);
}
 
/**
* @brief Get field latitude from set_global_position_setpoint_int message
*
* @return WGS84 Latitude position in degrees * 1E7
*/
static inline int32_t mavlink_msg_set_global_position_setpoint_int_get_latitude(const mavlink_message_t* msg)
{
return _MAV_RETURN_int32_t(msg, 0);
}
 
/**
* @brief Get field longitude from set_global_position_setpoint_int message
*
* @return WGS84 Longitude position in degrees * 1E7
*/
static inline int32_t mavlink_msg_set_global_position_setpoint_int_get_longitude(const mavlink_message_t* msg)
{
return _MAV_RETURN_int32_t(msg, 4);
}
 
/**
* @brief Get field altitude from set_global_position_setpoint_int message
*
* @return WGS84 Altitude in meters * 1000 (positive for up)
*/
static inline int32_t mavlink_msg_set_global_position_setpoint_int_get_altitude(const mavlink_message_t* msg)
{
return _MAV_RETURN_int32_t(msg, 8);
}
 
/**
* @brief Get field yaw from set_global_position_setpoint_int message
*
* @return Desired yaw angle in degrees * 100
*/
static inline int16_t mavlink_msg_set_global_position_setpoint_int_get_yaw(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 12);
}
 
/**
* @brief Decode a set_global_position_setpoint_int message into a struct
*
* @param msg The message to decode
* @param set_global_position_setpoint_int C-struct to decode the message contents into
*/
static inline void mavlink_msg_set_global_position_setpoint_int_decode(const mavlink_message_t* msg, mavlink_set_global_position_setpoint_int_t* set_global_position_setpoint_int)
{
#if MAVLINK_NEED_BYTE_SWAP
set_global_position_setpoint_int->latitude = mavlink_msg_set_global_position_setpoint_int_get_latitude(msg);
set_global_position_setpoint_int->longitude = mavlink_msg_set_global_position_setpoint_int_get_longitude(msg);
set_global_position_setpoint_int->altitude = mavlink_msg_set_global_position_setpoint_int_get_altitude(msg);
set_global_position_setpoint_int->yaw = mavlink_msg_set_global_position_setpoint_int_get_yaw(msg);
set_global_position_setpoint_int->coordinate_frame = mavlink_msg_set_global_position_setpoint_int_get_coordinate_frame(msg);
#else
memcpy(set_global_position_setpoint_int, _MAV_PAYLOAD(msg), 15);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v1.0/common/mavlink_msg_set_gps_global_origin.h
0,0 → 1,210
// MESSAGE SET_GPS_GLOBAL_ORIGIN PACKING
 
#define MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN 48
 
typedef struct __mavlink_set_gps_global_origin_t
{
int32_t latitude; ///< global position * 1E7
int32_t longitude; ///< global position * 1E7
int32_t altitude; ///< global position * 1000
uint8_t target_system; ///< System ID
} mavlink_set_gps_global_origin_t;
 
#define MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN_LEN 13
#define MAVLINK_MSG_ID_48_LEN 13
 
 
 
#define MAVLINK_MESSAGE_INFO_SET_GPS_GLOBAL_ORIGIN { \
"SET_GPS_GLOBAL_ORIGIN", \
4, \
{ { "latitude", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_set_gps_global_origin_t, latitude) }, \
{ "longitude", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_set_gps_global_origin_t, longitude) }, \
{ "altitude", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_set_gps_global_origin_t, altitude) }, \
{ "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 12, offsetof(mavlink_set_gps_global_origin_t, target_system) }, \
} \
}
 
 
/**
* @brief Pack a set_gps_global_origin message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param target_system System ID
* @param latitude global position * 1E7
* @param longitude global position * 1E7
* @param altitude global position * 1000
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_set_gps_global_origin_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t target_system, int32_t latitude, int32_t longitude, int32_t altitude)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[13];
_mav_put_int32_t(buf, 0, latitude);
_mav_put_int32_t(buf, 4, longitude);
_mav_put_int32_t(buf, 8, altitude);
_mav_put_uint8_t(buf, 12, target_system);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 13);
#else
mavlink_set_gps_global_origin_t packet;
packet.latitude = latitude;
packet.longitude = longitude;
packet.altitude = altitude;
packet.target_system = target_system;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 13);
#endif
 
msg->msgid = MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN;
return mavlink_finalize_message(msg, system_id, component_id, 13, 41);
}
 
/**
* @brief Pack a set_gps_global_origin message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param target_system System ID
* @param latitude global position * 1E7
* @param longitude global position * 1E7
* @param altitude global position * 1000
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_set_gps_global_origin_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint8_t target_system,int32_t latitude,int32_t longitude,int32_t altitude)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[13];
_mav_put_int32_t(buf, 0, latitude);
_mav_put_int32_t(buf, 4, longitude);
_mav_put_int32_t(buf, 8, altitude);
_mav_put_uint8_t(buf, 12, target_system);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 13);
#else
mavlink_set_gps_global_origin_t packet;
packet.latitude = latitude;
packet.longitude = longitude;
packet.altitude = altitude;
packet.target_system = target_system;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 13);
#endif
 
msg->msgid = MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 13, 41);
}
 
/**
* @brief Encode a set_gps_global_origin struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param set_gps_global_origin C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_set_gps_global_origin_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_gps_global_origin_t* set_gps_global_origin)
{
return mavlink_msg_set_gps_global_origin_pack(system_id, component_id, msg, set_gps_global_origin->target_system, set_gps_global_origin->latitude, set_gps_global_origin->longitude, set_gps_global_origin->altitude);
}
 
/**
* @brief Send a set_gps_global_origin message
* @param chan MAVLink channel to send the message
*
* @param target_system System ID
* @param latitude global position * 1E7
* @param longitude global position * 1E7
* @param altitude global position * 1000
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_set_gps_global_origin_send(mavlink_channel_t chan, uint8_t target_system, int32_t latitude, int32_t longitude, int32_t altitude)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[13];
_mav_put_int32_t(buf, 0, latitude);
_mav_put_int32_t(buf, 4, longitude);
_mav_put_int32_t(buf, 8, altitude);
_mav_put_uint8_t(buf, 12, target_system);
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN, buf, 13, 41);
#else
mavlink_set_gps_global_origin_t packet;
packet.latitude = latitude;
packet.longitude = longitude;
packet.altitude = altitude;
packet.target_system = target_system;
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_GPS_GLOBAL_ORIGIN, (const char *)&packet, 13, 41);
#endif
}
 
#endif
 
// MESSAGE SET_GPS_GLOBAL_ORIGIN UNPACKING
 
 
/**
* @brief Get field target_system from set_gps_global_origin message
*
* @return System ID
*/
static inline uint8_t mavlink_msg_set_gps_global_origin_get_target_system(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 12);
}
 
/**
* @brief Get field latitude from set_gps_global_origin message
*
* @return global position * 1E7
*/
static inline int32_t mavlink_msg_set_gps_global_origin_get_latitude(const mavlink_message_t* msg)
{
return _MAV_RETURN_int32_t(msg, 0);
}
 
/**
* @brief Get field longitude from set_gps_global_origin message
*
* @return global position * 1E7
*/
static inline int32_t mavlink_msg_set_gps_global_origin_get_longitude(const mavlink_message_t* msg)
{
return _MAV_RETURN_int32_t(msg, 4);
}
 
/**
* @brief Get field altitude from set_gps_global_origin message
*
* @return global position * 1000
*/
static inline int32_t mavlink_msg_set_gps_global_origin_get_altitude(const mavlink_message_t* msg)
{
return _MAV_RETURN_int32_t(msg, 8);
}
 
/**
* @brief Decode a set_gps_global_origin message into a struct
*
* @param msg The message to decode
* @param set_gps_global_origin C-struct to decode the message contents into
*/
static inline void mavlink_msg_set_gps_global_origin_decode(const mavlink_message_t* msg, mavlink_set_gps_global_origin_t* set_gps_global_origin)
{
#if MAVLINK_NEED_BYTE_SWAP
set_gps_global_origin->latitude = mavlink_msg_set_gps_global_origin_get_latitude(msg);
set_gps_global_origin->longitude = mavlink_msg_set_gps_global_origin_get_longitude(msg);
set_gps_global_origin->altitude = mavlink_msg_set_gps_global_origin_get_altitude(msg);
set_gps_global_origin->target_system = mavlink_msg_set_gps_global_origin_get_target_system(msg);
#else
memcpy(set_gps_global_origin, _MAV_PAYLOAD(msg), 13);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v1.0/common/mavlink_msg_set_local_position_setpoint.h
0,0 → 1,276
// MESSAGE SET_LOCAL_POSITION_SETPOINT PACKING
 
#define MAVLINK_MSG_ID_SET_LOCAL_POSITION_SETPOINT 50
 
typedef struct __mavlink_set_local_position_setpoint_t
{
float x; ///< x position
float y; ///< y position
float z; ///< z position
float yaw; ///< Desired yaw angle
uint8_t target_system; ///< System ID
uint8_t target_component; ///< Component ID
uint8_t coordinate_frame; ///< Coordinate frame - valid values are only MAV_FRAME_LOCAL_NED or MAV_FRAME_LOCAL_ENU
} mavlink_set_local_position_setpoint_t;
 
#define MAVLINK_MSG_ID_SET_LOCAL_POSITION_SETPOINT_LEN 19
#define MAVLINK_MSG_ID_50_LEN 19
 
 
 
#define MAVLINK_MESSAGE_INFO_SET_LOCAL_POSITION_SETPOINT { \
"SET_LOCAL_POSITION_SETPOINT", \
7, \
{ { "x", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_set_local_position_setpoint_t, x) }, \
{ "y", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_set_local_position_setpoint_t, y) }, \
{ "z", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_set_local_position_setpoint_t, z) }, \
{ "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_set_local_position_setpoint_t, yaw) }, \
{ "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 16, offsetof(mavlink_set_local_position_setpoint_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 17, offsetof(mavlink_set_local_position_setpoint_t, target_component) }, \
{ "coordinate_frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 18, offsetof(mavlink_set_local_position_setpoint_t, coordinate_frame) }, \
} \
}
 
 
/**
* @brief Pack a set_local_position_setpoint message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param target_system System ID
* @param target_component Component ID
* @param coordinate_frame Coordinate frame - valid values are only MAV_FRAME_LOCAL_NED or MAV_FRAME_LOCAL_ENU
* @param x x position
* @param y y position
* @param z z position
* @param yaw Desired yaw angle
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_set_local_position_setpoint_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t target_system, uint8_t target_component, uint8_t coordinate_frame, float x, float y, float z, float yaw)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[19];
_mav_put_float(buf, 0, x);
_mav_put_float(buf, 4, y);
_mav_put_float(buf, 8, z);
_mav_put_float(buf, 12, yaw);
_mav_put_uint8_t(buf, 16, target_system);
_mav_put_uint8_t(buf, 17, target_component);
_mav_put_uint8_t(buf, 18, coordinate_frame);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 19);
#else
mavlink_set_local_position_setpoint_t packet;
packet.x = x;
packet.y = y;
packet.z = z;
packet.yaw = yaw;
packet.target_system = target_system;
packet.target_component = target_component;
packet.coordinate_frame = coordinate_frame;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 19);
#endif
 
msg->msgid = MAVLINK_MSG_ID_SET_LOCAL_POSITION_SETPOINT;
return mavlink_finalize_message(msg, system_id, component_id, 19, 214);
}
 
/**
* @brief Pack a set_local_position_setpoint message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param target_system System ID
* @param target_component Component ID
* @param coordinate_frame Coordinate frame - valid values are only MAV_FRAME_LOCAL_NED or MAV_FRAME_LOCAL_ENU
* @param x x position
* @param y y position
* @param z z position
* @param yaw Desired yaw angle
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_set_local_position_setpoint_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 coordinate_frame,float x,float y,float z,float yaw)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[19];
_mav_put_float(buf, 0, x);
_mav_put_float(buf, 4, y);
_mav_put_float(buf, 8, z);
_mav_put_float(buf, 12, yaw);
_mav_put_uint8_t(buf, 16, target_system);
_mav_put_uint8_t(buf, 17, target_component);
_mav_put_uint8_t(buf, 18, coordinate_frame);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 19);
#else
mavlink_set_local_position_setpoint_t packet;
packet.x = x;
packet.y = y;
packet.z = z;
packet.yaw = yaw;
packet.target_system = target_system;
packet.target_component = target_component;
packet.coordinate_frame = coordinate_frame;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 19);
#endif
 
msg->msgid = MAVLINK_MSG_ID_SET_LOCAL_POSITION_SETPOINT;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 19, 214);
}
 
/**
* @brief Encode a set_local_position_setpoint struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param set_local_position_setpoint C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_set_local_position_setpoint_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_local_position_setpoint_t* set_local_position_setpoint)
{
return mavlink_msg_set_local_position_setpoint_pack(system_id, component_id, msg, set_local_position_setpoint->target_system, set_local_position_setpoint->target_component, set_local_position_setpoint->coordinate_frame, set_local_position_setpoint->x, set_local_position_setpoint->y, set_local_position_setpoint->z, set_local_position_setpoint->yaw);
}
 
/**
* @brief Send a set_local_position_setpoint message
* @param chan MAVLink channel to send the message
*
* @param target_system System ID
* @param target_component Component ID
* @param coordinate_frame Coordinate frame - valid values are only MAV_FRAME_LOCAL_NED or MAV_FRAME_LOCAL_ENU
* @param x x position
* @param y y position
* @param z z position
* @param yaw Desired yaw angle
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_set_local_position_setpoint_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t coordinate_frame, float x, float y, float z, float yaw)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[19];
_mav_put_float(buf, 0, x);
_mav_put_float(buf, 4, y);
_mav_put_float(buf, 8, z);
_mav_put_float(buf, 12, yaw);
_mav_put_uint8_t(buf, 16, target_system);
_mav_put_uint8_t(buf, 17, target_component);
_mav_put_uint8_t(buf, 18, coordinate_frame);
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_LOCAL_POSITION_SETPOINT, buf, 19, 214);
#else
mavlink_set_local_position_setpoint_t packet;
packet.x = x;
packet.y = y;
packet.z = z;
packet.yaw = yaw;
packet.target_system = target_system;
packet.target_component = target_component;
packet.coordinate_frame = coordinate_frame;
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_LOCAL_POSITION_SETPOINT, (const char *)&packet, 19, 214);
#endif
}
 
#endif
 
// MESSAGE SET_LOCAL_POSITION_SETPOINT UNPACKING
 
 
/**
* @brief Get field target_system from set_local_position_setpoint message
*
* @return System ID
*/
static inline uint8_t mavlink_msg_set_local_position_setpoint_get_target_system(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 16);
}
 
/**
* @brief Get field target_component from set_local_position_setpoint message
*
* @return Component ID
*/
static inline uint8_t mavlink_msg_set_local_position_setpoint_get_target_component(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 17);
}
 
/**
* @brief Get field coordinate_frame from set_local_position_setpoint message
*
* @return Coordinate frame - valid values are only MAV_FRAME_LOCAL_NED or MAV_FRAME_LOCAL_ENU
*/
static inline uint8_t mavlink_msg_set_local_position_setpoint_get_coordinate_frame(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 18);
}
 
/**
* @brief Get field x from set_local_position_setpoint message
*
* @return x position
*/
static inline float mavlink_msg_set_local_position_setpoint_get_x(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 0);
}
 
/**
* @brief Get field y from set_local_position_setpoint message
*
* @return y position
*/
static inline float mavlink_msg_set_local_position_setpoint_get_y(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 4);
}
 
/**
* @brief Get field z from set_local_position_setpoint message
*
* @return z position
*/
static inline float mavlink_msg_set_local_position_setpoint_get_z(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 8);
}
 
/**
* @brief Get field yaw from set_local_position_setpoint message
*
* @return Desired yaw angle
*/
static inline float mavlink_msg_set_local_position_setpoint_get_yaw(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 12);
}
 
/**
* @brief Decode a set_local_position_setpoint message into a struct
*
* @param msg The message to decode
* @param set_local_position_setpoint C-struct to decode the message contents into
*/
static inline void mavlink_msg_set_local_position_setpoint_decode(const mavlink_message_t* msg, mavlink_set_local_position_setpoint_t* set_local_position_setpoint)
{
#if MAVLINK_NEED_BYTE_SWAP
set_local_position_setpoint->x = mavlink_msg_set_local_position_setpoint_get_x(msg);
set_local_position_setpoint->y = mavlink_msg_set_local_position_setpoint_get_y(msg);
set_local_position_setpoint->z = mavlink_msg_set_local_position_setpoint_get_z(msg);
set_local_position_setpoint->yaw = mavlink_msg_set_local_position_setpoint_get_yaw(msg);
set_local_position_setpoint->target_system = mavlink_msg_set_local_position_setpoint_get_target_system(msg);
set_local_position_setpoint->target_component = mavlink_msg_set_local_position_setpoint_get_target_component(msg);
set_local_position_setpoint->coordinate_frame = mavlink_msg_set_local_position_setpoint_get_coordinate_frame(msg);
#else
memcpy(set_local_position_setpoint, _MAV_PAYLOAD(msg), 19);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v1.0/common/mavlink_msg_set_mode.h
0,0 → 1,188
// MESSAGE SET_MODE PACKING
 
#define MAVLINK_MSG_ID_SET_MODE 11
 
typedef struct __mavlink_set_mode_t
{
uint32_t custom_mode; ///< The new autopilot-specific mode. This field can be ignored by an autopilot.
uint8_t target_system; ///< The system setting the mode
uint8_t base_mode; ///< The new base mode
} mavlink_set_mode_t;
 
#define MAVLINK_MSG_ID_SET_MODE_LEN 6
#define MAVLINK_MSG_ID_11_LEN 6
 
 
 
#define MAVLINK_MESSAGE_INFO_SET_MODE { \
"SET_MODE", \
3, \
{ { "custom_mode", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_set_mode_t, custom_mode) }, \
{ "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_set_mode_t, target_system) }, \
{ "base_mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_set_mode_t, base_mode) }, \
} \
}
 
 
/**
* @brief Pack a set_mode message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param target_system The system setting the mode
* @param base_mode The new base mode
* @param custom_mode The new autopilot-specific mode. This field can be ignored by an autopilot.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_set_mode_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t target_system, uint8_t base_mode, uint32_t custom_mode)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[6];
_mav_put_uint32_t(buf, 0, custom_mode);
_mav_put_uint8_t(buf, 4, target_system);
_mav_put_uint8_t(buf, 5, base_mode);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 6);
#else
mavlink_set_mode_t packet;
packet.custom_mode = custom_mode;
packet.target_system = target_system;
packet.base_mode = base_mode;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 6);
#endif
 
msg->msgid = MAVLINK_MSG_ID_SET_MODE;
return mavlink_finalize_message(msg, system_id, component_id, 6, 89);
}
 
/**
* @brief Pack a set_mode message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param target_system The system setting the mode
* @param base_mode The new base mode
* @param custom_mode The new autopilot-specific mode. This field can be ignored by an autopilot.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_set_mode_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint8_t target_system,uint8_t base_mode,uint32_t custom_mode)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[6];
_mav_put_uint32_t(buf, 0, custom_mode);
_mav_put_uint8_t(buf, 4, target_system);
_mav_put_uint8_t(buf, 5, base_mode);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 6);
#else
mavlink_set_mode_t packet;
packet.custom_mode = custom_mode;
packet.target_system = target_system;
packet.base_mode = base_mode;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 6);
#endif
 
msg->msgid = MAVLINK_MSG_ID_SET_MODE;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 6, 89);
}
 
/**
* @brief Encode a set_mode struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param set_mode C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_set_mode_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_mode_t* set_mode)
{
return mavlink_msg_set_mode_pack(system_id, component_id, msg, set_mode->target_system, set_mode->base_mode, set_mode->custom_mode);
}
 
/**
* @brief Send a set_mode message
* @param chan MAVLink channel to send the message
*
* @param target_system The system setting the mode
* @param base_mode The new base mode
* @param custom_mode The new autopilot-specific mode. This field can be ignored by an autopilot.
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_set_mode_send(mavlink_channel_t chan, uint8_t target_system, uint8_t base_mode, uint32_t custom_mode)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[6];
_mav_put_uint32_t(buf, 0, custom_mode);
_mav_put_uint8_t(buf, 4, target_system);
_mav_put_uint8_t(buf, 5, base_mode);
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_MODE, buf, 6, 89);
#else
mavlink_set_mode_t packet;
packet.custom_mode = custom_mode;
packet.target_system = target_system;
packet.base_mode = base_mode;
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_MODE, (const char *)&packet, 6, 89);
#endif
}
 
#endif
 
// MESSAGE SET_MODE UNPACKING
 
 
/**
* @brief Get field target_system from set_mode message
*
* @return The system setting the mode
*/
static inline uint8_t mavlink_msg_set_mode_get_target_system(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 4);
}
 
/**
* @brief Get field base_mode from set_mode message
*
* @return The new base mode
*/
static inline uint8_t mavlink_msg_set_mode_get_base_mode(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 5);
}
 
/**
* @brief Get field custom_mode from set_mode message
*
* @return The new autopilot-specific mode. This field can be ignored by an autopilot.
*/
static inline uint32_t mavlink_msg_set_mode_get_custom_mode(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint32_t(msg, 0);
}
 
/**
* @brief Decode a set_mode message into a struct
*
* @param msg The message to decode
* @param set_mode C-struct to decode the message contents into
*/
static inline void mavlink_msg_set_mode_decode(const mavlink_message_t* msg, mavlink_set_mode_t* set_mode)
{
#if MAVLINK_NEED_BYTE_SWAP
set_mode->custom_mode = mavlink_msg_set_mode_get_custom_mode(msg);
set_mode->target_system = mavlink_msg_set_mode_get_target_system(msg);
set_mode->base_mode = mavlink_msg_set_mode_get_base_mode(msg);
#else
memcpy(set_mode, _MAV_PAYLOAD(msg), 6);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v1.0/common/mavlink_msg_set_quad_motors_setpoint.h
0,0 → 1,232
// MESSAGE SET_QUAD_MOTORS_SETPOINT PACKING
 
#define MAVLINK_MSG_ID_SET_QUAD_MOTORS_SETPOINT 60
 
typedef struct __mavlink_set_quad_motors_setpoint_t
{
uint16_t motor_front_nw; ///< Front motor in + configuration, front left motor in x configuration
uint16_t motor_right_ne; ///< Right motor in + configuration, front right motor in x configuration
uint16_t motor_back_se; ///< Back motor in + configuration, back right motor in x configuration
uint16_t motor_left_sw; ///< Left motor in + configuration, back left motor in x configuration
uint8_t target_system; ///< System ID of the system that should set these motor commands
} mavlink_set_quad_motors_setpoint_t;
 
#define MAVLINK_MSG_ID_SET_QUAD_MOTORS_SETPOINT_LEN 9
#define MAVLINK_MSG_ID_60_LEN 9
 
 
 
#define MAVLINK_MESSAGE_INFO_SET_QUAD_MOTORS_SETPOINT { \
"SET_QUAD_MOTORS_SETPOINT", \
5, \
{ { "motor_front_nw", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_set_quad_motors_setpoint_t, motor_front_nw) }, \
{ "motor_right_ne", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_set_quad_motors_setpoint_t, motor_right_ne) }, \
{ "motor_back_se", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_set_quad_motors_setpoint_t, motor_back_se) }, \
{ "motor_left_sw", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_set_quad_motors_setpoint_t, motor_left_sw) }, \
{ "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_set_quad_motors_setpoint_t, target_system) }, \
} \
}
 
 
/**
* @brief Pack a set_quad_motors_setpoint message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param target_system System ID of the system that should set these motor commands
* @param motor_front_nw Front motor in + configuration, front left motor in x configuration
* @param motor_right_ne Right motor in + configuration, front right motor in x configuration
* @param motor_back_se Back motor in + configuration, back right motor in x configuration
* @param motor_left_sw Left motor in + configuration, back left motor in x configuration
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_set_quad_motors_setpoint_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t target_system, uint16_t motor_front_nw, uint16_t motor_right_ne, uint16_t motor_back_se, uint16_t motor_left_sw)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[9];
_mav_put_uint16_t(buf, 0, motor_front_nw);
_mav_put_uint16_t(buf, 2, motor_right_ne);
_mav_put_uint16_t(buf, 4, motor_back_se);
_mav_put_uint16_t(buf, 6, motor_left_sw);
_mav_put_uint8_t(buf, 8, target_system);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 9);
#else
mavlink_set_quad_motors_setpoint_t packet;
packet.motor_front_nw = motor_front_nw;
packet.motor_right_ne = motor_right_ne;
packet.motor_back_se = motor_back_se;
packet.motor_left_sw = motor_left_sw;
packet.target_system = target_system;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 9);
#endif
 
msg->msgid = MAVLINK_MSG_ID_SET_QUAD_MOTORS_SETPOINT;
return mavlink_finalize_message(msg, system_id, component_id, 9, 30);
}
 
/**
* @brief Pack a set_quad_motors_setpoint message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param target_system System ID of the system that should set these motor commands
* @param motor_front_nw Front motor in + configuration, front left motor in x configuration
* @param motor_right_ne Right motor in + configuration, front right motor in x configuration
* @param motor_back_se Back motor in + configuration, back right motor in x configuration
* @param motor_left_sw Left motor in + configuration, back left motor in x configuration
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_set_quad_motors_setpoint_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint8_t target_system,uint16_t motor_front_nw,uint16_t motor_right_ne,uint16_t motor_back_se,uint16_t motor_left_sw)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[9];
_mav_put_uint16_t(buf, 0, motor_front_nw);
_mav_put_uint16_t(buf, 2, motor_right_ne);
_mav_put_uint16_t(buf, 4, motor_back_se);
_mav_put_uint16_t(buf, 6, motor_left_sw);
_mav_put_uint8_t(buf, 8, target_system);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 9);
#else
mavlink_set_quad_motors_setpoint_t packet;
packet.motor_front_nw = motor_front_nw;
packet.motor_right_ne = motor_right_ne;
packet.motor_back_se = motor_back_se;
packet.motor_left_sw = motor_left_sw;
packet.target_system = target_system;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 9);
#endif
 
msg->msgid = MAVLINK_MSG_ID_SET_QUAD_MOTORS_SETPOINT;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 9, 30);
}
 
/**
* @brief Encode a set_quad_motors_setpoint struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param set_quad_motors_setpoint C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_set_quad_motors_setpoint_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_quad_motors_setpoint_t* set_quad_motors_setpoint)
{
return mavlink_msg_set_quad_motors_setpoint_pack(system_id, component_id, msg, set_quad_motors_setpoint->target_system, set_quad_motors_setpoint->motor_front_nw, set_quad_motors_setpoint->motor_right_ne, set_quad_motors_setpoint->motor_back_se, set_quad_motors_setpoint->motor_left_sw);
}
 
/**
* @brief Send a set_quad_motors_setpoint message
* @param chan MAVLink channel to send the message
*
* @param target_system System ID of the system that should set these motor commands
* @param motor_front_nw Front motor in + configuration, front left motor in x configuration
* @param motor_right_ne Right motor in + configuration, front right motor in x configuration
* @param motor_back_se Back motor in + configuration, back right motor in x configuration
* @param motor_left_sw Left motor in + configuration, back left motor in x configuration
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_set_quad_motors_setpoint_send(mavlink_channel_t chan, uint8_t target_system, uint16_t motor_front_nw, uint16_t motor_right_ne, uint16_t motor_back_se, uint16_t motor_left_sw)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[9];
_mav_put_uint16_t(buf, 0, motor_front_nw);
_mav_put_uint16_t(buf, 2, motor_right_ne);
_mav_put_uint16_t(buf, 4, motor_back_se);
_mav_put_uint16_t(buf, 6, motor_left_sw);
_mav_put_uint8_t(buf, 8, target_system);
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_QUAD_MOTORS_SETPOINT, buf, 9, 30);
#else
mavlink_set_quad_motors_setpoint_t packet;
packet.motor_front_nw = motor_front_nw;
packet.motor_right_ne = motor_right_ne;
packet.motor_back_se = motor_back_se;
packet.motor_left_sw = motor_left_sw;
packet.target_system = target_system;
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_QUAD_MOTORS_SETPOINT, (const char *)&packet, 9, 30);
#endif
}
 
#endif
 
// MESSAGE SET_QUAD_MOTORS_SETPOINT UNPACKING
 
 
/**
* @brief Get field target_system from set_quad_motors_setpoint message
*
* @return System ID of the system that should set these motor commands
*/
static inline uint8_t mavlink_msg_set_quad_motors_setpoint_get_target_system(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 8);
}
 
/**
* @brief Get field motor_front_nw from set_quad_motors_setpoint message
*
* @return Front motor in + configuration, front left motor in x configuration
*/
static inline uint16_t mavlink_msg_set_quad_motors_setpoint_get_motor_front_nw(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 0);
}
 
/**
* @brief Get field motor_right_ne from set_quad_motors_setpoint message
*
* @return Right motor in + configuration, front right motor in x configuration
*/
static inline uint16_t mavlink_msg_set_quad_motors_setpoint_get_motor_right_ne(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 2);
}
 
/**
* @brief Get field motor_back_se from set_quad_motors_setpoint message
*
* @return Back motor in + configuration, back right motor in x configuration
*/
static inline uint16_t mavlink_msg_set_quad_motors_setpoint_get_motor_back_se(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 4);
}
 
/**
* @brief Get field motor_left_sw from set_quad_motors_setpoint message
*
* @return Left motor in + configuration, back left motor in x configuration
*/
static inline uint16_t mavlink_msg_set_quad_motors_setpoint_get_motor_left_sw(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 6);
}
 
/**
* @brief Decode a set_quad_motors_setpoint message into a struct
*
* @param msg The message to decode
* @param set_quad_motors_setpoint C-struct to decode the message contents into
*/
static inline void mavlink_msg_set_quad_motors_setpoint_decode(const mavlink_message_t* msg, mavlink_set_quad_motors_setpoint_t* set_quad_motors_setpoint)
{
#if MAVLINK_NEED_BYTE_SWAP
set_quad_motors_setpoint->motor_front_nw = mavlink_msg_set_quad_motors_setpoint_get_motor_front_nw(msg);
set_quad_motors_setpoint->motor_right_ne = mavlink_msg_set_quad_motors_setpoint_get_motor_right_ne(msg);
set_quad_motors_setpoint->motor_back_se = mavlink_msg_set_quad_motors_setpoint_get_motor_back_se(msg);
set_quad_motors_setpoint->motor_left_sw = mavlink_msg_set_quad_motors_setpoint_get_motor_left_sw(msg);
set_quad_motors_setpoint->target_system = mavlink_msg_set_quad_motors_setpoint_get_target_system(msg);
#else
memcpy(set_quad_motors_setpoint, _MAV_PAYLOAD(msg), 9);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v1.0/common/mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust.h
0,0 → 1,236
// MESSAGE SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST PACKING
 
#define MAVLINK_MSG_ID_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST 61
 
typedef struct __mavlink_set_quad_swarm_roll_pitch_yaw_thrust_t
{
int16_t roll[6]; ///< Desired roll angle in radians, scaled to int16 for 6 quadrotors: 0..5
int16_t pitch[6]; ///< Desired pitch angle in radians, scaled to int16 for 6 quadrotors: 0..5
int16_t yaw[6]; ///< Desired yaw angle in radians, scaled to int16 for 6 quadrotors: 0..5
uint16_t thrust[6]; ///< Collective thrust, scaled to uint16 for 6 quadrotors: 0..5
uint8_t target_systems[6]; ///< System IDs for 6 quadrotors: 0..5, the ID's are the MAVLink IDs
} mavlink_set_quad_swarm_roll_pitch_yaw_thrust_t;
 
#define MAVLINK_MSG_ID_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST_LEN 54
#define MAVLINK_MSG_ID_61_LEN 54
 
#define MAVLINK_MSG_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST_FIELD_ROLL_LEN 6
#define MAVLINK_MSG_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST_FIELD_PITCH_LEN 6
#define MAVLINK_MSG_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST_FIELD_YAW_LEN 6
#define MAVLINK_MSG_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST_FIELD_THRUST_LEN 6
#define MAVLINK_MSG_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST_FIELD_TARGET_SYSTEMS_LEN 6
 
#define MAVLINK_MESSAGE_INFO_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST { \
"SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST", \
5, \
{ { "roll", NULL, MAVLINK_TYPE_INT16_T, 6, 0, offsetof(mavlink_set_quad_swarm_roll_pitch_yaw_thrust_t, roll) }, \
{ "pitch", NULL, MAVLINK_TYPE_INT16_T, 6, 12, offsetof(mavlink_set_quad_swarm_roll_pitch_yaw_thrust_t, pitch) }, \
{ "yaw", NULL, MAVLINK_TYPE_INT16_T, 6, 24, offsetof(mavlink_set_quad_swarm_roll_pitch_yaw_thrust_t, yaw) }, \
{ "thrust", NULL, MAVLINK_TYPE_UINT16_T, 6, 36, offsetof(mavlink_set_quad_swarm_roll_pitch_yaw_thrust_t, thrust) }, \
{ "target_systems", NULL, MAVLINK_TYPE_UINT8_T, 6, 48, offsetof(mavlink_set_quad_swarm_roll_pitch_yaw_thrust_t, target_systems) }, \
} \
}
 
 
/**
* @brief Pack a set_quad_swarm_roll_pitch_yaw_thrust message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param target_systems System IDs for 6 quadrotors: 0..5, the ID's are the MAVLink IDs
* @param roll Desired roll angle in radians, scaled to int16 for 6 quadrotors: 0..5
* @param pitch Desired pitch angle in radians, scaled to int16 for 6 quadrotors: 0..5
* @param yaw Desired yaw angle in radians, scaled to int16 for 6 quadrotors: 0..5
* @param thrust Collective thrust, scaled to uint16 for 6 quadrotors: 0..5
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
const uint8_t *target_systems, const int16_t *roll, const int16_t *pitch, const int16_t *yaw, const uint16_t *thrust)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[54];
 
_mav_put_int16_t_array(buf, 0, roll, 6);
_mav_put_int16_t_array(buf, 12, pitch, 6);
_mav_put_int16_t_array(buf, 24, yaw, 6);
_mav_put_uint16_t_array(buf, 36, thrust, 6);
_mav_put_uint8_t_array(buf, 48, target_systems, 6);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 54);
#else
mavlink_set_quad_swarm_roll_pitch_yaw_thrust_t packet;
 
mav_array_memcpy(packet.roll, roll, sizeof(int16_t)*6);
mav_array_memcpy(packet.pitch, pitch, sizeof(int16_t)*6);
mav_array_memcpy(packet.yaw, yaw, sizeof(int16_t)*6);
mav_array_memcpy(packet.thrust, thrust, sizeof(uint16_t)*6);
mav_array_memcpy(packet.target_systems, target_systems, sizeof(uint8_t)*6);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 54);
#endif
 
msg->msgid = MAVLINK_MSG_ID_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST;
return mavlink_finalize_message(msg, system_id, component_id, 54, 200);
}
 
/**
* @brief Pack a set_quad_swarm_roll_pitch_yaw_thrust message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param target_systems System IDs for 6 quadrotors: 0..5, the ID's are the MAVLink IDs
* @param roll Desired roll angle in radians, scaled to int16 for 6 quadrotors: 0..5
* @param pitch Desired pitch angle in radians, scaled to int16 for 6 quadrotors: 0..5
* @param yaw Desired yaw angle in radians, scaled to int16 for 6 quadrotors: 0..5
* @param thrust Collective thrust, scaled to uint16 for 6 quadrotors: 0..5
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
const uint8_t *target_systems,const int16_t *roll,const int16_t *pitch,const int16_t *yaw,const uint16_t *thrust)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[54];
 
_mav_put_int16_t_array(buf, 0, roll, 6);
_mav_put_int16_t_array(buf, 12, pitch, 6);
_mav_put_int16_t_array(buf, 24, yaw, 6);
_mav_put_uint16_t_array(buf, 36, thrust, 6);
_mav_put_uint8_t_array(buf, 48, target_systems, 6);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 54);
#else
mavlink_set_quad_swarm_roll_pitch_yaw_thrust_t packet;
 
mav_array_memcpy(packet.roll, roll, sizeof(int16_t)*6);
mav_array_memcpy(packet.pitch, pitch, sizeof(int16_t)*6);
mav_array_memcpy(packet.yaw, yaw, sizeof(int16_t)*6);
mav_array_memcpy(packet.thrust, thrust, sizeof(uint16_t)*6);
mav_array_memcpy(packet.target_systems, target_systems, sizeof(uint8_t)*6);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 54);
#endif
 
msg->msgid = MAVLINK_MSG_ID_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 54, 200);
}
 
/**
* @brief Encode a set_quad_swarm_roll_pitch_yaw_thrust struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param set_quad_swarm_roll_pitch_yaw_thrust C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_quad_swarm_roll_pitch_yaw_thrust_t* set_quad_swarm_roll_pitch_yaw_thrust)
{
return mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust_pack(system_id, component_id, msg, set_quad_swarm_roll_pitch_yaw_thrust->target_systems, set_quad_swarm_roll_pitch_yaw_thrust->roll, set_quad_swarm_roll_pitch_yaw_thrust->pitch, set_quad_swarm_roll_pitch_yaw_thrust->yaw, set_quad_swarm_roll_pitch_yaw_thrust->thrust);
}
 
/**
* @brief Send a set_quad_swarm_roll_pitch_yaw_thrust message
* @param chan MAVLink channel to send the message
*
* @param target_systems System IDs for 6 quadrotors: 0..5, the ID's are the MAVLink IDs
* @param roll Desired roll angle in radians, scaled to int16 for 6 quadrotors: 0..5
* @param pitch Desired pitch angle in radians, scaled to int16 for 6 quadrotors: 0..5
* @param yaw Desired yaw angle in radians, scaled to int16 for 6 quadrotors: 0..5
* @param thrust Collective thrust, scaled to uint16 for 6 quadrotors: 0..5
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust_send(mavlink_channel_t chan, const uint8_t *target_systems, const int16_t *roll, const int16_t *pitch, const int16_t *yaw, const uint16_t *thrust)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[54];
 
_mav_put_int16_t_array(buf, 0, roll, 6);
_mav_put_int16_t_array(buf, 12, pitch, 6);
_mav_put_int16_t_array(buf, 24, yaw, 6);
_mav_put_uint16_t_array(buf, 36, thrust, 6);
_mav_put_uint8_t_array(buf, 48, target_systems, 6);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST, buf, 54, 200);
#else
mavlink_set_quad_swarm_roll_pitch_yaw_thrust_t packet;
 
mav_array_memcpy(packet.roll, roll, sizeof(int16_t)*6);
mav_array_memcpy(packet.pitch, pitch, sizeof(int16_t)*6);
mav_array_memcpy(packet.yaw, yaw, sizeof(int16_t)*6);
mav_array_memcpy(packet.thrust, thrust, sizeof(uint16_t)*6);
mav_array_memcpy(packet.target_systems, target_systems, sizeof(uint8_t)*6);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST, (const char *)&packet, 54, 200);
#endif
}
 
#endif
 
// MESSAGE SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST UNPACKING
 
 
/**
* @brief Get field target_systems from set_quad_swarm_roll_pitch_yaw_thrust message
*
* @return System IDs for 6 quadrotors: 0..5, the ID's are the MAVLink IDs
*/
static inline uint16_t mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust_get_target_systems(const mavlink_message_t* msg, uint8_t *target_systems)
{
return _MAV_RETURN_uint8_t_array(msg, target_systems, 6, 48);
}
 
/**
* @brief Get field roll from set_quad_swarm_roll_pitch_yaw_thrust message
*
* @return Desired roll angle in radians, scaled to int16 for 6 quadrotors: 0..5
*/
static inline uint16_t mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust_get_roll(const mavlink_message_t* msg, int16_t *roll)
{
return _MAV_RETURN_int16_t_array(msg, roll, 6, 0);
}
 
/**
* @brief Get field pitch from set_quad_swarm_roll_pitch_yaw_thrust message
*
* @return Desired pitch angle in radians, scaled to int16 for 6 quadrotors: 0..5
*/
static inline uint16_t mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust_get_pitch(const mavlink_message_t* msg, int16_t *pitch)
{
return _MAV_RETURN_int16_t_array(msg, pitch, 6, 12);
}
 
/**
* @brief Get field yaw from set_quad_swarm_roll_pitch_yaw_thrust message
*
* @return Desired yaw angle in radians, scaled to int16 for 6 quadrotors: 0..5
*/
static inline uint16_t mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust_get_yaw(const mavlink_message_t* msg, int16_t *yaw)
{
return _MAV_RETURN_int16_t_array(msg, yaw, 6, 24);
}
 
/**
* @brief Get field thrust from set_quad_swarm_roll_pitch_yaw_thrust message
*
* @return Collective thrust, scaled to uint16 for 6 quadrotors: 0..5
*/
static inline uint16_t mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust_get_thrust(const mavlink_message_t* msg, uint16_t *thrust)
{
return _MAV_RETURN_uint16_t_array(msg, thrust, 6, 36);
}
 
/**
* @brief Decode a set_quad_swarm_roll_pitch_yaw_thrust message into a struct
*
* @param msg The message to decode
* @param set_quad_swarm_roll_pitch_yaw_thrust C-struct to decode the message contents into
*/
static inline void mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust_decode(const mavlink_message_t* msg, mavlink_set_quad_swarm_roll_pitch_yaw_thrust_t* set_quad_swarm_roll_pitch_yaw_thrust)
{
#if MAVLINK_NEED_BYTE_SWAP
mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust_get_roll(msg, set_quad_swarm_roll_pitch_yaw_thrust->roll);
mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust_get_pitch(msg, set_quad_swarm_roll_pitch_yaw_thrust->pitch);
mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust_get_yaw(msg, set_quad_swarm_roll_pitch_yaw_thrust->yaw);
mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust_get_thrust(msg, set_quad_swarm_roll_pitch_yaw_thrust->thrust);
mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust_get_target_systems(msg, set_quad_swarm_roll_pitch_yaw_thrust->target_systems);
#else
memcpy(set_quad_swarm_roll_pitch_yaw_thrust, _MAV_PAYLOAD(msg), 54);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v1.0/common/mavlink_msg_set_roll_pitch_yaw_speed_thrust.h
0,0 → 1,254
// MESSAGE SET_ROLL_PITCH_YAW_SPEED_THRUST PACKING
 
#define MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED_THRUST 57
 
typedef struct __mavlink_set_roll_pitch_yaw_speed_thrust_t
{
float roll_speed; ///< Desired roll angular speed in rad/s
float pitch_speed; ///< Desired pitch angular speed in rad/s
float yaw_speed; ///< Desired yaw angular speed in rad/s
float thrust; ///< Collective thrust, normalized to 0 .. 1
uint8_t target_system; ///< System ID
uint8_t target_component; ///< Component ID
} mavlink_set_roll_pitch_yaw_speed_thrust_t;
 
#define MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED_THRUST_LEN 18
#define MAVLINK_MSG_ID_57_LEN 18
 
 
 
#define MAVLINK_MESSAGE_INFO_SET_ROLL_PITCH_YAW_SPEED_THRUST { \
"SET_ROLL_PITCH_YAW_SPEED_THRUST", \
6, \
{ { "roll_speed", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_set_roll_pitch_yaw_speed_thrust_t, roll_speed) }, \
{ "pitch_speed", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_set_roll_pitch_yaw_speed_thrust_t, pitch_speed) }, \
{ "yaw_speed", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_set_roll_pitch_yaw_speed_thrust_t, yaw_speed) }, \
{ "thrust", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_set_roll_pitch_yaw_speed_thrust_t, thrust) }, \
{ "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 16, offsetof(mavlink_set_roll_pitch_yaw_speed_thrust_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 17, offsetof(mavlink_set_roll_pitch_yaw_speed_thrust_t, target_component) }, \
} \
}
 
 
/**
* @brief Pack a set_roll_pitch_yaw_speed_thrust message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param target_system System ID
* @param target_component Component ID
* @param roll_speed Desired roll angular speed in rad/s
* @param pitch_speed Desired pitch angular speed in rad/s
* @param yaw_speed Desired yaw angular speed in rad/s
* @param thrust Collective thrust, normalized to 0 .. 1
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_set_roll_pitch_yaw_speed_thrust_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t target_system, uint8_t target_component, float roll_speed, float pitch_speed, float yaw_speed, float thrust)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[18];
_mav_put_float(buf, 0, roll_speed);
_mav_put_float(buf, 4, pitch_speed);
_mav_put_float(buf, 8, yaw_speed);
_mav_put_float(buf, 12, thrust);
_mav_put_uint8_t(buf, 16, target_system);
_mav_put_uint8_t(buf, 17, target_component);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 18);
#else
mavlink_set_roll_pitch_yaw_speed_thrust_t packet;
packet.roll_speed = roll_speed;
packet.pitch_speed = pitch_speed;
packet.yaw_speed = yaw_speed;
packet.thrust = thrust;
packet.target_system = target_system;
packet.target_component = target_component;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 18);
#endif
 
msg->msgid = MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED_THRUST;
return mavlink_finalize_message(msg, system_id, component_id, 18, 24);
}
 
/**
* @brief Pack a set_roll_pitch_yaw_speed_thrust message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param target_system System ID
* @param target_component Component ID
* @param roll_speed Desired roll angular speed in rad/s
* @param pitch_speed Desired pitch angular speed in rad/s
* @param yaw_speed Desired yaw angular speed in rad/s
* @param thrust Collective thrust, normalized to 0 .. 1
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_set_roll_pitch_yaw_speed_thrust_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,float roll_speed,float pitch_speed,float yaw_speed,float thrust)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[18];
_mav_put_float(buf, 0, roll_speed);
_mav_put_float(buf, 4, pitch_speed);
_mav_put_float(buf, 8, yaw_speed);
_mav_put_float(buf, 12, thrust);
_mav_put_uint8_t(buf, 16, target_system);
_mav_put_uint8_t(buf, 17, target_component);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 18);
#else
mavlink_set_roll_pitch_yaw_speed_thrust_t packet;
packet.roll_speed = roll_speed;
packet.pitch_speed = pitch_speed;
packet.yaw_speed = yaw_speed;
packet.thrust = thrust;
packet.target_system = target_system;
packet.target_component = target_component;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 18);
#endif
 
msg->msgid = MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED_THRUST;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 18, 24);
}
 
/**
* @brief Encode a set_roll_pitch_yaw_speed_thrust struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param set_roll_pitch_yaw_speed_thrust C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_set_roll_pitch_yaw_speed_thrust_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_roll_pitch_yaw_speed_thrust_t* set_roll_pitch_yaw_speed_thrust)
{
return mavlink_msg_set_roll_pitch_yaw_speed_thrust_pack(system_id, component_id, msg, set_roll_pitch_yaw_speed_thrust->target_system, set_roll_pitch_yaw_speed_thrust->target_component, set_roll_pitch_yaw_speed_thrust->roll_speed, set_roll_pitch_yaw_speed_thrust->pitch_speed, set_roll_pitch_yaw_speed_thrust->yaw_speed, set_roll_pitch_yaw_speed_thrust->thrust);
}
 
/**
* @brief Send a set_roll_pitch_yaw_speed_thrust message
* @param chan MAVLink channel to send the message
*
* @param target_system System ID
* @param target_component Component ID
* @param roll_speed Desired roll angular speed in rad/s
* @param pitch_speed Desired pitch angular speed in rad/s
* @param yaw_speed Desired yaw angular speed in rad/s
* @param thrust Collective thrust, normalized to 0 .. 1
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_set_roll_pitch_yaw_speed_thrust_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, float roll_speed, float pitch_speed, float yaw_speed, float thrust)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[18];
_mav_put_float(buf, 0, roll_speed);
_mav_put_float(buf, 4, pitch_speed);
_mav_put_float(buf, 8, yaw_speed);
_mav_put_float(buf, 12, thrust);
_mav_put_uint8_t(buf, 16, target_system);
_mav_put_uint8_t(buf, 17, target_component);
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED_THRUST, buf, 18, 24);
#else
mavlink_set_roll_pitch_yaw_speed_thrust_t packet;
packet.roll_speed = roll_speed;
packet.pitch_speed = pitch_speed;
packet.yaw_speed = yaw_speed;
packet.thrust = thrust;
packet.target_system = target_system;
packet.target_component = target_component;
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_SPEED_THRUST, (const char *)&packet, 18, 24);
#endif
}
 
#endif
 
// MESSAGE SET_ROLL_PITCH_YAW_SPEED_THRUST UNPACKING
 
 
/**
* @brief Get field target_system from set_roll_pitch_yaw_speed_thrust message
*
* @return System ID
*/
static inline uint8_t mavlink_msg_set_roll_pitch_yaw_speed_thrust_get_target_system(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 16);
}
 
/**
* @brief Get field target_component from set_roll_pitch_yaw_speed_thrust message
*
* @return Component ID
*/
static inline uint8_t mavlink_msg_set_roll_pitch_yaw_speed_thrust_get_target_component(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 17);
}
 
/**
* @brief Get field roll_speed from set_roll_pitch_yaw_speed_thrust message
*
* @return Desired roll angular speed in rad/s
*/
static inline float mavlink_msg_set_roll_pitch_yaw_speed_thrust_get_roll_speed(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 0);
}
 
/**
* @brief Get field pitch_speed from set_roll_pitch_yaw_speed_thrust message
*
* @return Desired pitch angular speed in rad/s
*/
static inline float mavlink_msg_set_roll_pitch_yaw_speed_thrust_get_pitch_speed(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 4);
}
 
/**
* @brief Get field yaw_speed from set_roll_pitch_yaw_speed_thrust message
*
* @return Desired yaw angular speed in rad/s
*/
static inline float mavlink_msg_set_roll_pitch_yaw_speed_thrust_get_yaw_speed(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 8);
}
 
/**
* @brief Get field thrust from set_roll_pitch_yaw_speed_thrust message
*
* @return Collective thrust, normalized to 0 .. 1
*/
static inline float mavlink_msg_set_roll_pitch_yaw_speed_thrust_get_thrust(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 12);
}
 
/**
* @brief Decode a set_roll_pitch_yaw_speed_thrust message into a struct
*
* @param msg The message to decode
* @param set_roll_pitch_yaw_speed_thrust C-struct to decode the message contents into
*/
static inline void mavlink_msg_set_roll_pitch_yaw_speed_thrust_decode(const mavlink_message_t* msg, mavlink_set_roll_pitch_yaw_speed_thrust_t* set_roll_pitch_yaw_speed_thrust)
{
#if MAVLINK_NEED_BYTE_SWAP
set_roll_pitch_yaw_speed_thrust->roll_speed = mavlink_msg_set_roll_pitch_yaw_speed_thrust_get_roll_speed(msg);
set_roll_pitch_yaw_speed_thrust->pitch_speed = mavlink_msg_set_roll_pitch_yaw_speed_thrust_get_pitch_speed(msg);
set_roll_pitch_yaw_speed_thrust->yaw_speed = mavlink_msg_set_roll_pitch_yaw_speed_thrust_get_yaw_speed(msg);
set_roll_pitch_yaw_speed_thrust->thrust = mavlink_msg_set_roll_pitch_yaw_speed_thrust_get_thrust(msg);
set_roll_pitch_yaw_speed_thrust->target_system = mavlink_msg_set_roll_pitch_yaw_speed_thrust_get_target_system(msg);
set_roll_pitch_yaw_speed_thrust->target_component = mavlink_msg_set_roll_pitch_yaw_speed_thrust_get_target_component(msg);
#else
memcpy(set_roll_pitch_yaw_speed_thrust, _MAV_PAYLOAD(msg), 18);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v1.0/common/mavlink_msg_set_roll_pitch_yaw_thrust.h
0,0 → 1,254
// MESSAGE SET_ROLL_PITCH_YAW_THRUST PACKING
 
#define MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST 56
 
typedef struct __mavlink_set_roll_pitch_yaw_thrust_t
{
float roll; ///< Desired roll angle in radians
float pitch; ///< Desired pitch angle in radians
float yaw; ///< Desired yaw angle in radians
float thrust; ///< Collective thrust, normalized to 0 .. 1
uint8_t target_system; ///< System ID
uint8_t target_component; ///< Component ID
} mavlink_set_roll_pitch_yaw_thrust_t;
 
#define MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST_LEN 18
#define MAVLINK_MSG_ID_56_LEN 18
 
 
 
#define MAVLINK_MESSAGE_INFO_SET_ROLL_PITCH_YAW_THRUST { \
"SET_ROLL_PITCH_YAW_THRUST", \
6, \
{ { "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_set_roll_pitch_yaw_thrust_t, roll) }, \
{ "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_set_roll_pitch_yaw_thrust_t, pitch) }, \
{ "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_set_roll_pitch_yaw_thrust_t, yaw) }, \
{ "thrust", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_set_roll_pitch_yaw_thrust_t, thrust) }, \
{ "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 16, offsetof(mavlink_set_roll_pitch_yaw_thrust_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 17, offsetof(mavlink_set_roll_pitch_yaw_thrust_t, target_component) }, \
} \
}
 
 
/**
* @brief Pack a set_roll_pitch_yaw_thrust message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param target_system System ID
* @param target_component Component ID
* @param roll Desired roll angle in radians
* @param pitch Desired pitch angle in radians
* @param yaw Desired yaw angle in radians
* @param thrust Collective thrust, normalized to 0 .. 1
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_set_roll_pitch_yaw_thrust_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t target_system, uint8_t target_component, float roll, float pitch, float yaw, float thrust)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[18];
_mav_put_float(buf, 0, roll);
_mav_put_float(buf, 4, pitch);
_mav_put_float(buf, 8, yaw);
_mav_put_float(buf, 12, thrust);
_mav_put_uint8_t(buf, 16, target_system);
_mav_put_uint8_t(buf, 17, target_component);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 18);
#else
mavlink_set_roll_pitch_yaw_thrust_t packet;
packet.roll = roll;
packet.pitch = pitch;
packet.yaw = yaw;
packet.thrust = thrust;
packet.target_system = target_system;
packet.target_component = target_component;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 18);
#endif
 
msg->msgid = MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST;
return mavlink_finalize_message(msg, system_id, component_id, 18, 100);
}
 
/**
* @brief Pack a set_roll_pitch_yaw_thrust message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param target_system System ID
* @param target_component Component ID
* @param roll Desired roll angle in radians
* @param pitch Desired pitch angle in radians
* @param yaw Desired yaw angle in radians
* @param thrust Collective thrust, normalized to 0 .. 1
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_set_roll_pitch_yaw_thrust_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,float roll,float pitch,float yaw,float thrust)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[18];
_mav_put_float(buf, 0, roll);
_mav_put_float(buf, 4, pitch);
_mav_put_float(buf, 8, yaw);
_mav_put_float(buf, 12, thrust);
_mav_put_uint8_t(buf, 16, target_system);
_mav_put_uint8_t(buf, 17, target_component);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 18);
#else
mavlink_set_roll_pitch_yaw_thrust_t packet;
packet.roll = roll;
packet.pitch = pitch;
packet.yaw = yaw;
packet.thrust = thrust;
packet.target_system = target_system;
packet.target_component = target_component;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 18);
#endif
 
msg->msgid = MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 18, 100);
}
 
/**
* @brief Encode a set_roll_pitch_yaw_thrust struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param set_roll_pitch_yaw_thrust C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_set_roll_pitch_yaw_thrust_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_set_roll_pitch_yaw_thrust_t* set_roll_pitch_yaw_thrust)
{
return mavlink_msg_set_roll_pitch_yaw_thrust_pack(system_id, component_id, msg, set_roll_pitch_yaw_thrust->target_system, set_roll_pitch_yaw_thrust->target_component, set_roll_pitch_yaw_thrust->roll, set_roll_pitch_yaw_thrust->pitch, set_roll_pitch_yaw_thrust->yaw, set_roll_pitch_yaw_thrust->thrust);
}
 
/**
* @brief Send a set_roll_pitch_yaw_thrust message
* @param chan MAVLink channel to send the message
*
* @param target_system System ID
* @param target_component Component ID
* @param roll Desired roll angle in radians
* @param pitch Desired pitch angle in radians
* @param yaw Desired yaw angle in radians
* @param thrust Collective thrust, normalized to 0 .. 1
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_set_roll_pitch_yaw_thrust_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, float roll, float pitch, float yaw, float thrust)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[18];
_mav_put_float(buf, 0, roll);
_mav_put_float(buf, 4, pitch);
_mav_put_float(buf, 8, yaw);
_mav_put_float(buf, 12, thrust);
_mav_put_uint8_t(buf, 16, target_system);
_mav_put_uint8_t(buf, 17, target_component);
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST, buf, 18, 100);
#else
mavlink_set_roll_pitch_yaw_thrust_t packet;
packet.roll = roll;
packet.pitch = pitch;
packet.yaw = yaw;
packet.thrust = thrust;
packet.target_system = target_system;
packet.target_component = target_component;
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SET_ROLL_PITCH_YAW_THRUST, (const char *)&packet, 18, 100);
#endif
}
 
#endif
 
// MESSAGE SET_ROLL_PITCH_YAW_THRUST UNPACKING
 
 
/**
* @brief Get field target_system from set_roll_pitch_yaw_thrust message
*
* @return System ID
*/
static inline uint8_t mavlink_msg_set_roll_pitch_yaw_thrust_get_target_system(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 16);
}
 
/**
* @brief Get field target_component from set_roll_pitch_yaw_thrust message
*
* @return Component ID
*/
static inline uint8_t mavlink_msg_set_roll_pitch_yaw_thrust_get_target_component(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 17);
}
 
/**
* @brief Get field roll from set_roll_pitch_yaw_thrust message
*
* @return Desired roll angle in radians
*/
static inline float mavlink_msg_set_roll_pitch_yaw_thrust_get_roll(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 0);
}
 
/**
* @brief Get field pitch from set_roll_pitch_yaw_thrust message
*
* @return Desired pitch angle in radians
*/
static inline float mavlink_msg_set_roll_pitch_yaw_thrust_get_pitch(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 4);
}
 
/**
* @brief Get field yaw from set_roll_pitch_yaw_thrust message
*
* @return Desired yaw angle in radians
*/
static inline float mavlink_msg_set_roll_pitch_yaw_thrust_get_yaw(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 8);
}
 
/**
* @brief Get field thrust from set_roll_pitch_yaw_thrust message
*
* @return Collective thrust, normalized to 0 .. 1
*/
static inline float mavlink_msg_set_roll_pitch_yaw_thrust_get_thrust(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 12);
}
 
/**
* @brief Decode a set_roll_pitch_yaw_thrust message into a struct
*
* @param msg The message to decode
* @param set_roll_pitch_yaw_thrust C-struct to decode the message contents into
*/
static inline void mavlink_msg_set_roll_pitch_yaw_thrust_decode(const mavlink_message_t* msg, mavlink_set_roll_pitch_yaw_thrust_t* set_roll_pitch_yaw_thrust)
{
#if MAVLINK_NEED_BYTE_SWAP
set_roll_pitch_yaw_thrust->roll = mavlink_msg_set_roll_pitch_yaw_thrust_get_roll(msg);
set_roll_pitch_yaw_thrust->pitch = mavlink_msg_set_roll_pitch_yaw_thrust_get_pitch(msg);
set_roll_pitch_yaw_thrust->yaw = mavlink_msg_set_roll_pitch_yaw_thrust_get_yaw(msg);
set_roll_pitch_yaw_thrust->thrust = mavlink_msg_set_roll_pitch_yaw_thrust_get_thrust(msg);
set_roll_pitch_yaw_thrust->target_system = mavlink_msg_set_roll_pitch_yaw_thrust_get_target_system(msg);
set_roll_pitch_yaw_thrust->target_component = mavlink_msg_set_roll_pitch_yaw_thrust_get_target_component(msg);
#else
memcpy(set_roll_pitch_yaw_thrust, _MAV_PAYLOAD(msg), 18);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v1.0/common/mavlink_msg_state_correction.h
0,0 → 1,320
// MESSAGE STATE_CORRECTION PACKING
 
#define MAVLINK_MSG_ID_STATE_CORRECTION 64
 
typedef struct __mavlink_state_correction_t
{
float xErr; ///< x position error
float yErr; ///< y position error
float zErr; ///< z position error
float rollErr; ///< roll error (radians)
float pitchErr; ///< pitch error (radians)
float yawErr; ///< yaw error (radians)
float vxErr; ///< x velocity
float vyErr; ///< y velocity
float vzErr; ///< z velocity
} mavlink_state_correction_t;
 
#define MAVLINK_MSG_ID_STATE_CORRECTION_LEN 36
#define MAVLINK_MSG_ID_64_LEN 36
 
 
 
#define MAVLINK_MESSAGE_INFO_STATE_CORRECTION { \
"STATE_CORRECTION", \
9, \
{ { "xErr", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_state_correction_t, xErr) }, \
{ "yErr", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_state_correction_t, yErr) }, \
{ "zErr", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_state_correction_t, zErr) }, \
{ "rollErr", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_state_correction_t, rollErr) }, \
{ "pitchErr", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_state_correction_t, pitchErr) }, \
{ "yawErr", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_state_correction_t, yawErr) }, \
{ "vxErr", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_state_correction_t, vxErr) }, \
{ "vyErr", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_state_correction_t, vyErr) }, \
{ "vzErr", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_state_correction_t, vzErr) }, \
} \
}
 
 
/**
* @brief Pack a state_correction message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param xErr x position error
* @param yErr y position error
* @param zErr z position error
* @param rollErr roll error (radians)
* @param pitchErr pitch error (radians)
* @param yawErr yaw error (radians)
* @param vxErr x velocity
* @param vyErr y velocity
* @param vzErr z velocity
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_state_correction_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
float xErr, float yErr, float zErr, float rollErr, float pitchErr, float yawErr, float vxErr, float vyErr, float vzErr)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[36];
_mav_put_float(buf, 0, xErr);
_mav_put_float(buf, 4, yErr);
_mav_put_float(buf, 8, zErr);
_mav_put_float(buf, 12, rollErr);
_mav_put_float(buf, 16, pitchErr);
_mav_put_float(buf, 20, yawErr);
_mav_put_float(buf, 24, vxErr);
_mav_put_float(buf, 28, vyErr);
_mav_put_float(buf, 32, vzErr);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 36);
#else
mavlink_state_correction_t packet;
packet.xErr = xErr;
packet.yErr = yErr;
packet.zErr = zErr;
packet.rollErr = rollErr;
packet.pitchErr = pitchErr;
packet.yawErr = yawErr;
packet.vxErr = vxErr;
packet.vyErr = vyErr;
packet.vzErr = vzErr;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 36);
#endif
 
msg->msgid = MAVLINK_MSG_ID_STATE_CORRECTION;
return mavlink_finalize_message(msg, system_id, component_id, 36, 130);
}
 
/**
* @brief Pack a state_correction message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param xErr x position error
* @param yErr y position error
* @param zErr z position error
* @param rollErr roll error (radians)
* @param pitchErr pitch error (radians)
* @param yawErr yaw error (radians)
* @param vxErr x velocity
* @param vyErr y velocity
* @param vzErr z velocity
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_state_correction_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
float xErr,float yErr,float zErr,float rollErr,float pitchErr,float yawErr,float vxErr,float vyErr,float vzErr)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[36];
_mav_put_float(buf, 0, xErr);
_mav_put_float(buf, 4, yErr);
_mav_put_float(buf, 8, zErr);
_mav_put_float(buf, 12, rollErr);
_mav_put_float(buf, 16, pitchErr);
_mav_put_float(buf, 20, yawErr);
_mav_put_float(buf, 24, vxErr);
_mav_put_float(buf, 28, vyErr);
_mav_put_float(buf, 32, vzErr);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 36);
#else
mavlink_state_correction_t packet;
packet.xErr = xErr;
packet.yErr = yErr;
packet.zErr = zErr;
packet.rollErr = rollErr;
packet.pitchErr = pitchErr;
packet.yawErr = yawErr;
packet.vxErr = vxErr;
packet.vyErr = vyErr;
packet.vzErr = vzErr;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 36);
#endif
 
msg->msgid = MAVLINK_MSG_ID_STATE_CORRECTION;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 36, 130);
}
 
/**
* @brief Encode a state_correction struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param state_correction C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_state_correction_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_state_correction_t* state_correction)
{
return mavlink_msg_state_correction_pack(system_id, component_id, msg, state_correction->xErr, state_correction->yErr, state_correction->zErr, state_correction->rollErr, state_correction->pitchErr, state_correction->yawErr, state_correction->vxErr, state_correction->vyErr, state_correction->vzErr);
}
 
/**
* @brief Send a state_correction message
* @param chan MAVLink channel to send the message
*
* @param xErr x position error
* @param yErr y position error
* @param zErr z position error
* @param rollErr roll error (radians)
* @param pitchErr pitch error (radians)
* @param yawErr yaw error (radians)
* @param vxErr x velocity
* @param vyErr y velocity
* @param vzErr z velocity
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_state_correction_send(mavlink_channel_t chan, float xErr, float yErr, float zErr, float rollErr, float pitchErr, float yawErr, float vxErr, float vyErr, float vzErr)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[36];
_mav_put_float(buf, 0, xErr);
_mav_put_float(buf, 4, yErr);
_mav_put_float(buf, 8, zErr);
_mav_put_float(buf, 12, rollErr);
_mav_put_float(buf, 16, pitchErr);
_mav_put_float(buf, 20, yawErr);
_mav_put_float(buf, 24, vxErr);
_mav_put_float(buf, 28, vyErr);
_mav_put_float(buf, 32, vzErr);
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_STATE_CORRECTION, buf, 36, 130);
#else
mavlink_state_correction_t packet;
packet.xErr = xErr;
packet.yErr = yErr;
packet.zErr = zErr;
packet.rollErr = rollErr;
packet.pitchErr = pitchErr;
packet.yawErr = yawErr;
packet.vxErr = vxErr;
packet.vyErr = vyErr;
packet.vzErr = vzErr;
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_STATE_CORRECTION, (const char *)&packet, 36, 130);
#endif
}
 
#endif
 
// MESSAGE STATE_CORRECTION UNPACKING
 
 
/**
* @brief Get field xErr from state_correction message
*
* @return x position error
*/
static inline float mavlink_msg_state_correction_get_xErr(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 0);
}
 
/**
* @brief Get field yErr from state_correction message
*
* @return y position error
*/
static inline float mavlink_msg_state_correction_get_yErr(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 4);
}
 
/**
* @brief Get field zErr from state_correction message
*
* @return z position error
*/
static inline float mavlink_msg_state_correction_get_zErr(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 8);
}
 
/**
* @brief Get field rollErr from state_correction message
*
* @return roll error (radians)
*/
static inline float mavlink_msg_state_correction_get_rollErr(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 12);
}
 
/**
* @brief Get field pitchErr from state_correction message
*
* @return pitch error (radians)
*/
static inline float mavlink_msg_state_correction_get_pitchErr(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 16);
}
 
/**
* @brief Get field yawErr from state_correction message
*
* @return yaw error (radians)
*/
static inline float mavlink_msg_state_correction_get_yawErr(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 20);
}
 
/**
* @brief Get field vxErr from state_correction message
*
* @return x velocity
*/
static inline float mavlink_msg_state_correction_get_vxErr(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 24);
}
 
/**
* @brief Get field vyErr from state_correction message
*
* @return y velocity
*/
static inline float mavlink_msg_state_correction_get_vyErr(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 28);
}
 
/**
* @brief Get field vzErr from state_correction message
*
* @return z velocity
*/
static inline float mavlink_msg_state_correction_get_vzErr(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 32);
}
 
/**
* @brief Decode a state_correction message into a struct
*
* @param msg The message to decode
* @param state_correction C-struct to decode the message contents into
*/
static inline void mavlink_msg_state_correction_decode(const mavlink_message_t* msg, mavlink_state_correction_t* state_correction)
{
#if MAVLINK_NEED_BYTE_SWAP
state_correction->xErr = mavlink_msg_state_correction_get_xErr(msg);
state_correction->yErr = mavlink_msg_state_correction_get_yErr(msg);
state_correction->zErr = mavlink_msg_state_correction_get_zErr(msg);
state_correction->rollErr = mavlink_msg_state_correction_get_rollErr(msg);
state_correction->pitchErr = mavlink_msg_state_correction_get_pitchErr(msg);
state_correction->yawErr = mavlink_msg_state_correction_get_yawErr(msg);
state_correction->vxErr = mavlink_msg_state_correction_get_vxErr(msg);
state_correction->vyErr = mavlink_msg_state_correction_get_vyErr(msg);
state_correction->vzErr = mavlink_msg_state_correction_get_vzErr(msg);
#else
memcpy(state_correction, _MAV_PAYLOAD(msg), 36);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v1.0/common/mavlink_msg_statustext.h
0,0 → 1,160
// MESSAGE STATUSTEXT PACKING
 
#define MAVLINK_MSG_ID_STATUSTEXT 253
 
typedef struct __mavlink_statustext_t
{
uint8_t severity; ///< Severity of status. Relies on the definitions within RFC-5424. See enum MAV_SEVERITY.
char text[50]; ///< Status text message, without null termination character
} mavlink_statustext_t;
 
#define MAVLINK_MSG_ID_STATUSTEXT_LEN 51
#define MAVLINK_MSG_ID_253_LEN 51
 
#define MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN 50
 
#define MAVLINK_MESSAGE_INFO_STATUSTEXT { \
"STATUSTEXT", \
2, \
{ { "severity", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_statustext_t, severity) }, \
{ "text", NULL, MAVLINK_TYPE_CHAR, 50, 1, offsetof(mavlink_statustext_t, text) }, \
} \
}
 
 
/**
* @brief Pack a statustext message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param severity Severity of status. Relies on the definitions within RFC-5424. See enum MAV_SEVERITY.
* @param text Status text message, without null termination character
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_statustext_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t severity, const char *text)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[51];
_mav_put_uint8_t(buf, 0, severity);
_mav_put_char_array(buf, 1, text, 50);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 51);
#else
mavlink_statustext_t packet;
packet.severity = severity;
mav_array_memcpy(packet.text, text, sizeof(char)*50);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 51);
#endif
 
msg->msgid = MAVLINK_MSG_ID_STATUSTEXT;
return mavlink_finalize_message(msg, system_id, component_id, 51, 83);
}
 
/**
* @brief Pack a statustext message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param severity Severity of status. Relies on the definitions within RFC-5424. See enum MAV_SEVERITY.
* @param text Status text message, without null termination character
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_statustext_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint8_t severity,const char *text)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[51];
_mav_put_uint8_t(buf, 0, severity);
_mav_put_char_array(buf, 1, text, 50);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 51);
#else
mavlink_statustext_t packet;
packet.severity = severity;
mav_array_memcpy(packet.text, text, sizeof(char)*50);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 51);
#endif
 
msg->msgid = MAVLINK_MSG_ID_STATUSTEXT;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 51, 83);
}
 
/**
* @brief Encode a statustext struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param statustext C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_statustext_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_statustext_t* statustext)
{
return mavlink_msg_statustext_pack(system_id, component_id, msg, statustext->severity, statustext->text);
}
 
/**
* @brief Send a statustext message
* @param chan MAVLink channel to send the message
*
* @param severity Severity of status. Relies on the definitions within RFC-5424. See enum MAV_SEVERITY.
* @param text Status text message, without null termination character
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_statustext_send(mavlink_channel_t chan, uint8_t severity, const char *text)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[51];
_mav_put_uint8_t(buf, 0, severity);
_mav_put_char_array(buf, 1, text, 50);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_STATUSTEXT, buf, 51, 83);
#else
mavlink_statustext_t packet;
packet.severity = severity;
mav_array_memcpy(packet.text, text, sizeof(char)*50);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_STATUSTEXT, (const char *)&packet, 51, 83);
#endif
}
 
#endif
 
// MESSAGE STATUSTEXT UNPACKING
 
 
/**
* @brief Get field severity from statustext message
*
* @return Severity of status. Relies on the definitions within RFC-5424. See enum MAV_SEVERITY.
*/
static inline uint8_t mavlink_msg_statustext_get_severity(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 0);
}
 
/**
* @brief Get field text from statustext message
*
* @return Status text message, without null termination character
*/
static inline uint16_t mavlink_msg_statustext_get_text(const mavlink_message_t* msg, char *text)
{
return _MAV_RETURN_char_array(msg, text, 50, 1);
}
 
/**
* @brief Decode a statustext message into a struct
*
* @param msg The message to decode
* @param statustext C-struct to decode the message contents into
*/
static inline void mavlink_msg_statustext_decode(const mavlink_message_t* msg, mavlink_statustext_t* statustext)
{
#if MAVLINK_NEED_BYTE_SWAP
statustext->severity = mavlink_msg_statustext_get_severity(msg);
mavlink_msg_statustext_get_text(msg, statustext->text);
#else
memcpy(statustext, _MAV_PAYLOAD(msg), 51);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v1.0/common/mavlink_msg_sys_status.h
0,0 → 1,408
// MESSAGE SYS_STATUS PACKING
 
#define MAVLINK_MSG_ID_SYS_STATUS 1
 
typedef struct __mavlink_sys_status_t
{
uint32_t onboard_control_sensors_present; ///< Bitmask showing which onboard controllers and sensors are present. Value of 0: not present. Value of 1: present. Indices: 0: 3D gyro, 1: 3D acc, 2: 3D mag, 3: absolute pressure, 4: differential pressure, 5: GPS, 6: optical flow, 7: computer vision position, 8: laser based position, 9: external ground-truth (Vicon or Leica). Controllers: 10: 3D angular rate control 11: attitude stabilization, 12: yaw position, 13: z/altitude control, 14: x/y position control, 15: motor outputs / control
uint32_t onboard_control_sensors_enabled; ///< Bitmask showing which onboard controllers and sensors are enabled: Value of 0: not enabled. Value of 1: enabled. Indices: 0: 3D gyro, 1: 3D acc, 2: 3D mag, 3: absolute pressure, 4: differential pressure, 5: GPS, 6: optical flow, 7: computer vision position, 8: laser based position, 9: external ground-truth (Vicon or Leica). Controllers: 10: 3D angular rate control 11: attitude stabilization, 12: yaw position, 13: z/altitude control, 14: x/y position control, 15: motor outputs / control
uint32_t onboard_control_sensors_health; ///< Bitmask showing which onboard controllers and sensors are operational or have an error: Value of 0: not enabled. Value of 1: enabled. Indices: 0: 3D gyro, 1: 3D acc, 2: 3D mag, 3: absolute pressure, 4: differential pressure, 5: GPS, 6: optical flow, 7: computer vision position, 8: laser based position, 9: external ground-truth (Vicon or Leica). Controllers: 10: 3D angular rate control 11: attitude stabilization, 12: yaw position, 13: z/altitude control, 14: x/y position control, 15: motor outputs / control
uint16_t load; ///< Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000
uint16_t voltage_battery; ///< Battery voltage, in millivolts (1 = 1 millivolt)
int16_t current_battery; ///< Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current
uint16_t drop_rate_comm; ///< Communication drops in percent, (0%: 0, 100%: 10'000), (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV)
uint16_t errors_comm; ///< Communication errors (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV)
uint16_t errors_count1; ///< Autopilot-specific errors
uint16_t errors_count2; ///< Autopilot-specific errors
uint16_t errors_count3; ///< Autopilot-specific errors
uint16_t errors_count4; ///< Autopilot-specific errors
int8_t battery_remaining; ///< Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot estimate the remaining battery
} mavlink_sys_status_t;
 
#define MAVLINK_MSG_ID_SYS_STATUS_LEN 31
#define MAVLINK_MSG_ID_1_LEN 31
 
 
 
#define MAVLINK_MESSAGE_INFO_SYS_STATUS { \
"SYS_STATUS", \
13, \
{ { "onboard_control_sensors_present", "0x%04x", MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_sys_status_t, onboard_control_sensors_present) }, \
{ "onboard_control_sensors_enabled", "0x%04x", MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_sys_status_t, onboard_control_sensors_enabled) }, \
{ "onboard_control_sensors_health", "0x%04x", MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_sys_status_t, onboard_control_sensors_health) }, \
{ "load", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_sys_status_t, load) }, \
{ "voltage_battery", NULL, MAVLINK_TYPE_UINT16_T, 0, 14, offsetof(mavlink_sys_status_t, voltage_battery) }, \
{ "current_battery", NULL, MAVLINK_TYPE_INT16_T, 0, 16, offsetof(mavlink_sys_status_t, current_battery) }, \
{ "drop_rate_comm", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_sys_status_t, drop_rate_comm) }, \
{ "errors_comm", NULL, MAVLINK_TYPE_UINT16_T, 0, 20, offsetof(mavlink_sys_status_t, errors_comm) }, \
{ "errors_count1", NULL, MAVLINK_TYPE_UINT16_T, 0, 22, offsetof(mavlink_sys_status_t, errors_count1) }, \
{ "errors_count2", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_sys_status_t, errors_count2) }, \
{ "errors_count3", NULL, MAVLINK_TYPE_UINT16_T, 0, 26, offsetof(mavlink_sys_status_t, errors_count3) }, \
{ "errors_count4", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_sys_status_t, errors_count4) }, \
{ "battery_remaining", NULL, MAVLINK_TYPE_INT8_T, 0, 30, offsetof(mavlink_sys_status_t, battery_remaining) }, \
} \
}
 
 
/**
* @brief Pack a sys_status message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param onboard_control_sensors_present Bitmask showing which onboard controllers and sensors are present. Value of 0: not present. Value of 1: present. Indices: 0: 3D gyro, 1: 3D acc, 2: 3D mag, 3: absolute pressure, 4: differential pressure, 5: GPS, 6: optical flow, 7: computer vision position, 8: laser based position, 9: external ground-truth (Vicon or Leica). Controllers: 10: 3D angular rate control 11: attitude stabilization, 12: yaw position, 13: z/altitude control, 14: x/y position control, 15: motor outputs / control
* @param onboard_control_sensors_enabled Bitmask showing which onboard controllers and sensors are enabled: Value of 0: not enabled. Value of 1: enabled. Indices: 0: 3D gyro, 1: 3D acc, 2: 3D mag, 3: absolute pressure, 4: differential pressure, 5: GPS, 6: optical flow, 7: computer vision position, 8: laser based position, 9: external ground-truth (Vicon or Leica). Controllers: 10: 3D angular rate control 11: attitude stabilization, 12: yaw position, 13: z/altitude control, 14: x/y position control, 15: motor outputs / control
* @param onboard_control_sensors_health Bitmask showing which onboard controllers and sensors are operational or have an error: Value of 0: not enabled. Value of 1: enabled. Indices: 0: 3D gyro, 1: 3D acc, 2: 3D mag, 3: absolute pressure, 4: differential pressure, 5: GPS, 6: optical flow, 7: computer vision position, 8: laser based position, 9: external ground-truth (Vicon or Leica). Controllers: 10: 3D angular rate control 11: attitude stabilization, 12: yaw position, 13: z/altitude control, 14: x/y position control, 15: motor outputs / control
* @param load Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000
* @param voltage_battery Battery voltage, in millivolts (1 = 1 millivolt)
* @param current_battery Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current
* @param battery_remaining Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot estimate the remaining battery
* @param drop_rate_comm Communication drops in percent, (0%: 0, 100%: 10'000), (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV)
* @param errors_comm Communication errors (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV)
* @param errors_count1 Autopilot-specific errors
* @param errors_count2 Autopilot-specific errors
* @param errors_count3 Autopilot-specific errors
* @param errors_count4 Autopilot-specific errors
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_sys_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint32_t onboard_control_sensors_present, uint32_t onboard_control_sensors_enabled, uint32_t onboard_control_sensors_health, uint16_t load, uint16_t voltage_battery, int16_t current_battery, int8_t battery_remaining, uint16_t drop_rate_comm, uint16_t errors_comm, uint16_t errors_count1, uint16_t errors_count2, uint16_t errors_count3, uint16_t errors_count4)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[31];
_mav_put_uint32_t(buf, 0, onboard_control_sensors_present);
_mav_put_uint32_t(buf, 4, onboard_control_sensors_enabled);
_mav_put_uint32_t(buf, 8, onboard_control_sensors_health);
_mav_put_uint16_t(buf, 12, load);
_mav_put_uint16_t(buf, 14, voltage_battery);
_mav_put_int16_t(buf, 16, current_battery);
_mav_put_uint16_t(buf, 18, drop_rate_comm);
_mav_put_uint16_t(buf, 20, errors_comm);
_mav_put_uint16_t(buf, 22, errors_count1);
_mav_put_uint16_t(buf, 24, errors_count2);
_mav_put_uint16_t(buf, 26, errors_count3);
_mav_put_uint16_t(buf, 28, errors_count4);
_mav_put_int8_t(buf, 30, battery_remaining);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 31);
#else
mavlink_sys_status_t packet;
packet.onboard_control_sensors_present = onboard_control_sensors_present;
packet.onboard_control_sensors_enabled = onboard_control_sensors_enabled;
packet.onboard_control_sensors_health = onboard_control_sensors_health;
packet.load = load;
packet.voltage_battery = voltage_battery;
packet.current_battery = current_battery;
packet.drop_rate_comm = drop_rate_comm;
packet.errors_comm = errors_comm;
packet.errors_count1 = errors_count1;
packet.errors_count2 = errors_count2;
packet.errors_count3 = errors_count3;
packet.errors_count4 = errors_count4;
packet.battery_remaining = battery_remaining;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 31);
#endif
 
msg->msgid = MAVLINK_MSG_ID_SYS_STATUS;
return mavlink_finalize_message(msg, system_id, component_id, 31, 124);
}
 
/**
* @brief Pack a sys_status message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param onboard_control_sensors_present Bitmask showing which onboard controllers and sensors are present. Value of 0: not present. Value of 1: present. Indices: 0: 3D gyro, 1: 3D acc, 2: 3D mag, 3: absolute pressure, 4: differential pressure, 5: GPS, 6: optical flow, 7: computer vision position, 8: laser based position, 9: external ground-truth (Vicon or Leica). Controllers: 10: 3D angular rate control 11: attitude stabilization, 12: yaw position, 13: z/altitude control, 14: x/y position control, 15: motor outputs / control
* @param onboard_control_sensors_enabled Bitmask showing which onboard controllers and sensors are enabled: Value of 0: not enabled. Value of 1: enabled. Indices: 0: 3D gyro, 1: 3D acc, 2: 3D mag, 3: absolute pressure, 4: differential pressure, 5: GPS, 6: optical flow, 7: computer vision position, 8: laser based position, 9: external ground-truth (Vicon or Leica). Controllers: 10: 3D angular rate control 11: attitude stabilization, 12: yaw position, 13: z/altitude control, 14: x/y position control, 15: motor outputs / control
* @param onboard_control_sensors_health Bitmask showing which onboard controllers and sensors are operational or have an error: Value of 0: not enabled. Value of 1: enabled. Indices: 0: 3D gyro, 1: 3D acc, 2: 3D mag, 3: absolute pressure, 4: differential pressure, 5: GPS, 6: optical flow, 7: computer vision position, 8: laser based position, 9: external ground-truth (Vicon or Leica). Controllers: 10: 3D angular rate control 11: attitude stabilization, 12: yaw position, 13: z/altitude control, 14: x/y position control, 15: motor outputs / control
* @param load Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000
* @param voltage_battery Battery voltage, in millivolts (1 = 1 millivolt)
* @param current_battery Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current
* @param battery_remaining Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot estimate the remaining battery
* @param drop_rate_comm Communication drops in percent, (0%: 0, 100%: 10'000), (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV)
* @param errors_comm Communication errors (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV)
* @param errors_count1 Autopilot-specific errors
* @param errors_count2 Autopilot-specific errors
* @param errors_count3 Autopilot-specific errors
* @param errors_count4 Autopilot-specific errors
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_sys_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint32_t onboard_control_sensors_present,uint32_t onboard_control_sensors_enabled,uint32_t onboard_control_sensors_health,uint16_t load,uint16_t voltage_battery,int16_t current_battery,int8_t battery_remaining,uint16_t drop_rate_comm,uint16_t errors_comm,uint16_t errors_count1,uint16_t errors_count2,uint16_t errors_count3,uint16_t errors_count4)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[31];
_mav_put_uint32_t(buf, 0, onboard_control_sensors_present);
_mav_put_uint32_t(buf, 4, onboard_control_sensors_enabled);
_mav_put_uint32_t(buf, 8, onboard_control_sensors_health);
_mav_put_uint16_t(buf, 12, load);
_mav_put_uint16_t(buf, 14, voltage_battery);
_mav_put_int16_t(buf, 16, current_battery);
_mav_put_uint16_t(buf, 18, drop_rate_comm);
_mav_put_uint16_t(buf, 20, errors_comm);
_mav_put_uint16_t(buf, 22, errors_count1);
_mav_put_uint16_t(buf, 24, errors_count2);
_mav_put_uint16_t(buf, 26, errors_count3);
_mav_put_uint16_t(buf, 28, errors_count4);
_mav_put_int8_t(buf, 30, battery_remaining);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 31);
#else
mavlink_sys_status_t packet;
packet.onboard_control_sensors_present = onboard_control_sensors_present;
packet.onboard_control_sensors_enabled = onboard_control_sensors_enabled;
packet.onboard_control_sensors_health = onboard_control_sensors_health;
packet.load = load;
packet.voltage_battery = voltage_battery;
packet.current_battery = current_battery;
packet.drop_rate_comm = drop_rate_comm;
packet.errors_comm = errors_comm;
packet.errors_count1 = errors_count1;
packet.errors_count2 = errors_count2;
packet.errors_count3 = errors_count3;
packet.errors_count4 = errors_count4;
packet.battery_remaining = battery_remaining;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 31);
#endif
 
msg->msgid = MAVLINK_MSG_ID_SYS_STATUS;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 31, 124);
}
 
/**
* @brief Encode a sys_status struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param sys_status C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_sys_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_sys_status_t* sys_status)
{
return mavlink_msg_sys_status_pack(system_id, component_id, msg, sys_status->onboard_control_sensors_present, sys_status->onboard_control_sensors_enabled, sys_status->onboard_control_sensors_health, sys_status->load, sys_status->voltage_battery, sys_status->current_battery, sys_status->battery_remaining, sys_status->drop_rate_comm, sys_status->errors_comm, sys_status->errors_count1, sys_status->errors_count2, sys_status->errors_count3, sys_status->errors_count4);
}
 
/**
* @brief Send a sys_status message
* @param chan MAVLink channel to send the message
*
* @param onboard_control_sensors_present Bitmask showing which onboard controllers and sensors are present. Value of 0: not present. Value of 1: present. Indices: 0: 3D gyro, 1: 3D acc, 2: 3D mag, 3: absolute pressure, 4: differential pressure, 5: GPS, 6: optical flow, 7: computer vision position, 8: laser based position, 9: external ground-truth (Vicon or Leica). Controllers: 10: 3D angular rate control 11: attitude stabilization, 12: yaw position, 13: z/altitude control, 14: x/y position control, 15: motor outputs / control
* @param onboard_control_sensors_enabled Bitmask showing which onboard controllers and sensors are enabled: Value of 0: not enabled. Value of 1: enabled. Indices: 0: 3D gyro, 1: 3D acc, 2: 3D mag, 3: absolute pressure, 4: differential pressure, 5: GPS, 6: optical flow, 7: computer vision position, 8: laser based position, 9: external ground-truth (Vicon or Leica). Controllers: 10: 3D angular rate control 11: attitude stabilization, 12: yaw position, 13: z/altitude control, 14: x/y position control, 15: motor outputs / control
* @param onboard_control_sensors_health Bitmask showing which onboard controllers and sensors are operational or have an error: Value of 0: not enabled. Value of 1: enabled. Indices: 0: 3D gyro, 1: 3D acc, 2: 3D mag, 3: absolute pressure, 4: differential pressure, 5: GPS, 6: optical flow, 7: computer vision position, 8: laser based position, 9: external ground-truth (Vicon or Leica). Controllers: 10: 3D angular rate control 11: attitude stabilization, 12: yaw position, 13: z/altitude control, 14: x/y position control, 15: motor outputs / control
* @param load Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000
* @param voltage_battery Battery voltage, in millivolts (1 = 1 millivolt)
* @param current_battery Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current
* @param battery_remaining Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot estimate the remaining battery
* @param drop_rate_comm Communication drops in percent, (0%: 0, 100%: 10'000), (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV)
* @param errors_comm Communication errors (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV)
* @param errors_count1 Autopilot-specific errors
* @param errors_count2 Autopilot-specific errors
* @param errors_count3 Autopilot-specific errors
* @param errors_count4 Autopilot-specific errors
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_sys_status_send(mavlink_channel_t chan, uint32_t onboard_control_sensors_present, uint32_t onboard_control_sensors_enabled, uint32_t onboard_control_sensors_health, uint16_t load, uint16_t voltage_battery, int16_t current_battery, int8_t battery_remaining, uint16_t drop_rate_comm, uint16_t errors_comm, uint16_t errors_count1, uint16_t errors_count2, uint16_t errors_count3, uint16_t errors_count4)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[31];
_mav_put_uint32_t(buf, 0, onboard_control_sensors_present);
_mav_put_uint32_t(buf, 4, onboard_control_sensors_enabled);
_mav_put_uint32_t(buf, 8, onboard_control_sensors_health);
_mav_put_uint16_t(buf, 12, load);
_mav_put_uint16_t(buf, 14, voltage_battery);
_mav_put_int16_t(buf, 16, current_battery);
_mav_put_uint16_t(buf, 18, drop_rate_comm);
_mav_put_uint16_t(buf, 20, errors_comm);
_mav_put_uint16_t(buf, 22, errors_count1);
_mav_put_uint16_t(buf, 24, errors_count2);
_mav_put_uint16_t(buf, 26, errors_count3);
_mav_put_uint16_t(buf, 28, errors_count4);
_mav_put_int8_t(buf, 30, battery_remaining);
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYS_STATUS, buf, 31, 124);
#else
mavlink_sys_status_t packet;
packet.onboard_control_sensors_present = onboard_control_sensors_present;
packet.onboard_control_sensors_enabled = onboard_control_sensors_enabled;
packet.onboard_control_sensors_health = onboard_control_sensors_health;
packet.load = load;
packet.voltage_battery = voltage_battery;
packet.current_battery = current_battery;
packet.drop_rate_comm = drop_rate_comm;
packet.errors_comm = errors_comm;
packet.errors_count1 = errors_count1;
packet.errors_count2 = errors_count2;
packet.errors_count3 = errors_count3;
packet.errors_count4 = errors_count4;
packet.battery_remaining = battery_remaining;
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYS_STATUS, (const char *)&packet, 31, 124);
#endif
}
 
#endif
 
// MESSAGE SYS_STATUS UNPACKING
 
 
/**
* @brief Get field onboard_control_sensors_present from sys_status message
*
* @return Bitmask showing which onboard controllers and sensors are present. Value of 0: not present. Value of 1: present. Indices: 0: 3D gyro, 1: 3D acc, 2: 3D mag, 3: absolute pressure, 4: differential pressure, 5: GPS, 6: optical flow, 7: computer vision position, 8: laser based position, 9: external ground-truth (Vicon or Leica). Controllers: 10: 3D angular rate control 11: attitude stabilization, 12: yaw position, 13: z/altitude control, 14: x/y position control, 15: motor outputs / control
*/
static inline uint32_t mavlink_msg_sys_status_get_onboard_control_sensors_present(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint32_t(msg, 0);
}
 
/**
* @brief Get field onboard_control_sensors_enabled from sys_status message
*
* @return Bitmask showing which onboard controllers and sensors are enabled: Value of 0: not enabled. Value of 1: enabled. Indices: 0: 3D gyro, 1: 3D acc, 2: 3D mag, 3: absolute pressure, 4: differential pressure, 5: GPS, 6: optical flow, 7: computer vision position, 8: laser based position, 9: external ground-truth (Vicon or Leica). Controllers: 10: 3D angular rate control 11: attitude stabilization, 12: yaw position, 13: z/altitude control, 14: x/y position control, 15: motor outputs / control
*/
static inline uint32_t mavlink_msg_sys_status_get_onboard_control_sensors_enabled(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint32_t(msg, 4);
}
 
/**
* @brief Get field onboard_control_sensors_health from sys_status message
*
* @return Bitmask showing which onboard controllers and sensors are operational or have an error: Value of 0: not enabled. Value of 1: enabled. Indices: 0: 3D gyro, 1: 3D acc, 2: 3D mag, 3: absolute pressure, 4: differential pressure, 5: GPS, 6: optical flow, 7: computer vision position, 8: laser based position, 9: external ground-truth (Vicon or Leica). Controllers: 10: 3D angular rate control 11: attitude stabilization, 12: yaw position, 13: z/altitude control, 14: x/y position control, 15: motor outputs / control
*/
static inline uint32_t mavlink_msg_sys_status_get_onboard_control_sensors_health(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint32_t(msg, 8);
}
 
/**
* @brief Get field load from sys_status message
*
* @return Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000
*/
static inline uint16_t mavlink_msg_sys_status_get_load(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 12);
}
 
/**
* @brief Get field voltage_battery from sys_status message
*
* @return Battery voltage, in millivolts (1 = 1 millivolt)
*/
static inline uint16_t mavlink_msg_sys_status_get_voltage_battery(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 14);
}
 
/**
* @brief Get field current_battery from sys_status message
*
* @return Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current
*/
static inline int16_t mavlink_msg_sys_status_get_current_battery(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 16);
}
 
/**
* @brief Get field battery_remaining from sys_status message
*
* @return Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot estimate the remaining battery
*/
static inline int8_t mavlink_msg_sys_status_get_battery_remaining(const mavlink_message_t* msg)
{
return _MAV_RETURN_int8_t(msg, 30);
}
 
/**
* @brief Get field drop_rate_comm from sys_status message
*
* @return Communication drops in percent, (0%: 0, 100%: 10'000), (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV)
*/
static inline uint16_t mavlink_msg_sys_status_get_drop_rate_comm(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 18);
}
 
/**
* @brief Get field errors_comm from sys_status message
*
* @return Communication errors (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV)
*/
static inline uint16_t mavlink_msg_sys_status_get_errors_comm(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 20);
}
 
/**
* @brief Get field errors_count1 from sys_status message
*
* @return Autopilot-specific errors
*/
static inline uint16_t mavlink_msg_sys_status_get_errors_count1(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 22);
}
 
/**
* @brief Get field errors_count2 from sys_status message
*
* @return Autopilot-specific errors
*/
static inline uint16_t mavlink_msg_sys_status_get_errors_count2(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 24);
}
 
/**
* @brief Get field errors_count3 from sys_status message
*
* @return Autopilot-specific errors
*/
static inline uint16_t mavlink_msg_sys_status_get_errors_count3(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 26);
}
 
/**
* @brief Get field errors_count4 from sys_status message
*
* @return Autopilot-specific errors
*/
static inline uint16_t mavlink_msg_sys_status_get_errors_count4(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 28);
}
 
/**
* @brief Decode a sys_status message into a struct
*
* @param msg The message to decode
* @param sys_status C-struct to decode the message contents into
*/
static inline void mavlink_msg_sys_status_decode(const mavlink_message_t* msg, mavlink_sys_status_t* sys_status)
{
#if MAVLINK_NEED_BYTE_SWAP
sys_status->onboard_control_sensors_present = mavlink_msg_sys_status_get_onboard_control_sensors_present(msg);
sys_status->onboard_control_sensors_enabled = mavlink_msg_sys_status_get_onboard_control_sensors_enabled(msg);
sys_status->onboard_control_sensors_health = mavlink_msg_sys_status_get_onboard_control_sensors_health(msg);
sys_status->load = mavlink_msg_sys_status_get_load(msg);
sys_status->voltage_battery = mavlink_msg_sys_status_get_voltage_battery(msg);
sys_status->current_battery = mavlink_msg_sys_status_get_current_battery(msg);
sys_status->drop_rate_comm = mavlink_msg_sys_status_get_drop_rate_comm(msg);
sys_status->errors_comm = mavlink_msg_sys_status_get_errors_comm(msg);
sys_status->errors_count1 = mavlink_msg_sys_status_get_errors_count1(msg);
sys_status->errors_count2 = mavlink_msg_sys_status_get_errors_count2(msg);
sys_status->errors_count3 = mavlink_msg_sys_status_get_errors_count3(msg);
sys_status->errors_count4 = mavlink_msg_sys_status_get_errors_count4(msg);
sys_status->battery_remaining = mavlink_msg_sys_status_get_battery_remaining(msg);
#else
memcpy(sys_status, _MAV_PAYLOAD(msg), 31);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v1.0/common/mavlink_msg_system_time.h
0,0 → 1,166
// MESSAGE SYSTEM_TIME PACKING
 
#define MAVLINK_MSG_ID_SYSTEM_TIME 2
 
typedef struct __mavlink_system_time_t
{
uint64_t time_unix_usec; ///< Timestamp of the master clock in microseconds since UNIX epoch.
uint32_t time_boot_ms; ///< Timestamp of the component clock since boot time in milliseconds.
} mavlink_system_time_t;
 
#define MAVLINK_MSG_ID_SYSTEM_TIME_LEN 12
#define MAVLINK_MSG_ID_2_LEN 12
 
 
 
#define MAVLINK_MESSAGE_INFO_SYSTEM_TIME { \
"SYSTEM_TIME", \
2, \
{ { "time_unix_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_system_time_t, time_unix_usec) }, \
{ "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_system_time_t, time_boot_ms) }, \
} \
}
 
 
/**
* @brief Pack a system_time message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param time_unix_usec Timestamp of the master clock in microseconds since UNIX epoch.
* @param time_boot_ms Timestamp of the component clock since boot time in milliseconds.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_system_time_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint64_t time_unix_usec, uint32_t time_boot_ms)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[12];
_mav_put_uint64_t(buf, 0, time_unix_usec);
_mav_put_uint32_t(buf, 8, time_boot_ms);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 12);
#else
mavlink_system_time_t packet;
packet.time_unix_usec = time_unix_usec;
packet.time_boot_ms = time_boot_ms;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 12);
#endif
 
msg->msgid = MAVLINK_MSG_ID_SYSTEM_TIME;
return mavlink_finalize_message(msg, system_id, component_id, 12, 137);
}
 
/**
* @brief Pack a system_time message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param time_unix_usec Timestamp of the master clock in microseconds since UNIX epoch.
* @param time_boot_ms Timestamp of the component clock since boot time in milliseconds.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_system_time_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint64_t time_unix_usec,uint32_t time_boot_ms)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[12];
_mav_put_uint64_t(buf, 0, time_unix_usec);
_mav_put_uint32_t(buf, 8, time_boot_ms);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 12);
#else
mavlink_system_time_t packet;
packet.time_unix_usec = time_unix_usec;
packet.time_boot_ms = time_boot_ms;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 12);
#endif
 
msg->msgid = MAVLINK_MSG_ID_SYSTEM_TIME;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 12, 137);
}
 
/**
* @brief Encode a system_time struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param system_time C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_system_time_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_system_time_t* system_time)
{
return mavlink_msg_system_time_pack(system_id, component_id, msg, system_time->time_unix_usec, system_time->time_boot_ms);
}
 
/**
* @brief Send a system_time message
* @param chan MAVLink channel to send the message
*
* @param time_unix_usec Timestamp of the master clock in microseconds since UNIX epoch.
* @param time_boot_ms Timestamp of the component clock since boot time in milliseconds.
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_system_time_send(mavlink_channel_t chan, uint64_t time_unix_usec, uint32_t time_boot_ms)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[12];
_mav_put_uint64_t(buf, 0, time_unix_usec);
_mav_put_uint32_t(buf, 8, time_boot_ms);
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYSTEM_TIME, buf, 12, 137);
#else
mavlink_system_time_t packet;
packet.time_unix_usec = time_unix_usec;
packet.time_boot_ms = time_boot_ms;
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYSTEM_TIME, (const char *)&packet, 12, 137);
#endif
}
 
#endif
 
// MESSAGE SYSTEM_TIME UNPACKING
 
 
/**
* @brief Get field time_unix_usec from system_time message
*
* @return Timestamp of the master clock in microseconds since UNIX epoch.
*/
static inline uint64_t mavlink_msg_system_time_get_time_unix_usec(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint64_t(msg, 0);
}
 
/**
* @brief Get field time_boot_ms from system_time message
*
* @return Timestamp of the component clock since boot time in milliseconds.
*/
static inline uint32_t mavlink_msg_system_time_get_time_boot_ms(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint32_t(msg, 8);
}
 
/**
* @brief Decode a system_time message into a struct
*
* @param msg The message to decode
* @param system_time C-struct to decode the message contents into
*/
static inline void mavlink_msg_system_time_decode(const mavlink_message_t* msg, mavlink_system_time_t* system_time)
{
#if MAVLINK_NEED_BYTE_SWAP
system_time->time_unix_usec = mavlink_msg_system_time_get_time_unix_usec(msg);
system_time->time_boot_ms = mavlink_msg_system_time_get_time_boot_ms(msg);
#else
memcpy(system_time, _MAV_PAYLOAD(msg), 12);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v1.0/common/mavlink_msg_vfr_hud.h
0,0 → 1,254
// MESSAGE VFR_HUD PACKING
 
#define MAVLINK_MSG_ID_VFR_HUD 74
 
typedef struct __mavlink_vfr_hud_t
{
float airspeed; ///< Current airspeed in m/s
float groundspeed; ///< Current ground speed in m/s
float alt; ///< Current altitude (MSL), in meters
float climb; ///< Current climb rate in meters/second
int16_t heading; ///< Current heading in degrees, in compass units (0..360, 0=north)
uint16_t throttle; ///< Current throttle setting in integer percent, 0 to 100
} mavlink_vfr_hud_t;
 
#define MAVLINK_MSG_ID_VFR_HUD_LEN 20
#define MAVLINK_MSG_ID_74_LEN 20
 
 
 
#define MAVLINK_MESSAGE_INFO_VFR_HUD { \
"VFR_HUD", \
6, \
{ { "airspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_vfr_hud_t, airspeed) }, \
{ "groundspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_vfr_hud_t, groundspeed) }, \
{ "alt", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_vfr_hud_t, alt) }, \
{ "climb", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_vfr_hud_t, climb) }, \
{ "heading", NULL, MAVLINK_TYPE_INT16_T, 0, 16, offsetof(mavlink_vfr_hud_t, heading) }, \
{ "throttle", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_vfr_hud_t, throttle) }, \
} \
}
 
 
/**
* @brief Pack a vfr_hud message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param airspeed Current airspeed in m/s
* @param groundspeed Current ground speed in m/s
* @param heading Current heading in degrees, in compass units (0..360, 0=north)
* @param throttle Current throttle setting in integer percent, 0 to 100
* @param alt Current altitude (MSL), in meters
* @param climb Current climb rate in meters/second
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_vfr_hud_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
float airspeed, float groundspeed, int16_t heading, uint16_t throttle, float alt, float climb)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[20];
_mav_put_float(buf, 0, airspeed);
_mav_put_float(buf, 4, groundspeed);
_mav_put_float(buf, 8, alt);
_mav_put_float(buf, 12, climb);
_mav_put_int16_t(buf, 16, heading);
_mav_put_uint16_t(buf, 18, throttle);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 20);
#else
mavlink_vfr_hud_t packet;
packet.airspeed = airspeed;
packet.groundspeed = groundspeed;
packet.alt = alt;
packet.climb = climb;
packet.heading = heading;
packet.throttle = throttle;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 20);
#endif
 
msg->msgid = MAVLINK_MSG_ID_VFR_HUD;
return mavlink_finalize_message(msg, system_id, component_id, 20, 20);
}
 
/**
* @brief Pack a vfr_hud message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param airspeed Current airspeed in m/s
* @param groundspeed Current ground speed in m/s
* @param heading Current heading in degrees, in compass units (0..360, 0=north)
* @param throttle Current throttle setting in integer percent, 0 to 100
* @param alt Current altitude (MSL), in meters
* @param climb Current climb rate in meters/second
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_vfr_hud_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
float airspeed,float groundspeed,int16_t heading,uint16_t throttle,float alt,float climb)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[20];
_mav_put_float(buf, 0, airspeed);
_mav_put_float(buf, 4, groundspeed);
_mav_put_float(buf, 8, alt);
_mav_put_float(buf, 12, climb);
_mav_put_int16_t(buf, 16, heading);
_mav_put_uint16_t(buf, 18, throttle);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 20);
#else
mavlink_vfr_hud_t packet;
packet.airspeed = airspeed;
packet.groundspeed = groundspeed;
packet.alt = alt;
packet.climb = climb;
packet.heading = heading;
packet.throttle = throttle;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 20);
#endif
 
msg->msgid = MAVLINK_MSG_ID_VFR_HUD;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 20, 20);
}
 
/**
* @brief Encode a vfr_hud struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param vfr_hud C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_vfr_hud_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_vfr_hud_t* vfr_hud)
{
return mavlink_msg_vfr_hud_pack(system_id, component_id, msg, vfr_hud->airspeed, vfr_hud->groundspeed, vfr_hud->heading, vfr_hud->throttle, vfr_hud->alt, vfr_hud->climb);
}
 
/**
* @brief Send a vfr_hud message
* @param chan MAVLink channel to send the message
*
* @param airspeed Current airspeed in m/s
* @param groundspeed Current ground speed in m/s
* @param heading Current heading in degrees, in compass units (0..360, 0=north)
* @param throttle Current throttle setting in integer percent, 0 to 100
* @param alt Current altitude (MSL), in meters
* @param climb Current climb rate in meters/second
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_vfr_hud_send(mavlink_channel_t chan, float airspeed, float groundspeed, int16_t heading, uint16_t throttle, float alt, float climb)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[20];
_mav_put_float(buf, 0, airspeed);
_mav_put_float(buf, 4, groundspeed);
_mav_put_float(buf, 8, alt);
_mav_put_float(buf, 12, climb);
_mav_put_int16_t(buf, 16, heading);
_mav_put_uint16_t(buf, 18, throttle);
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VFR_HUD, buf, 20, 20);
#else
mavlink_vfr_hud_t packet;
packet.airspeed = airspeed;
packet.groundspeed = groundspeed;
packet.alt = alt;
packet.climb = climb;
packet.heading = heading;
packet.throttle = throttle;
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VFR_HUD, (const char *)&packet, 20, 20);
#endif
}
 
#endif
 
// MESSAGE VFR_HUD UNPACKING
 
 
/**
* @brief Get field airspeed from vfr_hud message
*
* @return Current airspeed in m/s
*/
static inline float mavlink_msg_vfr_hud_get_airspeed(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 0);
}
 
/**
* @brief Get field groundspeed from vfr_hud message
*
* @return Current ground speed in m/s
*/
static inline float mavlink_msg_vfr_hud_get_groundspeed(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 4);
}
 
/**
* @brief Get field heading from vfr_hud message
*
* @return Current heading in degrees, in compass units (0..360, 0=north)
*/
static inline int16_t mavlink_msg_vfr_hud_get_heading(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 16);
}
 
/**
* @brief Get field throttle from vfr_hud message
*
* @return Current throttle setting in integer percent, 0 to 100
*/
static inline uint16_t mavlink_msg_vfr_hud_get_throttle(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 18);
}
 
/**
* @brief Get field alt from vfr_hud message
*
* @return Current altitude (MSL), in meters
*/
static inline float mavlink_msg_vfr_hud_get_alt(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 8);
}
 
/**
* @brief Get field climb from vfr_hud message
*
* @return Current climb rate in meters/second
*/
static inline float mavlink_msg_vfr_hud_get_climb(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 12);
}
 
/**
* @brief Decode a vfr_hud message into a struct
*
* @param msg The message to decode
* @param vfr_hud C-struct to decode the message contents into
*/
static inline void mavlink_msg_vfr_hud_decode(const mavlink_message_t* msg, mavlink_vfr_hud_t* vfr_hud)
{
#if MAVLINK_NEED_BYTE_SWAP
vfr_hud->airspeed = mavlink_msg_vfr_hud_get_airspeed(msg);
vfr_hud->groundspeed = mavlink_msg_vfr_hud_get_groundspeed(msg);
vfr_hud->alt = mavlink_msg_vfr_hud_get_alt(msg);
vfr_hud->climb = mavlink_msg_vfr_hud_get_climb(msg);
vfr_hud->heading = mavlink_msg_vfr_hud_get_heading(msg);
vfr_hud->throttle = mavlink_msg_vfr_hud_get_throttle(msg);
#else
memcpy(vfr_hud, _MAV_PAYLOAD(msg), 20);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v1.0/common/mavlink_msg_vicon_position_estimate.h
0,0 → 1,276
// MESSAGE VICON_POSITION_ESTIMATE PACKING
 
#define MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE 104
 
typedef struct __mavlink_vicon_position_estimate_t
{
uint64_t usec; ///< Timestamp (milliseconds)
float x; ///< Global X position
float y; ///< Global Y position
float z; ///< Global Z position
float roll; ///< Roll angle in rad
float pitch; ///< Pitch angle in rad
float yaw; ///< Yaw angle in rad
} mavlink_vicon_position_estimate_t;
 
#define MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE_LEN 32
#define MAVLINK_MSG_ID_104_LEN 32
 
 
 
#define MAVLINK_MESSAGE_INFO_VICON_POSITION_ESTIMATE { \
"VICON_POSITION_ESTIMATE", \
7, \
{ { "usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_vicon_position_estimate_t, usec) }, \
{ "x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_vicon_position_estimate_t, x) }, \
{ "y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_vicon_position_estimate_t, y) }, \
{ "z", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_vicon_position_estimate_t, z) }, \
{ "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_vicon_position_estimate_t, roll) }, \
{ "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_vicon_position_estimate_t, pitch) }, \
{ "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_vicon_position_estimate_t, yaw) }, \
} \
}
 
 
/**
* @brief Pack a vicon_position_estimate message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param usec Timestamp (milliseconds)
* @param x Global X position
* @param y Global Y position
* @param z Global Z position
* @param roll Roll angle in rad
* @param pitch Pitch angle in rad
* @param yaw Yaw angle in rad
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_vicon_position_estimate_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint64_t usec, float x, float y, float z, float roll, float pitch, float yaw)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[32];
_mav_put_uint64_t(buf, 0, usec);
_mav_put_float(buf, 8, x);
_mav_put_float(buf, 12, y);
_mav_put_float(buf, 16, z);
_mav_put_float(buf, 20, roll);
_mav_put_float(buf, 24, pitch);
_mav_put_float(buf, 28, yaw);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 32);
#else
mavlink_vicon_position_estimate_t packet;
packet.usec = usec;
packet.x = x;
packet.y = y;
packet.z = z;
packet.roll = roll;
packet.pitch = pitch;
packet.yaw = yaw;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 32);
#endif
 
msg->msgid = MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE;
return mavlink_finalize_message(msg, system_id, component_id, 32, 56);
}
 
/**
* @brief Pack a vicon_position_estimate message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param usec Timestamp (milliseconds)
* @param x Global X position
* @param y Global Y position
* @param z Global Z position
* @param roll Roll angle in rad
* @param pitch Pitch angle in rad
* @param yaw Yaw angle in rad
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_vicon_position_estimate_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint64_t usec,float x,float y,float z,float roll,float pitch,float yaw)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[32];
_mav_put_uint64_t(buf, 0, usec);
_mav_put_float(buf, 8, x);
_mav_put_float(buf, 12, y);
_mav_put_float(buf, 16, z);
_mav_put_float(buf, 20, roll);
_mav_put_float(buf, 24, pitch);
_mav_put_float(buf, 28, yaw);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 32);
#else
mavlink_vicon_position_estimate_t packet;
packet.usec = usec;
packet.x = x;
packet.y = y;
packet.z = z;
packet.roll = roll;
packet.pitch = pitch;
packet.yaw = yaw;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 32);
#endif
 
msg->msgid = MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 32, 56);
}
 
/**
* @brief Encode a vicon_position_estimate struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param vicon_position_estimate C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_vicon_position_estimate_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_vicon_position_estimate_t* vicon_position_estimate)
{
return mavlink_msg_vicon_position_estimate_pack(system_id, component_id, msg, vicon_position_estimate->usec, vicon_position_estimate->x, vicon_position_estimate->y, vicon_position_estimate->z, vicon_position_estimate->roll, vicon_position_estimate->pitch, vicon_position_estimate->yaw);
}
 
/**
* @brief Send a vicon_position_estimate message
* @param chan MAVLink channel to send the message
*
* @param usec Timestamp (milliseconds)
* @param x Global X position
* @param y Global Y position
* @param z Global Z position
* @param roll Roll angle in rad
* @param pitch Pitch angle in rad
* @param yaw Yaw angle in rad
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_vicon_position_estimate_send(mavlink_channel_t chan, uint64_t usec, float x, float y, float z, float roll, float pitch, float yaw)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[32];
_mav_put_uint64_t(buf, 0, usec);
_mav_put_float(buf, 8, x);
_mav_put_float(buf, 12, y);
_mav_put_float(buf, 16, z);
_mav_put_float(buf, 20, roll);
_mav_put_float(buf, 24, pitch);
_mav_put_float(buf, 28, yaw);
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE, buf, 32, 56);
#else
mavlink_vicon_position_estimate_t packet;
packet.usec = usec;
packet.x = x;
packet.y = y;
packet.z = z;
packet.roll = roll;
packet.pitch = pitch;
packet.yaw = yaw;
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE, (const char *)&packet, 32, 56);
#endif
}
 
#endif
 
// MESSAGE VICON_POSITION_ESTIMATE UNPACKING
 
 
/**
* @brief Get field usec from vicon_position_estimate message
*
* @return Timestamp (milliseconds)
*/
static inline uint64_t mavlink_msg_vicon_position_estimate_get_usec(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint64_t(msg, 0);
}
 
/**
* @brief Get field x from vicon_position_estimate message
*
* @return Global X position
*/
static inline float mavlink_msg_vicon_position_estimate_get_x(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 8);
}
 
/**
* @brief Get field y from vicon_position_estimate message
*
* @return Global Y position
*/
static inline float mavlink_msg_vicon_position_estimate_get_y(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 12);
}
 
/**
* @brief Get field z from vicon_position_estimate message
*
* @return Global Z position
*/
static inline float mavlink_msg_vicon_position_estimate_get_z(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 16);
}
 
/**
* @brief Get field roll from vicon_position_estimate message
*
* @return Roll angle in rad
*/
static inline float mavlink_msg_vicon_position_estimate_get_roll(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 20);
}
 
/**
* @brief Get field pitch from vicon_position_estimate message
*
* @return Pitch angle in rad
*/
static inline float mavlink_msg_vicon_position_estimate_get_pitch(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 24);
}
 
/**
* @brief Get field yaw from vicon_position_estimate message
*
* @return Yaw angle in rad
*/
static inline float mavlink_msg_vicon_position_estimate_get_yaw(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 28);
}
 
/**
* @brief Decode a vicon_position_estimate message into a struct
*
* @param msg The message to decode
* @param vicon_position_estimate C-struct to decode the message contents into
*/
static inline void mavlink_msg_vicon_position_estimate_decode(const mavlink_message_t* msg, mavlink_vicon_position_estimate_t* vicon_position_estimate)
{
#if MAVLINK_NEED_BYTE_SWAP
vicon_position_estimate->usec = mavlink_msg_vicon_position_estimate_get_usec(msg);
vicon_position_estimate->x = mavlink_msg_vicon_position_estimate_get_x(msg);
vicon_position_estimate->y = mavlink_msg_vicon_position_estimate_get_y(msg);
vicon_position_estimate->z = mavlink_msg_vicon_position_estimate_get_z(msg);
vicon_position_estimate->roll = mavlink_msg_vicon_position_estimate_get_roll(msg);
vicon_position_estimate->pitch = mavlink_msg_vicon_position_estimate_get_pitch(msg);
vicon_position_estimate->yaw = mavlink_msg_vicon_position_estimate_get_yaw(msg);
#else
memcpy(vicon_position_estimate, _MAV_PAYLOAD(msg), 32);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v1.0/common/mavlink_msg_vision_position_estimate.h
0,0 → 1,276
// MESSAGE VISION_POSITION_ESTIMATE PACKING
 
#define MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE 102
 
typedef struct __mavlink_vision_position_estimate_t
{
uint64_t usec; ///< Timestamp (milliseconds)
float x; ///< Global X position
float y; ///< Global Y position
float z; ///< Global Z position
float roll; ///< Roll angle in rad
float pitch; ///< Pitch angle in rad
float yaw; ///< Yaw angle in rad
} mavlink_vision_position_estimate_t;
 
#define MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE_LEN 32
#define MAVLINK_MSG_ID_102_LEN 32
 
 
 
#define MAVLINK_MESSAGE_INFO_VISION_POSITION_ESTIMATE { \
"VISION_POSITION_ESTIMATE", \
7, \
{ { "usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_vision_position_estimate_t, usec) }, \
{ "x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_vision_position_estimate_t, x) }, \
{ "y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_vision_position_estimate_t, y) }, \
{ "z", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_vision_position_estimate_t, z) }, \
{ "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_vision_position_estimate_t, roll) }, \
{ "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_vision_position_estimate_t, pitch) }, \
{ "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_vision_position_estimate_t, yaw) }, \
} \
}
 
 
/**
* @brief Pack a vision_position_estimate message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param usec Timestamp (milliseconds)
* @param x Global X position
* @param y Global Y position
* @param z Global Z position
* @param roll Roll angle in rad
* @param pitch Pitch angle in rad
* @param yaw Yaw angle in rad
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_vision_position_estimate_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint64_t usec, float x, float y, float z, float roll, float pitch, float yaw)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[32];
_mav_put_uint64_t(buf, 0, usec);
_mav_put_float(buf, 8, x);
_mav_put_float(buf, 12, y);
_mav_put_float(buf, 16, z);
_mav_put_float(buf, 20, roll);
_mav_put_float(buf, 24, pitch);
_mav_put_float(buf, 28, yaw);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 32);
#else
mavlink_vision_position_estimate_t packet;
packet.usec = usec;
packet.x = x;
packet.y = y;
packet.z = z;
packet.roll = roll;
packet.pitch = pitch;
packet.yaw = yaw;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 32);
#endif
 
msg->msgid = MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE;
return mavlink_finalize_message(msg, system_id, component_id, 32, 158);
}
 
/**
* @brief Pack a vision_position_estimate message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param usec Timestamp (milliseconds)
* @param x Global X position
* @param y Global Y position
* @param z Global Z position
* @param roll Roll angle in rad
* @param pitch Pitch angle in rad
* @param yaw Yaw angle in rad
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_vision_position_estimate_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint64_t usec,float x,float y,float z,float roll,float pitch,float yaw)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[32];
_mav_put_uint64_t(buf, 0, usec);
_mav_put_float(buf, 8, x);
_mav_put_float(buf, 12, y);
_mav_put_float(buf, 16, z);
_mav_put_float(buf, 20, roll);
_mav_put_float(buf, 24, pitch);
_mav_put_float(buf, 28, yaw);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 32);
#else
mavlink_vision_position_estimate_t packet;
packet.usec = usec;
packet.x = x;
packet.y = y;
packet.z = z;
packet.roll = roll;
packet.pitch = pitch;
packet.yaw = yaw;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 32);
#endif
 
msg->msgid = MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 32, 158);
}
 
/**
* @brief Encode a vision_position_estimate struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param vision_position_estimate C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_vision_position_estimate_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_vision_position_estimate_t* vision_position_estimate)
{
return mavlink_msg_vision_position_estimate_pack(system_id, component_id, msg, vision_position_estimate->usec, vision_position_estimate->x, vision_position_estimate->y, vision_position_estimate->z, vision_position_estimate->roll, vision_position_estimate->pitch, vision_position_estimate->yaw);
}
 
/**
* @brief Send a vision_position_estimate message
* @param chan MAVLink channel to send the message
*
* @param usec Timestamp (milliseconds)
* @param x Global X position
* @param y Global Y position
* @param z Global Z position
* @param roll Roll angle in rad
* @param pitch Pitch angle in rad
* @param yaw Yaw angle in rad
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_vision_position_estimate_send(mavlink_channel_t chan, uint64_t usec, float x, float y, float z, float roll, float pitch, float yaw)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[32];
_mav_put_uint64_t(buf, 0, usec);
_mav_put_float(buf, 8, x);
_mav_put_float(buf, 12, y);
_mav_put_float(buf, 16, z);
_mav_put_float(buf, 20, roll);
_mav_put_float(buf, 24, pitch);
_mav_put_float(buf, 28, yaw);
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE, buf, 32, 158);
#else
mavlink_vision_position_estimate_t packet;
packet.usec = usec;
packet.x = x;
packet.y = y;
packet.z = z;
packet.roll = roll;
packet.pitch = pitch;
packet.yaw = yaw;
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VISION_POSITION_ESTIMATE, (const char *)&packet, 32, 158);
#endif
}
 
#endif
 
// MESSAGE VISION_POSITION_ESTIMATE UNPACKING
 
 
/**
* @brief Get field usec from vision_position_estimate message
*
* @return Timestamp (milliseconds)
*/
static inline uint64_t mavlink_msg_vision_position_estimate_get_usec(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint64_t(msg, 0);
}
 
/**
* @brief Get field x from vision_position_estimate message
*
* @return Global X position
*/
static inline float mavlink_msg_vision_position_estimate_get_x(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 8);
}
 
/**
* @brief Get field y from vision_position_estimate message
*
* @return Global Y position
*/
static inline float mavlink_msg_vision_position_estimate_get_y(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 12);
}
 
/**
* @brief Get field z from vision_position_estimate message
*
* @return Global Z position
*/
static inline float mavlink_msg_vision_position_estimate_get_z(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 16);
}
 
/**
* @brief Get field roll from vision_position_estimate message
*
* @return Roll angle in rad
*/
static inline float mavlink_msg_vision_position_estimate_get_roll(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 20);
}
 
/**
* @brief Get field pitch from vision_position_estimate message
*
* @return Pitch angle in rad
*/
static inline float mavlink_msg_vision_position_estimate_get_pitch(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 24);
}
 
/**
* @brief Get field yaw from vision_position_estimate message
*
* @return Yaw angle in rad
*/
static inline float mavlink_msg_vision_position_estimate_get_yaw(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 28);
}
 
/**
* @brief Decode a vision_position_estimate message into a struct
*
* @param msg The message to decode
* @param vision_position_estimate C-struct to decode the message contents into
*/
static inline void mavlink_msg_vision_position_estimate_decode(const mavlink_message_t* msg, mavlink_vision_position_estimate_t* vision_position_estimate)
{
#if MAVLINK_NEED_BYTE_SWAP
vision_position_estimate->usec = mavlink_msg_vision_position_estimate_get_usec(msg);
vision_position_estimate->x = mavlink_msg_vision_position_estimate_get_x(msg);
vision_position_estimate->y = mavlink_msg_vision_position_estimate_get_y(msg);
vision_position_estimate->z = mavlink_msg_vision_position_estimate_get_z(msg);
vision_position_estimate->roll = mavlink_msg_vision_position_estimate_get_roll(msg);
vision_position_estimate->pitch = mavlink_msg_vision_position_estimate_get_pitch(msg);
vision_position_estimate->yaw = mavlink_msg_vision_position_estimate_get_yaw(msg);
#else
memcpy(vision_position_estimate, _MAV_PAYLOAD(msg), 32);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v1.0/common/mavlink_msg_vision_speed_estimate.h
0,0 → 1,210
// MESSAGE VISION_SPEED_ESTIMATE PACKING
 
#define MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE 103
 
typedef struct __mavlink_vision_speed_estimate_t
{
uint64_t usec; ///< Timestamp (milliseconds)
float x; ///< Global X speed
float y; ///< Global Y speed
float z; ///< Global Z speed
} mavlink_vision_speed_estimate_t;
 
#define MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE_LEN 20
#define MAVLINK_MSG_ID_103_LEN 20
 
 
 
#define MAVLINK_MESSAGE_INFO_VISION_SPEED_ESTIMATE { \
"VISION_SPEED_ESTIMATE", \
4, \
{ { "usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_vision_speed_estimate_t, usec) }, \
{ "x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_vision_speed_estimate_t, x) }, \
{ "y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_vision_speed_estimate_t, y) }, \
{ "z", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_vision_speed_estimate_t, z) }, \
} \
}
 
 
/**
* @brief Pack a vision_speed_estimate message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param usec Timestamp (milliseconds)
* @param x Global X speed
* @param y Global Y speed
* @param z Global Z speed
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_vision_speed_estimate_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint64_t usec, float x, float y, float z)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[20];
_mav_put_uint64_t(buf, 0, usec);
_mav_put_float(buf, 8, x);
_mav_put_float(buf, 12, y);
_mav_put_float(buf, 16, z);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 20);
#else
mavlink_vision_speed_estimate_t packet;
packet.usec = usec;
packet.x = x;
packet.y = y;
packet.z = z;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 20);
#endif
 
msg->msgid = MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE;
return mavlink_finalize_message(msg, system_id, component_id, 20, 208);
}
 
/**
* @brief Pack a vision_speed_estimate message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param usec Timestamp (milliseconds)
* @param x Global X speed
* @param y Global Y speed
* @param z Global Z speed
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_vision_speed_estimate_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint64_t usec,float x,float y,float z)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[20];
_mav_put_uint64_t(buf, 0, usec);
_mav_put_float(buf, 8, x);
_mav_put_float(buf, 12, y);
_mav_put_float(buf, 16, z);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 20);
#else
mavlink_vision_speed_estimate_t packet;
packet.usec = usec;
packet.x = x;
packet.y = y;
packet.z = z;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 20);
#endif
 
msg->msgid = MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 20, 208);
}
 
/**
* @brief Encode a vision_speed_estimate struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param vision_speed_estimate C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_vision_speed_estimate_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_vision_speed_estimate_t* vision_speed_estimate)
{
return mavlink_msg_vision_speed_estimate_pack(system_id, component_id, msg, vision_speed_estimate->usec, vision_speed_estimate->x, vision_speed_estimate->y, vision_speed_estimate->z);
}
 
/**
* @brief Send a vision_speed_estimate message
* @param chan MAVLink channel to send the message
*
* @param usec Timestamp (milliseconds)
* @param x Global X speed
* @param y Global Y speed
* @param z Global Z speed
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_vision_speed_estimate_send(mavlink_channel_t chan, uint64_t usec, float x, float y, float z)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[20];
_mav_put_uint64_t(buf, 0, usec);
_mav_put_float(buf, 8, x);
_mav_put_float(buf, 12, y);
_mav_put_float(buf, 16, z);
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE, buf, 20, 208);
#else
mavlink_vision_speed_estimate_t packet;
packet.usec = usec;
packet.x = x;
packet.y = y;
packet.z = z;
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_VISION_SPEED_ESTIMATE, (const char *)&packet, 20, 208);
#endif
}
 
#endif
 
// MESSAGE VISION_SPEED_ESTIMATE UNPACKING
 
 
/**
* @brief Get field usec from vision_speed_estimate message
*
* @return Timestamp (milliseconds)
*/
static inline uint64_t mavlink_msg_vision_speed_estimate_get_usec(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint64_t(msg, 0);
}
 
/**
* @brief Get field x from vision_speed_estimate message
*
* @return Global X speed
*/
static inline float mavlink_msg_vision_speed_estimate_get_x(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 8);
}
 
/**
* @brief Get field y from vision_speed_estimate message
*
* @return Global Y speed
*/
static inline float mavlink_msg_vision_speed_estimate_get_y(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 12);
}
 
/**
* @brief Get field z from vision_speed_estimate message
*
* @return Global Z speed
*/
static inline float mavlink_msg_vision_speed_estimate_get_z(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 16);
}
 
/**
* @brief Decode a vision_speed_estimate message into a struct
*
* @param msg The message to decode
* @param vision_speed_estimate C-struct to decode the message contents into
*/
static inline void mavlink_msg_vision_speed_estimate_decode(const mavlink_message_t* msg, mavlink_vision_speed_estimate_t* vision_speed_estimate)
{
#if MAVLINK_NEED_BYTE_SWAP
vision_speed_estimate->usec = mavlink_msg_vision_speed_estimate_get_usec(msg);
vision_speed_estimate->x = mavlink_msg_vision_speed_estimate_get_x(msg);
vision_speed_estimate->y = mavlink_msg_vision_speed_estimate_get_y(msg);
vision_speed_estimate->z = mavlink_msg_vision_speed_estimate_get_z(msg);
#else
memcpy(vision_speed_estimate, _MAV_PAYLOAD(msg), 20);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v1.0/common/testsuite.h
0,0 → 1,4024
/** @file
* @brief MAVLink comm protocol testsuite generated from common.xml
* @see http://qgroundcontrol.org/mavlink/
*/
#ifndef COMMON_TESTSUITE_H
#define COMMON_TESTSUITE_H
 
#ifdef __cplusplus
extern "C" {
#endif
 
#ifndef MAVLINK_TEST_ALL
#define MAVLINK_TEST_ALL
 
static void mavlink_test_common(uint8_t, uint8_t, mavlink_message_t *last_msg);
 
static void mavlink_test_all(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
 
mavlink_test_common(system_id, component_id, last_msg);
}
#endif
 
 
 
 
static void mavlink_test_heartbeat(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_heartbeat_t packet_in = {
963497464,
17,
84,
151,
218,
3,
};
mavlink_heartbeat_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.custom_mode = packet_in.custom_mode;
packet1.type = packet_in.type;
packet1.autopilot = packet_in.autopilot;
packet1.base_mode = packet_in.base_mode;
packet1.system_status = packet_in.system_status;
packet1.mavlink_version = packet_in.mavlink_version;
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_heartbeat_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_heartbeat_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_heartbeat_pack(system_id, component_id, &msg , packet1.type , packet1.autopilot , packet1.base_mode , packet1.custom_mode , packet1.system_status );
mavlink_msg_heartbeat_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_heartbeat_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.type , packet1.autopilot , packet1.base_mode , packet1.custom_mode , packet1.system_status );
mavlink_msg_heartbeat_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_heartbeat_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_heartbeat_send(MAVLINK_COMM_1 , packet1.type , packet1.autopilot , packet1.base_mode , packet1.custom_mode , packet1.system_status );
mavlink_msg_heartbeat_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_sys_status(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_sys_status_t packet_in = {
963497464,
963497672,
963497880,
17859,
17963,
18067,
18171,
18275,
18379,
18483,
18587,
18691,
223,
};
mavlink_sys_status_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.onboard_control_sensors_present = packet_in.onboard_control_sensors_present;
packet1.onboard_control_sensors_enabled = packet_in.onboard_control_sensors_enabled;
packet1.onboard_control_sensors_health = packet_in.onboard_control_sensors_health;
packet1.load = packet_in.load;
packet1.voltage_battery = packet_in.voltage_battery;
packet1.current_battery = packet_in.current_battery;
packet1.drop_rate_comm = packet_in.drop_rate_comm;
packet1.errors_comm = packet_in.errors_comm;
packet1.errors_count1 = packet_in.errors_count1;
packet1.errors_count2 = packet_in.errors_count2;
packet1.errors_count3 = packet_in.errors_count3;
packet1.errors_count4 = packet_in.errors_count4;
packet1.battery_remaining = packet_in.battery_remaining;
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_sys_status_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_sys_status_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_sys_status_pack(system_id, component_id, &msg , packet1.onboard_control_sensors_present , packet1.onboard_control_sensors_enabled , packet1.onboard_control_sensors_health , packet1.load , packet1.voltage_battery , packet1.current_battery , packet1.battery_remaining , packet1.drop_rate_comm , packet1.errors_comm , packet1.errors_count1 , packet1.errors_count2 , packet1.errors_count3 , packet1.errors_count4 );
mavlink_msg_sys_status_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_sys_status_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.onboard_control_sensors_present , packet1.onboard_control_sensors_enabled , packet1.onboard_control_sensors_health , packet1.load , packet1.voltage_battery , packet1.current_battery , packet1.battery_remaining , packet1.drop_rate_comm , packet1.errors_comm , packet1.errors_count1 , packet1.errors_count2 , packet1.errors_count3 , packet1.errors_count4 );
mavlink_msg_sys_status_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_sys_status_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_sys_status_send(MAVLINK_COMM_1 , packet1.onboard_control_sensors_present , packet1.onboard_control_sensors_enabled , packet1.onboard_control_sensors_health , packet1.load , packet1.voltage_battery , packet1.current_battery , packet1.battery_remaining , packet1.drop_rate_comm , packet1.errors_comm , packet1.errors_count1 , packet1.errors_count2 , packet1.errors_count3 , packet1.errors_count4 );
mavlink_msg_sys_status_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_system_time(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_system_time_t packet_in = {
93372036854775807ULL,
963497880,
};
mavlink_system_time_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.time_unix_usec = packet_in.time_unix_usec;
packet1.time_boot_ms = packet_in.time_boot_ms;
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_system_time_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_system_time_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_system_time_pack(system_id, component_id, &msg , packet1.time_unix_usec , packet1.time_boot_ms );
mavlink_msg_system_time_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_system_time_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_unix_usec , packet1.time_boot_ms );
mavlink_msg_system_time_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_system_time_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_system_time_send(MAVLINK_COMM_1 , packet1.time_unix_usec , packet1.time_boot_ms );
mavlink_msg_system_time_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_ping(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_ping_t packet_in = {
93372036854775807ULL,
963497880,
41,
108,
};
mavlink_ping_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.time_usec = packet_in.time_usec;
packet1.seq = packet_in.seq;
packet1.target_system = packet_in.target_system;
packet1.target_component = packet_in.target_component;
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_ping_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_ping_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_ping_pack(system_id, component_id, &msg , packet1.time_usec , packet1.seq , packet1.target_system , packet1.target_component );
mavlink_msg_ping_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_ping_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_usec , packet1.seq , packet1.target_system , packet1.target_component );
mavlink_msg_ping_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_ping_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_ping_send(MAVLINK_COMM_1 , packet1.time_usec , packet1.seq , packet1.target_system , packet1.target_component );
mavlink_msg_ping_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_change_operator_control(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_change_operator_control_t packet_in = {
5,
72,
139,
"DEFGHIJKLMNOPQRSTUVWXYZA",
};
mavlink_change_operator_control_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.target_system = packet_in.target_system;
packet1.control_request = packet_in.control_request;
packet1.version = packet_in.version;
mav_array_memcpy(packet1.passkey, packet_in.passkey, sizeof(char)*25);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_change_operator_control_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_change_operator_control_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_change_operator_control_pack(system_id, component_id, &msg , packet1.target_system , packet1.control_request , packet1.version , packet1.passkey );
mavlink_msg_change_operator_control_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_change_operator_control_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.control_request , packet1.version , packet1.passkey );
mavlink_msg_change_operator_control_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_change_operator_control_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_change_operator_control_send(MAVLINK_COMM_1 , packet1.target_system , packet1.control_request , packet1.version , packet1.passkey );
mavlink_msg_change_operator_control_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_change_operator_control_ack(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_change_operator_control_ack_t packet_in = {
5,
72,
139,
};
mavlink_change_operator_control_ack_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.gcs_system_id = packet_in.gcs_system_id;
packet1.control_request = packet_in.control_request;
packet1.ack = packet_in.ack;
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_change_operator_control_ack_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_change_operator_control_ack_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_change_operator_control_ack_pack(system_id, component_id, &msg , packet1.gcs_system_id , packet1.control_request , packet1.ack );
mavlink_msg_change_operator_control_ack_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_change_operator_control_ack_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.gcs_system_id , packet1.control_request , packet1.ack );
mavlink_msg_change_operator_control_ack_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_change_operator_control_ack_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_change_operator_control_ack_send(MAVLINK_COMM_1 , packet1.gcs_system_id , packet1.control_request , packet1.ack );
mavlink_msg_change_operator_control_ack_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_auth_key(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_auth_key_t packet_in = {
"ABCDEFGHIJKLMNOPQRSTUVWXYZABCDE",
};
mavlink_auth_key_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
mav_array_memcpy(packet1.key, packet_in.key, sizeof(char)*32);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_auth_key_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_auth_key_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_auth_key_pack(system_id, component_id, &msg , packet1.key );
mavlink_msg_auth_key_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_auth_key_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.key );
mavlink_msg_auth_key_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_auth_key_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_auth_key_send(MAVLINK_COMM_1 , packet1.key );
mavlink_msg_auth_key_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_set_mode(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_set_mode_t packet_in = {
963497464,
17,
84,
};
mavlink_set_mode_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.custom_mode = packet_in.custom_mode;
packet1.target_system = packet_in.target_system;
packet1.base_mode = packet_in.base_mode;
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_set_mode_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_set_mode_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_set_mode_pack(system_id, component_id, &msg , packet1.target_system , packet1.base_mode , packet1.custom_mode );
mavlink_msg_set_mode_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_set_mode_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.base_mode , packet1.custom_mode );
mavlink_msg_set_mode_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_set_mode_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_set_mode_send(MAVLINK_COMM_1 , packet1.target_system , packet1.base_mode , packet1.custom_mode );
mavlink_msg_set_mode_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_param_request_read(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_param_request_read_t packet_in = {
17235,
139,
206,
"EFGHIJKLMNOPQRS",
};
mavlink_param_request_read_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.param_index = packet_in.param_index;
packet1.target_system = packet_in.target_system;
packet1.target_component = packet_in.target_component;
mav_array_memcpy(packet1.param_id, packet_in.param_id, sizeof(char)*16);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_param_request_read_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_param_request_read_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_param_request_read_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.param_id , packet1.param_index );
mavlink_msg_param_request_read_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_param_request_read_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.param_id , packet1.param_index );
mavlink_msg_param_request_read_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_param_request_read_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_param_request_read_send(MAVLINK_COMM_1 , packet1.target_system , packet1.target_component , packet1.param_id , packet1.param_index );
mavlink_msg_param_request_read_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_param_request_list(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_param_request_list_t packet_in = {
5,
72,
};
mavlink_param_request_list_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.target_system = packet_in.target_system;
packet1.target_component = packet_in.target_component;
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_param_request_list_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_param_request_list_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_param_request_list_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component );
mavlink_msg_param_request_list_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_param_request_list_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component );
mavlink_msg_param_request_list_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_param_request_list_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_param_request_list_send(MAVLINK_COMM_1 , packet1.target_system , packet1.target_component );
mavlink_msg_param_request_list_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_param_value(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_param_value_t packet_in = {
17.0,
17443,
17547,
"IJKLMNOPQRSTUVW",
77,
};
mavlink_param_value_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.param_value = packet_in.param_value;
packet1.param_count = packet_in.param_count;
packet1.param_index = packet_in.param_index;
packet1.param_type = packet_in.param_type;
mav_array_memcpy(packet1.param_id, packet_in.param_id, sizeof(char)*16);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_param_value_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_param_value_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_param_value_pack(system_id, component_id, &msg , packet1.param_id , packet1.param_value , packet1.param_type , packet1.param_count , packet1.param_index );
mavlink_msg_param_value_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_param_value_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.param_id , packet1.param_value , packet1.param_type , packet1.param_count , packet1.param_index );
mavlink_msg_param_value_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_param_value_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_param_value_send(MAVLINK_COMM_1 , packet1.param_id , packet1.param_value , packet1.param_type , packet1.param_count , packet1.param_index );
mavlink_msg_param_value_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_param_set(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_param_set_t packet_in = {
17.0,
17,
84,
"GHIJKLMNOPQRSTU",
199,
};
mavlink_param_set_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.param_value = packet_in.param_value;
packet1.target_system = packet_in.target_system;
packet1.target_component = packet_in.target_component;
packet1.param_type = packet_in.param_type;
mav_array_memcpy(packet1.param_id, packet_in.param_id, sizeof(char)*16);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_param_set_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_param_set_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_param_set_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.param_id , packet1.param_value , packet1.param_type );
mavlink_msg_param_set_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_param_set_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.param_id , packet1.param_value , packet1.param_type );
mavlink_msg_param_set_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_param_set_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_param_set_send(MAVLINK_COMM_1 , packet1.target_system , packet1.target_component , packet1.param_id , packet1.param_value , packet1.param_type );
mavlink_msg_param_set_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_gps_raw_int(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_gps_raw_int_t packet_in = {
93372036854775807ULL,
963497880,
963498088,
963498296,
18275,
18379,
18483,
18587,
89,
156,
};
mavlink_gps_raw_int_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.time_usec = packet_in.time_usec;
packet1.lat = packet_in.lat;
packet1.lon = packet_in.lon;
packet1.alt = packet_in.alt;
packet1.eph = packet_in.eph;
packet1.epv = packet_in.epv;
packet1.vel = packet_in.vel;
packet1.cog = packet_in.cog;
packet1.fix_type = packet_in.fix_type;
packet1.satellites_visible = packet_in.satellites_visible;
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_gps_raw_int_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_gps_raw_int_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_gps_raw_int_pack(system_id, component_id, &msg , packet1.time_usec , packet1.fix_type , packet1.lat , packet1.lon , packet1.alt , packet1.eph , packet1.epv , packet1.vel , packet1.cog , packet1.satellites_visible );
mavlink_msg_gps_raw_int_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_gps_raw_int_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_usec , packet1.fix_type , packet1.lat , packet1.lon , packet1.alt , packet1.eph , packet1.epv , packet1.vel , packet1.cog , packet1.satellites_visible );
mavlink_msg_gps_raw_int_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_gps_raw_int_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_gps_raw_int_send(MAVLINK_COMM_1 , packet1.time_usec , packet1.fix_type , packet1.lat , packet1.lon , packet1.alt , packet1.eph , packet1.epv , packet1.vel , packet1.cog , packet1.satellites_visible );
mavlink_msg_gps_raw_int_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_gps_status(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_gps_status_t packet_in = {
5,
{ 72, 73, 74, 75, 76, 77, 78, 79, 80, 81, 82, 83, 84, 85, 86, 87, 88, 89, 90, 91 },
{ 132, 133, 134, 135, 136, 137, 138, 139, 140, 141, 142, 143, 144, 145, 146, 147, 148, 149, 150, 151 },
{ 192, 193, 194, 195, 196, 197, 198, 199, 200, 201, 202, 203, 204, 205, 206, 207, 208, 209, 210, 211 },
{ 252, 253, 254, 255, 0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15 },
{ 56, 57, 58, 59, 60, 61, 62, 63, 64, 65, 66, 67, 68, 69, 70, 71, 72, 73, 74, 75 },
};
mavlink_gps_status_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.satellites_visible = packet_in.satellites_visible;
mav_array_memcpy(packet1.satellite_prn, packet_in.satellite_prn, sizeof(uint8_t)*20);
mav_array_memcpy(packet1.satellite_used, packet_in.satellite_used, sizeof(uint8_t)*20);
mav_array_memcpy(packet1.satellite_elevation, packet_in.satellite_elevation, sizeof(uint8_t)*20);
mav_array_memcpy(packet1.satellite_azimuth, packet_in.satellite_azimuth, sizeof(uint8_t)*20);
mav_array_memcpy(packet1.satellite_snr, packet_in.satellite_snr, sizeof(uint8_t)*20);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_gps_status_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_gps_status_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_gps_status_pack(system_id, component_id, &msg , packet1.satellites_visible , packet1.satellite_prn , packet1.satellite_used , packet1.satellite_elevation , packet1.satellite_azimuth , packet1.satellite_snr );
mavlink_msg_gps_status_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_gps_status_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.satellites_visible , packet1.satellite_prn , packet1.satellite_used , packet1.satellite_elevation , packet1.satellite_azimuth , packet1.satellite_snr );
mavlink_msg_gps_status_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_gps_status_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_gps_status_send(MAVLINK_COMM_1 , packet1.satellites_visible , packet1.satellite_prn , packet1.satellite_used , packet1.satellite_elevation , packet1.satellite_azimuth , packet1.satellite_snr );
mavlink_msg_gps_status_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_scaled_imu(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_scaled_imu_t packet_in = {
963497464,
17443,
17547,
17651,
17755,
17859,
17963,
18067,
18171,
18275,
};
mavlink_scaled_imu_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.time_boot_ms = packet_in.time_boot_ms;
packet1.xacc = packet_in.xacc;
packet1.yacc = packet_in.yacc;
packet1.zacc = packet_in.zacc;
packet1.xgyro = packet_in.xgyro;
packet1.ygyro = packet_in.ygyro;
packet1.zgyro = packet_in.zgyro;
packet1.xmag = packet_in.xmag;
packet1.ymag = packet_in.ymag;
packet1.zmag = packet_in.zmag;
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_scaled_imu_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_scaled_imu_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_scaled_imu_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.xacc , packet1.yacc , packet1.zacc , packet1.xgyro , packet1.ygyro , packet1.zgyro , packet1.xmag , packet1.ymag , packet1.zmag );
mavlink_msg_scaled_imu_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_scaled_imu_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.xacc , packet1.yacc , packet1.zacc , packet1.xgyro , packet1.ygyro , packet1.zgyro , packet1.xmag , packet1.ymag , packet1.zmag );
mavlink_msg_scaled_imu_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_scaled_imu_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_scaled_imu_send(MAVLINK_COMM_1 , packet1.time_boot_ms , packet1.xacc , packet1.yacc , packet1.zacc , packet1.xgyro , packet1.ygyro , packet1.zgyro , packet1.xmag , packet1.ymag , packet1.zmag );
mavlink_msg_scaled_imu_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_raw_imu(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_raw_imu_t packet_in = {
93372036854775807ULL,
17651,
17755,
17859,
17963,
18067,
18171,
18275,
18379,
18483,
};
mavlink_raw_imu_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.time_usec = packet_in.time_usec;
packet1.xacc = packet_in.xacc;
packet1.yacc = packet_in.yacc;
packet1.zacc = packet_in.zacc;
packet1.xgyro = packet_in.xgyro;
packet1.ygyro = packet_in.ygyro;
packet1.zgyro = packet_in.zgyro;
packet1.xmag = packet_in.xmag;
packet1.ymag = packet_in.ymag;
packet1.zmag = packet_in.zmag;
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_raw_imu_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_raw_imu_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_raw_imu_pack(system_id, component_id, &msg , packet1.time_usec , packet1.xacc , packet1.yacc , packet1.zacc , packet1.xgyro , packet1.ygyro , packet1.zgyro , packet1.xmag , packet1.ymag , packet1.zmag );
mavlink_msg_raw_imu_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_raw_imu_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_usec , packet1.xacc , packet1.yacc , packet1.zacc , packet1.xgyro , packet1.ygyro , packet1.zgyro , packet1.xmag , packet1.ymag , packet1.zmag );
mavlink_msg_raw_imu_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_raw_imu_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_raw_imu_send(MAVLINK_COMM_1 , packet1.time_usec , packet1.xacc , packet1.yacc , packet1.zacc , packet1.xgyro , packet1.ygyro , packet1.zgyro , packet1.xmag , packet1.ymag , packet1.zmag );
mavlink_msg_raw_imu_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_raw_pressure(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_raw_pressure_t packet_in = {
93372036854775807ULL,
17651,
17755,
17859,
17963,
};
mavlink_raw_pressure_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.time_usec = packet_in.time_usec;
packet1.press_abs = packet_in.press_abs;
packet1.press_diff1 = packet_in.press_diff1;
packet1.press_diff2 = packet_in.press_diff2;
packet1.temperature = packet_in.temperature;
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_raw_pressure_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_raw_pressure_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_raw_pressure_pack(system_id, component_id, &msg , packet1.time_usec , packet1.press_abs , packet1.press_diff1 , packet1.press_diff2 , packet1.temperature );
mavlink_msg_raw_pressure_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_raw_pressure_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_usec , packet1.press_abs , packet1.press_diff1 , packet1.press_diff2 , packet1.temperature );
mavlink_msg_raw_pressure_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_raw_pressure_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_raw_pressure_send(MAVLINK_COMM_1 , packet1.time_usec , packet1.press_abs , packet1.press_diff1 , packet1.press_diff2 , packet1.temperature );
mavlink_msg_raw_pressure_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_scaled_pressure(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_scaled_pressure_t packet_in = {
963497464,
45.0,
73.0,
17859,
};
mavlink_scaled_pressure_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.time_boot_ms = packet_in.time_boot_ms;
packet1.press_abs = packet_in.press_abs;
packet1.press_diff = packet_in.press_diff;
packet1.temperature = packet_in.temperature;
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_scaled_pressure_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_scaled_pressure_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_scaled_pressure_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.press_abs , packet1.press_diff , packet1.temperature );
mavlink_msg_scaled_pressure_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_scaled_pressure_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.press_abs , packet1.press_diff , packet1.temperature );
mavlink_msg_scaled_pressure_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_scaled_pressure_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_scaled_pressure_send(MAVLINK_COMM_1 , packet1.time_boot_ms , packet1.press_abs , packet1.press_diff , packet1.temperature );
mavlink_msg_scaled_pressure_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_attitude(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_attitude_t packet_in = {
963497464,
45.0,
73.0,
101.0,
129.0,
157.0,
185.0,
};
mavlink_attitude_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.time_boot_ms = packet_in.time_boot_ms;
packet1.roll = packet_in.roll;
packet1.pitch = packet_in.pitch;
packet1.yaw = packet_in.yaw;
packet1.rollspeed = packet_in.rollspeed;
packet1.pitchspeed = packet_in.pitchspeed;
packet1.yawspeed = packet_in.yawspeed;
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_attitude_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_attitude_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_attitude_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.roll , packet1.pitch , packet1.yaw , packet1.rollspeed , packet1.pitchspeed , packet1.yawspeed );
mavlink_msg_attitude_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_attitude_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.roll , packet1.pitch , packet1.yaw , packet1.rollspeed , packet1.pitchspeed , packet1.yawspeed );
mavlink_msg_attitude_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_attitude_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_attitude_send(MAVLINK_COMM_1 , packet1.time_boot_ms , packet1.roll , packet1.pitch , packet1.yaw , packet1.rollspeed , packet1.pitchspeed , packet1.yawspeed );
mavlink_msg_attitude_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_attitude_quaternion(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_attitude_quaternion_t packet_in = {
963497464,
45.0,
73.0,
101.0,
129.0,
157.0,
185.0,
213.0,
};
mavlink_attitude_quaternion_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.time_boot_ms = packet_in.time_boot_ms;
packet1.q1 = packet_in.q1;
packet1.q2 = packet_in.q2;
packet1.q3 = packet_in.q3;
packet1.q4 = packet_in.q4;
packet1.rollspeed = packet_in.rollspeed;
packet1.pitchspeed = packet_in.pitchspeed;
packet1.yawspeed = packet_in.yawspeed;
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_attitude_quaternion_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_attitude_quaternion_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_attitude_quaternion_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.q1 , packet1.q2 , packet1.q3 , packet1.q4 , packet1.rollspeed , packet1.pitchspeed , packet1.yawspeed );
mavlink_msg_attitude_quaternion_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_attitude_quaternion_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.q1 , packet1.q2 , packet1.q3 , packet1.q4 , packet1.rollspeed , packet1.pitchspeed , packet1.yawspeed );
mavlink_msg_attitude_quaternion_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_attitude_quaternion_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_attitude_quaternion_send(MAVLINK_COMM_1 , packet1.time_boot_ms , packet1.q1 , packet1.q2 , packet1.q3 , packet1.q4 , packet1.rollspeed , packet1.pitchspeed , packet1.yawspeed );
mavlink_msg_attitude_quaternion_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_local_position_ned(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_local_position_ned_t packet_in = {
963497464,
45.0,
73.0,
101.0,
129.0,
157.0,
185.0,
};
mavlink_local_position_ned_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.time_boot_ms = packet_in.time_boot_ms;
packet1.x = packet_in.x;
packet1.y = packet_in.y;
packet1.z = packet_in.z;
packet1.vx = packet_in.vx;
packet1.vy = packet_in.vy;
packet1.vz = packet_in.vz;
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_local_position_ned_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_local_position_ned_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_local_position_ned_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.x , packet1.y , packet1.z , packet1.vx , packet1.vy , packet1.vz );
mavlink_msg_local_position_ned_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_local_position_ned_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.x , packet1.y , packet1.z , packet1.vx , packet1.vy , packet1.vz );
mavlink_msg_local_position_ned_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_local_position_ned_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_local_position_ned_send(MAVLINK_COMM_1 , packet1.time_boot_ms , packet1.x , packet1.y , packet1.z , packet1.vx , packet1.vy , packet1.vz );
mavlink_msg_local_position_ned_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_global_position_int(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_global_position_int_t packet_in = {
963497464,
963497672,
963497880,
963498088,
963498296,
18275,
18379,
18483,
18587,
};
mavlink_global_position_int_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.time_boot_ms = packet_in.time_boot_ms;
packet1.lat = packet_in.lat;
packet1.lon = packet_in.lon;
packet1.alt = packet_in.alt;
packet1.relative_alt = packet_in.relative_alt;
packet1.vx = packet_in.vx;
packet1.vy = packet_in.vy;
packet1.vz = packet_in.vz;
packet1.hdg = packet_in.hdg;
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_global_position_int_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_global_position_int_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_global_position_int_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.lat , packet1.lon , packet1.alt , packet1.relative_alt , packet1.vx , packet1.vy , packet1.vz , packet1.hdg );
mavlink_msg_global_position_int_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_global_position_int_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.lat , packet1.lon , packet1.alt , packet1.relative_alt , packet1.vx , packet1.vy , packet1.vz , packet1.hdg );
mavlink_msg_global_position_int_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_global_position_int_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_global_position_int_send(MAVLINK_COMM_1 , packet1.time_boot_ms , packet1.lat , packet1.lon , packet1.alt , packet1.relative_alt , packet1.vx , packet1.vy , packet1.vz , packet1.hdg );
mavlink_msg_global_position_int_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_rc_channels_scaled(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_rc_channels_scaled_t packet_in = {
963497464,
17443,
17547,
17651,
17755,
17859,
17963,
18067,
18171,
65,
132,
};
mavlink_rc_channels_scaled_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.time_boot_ms = packet_in.time_boot_ms;
packet1.chan1_scaled = packet_in.chan1_scaled;
packet1.chan2_scaled = packet_in.chan2_scaled;
packet1.chan3_scaled = packet_in.chan3_scaled;
packet1.chan4_scaled = packet_in.chan4_scaled;
packet1.chan5_scaled = packet_in.chan5_scaled;
packet1.chan6_scaled = packet_in.chan6_scaled;
packet1.chan7_scaled = packet_in.chan7_scaled;
packet1.chan8_scaled = packet_in.chan8_scaled;
packet1.port = packet_in.port;
packet1.rssi = packet_in.rssi;
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_rc_channels_scaled_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_rc_channels_scaled_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_rc_channels_scaled_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.port , packet1.chan1_scaled , packet1.chan2_scaled , packet1.chan3_scaled , packet1.chan4_scaled , packet1.chan5_scaled , packet1.chan6_scaled , packet1.chan7_scaled , packet1.chan8_scaled , packet1.rssi );
mavlink_msg_rc_channels_scaled_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_rc_channels_scaled_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.port , packet1.chan1_scaled , packet1.chan2_scaled , packet1.chan3_scaled , packet1.chan4_scaled , packet1.chan5_scaled , packet1.chan6_scaled , packet1.chan7_scaled , packet1.chan8_scaled , packet1.rssi );
mavlink_msg_rc_channels_scaled_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_rc_channels_scaled_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_rc_channels_scaled_send(MAVLINK_COMM_1 , packet1.time_boot_ms , packet1.port , packet1.chan1_scaled , packet1.chan2_scaled , packet1.chan3_scaled , packet1.chan4_scaled , packet1.chan5_scaled , packet1.chan6_scaled , packet1.chan7_scaled , packet1.chan8_scaled , packet1.rssi );
mavlink_msg_rc_channels_scaled_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_rc_channels_raw(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_rc_channels_raw_t packet_in = {
963497464,
17443,
17547,
17651,
17755,
17859,
17963,
18067,
18171,
65,
132,
};
mavlink_rc_channels_raw_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.time_boot_ms = packet_in.time_boot_ms;
packet1.chan1_raw = packet_in.chan1_raw;
packet1.chan2_raw = packet_in.chan2_raw;
packet1.chan3_raw = packet_in.chan3_raw;
packet1.chan4_raw = packet_in.chan4_raw;
packet1.chan5_raw = packet_in.chan5_raw;
packet1.chan6_raw = packet_in.chan6_raw;
packet1.chan7_raw = packet_in.chan7_raw;
packet1.chan8_raw = packet_in.chan8_raw;
packet1.port = packet_in.port;
packet1.rssi = packet_in.rssi;
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_rc_channels_raw_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_rc_channels_raw_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_rc_channels_raw_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.port , packet1.chan1_raw , packet1.chan2_raw , packet1.chan3_raw , packet1.chan4_raw , packet1.chan5_raw , packet1.chan6_raw , packet1.chan7_raw , packet1.chan8_raw , packet1.rssi );
mavlink_msg_rc_channels_raw_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_rc_channels_raw_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.port , packet1.chan1_raw , packet1.chan2_raw , packet1.chan3_raw , packet1.chan4_raw , packet1.chan5_raw , packet1.chan6_raw , packet1.chan7_raw , packet1.chan8_raw , packet1.rssi );
mavlink_msg_rc_channels_raw_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_rc_channels_raw_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_rc_channels_raw_send(MAVLINK_COMM_1 , packet1.time_boot_ms , packet1.port , packet1.chan1_raw , packet1.chan2_raw , packet1.chan3_raw , packet1.chan4_raw , packet1.chan5_raw , packet1.chan6_raw , packet1.chan7_raw , packet1.chan8_raw , packet1.rssi );
mavlink_msg_rc_channels_raw_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_servo_output_raw(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_servo_output_raw_t packet_in = {
963497464,
17443,
17547,
17651,
17755,
17859,
17963,
18067,
18171,
65,
};
mavlink_servo_output_raw_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.time_usec = packet_in.time_usec;
packet1.servo1_raw = packet_in.servo1_raw;
packet1.servo2_raw = packet_in.servo2_raw;
packet1.servo3_raw = packet_in.servo3_raw;
packet1.servo4_raw = packet_in.servo4_raw;
packet1.servo5_raw = packet_in.servo5_raw;
packet1.servo6_raw = packet_in.servo6_raw;
packet1.servo7_raw = packet_in.servo7_raw;
packet1.servo8_raw = packet_in.servo8_raw;
packet1.port = packet_in.port;
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_servo_output_raw_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_servo_output_raw_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_servo_output_raw_pack(system_id, component_id, &msg , packet1.time_usec , packet1.port , packet1.servo1_raw , packet1.servo2_raw , packet1.servo3_raw , packet1.servo4_raw , packet1.servo5_raw , packet1.servo6_raw , packet1.servo7_raw , packet1.servo8_raw );
mavlink_msg_servo_output_raw_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_servo_output_raw_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_usec , packet1.port , packet1.servo1_raw , packet1.servo2_raw , packet1.servo3_raw , packet1.servo4_raw , packet1.servo5_raw , packet1.servo6_raw , packet1.servo7_raw , packet1.servo8_raw );
mavlink_msg_servo_output_raw_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_servo_output_raw_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_servo_output_raw_send(MAVLINK_COMM_1 , packet1.time_usec , packet1.port , packet1.servo1_raw , packet1.servo2_raw , packet1.servo3_raw , packet1.servo4_raw , packet1.servo5_raw , packet1.servo6_raw , packet1.servo7_raw , packet1.servo8_raw );
mavlink_msg_servo_output_raw_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_mission_request_partial_list(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_mission_request_partial_list_t packet_in = {
17235,
17339,
17,
84,
};
mavlink_mission_request_partial_list_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.start_index = packet_in.start_index;
packet1.end_index = packet_in.end_index;
packet1.target_system = packet_in.target_system;
packet1.target_component = packet_in.target_component;
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_mission_request_partial_list_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_mission_request_partial_list_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_mission_request_partial_list_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.start_index , packet1.end_index );
mavlink_msg_mission_request_partial_list_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_mission_request_partial_list_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.start_index , packet1.end_index );
mavlink_msg_mission_request_partial_list_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_mission_request_partial_list_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_mission_request_partial_list_send(MAVLINK_COMM_1 , packet1.target_system , packet1.target_component , packet1.start_index , packet1.end_index );
mavlink_msg_mission_request_partial_list_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_mission_write_partial_list(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_mission_write_partial_list_t packet_in = {
17235,
17339,
17,
84,
};
mavlink_mission_write_partial_list_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.start_index = packet_in.start_index;
packet1.end_index = packet_in.end_index;
packet1.target_system = packet_in.target_system;
packet1.target_component = packet_in.target_component;
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_mission_write_partial_list_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_mission_write_partial_list_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_mission_write_partial_list_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.start_index , packet1.end_index );
mavlink_msg_mission_write_partial_list_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_mission_write_partial_list_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.start_index , packet1.end_index );
mavlink_msg_mission_write_partial_list_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_mission_write_partial_list_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_mission_write_partial_list_send(MAVLINK_COMM_1 , packet1.target_system , packet1.target_component , packet1.start_index , packet1.end_index );
mavlink_msg_mission_write_partial_list_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_mission_item(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_mission_item_t packet_in = {
17.0,
45.0,
73.0,
101.0,
129.0,
157.0,
185.0,
18691,
18795,
101,
168,
235,
46,
113,
};
mavlink_mission_item_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.param1 = packet_in.param1;
packet1.param2 = packet_in.param2;
packet1.param3 = packet_in.param3;
packet1.param4 = packet_in.param4;
packet1.x = packet_in.x;
packet1.y = packet_in.y;
packet1.z = packet_in.z;
packet1.seq = packet_in.seq;
packet1.command = packet_in.command;
packet1.target_system = packet_in.target_system;
packet1.target_component = packet_in.target_component;
packet1.frame = packet_in.frame;
packet1.current = packet_in.current;
packet1.autocontinue = packet_in.autocontinue;
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_mission_item_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_mission_item_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_mission_item_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.seq , packet1.frame , packet1.command , packet1.current , packet1.autocontinue , packet1.param1 , packet1.param2 , packet1.param3 , packet1.param4 , packet1.x , packet1.y , packet1.z );
mavlink_msg_mission_item_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_mission_item_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.seq , packet1.frame , packet1.command , packet1.current , packet1.autocontinue , packet1.param1 , packet1.param2 , packet1.param3 , packet1.param4 , packet1.x , packet1.y , packet1.z );
mavlink_msg_mission_item_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_mission_item_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_mission_item_send(MAVLINK_COMM_1 , packet1.target_system , packet1.target_component , packet1.seq , packet1.frame , packet1.command , packet1.current , packet1.autocontinue , packet1.param1 , packet1.param2 , packet1.param3 , packet1.param4 , packet1.x , packet1.y , packet1.z );
mavlink_msg_mission_item_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_mission_request(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_mission_request_t packet_in = {
17235,
139,
206,
};
mavlink_mission_request_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.seq = packet_in.seq;
packet1.target_system = packet_in.target_system;
packet1.target_component = packet_in.target_component;
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_mission_request_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_mission_request_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_mission_request_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.seq );
mavlink_msg_mission_request_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_mission_request_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.seq );
mavlink_msg_mission_request_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_mission_request_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_mission_request_send(MAVLINK_COMM_1 , packet1.target_system , packet1.target_component , packet1.seq );
mavlink_msg_mission_request_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_mission_set_current(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_mission_set_current_t packet_in = {
17235,
139,
206,
};
mavlink_mission_set_current_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.seq = packet_in.seq;
packet1.target_system = packet_in.target_system;
packet1.target_component = packet_in.target_component;
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_mission_set_current_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_mission_set_current_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_mission_set_current_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.seq );
mavlink_msg_mission_set_current_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_mission_set_current_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.seq );
mavlink_msg_mission_set_current_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_mission_set_current_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_mission_set_current_send(MAVLINK_COMM_1 , packet1.target_system , packet1.target_component , packet1.seq );
mavlink_msg_mission_set_current_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_mission_current(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_mission_current_t packet_in = {
17235,
};
mavlink_mission_current_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.seq = packet_in.seq;
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_mission_current_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_mission_current_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_mission_current_pack(system_id, component_id, &msg , packet1.seq );
mavlink_msg_mission_current_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_mission_current_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.seq );
mavlink_msg_mission_current_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_mission_current_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_mission_current_send(MAVLINK_COMM_1 , packet1.seq );
mavlink_msg_mission_current_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_mission_request_list(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_mission_request_list_t packet_in = {
5,
72,
};
mavlink_mission_request_list_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.target_system = packet_in.target_system;
packet1.target_component = packet_in.target_component;
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_mission_request_list_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_mission_request_list_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_mission_request_list_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component );
mavlink_msg_mission_request_list_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_mission_request_list_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component );
mavlink_msg_mission_request_list_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_mission_request_list_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_mission_request_list_send(MAVLINK_COMM_1 , packet1.target_system , packet1.target_component );
mavlink_msg_mission_request_list_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_mission_count(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_mission_count_t packet_in = {
17235,
139,
206,
};
mavlink_mission_count_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.count = packet_in.count;
packet1.target_system = packet_in.target_system;
packet1.target_component = packet_in.target_component;
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_mission_count_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_mission_count_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_mission_count_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.count );
mavlink_msg_mission_count_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_mission_count_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.count );
mavlink_msg_mission_count_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_mission_count_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_mission_count_send(MAVLINK_COMM_1 , packet1.target_system , packet1.target_component , packet1.count );
mavlink_msg_mission_count_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_mission_clear_all(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_mission_clear_all_t packet_in = {
5,
72,
};
mavlink_mission_clear_all_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.target_system = packet_in.target_system;
packet1.target_component = packet_in.target_component;
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_mission_clear_all_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_mission_clear_all_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_mission_clear_all_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component );
mavlink_msg_mission_clear_all_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_mission_clear_all_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component );
mavlink_msg_mission_clear_all_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_mission_clear_all_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_mission_clear_all_send(MAVLINK_COMM_1 , packet1.target_system , packet1.target_component );
mavlink_msg_mission_clear_all_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_mission_item_reached(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_mission_item_reached_t packet_in = {
17235,
};
mavlink_mission_item_reached_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.seq = packet_in.seq;
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_mission_item_reached_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_mission_item_reached_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_mission_item_reached_pack(system_id, component_id, &msg , packet1.seq );
mavlink_msg_mission_item_reached_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_mission_item_reached_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.seq );
mavlink_msg_mission_item_reached_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_mission_item_reached_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_mission_item_reached_send(MAVLINK_COMM_1 , packet1.seq );
mavlink_msg_mission_item_reached_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_mission_ack(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_mission_ack_t packet_in = {
5,
72,
139,
};
mavlink_mission_ack_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.target_system = packet_in.target_system;
packet1.target_component = packet_in.target_component;
packet1.type = packet_in.type;
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_mission_ack_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_mission_ack_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_mission_ack_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.type );
mavlink_msg_mission_ack_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_mission_ack_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.type );
mavlink_msg_mission_ack_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_mission_ack_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_mission_ack_send(MAVLINK_COMM_1 , packet1.target_system , packet1.target_component , packet1.type );
mavlink_msg_mission_ack_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_set_gps_global_origin(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_set_gps_global_origin_t packet_in = {
963497464,
963497672,
963497880,
41,
};
mavlink_set_gps_global_origin_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.latitude = packet_in.latitude;
packet1.longitude = packet_in.longitude;
packet1.altitude = packet_in.altitude;
packet1.target_system = packet_in.target_system;
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_set_gps_global_origin_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_set_gps_global_origin_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_set_gps_global_origin_pack(system_id, component_id, &msg , packet1.target_system , packet1.latitude , packet1.longitude , packet1.altitude );
mavlink_msg_set_gps_global_origin_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_set_gps_global_origin_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.latitude , packet1.longitude , packet1.altitude );
mavlink_msg_set_gps_global_origin_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_set_gps_global_origin_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_set_gps_global_origin_send(MAVLINK_COMM_1 , packet1.target_system , packet1.latitude , packet1.longitude , packet1.altitude );
mavlink_msg_set_gps_global_origin_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_gps_global_origin(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_gps_global_origin_t packet_in = {
963497464,
963497672,
963497880,
};
mavlink_gps_global_origin_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.latitude = packet_in.latitude;
packet1.longitude = packet_in.longitude;
packet1.altitude = packet_in.altitude;
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_gps_global_origin_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_gps_global_origin_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_gps_global_origin_pack(system_id, component_id, &msg , packet1.latitude , packet1.longitude , packet1.altitude );
mavlink_msg_gps_global_origin_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_gps_global_origin_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.latitude , packet1.longitude , packet1.altitude );
mavlink_msg_gps_global_origin_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_gps_global_origin_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_gps_global_origin_send(MAVLINK_COMM_1 , packet1.latitude , packet1.longitude , packet1.altitude );
mavlink_msg_gps_global_origin_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_set_local_position_setpoint(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_set_local_position_setpoint_t packet_in = {
17.0,
45.0,
73.0,
101.0,
53,
120,
187,
};
mavlink_set_local_position_setpoint_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.x = packet_in.x;
packet1.y = packet_in.y;
packet1.z = packet_in.z;
packet1.yaw = packet_in.yaw;
packet1.target_system = packet_in.target_system;
packet1.target_component = packet_in.target_component;
packet1.coordinate_frame = packet_in.coordinate_frame;
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_set_local_position_setpoint_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_set_local_position_setpoint_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_set_local_position_setpoint_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.coordinate_frame , packet1.x , packet1.y , packet1.z , packet1.yaw );
mavlink_msg_set_local_position_setpoint_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_set_local_position_setpoint_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.coordinate_frame , packet1.x , packet1.y , packet1.z , packet1.yaw );
mavlink_msg_set_local_position_setpoint_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_set_local_position_setpoint_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_set_local_position_setpoint_send(MAVLINK_COMM_1 , packet1.target_system , packet1.target_component , packet1.coordinate_frame , packet1.x , packet1.y , packet1.z , packet1.yaw );
mavlink_msg_set_local_position_setpoint_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_local_position_setpoint(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_local_position_setpoint_t packet_in = {
17.0,
45.0,
73.0,
101.0,
53,
};
mavlink_local_position_setpoint_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.x = packet_in.x;
packet1.y = packet_in.y;
packet1.z = packet_in.z;
packet1.yaw = packet_in.yaw;
packet1.coordinate_frame = packet_in.coordinate_frame;
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_local_position_setpoint_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_local_position_setpoint_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_local_position_setpoint_pack(system_id, component_id, &msg , packet1.coordinate_frame , packet1.x , packet1.y , packet1.z , packet1.yaw );
mavlink_msg_local_position_setpoint_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_local_position_setpoint_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.coordinate_frame , packet1.x , packet1.y , packet1.z , packet1.yaw );
mavlink_msg_local_position_setpoint_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_local_position_setpoint_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_local_position_setpoint_send(MAVLINK_COMM_1 , packet1.coordinate_frame , packet1.x , packet1.y , packet1.z , packet1.yaw );
mavlink_msg_local_position_setpoint_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_global_position_setpoint_int(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_global_position_setpoint_int_t packet_in = {
963497464,
963497672,
963497880,
17859,
175,
};
mavlink_global_position_setpoint_int_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.latitude = packet_in.latitude;
packet1.longitude = packet_in.longitude;
packet1.altitude = packet_in.altitude;
packet1.yaw = packet_in.yaw;
packet1.coordinate_frame = packet_in.coordinate_frame;
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_global_position_setpoint_int_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_global_position_setpoint_int_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_global_position_setpoint_int_pack(system_id, component_id, &msg , packet1.coordinate_frame , packet1.latitude , packet1.longitude , packet1.altitude , packet1.yaw );
mavlink_msg_global_position_setpoint_int_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_global_position_setpoint_int_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.coordinate_frame , packet1.latitude , packet1.longitude , packet1.altitude , packet1.yaw );
mavlink_msg_global_position_setpoint_int_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_global_position_setpoint_int_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_global_position_setpoint_int_send(MAVLINK_COMM_1 , packet1.coordinate_frame , packet1.latitude , packet1.longitude , packet1.altitude , packet1.yaw );
mavlink_msg_global_position_setpoint_int_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_set_global_position_setpoint_int(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_set_global_position_setpoint_int_t packet_in = {
963497464,
963497672,
963497880,
17859,
175,
};
mavlink_set_global_position_setpoint_int_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.latitude = packet_in.latitude;
packet1.longitude = packet_in.longitude;
packet1.altitude = packet_in.altitude;
packet1.yaw = packet_in.yaw;
packet1.coordinate_frame = packet_in.coordinate_frame;
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_set_global_position_setpoint_int_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_set_global_position_setpoint_int_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_set_global_position_setpoint_int_pack(system_id, component_id, &msg , packet1.coordinate_frame , packet1.latitude , packet1.longitude , packet1.altitude , packet1.yaw );
mavlink_msg_set_global_position_setpoint_int_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_set_global_position_setpoint_int_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.coordinate_frame , packet1.latitude , packet1.longitude , packet1.altitude , packet1.yaw );
mavlink_msg_set_global_position_setpoint_int_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_set_global_position_setpoint_int_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_set_global_position_setpoint_int_send(MAVLINK_COMM_1 , packet1.coordinate_frame , packet1.latitude , packet1.longitude , packet1.altitude , packet1.yaw );
mavlink_msg_set_global_position_setpoint_int_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_safety_set_allowed_area(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_safety_set_allowed_area_t packet_in = {
17.0,
45.0,
73.0,
101.0,
129.0,
157.0,
77,
144,
211,
};
mavlink_safety_set_allowed_area_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.p1x = packet_in.p1x;
packet1.p1y = packet_in.p1y;
packet1.p1z = packet_in.p1z;
packet1.p2x = packet_in.p2x;
packet1.p2y = packet_in.p2y;
packet1.p2z = packet_in.p2z;
packet1.target_system = packet_in.target_system;
packet1.target_component = packet_in.target_component;
packet1.frame = packet_in.frame;
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_safety_set_allowed_area_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_safety_set_allowed_area_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_safety_set_allowed_area_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.frame , packet1.p1x , packet1.p1y , packet1.p1z , packet1.p2x , packet1.p2y , packet1.p2z );
mavlink_msg_safety_set_allowed_area_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_safety_set_allowed_area_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.frame , packet1.p1x , packet1.p1y , packet1.p1z , packet1.p2x , packet1.p2y , packet1.p2z );
mavlink_msg_safety_set_allowed_area_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_safety_set_allowed_area_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_safety_set_allowed_area_send(MAVLINK_COMM_1 , packet1.target_system , packet1.target_component , packet1.frame , packet1.p1x , packet1.p1y , packet1.p1z , packet1.p2x , packet1.p2y , packet1.p2z );
mavlink_msg_safety_set_allowed_area_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_safety_allowed_area(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_safety_allowed_area_t packet_in = {
17.0,
45.0,
73.0,
101.0,
129.0,
157.0,
77,
};
mavlink_safety_allowed_area_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.p1x = packet_in.p1x;
packet1.p1y = packet_in.p1y;
packet1.p1z = packet_in.p1z;
packet1.p2x = packet_in.p2x;
packet1.p2y = packet_in.p2y;
packet1.p2z = packet_in.p2z;
packet1.frame = packet_in.frame;
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_safety_allowed_area_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_safety_allowed_area_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_safety_allowed_area_pack(system_id, component_id, &msg , packet1.frame , packet1.p1x , packet1.p1y , packet1.p1z , packet1.p2x , packet1.p2y , packet1.p2z );
mavlink_msg_safety_allowed_area_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_safety_allowed_area_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.frame , packet1.p1x , packet1.p1y , packet1.p1z , packet1.p2x , packet1.p2y , packet1.p2z );
mavlink_msg_safety_allowed_area_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_safety_allowed_area_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_safety_allowed_area_send(MAVLINK_COMM_1 , packet1.frame , packet1.p1x , packet1.p1y , packet1.p1z , packet1.p2x , packet1.p2y , packet1.p2z );
mavlink_msg_safety_allowed_area_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_set_roll_pitch_yaw_thrust(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_set_roll_pitch_yaw_thrust_t packet_in = {
17.0,
45.0,
73.0,
101.0,
53,
120,
};
mavlink_set_roll_pitch_yaw_thrust_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.roll = packet_in.roll;
packet1.pitch = packet_in.pitch;
packet1.yaw = packet_in.yaw;
packet1.thrust = packet_in.thrust;
packet1.target_system = packet_in.target_system;
packet1.target_component = packet_in.target_component;
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_set_roll_pitch_yaw_thrust_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_set_roll_pitch_yaw_thrust_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_set_roll_pitch_yaw_thrust_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.roll , packet1.pitch , packet1.yaw , packet1.thrust );
mavlink_msg_set_roll_pitch_yaw_thrust_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_set_roll_pitch_yaw_thrust_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.roll , packet1.pitch , packet1.yaw , packet1.thrust );
mavlink_msg_set_roll_pitch_yaw_thrust_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_set_roll_pitch_yaw_thrust_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_set_roll_pitch_yaw_thrust_send(MAVLINK_COMM_1 , packet1.target_system , packet1.target_component , packet1.roll , packet1.pitch , packet1.yaw , packet1.thrust );
mavlink_msg_set_roll_pitch_yaw_thrust_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_set_roll_pitch_yaw_speed_thrust(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_set_roll_pitch_yaw_speed_thrust_t packet_in = {
17.0,
45.0,
73.0,
101.0,
53,
120,
};
mavlink_set_roll_pitch_yaw_speed_thrust_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.roll_speed = packet_in.roll_speed;
packet1.pitch_speed = packet_in.pitch_speed;
packet1.yaw_speed = packet_in.yaw_speed;
packet1.thrust = packet_in.thrust;
packet1.target_system = packet_in.target_system;
packet1.target_component = packet_in.target_component;
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_set_roll_pitch_yaw_speed_thrust_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_set_roll_pitch_yaw_speed_thrust_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_set_roll_pitch_yaw_speed_thrust_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.roll_speed , packet1.pitch_speed , packet1.yaw_speed , packet1.thrust );
mavlink_msg_set_roll_pitch_yaw_speed_thrust_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_set_roll_pitch_yaw_speed_thrust_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.roll_speed , packet1.pitch_speed , packet1.yaw_speed , packet1.thrust );
mavlink_msg_set_roll_pitch_yaw_speed_thrust_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_set_roll_pitch_yaw_speed_thrust_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_set_roll_pitch_yaw_speed_thrust_send(MAVLINK_COMM_1 , packet1.target_system , packet1.target_component , packet1.roll_speed , packet1.pitch_speed , packet1.yaw_speed , packet1.thrust );
mavlink_msg_set_roll_pitch_yaw_speed_thrust_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_roll_pitch_yaw_thrust_setpoint(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_roll_pitch_yaw_thrust_setpoint_t packet_in = {
963497464,
45.0,
73.0,
101.0,
129.0,
};
mavlink_roll_pitch_yaw_thrust_setpoint_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.time_boot_ms = packet_in.time_boot_ms;
packet1.roll = packet_in.roll;
packet1.pitch = packet_in.pitch;
packet1.yaw = packet_in.yaw;
packet1.thrust = packet_in.thrust;
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_roll_pitch_yaw_thrust_setpoint_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_roll_pitch_yaw_thrust_setpoint_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_roll_pitch_yaw_thrust_setpoint_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.roll , packet1.pitch , packet1.yaw , packet1.thrust );
mavlink_msg_roll_pitch_yaw_thrust_setpoint_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_roll_pitch_yaw_thrust_setpoint_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.roll , packet1.pitch , packet1.yaw , packet1.thrust );
mavlink_msg_roll_pitch_yaw_thrust_setpoint_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_roll_pitch_yaw_thrust_setpoint_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_roll_pitch_yaw_thrust_setpoint_send(MAVLINK_COMM_1 , packet1.time_boot_ms , packet1.roll , packet1.pitch , packet1.yaw , packet1.thrust );
mavlink_msg_roll_pitch_yaw_thrust_setpoint_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_roll_pitch_yaw_speed_thrust_setpoint(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_roll_pitch_yaw_speed_thrust_setpoint_t packet_in = {
963497464,
45.0,
73.0,
101.0,
129.0,
};
mavlink_roll_pitch_yaw_speed_thrust_setpoint_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.time_boot_ms = packet_in.time_boot_ms;
packet1.roll_speed = packet_in.roll_speed;
packet1.pitch_speed = packet_in.pitch_speed;
packet1.yaw_speed = packet_in.yaw_speed;
packet1.thrust = packet_in.thrust;
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.roll_speed , packet1.pitch_speed , packet1.yaw_speed , packet1.thrust );
mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.roll_speed , packet1.pitch_speed , packet1.yaw_speed , packet1.thrust );
mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_send(MAVLINK_COMM_1 , packet1.time_boot_ms , packet1.roll_speed , packet1.pitch_speed , packet1.yaw_speed , packet1.thrust );
mavlink_msg_roll_pitch_yaw_speed_thrust_setpoint_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_set_quad_motors_setpoint(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_set_quad_motors_setpoint_t packet_in = {
17235,
17339,
17443,
17547,
29,
};
mavlink_set_quad_motors_setpoint_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.motor_front_nw = packet_in.motor_front_nw;
packet1.motor_right_ne = packet_in.motor_right_ne;
packet1.motor_back_se = packet_in.motor_back_se;
packet1.motor_left_sw = packet_in.motor_left_sw;
packet1.target_system = packet_in.target_system;
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_set_quad_motors_setpoint_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_set_quad_motors_setpoint_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_set_quad_motors_setpoint_pack(system_id, component_id, &msg , packet1.target_system , packet1.motor_front_nw , packet1.motor_right_ne , packet1.motor_back_se , packet1.motor_left_sw );
mavlink_msg_set_quad_motors_setpoint_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_set_quad_motors_setpoint_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.motor_front_nw , packet1.motor_right_ne , packet1.motor_back_se , packet1.motor_left_sw );
mavlink_msg_set_quad_motors_setpoint_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_set_quad_motors_setpoint_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_set_quad_motors_setpoint_send(MAVLINK_COMM_1 , packet1.target_system , packet1.motor_front_nw , packet1.motor_right_ne , packet1.motor_back_se , packet1.motor_left_sw );
mavlink_msg_set_quad_motors_setpoint_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_set_quad_swarm_roll_pitch_yaw_thrust(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_set_quad_swarm_roll_pitch_yaw_thrust_t packet_in = {
{ 17235, 17236, 17237, 17238, 17239, 17240 },
{ 17859, 17860, 17861, 17862, 17863, 17864 },
{ 18483, 18484, 18485, 18486, 18487, 18488 },
{ 19107, 19108, 19109, 19110, 19111, 19112 },
{ 149, 150, 151, 152, 153, 154 },
};
mavlink_set_quad_swarm_roll_pitch_yaw_thrust_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
mav_array_memcpy(packet1.roll, packet_in.roll, sizeof(int16_t)*6);
mav_array_memcpy(packet1.pitch, packet_in.pitch, sizeof(int16_t)*6);
mav_array_memcpy(packet1.yaw, packet_in.yaw, sizeof(int16_t)*6);
mav_array_memcpy(packet1.thrust, packet_in.thrust, sizeof(uint16_t)*6);
mav_array_memcpy(packet1.target_systems, packet_in.target_systems, sizeof(uint8_t)*6);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust_pack(system_id, component_id, &msg , packet1.target_systems , packet1.roll , packet1.pitch , packet1.yaw , packet1.thrust );
mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_systems , packet1.roll , packet1.pitch , packet1.yaw , packet1.thrust );
mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust_send(MAVLINK_COMM_1 , packet1.target_systems , packet1.roll , packet1.pitch , packet1.yaw , packet1.thrust );
mavlink_msg_set_quad_swarm_roll_pitch_yaw_thrust_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_nav_controller_output(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_nav_controller_output_t packet_in = {
17.0,
45.0,
73.0,
101.0,
129.0,
18275,
18379,
18483,
};
mavlink_nav_controller_output_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.nav_roll = packet_in.nav_roll;
packet1.nav_pitch = packet_in.nav_pitch;
packet1.alt_error = packet_in.alt_error;
packet1.aspd_error = packet_in.aspd_error;
packet1.xtrack_error = packet_in.xtrack_error;
packet1.nav_bearing = packet_in.nav_bearing;
packet1.target_bearing = packet_in.target_bearing;
packet1.wp_dist = packet_in.wp_dist;
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_nav_controller_output_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_nav_controller_output_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_nav_controller_output_pack(system_id, component_id, &msg , packet1.nav_roll , packet1.nav_pitch , packet1.nav_bearing , packet1.target_bearing , packet1.wp_dist , packet1.alt_error , packet1.aspd_error , packet1.xtrack_error );
mavlink_msg_nav_controller_output_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_nav_controller_output_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.nav_roll , packet1.nav_pitch , packet1.nav_bearing , packet1.target_bearing , packet1.wp_dist , packet1.alt_error , packet1.aspd_error , packet1.xtrack_error );
mavlink_msg_nav_controller_output_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_nav_controller_output_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_nav_controller_output_send(MAVLINK_COMM_1 , packet1.nav_roll , packet1.nav_pitch , packet1.nav_bearing , packet1.target_bearing , packet1.wp_dist , packet1.alt_error , packet1.aspd_error , packet1.xtrack_error );
mavlink_msg_nav_controller_output_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_state_correction(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_state_correction_t packet_in = {
17.0,
45.0,
73.0,
101.0,
129.0,
157.0,
185.0,
213.0,
241.0,
};
mavlink_state_correction_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.xErr = packet_in.xErr;
packet1.yErr = packet_in.yErr;
packet1.zErr = packet_in.zErr;
packet1.rollErr = packet_in.rollErr;
packet1.pitchErr = packet_in.pitchErr;
packet1.yawErr = packet_in.yawErr;
packet1.vxErr = packet_in.vxErr;
packet1.vyErr = packet_in.vyErr;
packet1.vzErr = packet_in.vzErr;
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_state_correction_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_state_correction_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_state_correction_pack(system_id, component_id, &msg , packet1.xErr , packet1.yErr , packet1.zErr , packet1.rollErr , packet1.pitchErr , packet1.yawErr , packet1.vxErr , packet1.vyErr , packet1.vzErr );
mavlink_msg_state_correction_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_state_correction_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.xErr , packet1.yErr , packet1.zErr , packet1.rollErr , packet1.pitchErr , packet1.yawErr , packet1.vxErr , packet1.vyErr , packet1.vzErr );
mavlink_msg_state_correction_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_state_correction_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_state_correction_send(MAVLINK_COMM_1 , packet1.xErr , packet1.yErr , packet1.zErr , packet1.rollErr , packet1.pitchErr , packet1.yawErr , packet1.vxErr , packet1.vyErr , packet1.vzErr );
mavlink_msg_state_correction_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_request_data_stream(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_request_data_stream_t packet_in = {
17235,
139,
206,
17,
84,
};
mavlink_request_data_stream_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.req_message_rate = packet_in.req_message_rate;
packet1.target_system = packet_in.target_system;
packet1.target_component = packet_in.target_component;
packet1.req_stream_id = packet_in.req_stream_id;
packet1.start_stop = packet_in.start_stop;
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_request_data_stream_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_request_data_stream_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_request_data_stream_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.req_stream_id , packet1.req_message_rate , packet1.start_stop );
mavlink_msg_request_data_stream_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_request_data_stream_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.req_stream_id , packet1.req_message_rate , packet1.start_stop );
mavlink_msg_request_data_stream_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_request_data_stream_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_request_data_stream_send(MAVLINK_COMM_1 , packet1.target_system , packet1.target_component , packet1.req_stream_id , packet1.req_message_rate , packet1.start_stop );
mavlink_msg_request_data_stream_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_data_stream(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_data_stream_t packet_in = {
17235,
139,
206,
};
mavlink_data_stream_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.message_rate = packet_in.message_rate;
packet1.stream_id = packet_in.stream_id;
packet1.on_off = packet_in.on_off;
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_data_stream_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_data_stream_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_data_stream_pack(system_id, component_id, &msg , packet1.stream_id , packet1.message_rate , packet1.on_off );
mavlink_msg_data_stream_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_data_stream_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.stream_id , packet1.message_rate , packet1.on_off );
mavlink_msg_data_stream_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_data_stream_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_data_stream_send(MAVLINK_COMM_1 , packet1.stream_id , packet1.message_rate , packet1.on_off );
mavlink_msg_data_stream_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_manual_control(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_manual_control_t packet_in = {
17.0,
45.0,
73.0,
101.0,
53,
120,
187,
254,
65,
};
mavlink_manual_control_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.roll = packet_in.roll;
packet1.pitch = packet_in.pitch;
packet1.yaw = packet_in.yaw;
packet1.thrust = packet_in.thrust;
packet1.target = packet_in.target;
packet1.roll_manual = packet_in.roll_manual;
packet1.pitch_manual = packet_in.pitch_manual;
packet1.yaw_manual = packet_in.yaw_manual;
packet1.thrust_manual = packet_in.thrust_manual;
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_manual_control_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_manual_control_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_manual_control_pack(system_id, component_id, &msg , packet1.target , packet1.roll , packet1.pitch , packet1.yaw , packet1.thrust , packet1.roll_manual , packet1.pitch_manual , packet1.yaw_manual , packet1.thrust_manual );
mavlink_msg_manual_control_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_manual_control_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target , packet1.roll , packet1.pitch , packet1.yaw , packet1.thrust , packet1.roll_manual , packet1.pitch_manual , packet1.yaw_manual , packet1.thrust_manual );
mavlink_msg_manual_control_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_manual_control_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_manual_control_send(MAVLINK_COMM_1 , packet1.target , packet1.roll , packet1.pitch , packet1.yaw , packet1.thrust , packet1.roll_manual , packet1.pitch_manual , packet1.yaw_manual , packet1.thrust_manual );
mavlink_msg_manual_control_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_rc_channels_override(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_rc_channels_override_t packet_in = {
17235,
17339,
17443,
17547,
17651,
17755,
17859,
17963,
53,
120,
};
mavlink_rc_channels_override_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.chan1_raw = packet_in.chan1_raw;
packet1.chan2_raw = packet_in.chan2_raw;
packet1.chan3_raw = packet_in.chan3_raw;
packet1.chan4_raw = packet_in.chan4_raw;
packet1.chan5_raw = packet_in.chan5_raw;
packet1.chan6_raw = packet_in.chan6_raw;
packet1.chan7_raw = packet_in.chan7_raw;
packet1.chan8_raw = packet_in.chan8_raw;
packet1.target_system = packet_in.target_system;
packet1.target_component = packet_in.target_component;
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_rc_channels_override_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_rc_channels_override_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_rc_channels_override_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.chan1_raw , packet1.chan2_raw , packet1.chan3_raw , packet1.chan4_raw , packet1.chan5_raw , packet1.chan6_raw , packet1.chan7_raw , packet1.chan8_raw );
mavlink_msg_rc_channels_override_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_rc_channels_override_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.chan1_raw , packet1.chan2_raw , packet1.chan3_raw , packet1.chan4_raw , packet1.chan5_raw , packet1.chan6_raw , packet1.chan7_raw , packet1.chan8_raw );
mavlink_msg_rc_channels_override_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_rc_channels_override_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_rc_channels_override_send(MAVLINK_COMM_1 , packet1.target_system , packet1.target_component , packet1.chan1_raw , packet1.chan2_raw , packet1.chan3_raw , packet1.chan4_raw , packet1.chan5_raw , packet1.chan6_raw , packet1.chan7_raw , packet1.chan8_raw );
mavlink_msg_rc_channels_override_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_vfr_hud(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_vfr_hud_t packet_in = {
17.0,
45.0,
73.0,
101.0,
18067,
18171,
};
mavlink_vfr_hud_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.airspeed = packet_in.airspeed;
packet1.groundspeed = packet_in.groundspeed;
packet1.alt = packet_in.alt;
packet1.climb = packet_in.climb;
packet1.heading = packet_in.heading;
packet1.throttle = packet_in.throttle;
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_vfr_hud_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_vfr_hud_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_vfr_hud_pack(system_id, component_id, &msg , packet1.airspeed , packet1.groundspeed , packet1.heading , packet1.throttle , packet1.alt , packet1.climb );
mavlink_msg_vfr_hud_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_vfr_hud_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.airspeed , packet1.groundspeed , packet1.heading , packet1.throttle , packet1.alt , packet1.climb );
mavlink_msg_vfr_hud_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_vfr_hud_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_vfr_hud_send(MAVLINK_COMM_1 , packet1.airspeed , packet1.groundspeed , packet1.heading , packet1.throttle , packet1.alt , packet1.climb );
mavlink_msg_vfr_hud_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_command_long(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_command_long_t packet_in = {
17.0,
45.0,
73.0,
101.0,
129.0,
157.0,
185.0,
18691,
223,
34,
101,
};
mavlink_command_long_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.param1 = packet_in.param1;
packet1.param2 = packet_in.param2;
packet1.param3 = packet_in.param3;
packet1.param4 = packet_in.param4;
packet1.param5 = packet_in.param5;
packet1.param6 = packet_in.param6;
packet1.param7 = packet_in.param7;
packet1.command = packet_in.command;
packet1.target_system = packet_in.target_system;
packet1.target_component = packet_in.target_component;
packet1.confirmation = packet_in.confirmation;
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_command_long_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_command_long_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_command_long_pack(system_id, component_id, &msg , packet1.target_system , packet1.target_component , packet1.command , packet1.confirmation , packet1.param1 , packet1.param2 , packet1.param3 , packet1.param4 , packet1.param5 , packet1.param6 , packet1.param7 );
mavlink_msg_command_long_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_command_long_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target_system , packet1.target_component , packet1.command , packet1.confirmation , packet1.param1 , packet1.param2 , packet1.param3 , packet1.param4 , packet1.param5 , packet1.param6 , packet1.param7 );
mavlink_msg_command_long_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_command_long_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_command_long_send(MAVLINK_COMM_1 , packet1.target_system , packet1.target_component , packet1.command , packet1.confirmation , packet1.param1 , packet1.param2 , packet1.param3 , packet1.param4 , packet1.param5 , packet1.param6 , packet1.param7 );
mavlink_msg_command_long_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_command_ack(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_command_ack_t packet_in = {
17235,
139,
};
mavlink_command_ack_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.command = packet_in.command;
packet1.result = packet_in.result;
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_command_ack_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_command_ack_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_command_ack_pack(system_id, component_id, &msg , packet1.command , packet1.result );
mavlink_msg_command_ack_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_command_ack_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.command , packet1.result );
mavlink_msg_command_ack_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_command_ack_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_command_ack_send(MAVLINK_COMM_1 , packet1.command , packet1.result );
mavlink_msg_command_ack_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_local_position_ned_system_global_offset(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_local_position_ned_system_global_offset_t packet_in = {
963497464,
45.0,
73.0,
101.0,
129.0,
157.0,
185.0,
};
mavlink_local_position_ned_system_global_offset_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.time_boot_ms = packet_in.time_boot_ms;
packet1.x = packet_in.x;
packet1.y = packet_in.y;
packet1.z = packet_in.z;
packet1.roll = packet_in.roll;
packet1.pitch = packet_in.pitch;
packet1.yaw = packet_in.yaw;
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_local_position_ned_system_global_offset_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_local_position_ned_system_global_offset_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_local_position_ned_system_global_offset_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.x , packet1.y , packet1.z , packet1.roll , packet1.pitch , packet1.yaw );
mavlink_msg_local_position_ned_system_global_offset_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_local_position_ned_system_global_offset_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.x , packet1.y , packet1.z , packet1.roll , packet1.pitch , packet1.yaw );
mavlink_msg_local_position_ned_system_global_offset_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_local_position_ned_system_global_offset_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_local_position_ned_system_global_offset_send(MAVLINK_COMM_1 , packet1.time_boot_ms , packet1.x , packet1.y , packet1.z , packet1.roll , packet1.pitch , packet1.yaw );
mavlink_msg_local_position_ned_system_global_offset_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_hil_state(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_hil_state_t packet_in = {
93372036854775807ULL,
73.0,
101.0,
129.0,
157.0,
185.0,
213.0,
963499128,
963499336,
963499544,
19523,
19627,
19731,
19835,
19939,
20043,
};
mavlink_hil_state_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.time_usec = packet_in.time_usec;
packet1.roll = packet_in.roll;
packet1.pitch = packet_in.pitch;
packet1.yaw = packet_in.yaw;
packet1.rollspeed = packet_in.rollspeed;
packet1.pitchspeed = packet_in.pitchspeed;
packet1.yawspeed = packet_in.yawspeed;
packet1.lat = packet_in.lat;
packet1.lon = packet_in.lon;
packet1.alt = packet_in.alt;
packet1.vx = packet_in.vx;
packet1.vy = packet_in.vy;
packet1.vz = packet_in.vz;
packet1.xacc = packet_in.xacc;
packet1.yacc = packet_in.yacc;
packet1.zacc = packet_in.zacc;
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_hil_state_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_hil_state_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_hil_state_pack(system_id, component_id, &msg , packet1.time_usec , packet1.roll , packet1.pitch , packet1.yaw , packet1.rollspeed , packet1.pitchspeed , packet1.yawspeed , packet1.lat , packet1.lon , packet1.alt , packet1.vx , packet1.vy , packet1.vz , packet1.xacc , packet1.yacc , packet1.zacc );
mavlink_msg_hil_state_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_hil_state_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_usec , packet1.roll , packet1.pitch , packet1.yaw , packet1.rollspeed , packet1.pitchspeed , packet1.yawspeed , packet1.lat , packet1.lon , packet1.alt , packet1.vx , packet1.vy , packet1.vz , packet1.xacc , packet1.yacc , packet1.zacc );
mavlink_msg_hil_state_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_hil_state_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_hil_state_send(MAVLINK_COMM_1 , packet1.time_usec , packet1.roll , packet1.pitch , packet1.yaw , packet1.rollspeed , packet1.pitchspeed , packet1.yawspeed , packet1.lat , packet1.lon , packet1.alt , packet1.vx , packet1.vy , packet1.vz , packet1.xacc , packet1.yacc , packet1.zacc );
mavlink_msg_hil_state_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_hil_controls(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_hil_controls_t packet_in = {
93372036854775807ULL,
73.0,
101.0,
129.0,
157.0,
185.0,
213.0,
241.0,
269.0,
125,
192,
};
mavlink_hil_controls_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.time_usec = packet_in.time_usec;
packet1.roll_ailerons = packet_in.roll_ailerons;
packet1.pitch_elevator = packet_in.pitch_elevator;
packet1.yaw_rudder = packet_in.yaw_rudder;
packet1.throttle = packet_in.throttle;
packet1.aux1 = packet_in.aux1;
packet1.aux2 = packet_in.aux2;
packet1.aux3 = packet_in.aux3;
packet1.aux4 = packet_in.aux4;
packet1.mode = packet_in.mode;
packet1.nav_mode = packet_in.nav_mode;
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_hil_controls_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_hil_controls_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_hil_controls_pack(system_id, component_id, &msg , packet1.time_usec , packet1.roll_ailerons , packet1.pitch_elevator , packet1.yaw_rudder , packet1.throttle , packet1.aux1 , packet1.aux2 , packet1.aux3 , packet1.aux4 , packet1.mode , packet1.nav_mode );
mavlink_msg_hil_controls_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_hil_controls_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_usec , packet1.roll_ailerons , packet1.pitch_elevator , packet1.yaw_rudder , packet1.throttle , packet1.aux1 , packet1.aux2 , packet1.aux3 , packet1.aux4 , packet1.mode , packet1.nav_mode );
mavlink_msg_hil_controls_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_hil_controls_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_hil_controls_send(MAVLINK_COMM_1 , packet1.time_usec , packet1.roll_ailerons , packet1.pitch_elevator , packet1.yaw_rudder , packet1.throttle , packet1.aux1 , packet1.aux2 , packet1.aux3 , packet1.aux4 , packet1.mode , packet1.nav_mode );
mavlink_msg_hil_controls_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_hil_rc_inputs_raw(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_hil_rc_inputs_raw_t packet_in = {
93372036854775807ULL,
17651,
17755,
17859,
17963,
18067,
18171,
18275,
18379,
18483,
18587,
18691,
18795,
101,
};
mavlink_hil_rc_inputs_raw_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.time_usec = packet_in.time_usec;
packet1.chan1_raw = packet_in.chan1_raw;
packet1.chan2_raw = packet_in.chan2_raw;
packet1.chan3_raw = packet_in.chan3_raw;
packet1.chan4_raw = packet_in.chan4_raw;
packet1.chan5_raw = packet_in.chan5_raw;
packet1.chan6_raw = packet_in.chan6_raw;
packet1.chan7_raw = packet_in.chan7_raw;
packet1.chan8_raw = packet_in.chan8_raw;
packet1.chan9_raw = packet_in.chan9_raw;
packet1.chan10_raw = packet_in.chan10_raw;
packet1.chan11_raw = packet_in.chan11_raw;
packet1.chan12_raw = packet_in.chan12_raw;
packet1.rssi = packet_in.rssi;
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_hil_rc_inputs_raw_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_hil_rc_inputs_raw_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_hil_rc_inputs_raw_pack(system_id, component_id, &msg , packet1.time_usec , packet1.chan1_raw , packet1.chan2_raw , packet1.chan3_raw , packet1.chan4_raw , packet1.chan5_raw , packet1.chan6_raw , packet1.chan7_raw , packet1.chan8_raw , packet1.chan9_raw , packet1.chan10_raw , packet1.chan11_raw , packet1.chan12_raw , packet1.rssi );
mavlink_msg_hil_rc_inputs_raw_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_hil_rc_inputs_raw_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_usec , packet1.chan1_raw , packet1.chan2_raw , packet1.chan3_raw , packet1.chan4_raw , packet1.chan5_raw , packet1.chan6_raw , packet1.chan7_raw , packet1.chan8_raw , packet1.chan9_raw , packet1.chan10_raw , packet1.chan11_raw , packet1.chan12_raw , packet1.rssi );
mavlink_msg_hil_rc_inputs_raw_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_hil_rc_inputs_raw_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_hil_rc_inputs_raw_send(MAVLINK_COMM_1 , packet1.time_usec , packet1.chan1_raw , packet1.chan2_raw , packet1.chan3_raw , packet1.chan4_raw , packet1.chan5_raw , packet1.chan6_raw , packet1.chan7_raw , packet1.chan8_raw , packet1.chan9_raw , packet1.chan10_raw , packet1.chan11_raw , packet1.chan12_raw , packet1.rssi );
mavlink_msg_hil_rc_inputs_raw_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_optical_flow(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_optical_flow_t packet_in = {
93372036854775807ULL,
73.0,
101.0,
129.0,
18275,
18379,
77,
144,
};
mavlink_optical_flow_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.time_usec = packet_in.time_usec;
packet1.flow_comp_m_x = packet_in.flow_comp_m_x;
packet1.flow_comp_m_y = packet_in.flow_comp_m_y;
packet1.ground_distance = packet_in.ground_distance;
packet1.flow_x = packet_in.flow_x;
packet1.flow_y = packet_in.flow_y;
packet1.sensor_id = packet_in.sensor_id;
packet1.quality = packet_in.quality;
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_optical_flow_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_optical_flow_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_optical_flow_pack(system_id, component_id, &msg , packet1.time_usec , packet1.sensor_id , packet1.flow_x , packet1.flow_y , packet1.flow_comp_m_x , packet1.flow_comp_m_y , packet1.quality , packet1.ground_distance );
mavlink_msg_optical_flow_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_optical_flow_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_usec , packet1.sensor_id , packet1.flow_x , packet1.flow_y , packet1.flow_comp_m_x , packet1.flow_comp_m_y , packet1.quality , packet1.ground_distance );
mavlink_msg_optical_flow_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_optical_flow_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_optical_flow_send(MAVLINK_COMM_1 , packet1.time_usec , packet1.sensor_id , packet1.flow_x , packet1.flow_y , packet1.flow_comp_m_x , packet1.flow_comp_m_y , packet1.quality , packet1.ground_distance );
mavlink_msg_optical_flow_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_global_vision_position_estimate(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_global_vision_position_estimate_t packet_in = {
93372036854775807ULL,
73.0,
101.0,
129.0,
157.0,
185.0,
213.0,
};
mavlink_global_vision_position_estimate_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.usec = packet_in.usec;
packet1.x = packet_in.x;
packet1.y = packet_in.y;
packet1.z = packet_in.z;
packet1.roll = packet_in.roll;
packet1.pitch = packet_in.pitch;
packet1.yaw = packet_in.yaw;
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_global_vision_position_estimate_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_global_vision_position_estimate_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_global_vision_position_estimate_pack(system_id, component_id, &msg , packet1.usec , packet1.x , packet1.y , packet1.z , packet1.roll , packet1.pitch , packet1.yaw );
mavlink_msg_global_vision_position_estimate_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_global_vision_position_estimate_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.usec , packet1.x , packet1.y , packet1.z , packet1.roll , packet1.pitch , packet1.yaw );
mavlink_msg_global_vision_position_estimate_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_global_vision_position_estimate_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_global_vision_position_estimate_send(MAVLINK_COMM_1 , packet1.usec , packet1.x , packet1.y , packet1.z , packet1.roll , packet1.pitch , packet1.yaw );
mavlink_msg_global_vision_position_estimate_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_vision_position_estimate(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_vision_position_estimate_t packet_in = {
93372036854775807ULL,
73.0,
101.0,
129.0,
157.0,
185.0,
213.0,
};
mavlink_vision_position_estimate_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.usec = packet_in.usec;
packet1.x = packet_in.x;
packet1.y = packet_in.y;
packet1.z = packet_in.z;
packet1.roll = packet_in.roll;
packet1.pitch = packet_in.pitch;
packet1.yaw = packet_in.yaw;
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_vision_position_estimate_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_vision_position_estimate_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_vision_position_estimate_pack(system_id, component_id, &msg , packet1.usec , packet1.x , packet1.y , packet1.z , packet1.roll , packet1.pitch , packet1.yaw );
mavlink_msg_vision_position_estimate_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_vision_position_estimate_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.usec , packet1.x , packet1.y , packet1.z , packet1.roll , packet1.pitch , packet1.yaw );
mavlink_msg_vision_position_estimate_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_vision_position_estimate_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_vision_position_estimate_send(MAVLINK_COMM_1 , packet1.usec , packet1.x , packet1.y , packet1.z , packet1.roll , packet1.pitch , packet1.yaw );
mavlink_msg_vision_position_estimate_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_vision_speed_estimate(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_vision_speed_estimate_t packet_in = {
93372036854775807ULL,
73.0,
101.0,
129.0,
};
mavlink_vision_speed_estimate_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.usec = packet_in.usec;
packet1.x = packet_in.x;
packet1.y = packet_in.y;
packet1.z = packet_in.z;
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_vision_speed_estimate_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_vision_speed_estimate_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_vision_speed_estimate_pack(system_id, component_id, &msg , packet1.usec , packet1.x , packet1.y , packet1.z );
mavlink_msg_vision_speed_estimate_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_vision_speed_estimate_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.usec , packet1.x , packet1.y , packet1.z );
mavlink_msg_vision_speed_estimate_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_vision_speed_estimate_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_vision_speed_estimate_send(MAVLINK_COMM_1 , packet1.usec , packet1.x , packet1.y , packet1.z );
mavlink_msg_vision_speed_estimate_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_vicon_position_estimate(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_vicon_position_estimate_t packet_in = {
93372036854775807ULL,
73.0,
101.0,
129.0,
157.0,
185.0,
213.0,
};
mavlink_vicon_position_estimate_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.usec = packet_in.usec;
packet1.x = packet_in.x;
packet1.y = packet_in.y;
packet1.z = packet_in.z;
packet1.roll = packet_in.roll;
packet1.pitch = packet_in.pitch;
packet1.yaw = packet_in.yaw;
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_vicon_position_estimate_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_vicon_position_estimate_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_vicon_position_estimate_pack(system_id, component_id, &msg , packet1.usec , packet1.x , packet1.y , packet1.z , packet1.roll , packet1.pitch , packet1.yaw );
mavlink_msg_vicon_position_estimate_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_vicon_position_estimate_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.usec , packet1.x , packet1.y , packet1.z , packet1.roll , packet1.pitch , packet1.yaw );
mavlink_msg_vicon_position_estimate_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_vicon_position_estimate_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_vicon_position_estimate_send(MAVLINK_COMM_1 , packet1.usec , packet1.x , packet1.y , packet1.z , packet1.roll , packet1.pitch , packet1.yaw );
mavlink_msg_vicon_position_estimate_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_memory_vect(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_memory_vect_t packet_in = {
17235,
139,
206,
{ 17, 18, 19, 20, 21, 22, 23, 24, 25, 26, 27, 28, 29, 30, 31, 32, 33, 34, 35, 36, 37, 38, 39, 40, 41, 42, 43, 44, 45, 46, 47, 48 },
};
mavlink_memory_vect_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.address = packet_in.address;
packet1.ver = packet_in.ver;
packet1.type = packet_in.type;
mav_array_memcpy(packet1.value, packet_in.value, sizeof(int8_t)*32);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_memory_vect_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_memory_vect_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_memory_vect_pack(system_id, component_id, &msg , packet1.address , packet1.ver , packet1.type , packet1.value );
mavlink_msg_memory_vect_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_memory_vect_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.address , packet1.ver , packet1.type , packet1.value );
mavlink_msg_memory_vect_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_memory_vect_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_memory_vect_send(MAVLINK_COMM_1 , packet1.address , packet1.ver , packet1.type , packet1.value );
mavlink_msg_memory_vect_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_debug_vect(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_debug_vect_t packet_in = {
93372036854775807ULL,
73.0,
101.0,
129.0,
"UVWXYZABC",
};
mavlink_debug_vect_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.time_usec = packet_in.time_usec;
packet1.x = packet_in.x;
packet1.y = packet_in.y;
packet1.z = packet_in.z;
mav_array_memcpy(packet1.name, packet_in.name, sizeof(char)*10);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_debug_vect_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_debug_vect_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_debug_vect_pack(system_id, component_id, &msg , packet1.name , packet1.time_usec , packet1.x , packet1.y , packet1.z );
mavlink_msg_debug_vect_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_debug_vect_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.name , packet1.time_usec , packet1.x , packet1.y , packet1.z );
mavlink_msg_debug_vect_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_debug_vect_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_debug_vect_send(MAVLINK_COMM_1 , packet1.name , packet1.time_usec , packet1.x , packet1.y , packet1.z );
mavlink_msg_debug_vect_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_named_value_float(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_named_value_float_t packet_in = {
963497464,
45.0,
"IJKLMNOPQ",
};
mavlink_named_value_float_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.time_boot_ms = packet_in.time_boot_ms;
packet1.value = packet_in.value;
mav_array_memcpy(packet1.name, packet_in.name, sizeof(char)*10);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_named_value_float_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_named_value_float_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_named_value_float_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.name , packet1.value );
mavlink_msg_named_value_float_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_named_value_float_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.name , packet1.value );
mavlink_msg_named_value_float_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_named_value_float_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_named_value_float_send(MAVLINK_COMM_1 , packet1.time_boot_ms , packet1.name , packet1.value );
mavlink_msg_named_value_float_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_named_value_int(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_named_value_int_t packet_in = {
963497464,
963497672,
"IJKLMNOPQ",
};
mavlink_named_value_int_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.time_boot_ms = packet_in.time_boot_ms;
packet1.value = packet_in.value;
mav_array_memcpy(packet1.name, packet_in.name, sizeof(char)*10);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_named_value_int_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_named_value_int_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_named_value_int_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.name , packet1.value );
mavlink_msg_named_value_int_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_named_value_int_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.name , packet1.value );
mavlink_msg_named_value_int_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_named_value_int_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_named_value_int_send(MAVLINK_COMM_1 , packet1.time_boot_ms , packet1.name , packet1.value );
mavlink_msg_named_value_int_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_statustext(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_statustext_t packet_in = {
5,
"BCDEFGHIJKLMNOPQRSTUVWXYZABCDEFGHIJKLMNOPQRSTUVWX",
};
mavlink_statustext_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.severity = packet_in.severity;
mav_array_memcpy(packet1.text, packet_in.text, sizeof(char)*50);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_statustext_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_statustext_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_statustext_pack(system_id, component_id, &msg , packet1.severity , packet1.text );
mavlink_msg_statustext_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_statustext_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.severity , packet1.text );
mavlink_msg_statustext_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_statustext_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_statustext_send(MAVLINK_COMM_1 , packet1.severity , packet1.text );
mavlink_msg_statustext_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_debug(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_debug_t packet_in = {
963497464,
45.0,
29,
};
mavlink_debug_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.time_boot_ms = packet_in.time_boot_ms;
packet1.value = packet_in.value;
packet1.ind = packet_in.ind;
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_debug_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_debug_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_debug_pack(system_id, component_id, &msg , packet1.time_boot_ms , packet1.ind , packet1.value );
mavlink_msg_debug_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_debug_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.time_boot_ms , packet1.ind , packet1.value );
mavlink_msg_debug_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_debug_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_debug_send(MAVLINK_COMM_1 , packet1.time_boot_ms , packet1.ind , packet1.value );
mavlink_msg_debug_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_common(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_test_heartbeat(system_id, component_id, last_msg);
mavlink_test_sys_status(system_id, component_id, last_msg);
mavlink_test_system_time(system_id, component_id, last_msg);
mavlink_test_ping(system_id, component_id, last_msg);
mavlink_test_change_operator_control(system_id, component_id, last_msg);
mavlink_test_change_operator_control_ack(system_id, component_id, last_msg);
mavlink_test_auth_key(system_id, component_id, last_msg);
mavlink_test_set_mode(system_id, component_id, last_msg);
mavlink_test_param_request_read(system_id, component_id, last_msg);
mavlink_test_param_request_list(system_id, component_id, last_msg);
mavlink_test_param_value(system_id, component_id, last_msg);
mavlink_test_param_set(system_id, component_id, last_msg);
mavlink_test_gps_raw_int(system_id, component_id, last_msg);
mavlink_test_gps_status(system_id, component_id, last_msg);
mavlink_test_scaled_imu(system_id, component_id, last_msg);
mavlink_test_raw_imu(system_id, component_id, last_msg);
mavlink_test_raw_pressure(system_id, component_id, last_msg);
mavlink_test_scaled_pressure(system_id, component_id, last_msg);
mavlink_test_attitude(system_id, component_id, last_msg);
mavlink_test_attitude_quaternion(system_id, component_id, last_msg);
mavlink_test_local_position_ned(system_id, component_id, last_msg);
mavlink_test_global_position_int(system_id, component_id, last_msg);
mavlink_test_rc_channels_scaled(system_id, component_id, last_msg);
mavlink_test_rc_channels_raw(system_id, component_id, last_msg);
mavlink_test_servo_output_raw(system_id, component_id, last_msg);
mavlink_test_mission_request_partial_list(system_id, component_id, last_msg);
mavlink_test_mission_write_partial_list(system_id, component_id, last_msg);
mavlink_test_mission_item(system_id, component_id, last_msg);
mavlink_test_mission_request(system_id, component_id, last_msg);
mavlink_test_mission_set_current(system_id, component_id, last_msg);
mavlink_test_mission_current(system_id, component_id, last_msg);
mavlink_test_mission_request_list(system_id, component_id, last_msg);
mavlink_test_mission_count(system_id, component_id, last_msg);
mavlink_test_mission_clear_all(system_id, component_id, last_msg);
mavlink_test_mission_item_reached(system_id, component_id, last_msg);
mavlink_test_mission_ack(system_id, component_id, last_msg);
mavlink_test_set_gps_global_origin(system_id, component_id, last_msg);
mavlink_test_gps_global_origin(system_id, component_id, last_msg);
mavlink_test_set_local_position_setpoint(system_id, component_id, last_msg);
mavlink_test_local_position_setpoint(system_id, component_id, last_msg);
mavlink_test_global_position_setpoint_int(system_id, component_id, last_msg);
mavlink_test_set_global_position_setpoint_int(system_id, component_id, last_msg);
mavlink_test_safety_set_allowed_area(system_id, component_id, last_msg);
mavlink_test_safety_allowed_area(system_id, component_id, last_msg);
mavlink_test_set_roll_pitch_yaw_thrust(system_id, component_id, last_msg);
mavlink_test_set_roll_pitch_yaw_speed_thrust(system_id, component_id, last_msg);
mavlink_test_roll_pitch_yaw_thrust_setpoint(system_id, component_id, last_msg);
mavlink_test_roll_pitch_yaw_speed_thrust_setpoint(system_id, component_id, last_msg);
mavlink_test_set_quad_motors_setpoint(system_id, component_id, last_msg);
mavlink_test_set_quad_swarm_roll_pitch_yaw_thrust(system_id, component_id, last_msg);
mavlink_test_nav_controller_output(system_id, component_id, last_msg);
mavlink_test_state_correction(system_id, component_id, last_msg);
mavlink_test_request_data_stream(system_id, component_id, last_msg);
mavlink_test_data_stream(system_id, component_id, last_msg);
mavlink_test_manual_control(system_id, component_id, last_msg);
mavlink_test_rc_channels_override(system_id, component_id, last_msg);
mavlink_test_vfr_hud(system_id, component_id, last_msg);
mavlink_test_command_long(system_id, component_id, last_msg);
mavlink_test_command_ack(system_id, component_id, last_msg);
mavlink_test_local_position_ned_system_global_offset(system_id, component_id, last_msg);
mavlink_test_hil_state(system_id, component_id, last_msg);
mavlink_test_hil_controls(system_id, component_id, last_msg);
mavlink_test_hil_rc_inputs_raw(system_id, component_id, last_msg);
mavlink_test_optical_flow(system_id, component_id, last_msg);
mavlink_test_global_vision_position_estimate(system_id, component_id, last_msg);
mavlink_test_vision_position_estimate(system_id, component_id, last_msg);
mavlink_test_vision_speed_estimate(system_id, component_id, last_msg);
mavlink_test_vicon_position_estimate(system_id, component_id, last_msg);
mavlink_test_memory_vect(system_id, component_id, last_msg);
mavlink_test_debug_vect(system_id, component_id, last_msg);
mavlink_test_named_value_float(system_id, component_id, last_msg);
mavlink_test_named_value_int(system_id, component_id, last_msg);
mavlink_test_statustext(system_id, component_id, last_msg);
mavlink_test_debug(system_id, component_id, last_msg);
}
 
#ifdef __cplusplus
}
#endif // __cplusplus
#endif // COMMON_TESTSUITE_H
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v1.0/common/version.h
0,0 → 1,12
/** @file
* @brief MAVLink comm protocol built from common.xml
* @see http://pixhawk.ethz.ch/software/mavlink
*/
#ifndef MAVLINK_VERSION_H
#define MAVLINK_VERSION_H
 
#define MAVLINK_BUILD_DATE "Mon Apr 30 11:40:12 2012"
#define MAVLINK_WIRE_PROTOCOL_VERSION "1.0"
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 101
#endif // MAVLINK_VERSION_H
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v1.0/matrixpilot/matrixpilot.h
0,0 → 1,53
/** @file
* @brief MAVLink comm protocol generated from matrixpilot.xml
* @see http://qgroundcontrol.org/mavlink/
*/
#ifndef MATRIXPILOT_H
#define MATRIXPILOT_H
 
#ifdef __cplusplus
extern "C" {
#endif
 
// MESSAGE LENGTHS AND CRCS
 
#ifndef MAVLINK_MESSAGE_LENGTHS
#define MAVLINK_MESSAGE_LENGTHS {9, 31, 12, 0, 14, 28, 3, 32, 0, 0, 0, 6, 0, 0, 0, 0, 0, 0, 0, 0, 20, 2, 25, 23, 30, 101, 22, 26, 16, 14, 28, 32, 28, 28, 22, 22, 21, 6, 6, 37, 4, 4, 2, 2, 4, 2, 2, 3, 13, 12, 19, 17, 15, 15, 27, 25, 18, 18, 20, 20, 9, 54, 26, 0, 36, 0, 6, 4, 0, 21, 18, 0, 0, 0, 20, 0, 33, 3, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 28, 56, 42, 33, 0, 0, 0, 0, 0, 0, 0, 26, 32, 32, 20, 32, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 36, 30, 18, 18, 51, 9, 0}
#endif
 
#ifndef MAVLINK_MESSAGE_CRCS
#define MAVLINK_MESSAGE_CRCS {50, 124, 137, 0, 237, 217, 104, 119, 0, 0, 0, 89, 0, 0, 0, 0, 0, 0, 0, 0, 214, 159, 220, 168, 24, 23, 170, 144, 67, 115, 39, 246, 185, 104, 237, 244, 222, 212, 9, 254, 230, 28, 28, 132, 221, 232, 11, 153, 41, 39, 214, 223, 141, 33, 15, 3, 100, 24, 239, 238, 30, 200, 183, 0, 130, 0, 148, 21, 0, 52, 124, 0, 0, 0, 20, 0, 152, 143, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 231, 183, 63, 54, 0, 0, 0, 0, 0, 0, 0, 175, 102, 158, 208, 56, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 204, 49, 170, 44, 83, 46, 0}
#endif
 
#ifndef MAVLINK_MESSAGE_INFO
#define MAVLINK_MESSAGE_INFO {MAVLINK_MESSAGE_INFO_HEARTBEAT, MAVLINK_MESSAGE_INFO_SYS_STATUS, MAVLINK_MESSAGE_INFO_SYSTEM_TIME, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_PING, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL_ACK, MAVLINK_MESSAGE_INFO_AUTH_KEY, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_SET_MODE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_READ, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_LIST, MAVLINK_MESSAGE_INFO_PARAM_VALUE, MAVLINK_MESSAGE_INFO_PARAM_SET, MAVLINK_MESSAGE_INFO_GPS_RAW_INT, MAVLINK_MESSAGE_INFO_GPS_STATUS, MAVLINK_MESSAGE_INFO_SCALED_IMU, MAVLINK_MESSAGE_INFO_RAW_IMU, MAVLINK_MESSAGE_INFO_RAW_PRESSURE, MAVLINK_MESSAGE_INFO_SCALED_PRESSURE, MAVLINK_MESSAGE_INFO_ATTITUDE, MAVLINK_MESSAGE_INFO_ATTITUDE_QUATERNION, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_INT, MAVLINK_MESSAGE_INFO_RC_CHANNELS_SCALED, MAVLINK_MESSAGE_INFO_RC_CHANNELS_RAW, MAVLINK_MESSAGE_INFO_SERVO_OUTPUT_RAW, MAVLINK_MESSAGE_INFO_MISSION_REQUEST_PARTIAL_LIST, MAVLINK_MESSAGE_INFO_MISSION_WRITE_PARTIAL_LIST, MAVLINK_MESSAGE_INFO_MISSION_ITEM, MAVLINK_MESSAGE_INFO_MISSION_REQUEST, MAVLINK_MESSAGE_INFO_MISSION_SET_CURRENT, MAVLINK_MESSAGE_INFO_MISSION_CURRENT, MAVLINK_MESSAGE_INFO_MISSION_REQUEST_LIST, MAVLINK_MESSAGE_INFO_MISSION_COUNT, MAVLINK_MESSAGE_INFO_MISSION_CLEAR_ALL, MAVLINK_MESSAGE_INFO_MISSION_ITEM_REACHED, MAVLINK_MESSAGE_INFO_MISSION_ACK, MAVLINK_MESSAGE_INFO_SET_GPS_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_GPS_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_SET_LOCAL_POSITION_SETPOINT, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_SETPOINT, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_SETPOINT_INT, MAVLINK_MESSAGE_INFO_SET_GLOBAL_POSITION_SETPOINT_INT, MAVLINK_MESSAGE_INFO_SAFETY_SET_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SAFETY_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SET_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_SET_ROLL_PITCH_YAW_SPEED_THRUST, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_SET_QUAD_MOTORS_SETPOINT, MAVLINK_MESSAGE_INFO_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_NAV_CONTROLLER_OUTPUT, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_STATE_CORRECTION, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_REQUEST_DATA_STREAM, MAVLINK_MESSAGE_INFO_DATA_STREAM, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_MANUAL_CONTROL, MAVLINK_MESSAGE_INFO_RC_CHANNELS_OVERRIDE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_VFR_HUD, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_COMMAND_LONG, MAVLINK_MESSAGE_INFO_COMMAND_ACK, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET, MAVLINK_MESSAGE_INFO_HIL_STATE, MAVLINK_MESSAGE_INFO_HIL_CONTROLS, MAVLINK_MESSAGE_INFO_HIL_RC_INPUTS_RAW, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_OPTICAL_FLOW, MAVLINK_MESSAGE_INFO_GLOBAL_VISION_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_VISION_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_VISION_SPEED_ESTIMATE, MAVLINK_MESSAGE_INFO_VICON_POSITION_ESTIMATE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_MEMORY_VECT, MAVLINK_MESSAGE_INFO_DEBUG_VECT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_FLOAT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_INT, MAVLINK_MESSAGE_INFO_STATUSTEXT, MAVLINK_MESSAGE_INFO_DEBUG, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}}
#endif
 
#include "../protocol.h"
 
#define MAVLINK_ENABLED_MATRIXPILOT
 
#include "../common/common.h"
 
// MAVLINK VERSION
 
#ifndef MAVLINK_VERSION
#define MAVLINK_VERSION 2
#endif
 
#if (MAVLINK_VERSION == 0)
#undef MAVLINK_VERSION
#define MAVLINK_VERSION 2
#endif
 
// ENUM DEFINITIONS
 
 
 
// MESSAGE DEFINITIONS
 
 
#ifdef __cplusplus
}
#endif // __cplusplus
#endif // MATRIXPILOT_H
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v1.0/matrixpilot/mavlink.h
0,0 → 1,27
/** @file
* @brief MAVLink comm protocol built from matrixpilot.xml
* @see http://pixhawk.ethz.ch/software/mavlink
*/
#ifndef MAVLINK_H
#define MAVLINK_H
 
#ifndef MAVLINK_STX
#define MAVLINK_STX 254
#endif
 
#ifndef MAVLINK_ENDIAN
#define MAVLINK_ENDIAN MAVLINK_LITTLE_ENDIAN
#endif
 
#ifndef MAVLINK_ALIGNED_FIELDS
#define MAVLINK_ALIGNED_FIELDS 1
#endif
 
#ifndef MAVLINK_CRC_EXTRA
#define MAVLINK_CRC_EXTRA 1
#endif
 
#include "version.h"
#include "matrixpilot.h"
 
#endif // MAVLINK_H
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v1.0/matrixpilot/testsuite.h
0,0 → 1,36
/** @file
* @brief MAVLink comm protocol testsuite generated from matrixpilot.xml
* @see http://qgroundcontrol.org/mavlink/
*/
#ifndef MATRIXPILOT_TESTSUITE_H
#define MATRIXPILOT_TESTSUITE_H
 
#ifdef __cplusplus
extern "C" {
#endif
 
#ifndef MAVLINK_TEST_ALL
#define MAVLINK_TEST_ALL
static void mavlink_test_common(uint8_t, uint8_t, mavlink_message_t *last_msg);
static void mavlink_test_matrixpilot(uint8_t, uint8_t, mavlink_message_t *last_msg);
 
static void mavlink_test_all(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_test_common(system_id, component_id, last_msg);
mavlink_test_matrixpilot(system_id, component_id, last_msg);
}
#endif
 
#include "../common/testsuite.h"
 
 
 
static void mavlink_test_matrixpilot(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
 
}
 
#ifdef __cplusplus
}
#endif // __cplusplus
#endif // MATRIXPILOT_TESTSUITE_H
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v1.0/matrixpilot/version.h
0,0 → 1,12
/** @file
* @brief MAVLink comm protocol built from matrixpilot.xml
* @see http://pixhawk.ethz.ch/software/mavlink
*/
#ifndef MAVLINK_VERSION_H
#define MAVLINK_VERSION_H
 
#define MAVLINK_BUILD_DATE "Fri Apr 20 12:22:49 2012"
#define MAVLINK_WIRE_PROTOCOL_VERSION "1.0"
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 101
#endif // MAVLINK_VERSION_H
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v1.0/mavlink_helpers.h
0,0 → 1,507
#ifndef _MAVLINK_HELPERS_H_
#define _MAVLINK_HELPERS_H_
 
#include "string.h"
#include "checksum.h"
#include "mavlink_types.h"
 
#ifndef MAVLINK_HELPER
#define MAVLINK_HELPER
#endif
 
/*
internal function to give access to the channel status for each channel
*/
MAVLINK_HELPER mavlink_status_t* mavlink_get_channel_status(uint8_t chan)
{
static mavlink_status_t m_mavlink_status[MAVLINK_COMM_NUM_BUFFERS];
return &m_mavlink_status[chan];
}
 
/*
internal function to give access to the channel buffer for each channel
*/
MAVLINK_HELPER mavlink_message_t* mavlink_get_channel_buffer(uint8_t chan)
{
#if MAVLINK_EXTERNAL_RX_BUFFER
// No m_mavlink_message array defined in function,
// has to be defined externally
#ifndef m_mavlink_message
#error ERROR: IF #define MAVLINK_EXTERNAL_RX_BUFFER IS SET, THE BUFFER HAS TO BE ALLOCATED OUTSIDE OF THIS FUNCTION (mavlink_message_t m_mavlink_buffer[MAVLINK_COMM_NUM_BUFFERS];)
#endif
#else
static mavlink_message_t m_mavlink_buffer[MAVLINK_COMM_NUM_BUFFERS];
#endif
return &m_mavlink_buffer[chan];
}
 
/**
* @brief Finalize a MAVLink message with channel assignment
*
* This function calculates the checksum and sets length and aircraft id correctly.
* It assumes that the message id and the payload are already correctly set. This function
* can also be used if the message header has already been written before (as in mavlink_msg_xxx_pack
* instead of mavlink_msg_xxx_pack_headerless), it just introduces little extra overhead.
*
* @param msg Message to finalize
* @param system_id Id of the sending (this) system, 1-127
* @param length Message length
*/
#if MAVLINK_CRC_EXTRA
MAVLINK_HELPER uint16_t mavlink_finalize_message_chan(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id,
uint8_t chan, uint8_t length, uint8_t crc_extra)
#else
MAVLINK_HELPER uint16_t mavlink_finalize_message_chan(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id,
uint8_t chan, uint8_t length)
#endif
{
// This code part is the same for all messages;
uint16_t checksum;
msg->magic = MAVLINK_STX;
msg->len = length;
msg->sysid = system_id;
msg->compid = component_id;
// One sequence number per component
msg->seq = mavlink_get_channel_status(chan)->current_tx_seq;
mavlink_get_channel_status(chan)->current_tx_seq = mavlink_get_channel_status(chan)->current_tx_seq+1;
checksum = crc_calculate((uint8_t*)&msg->len, length + MAVLINK_CORE_HEADER_LEN);
#if MAVLINK_CRC_EXTRA
crc_accumulate(crc_extra, &checksum);
#endif
mavlink_ck_a(msg) = (uint8_t)(checksum & 0xFF);
mavlink_ck_b(msg) = (uint8_t)(checksum >> 8);
 
return length + MAVLINK_NUM_NON_PAYLOAD_BYTES;
}
 
 
/**
* @brief Finalize a MAVLink message with MAVLINK_COMM_0 as default channel
*/
#if MAVLINK_CRC_EXTRA
MAVLINK_HELPER uint16_t mavlink_finalize_message(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id,
uint8_t length, uint8_t crc_extra)
{
return mavlink_finalize_message_chan(msg, system_id, component_id, MAVLINK_COMM_0, length, crc_extra);
}
#else
MAVLINK_HELPER uint16_t mavlink_finalize_message(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id,
uint8_t length)
{
return mavlink_finalize_message_chan(msg, system_id, component_id, MAVLINK_COMM_0, length);
}
#endif
 
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
MAVLINK_HELPER void _mavlink_send_uart(mavlink_channel_t chan, const char *buf, uint16_t len);
 
/**
* @brief Finalize a MAVLink message with channel assignment and send
*/
#if MAVLINK_CRC_EXTRA
MAVLINK_HELPER void _mav_finalize_message_chan_send(mavlink_channel_t chan, uint8_t msgid, const char *packet,
uint8_t length, uint8_t crc_extra)
#else
MAVLINK_HELPER void _mav_finalize_message_chan_send(mavlink_channel_t chan, uint8_t msgid, const char *packet, uint8_t length)
#endif
{
uint16_t checksum;
uint8_t buf[MAVLINK_NUM_HEADER_BYTES];
uint8_t ck[2];
mavlink_status_t *status = mavlink_get_channel_status(chan);
buf[0] = MAVLINK_STX;
buf[1] = length;
buf[2] = status->current_tx_seq;
buf[3] = mavlink_system.sysid;
buf[4] = mavlink_system.compid;
buf[5] = msgid;
status->current_tx_seq++;
checksum = crc_calculate((uint8_t*)&buf[1], MAVLINK_CORE_HEADER_LEN);
crc_accumulate_buffer(&checksum, packet, length);
#if MAVLINK_CRC_EXTRA
crc_accumulate(crc_extra, &checksum);
#endif
ck[0] = (uint8_t)(checksum & 0xFF);
ck[1] = (uint8_t)(checksum >> 8);
 
MAVLINK_START_UART_SEND(chan, MAVLINK_NUM_NON_PAYLOAD_BYTES + (uint16_t)length);
_mavlink_send_uart(chan, (const char *)buf, MAVLINK_NUM_HEADER_BYTES);
_mavlink_send_uart(chan, packet, length);
_mavlink_send_uart(chan, (const char *)ck, 2);
MAVLINK_END_UART_SEND(chan, MAVLINK_NUM_NON_PAYLOAD_BYTES + (uint16_t)length);
}
#endif // MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
/**
* @brief Pack a message to send it over a serial byte stream
*/
MAVLINK_HELPER uint16_t mavlink_msg_to_send_buffer(uint8_t *buffer, const mavlink_message_t *msg)
{
memcpy(buffer, (const uint8_t *)&msg->magic, MAVLINK_NUM_NON_PAYLOAD_BYTES + (uint16_t)msg->len);
return MAVLINK_NUM_NON_PAYLOAD_BYTES + (uint16_t)msg->len;
}
 
union __mavlink_bitfield {
uint8_t uint8;
int8_t int8;
uint16_t uint16;
int16_t int16;
uint32_t uint32;
int32_t int32;
};
 
 
MAVLINK_HELPER void mavlink_start_checksum(mavlink_message_t* msg)
{
crc_init(&msg->checksum);
}
 
MAVLINK_HELPER void mavlink_update_checksum(mavlink_message_t* msg, uint8_t c)
{
crc_accumulate(c, &msg->checksum);
}
 
/**
* This is a convenience function which handles the complete MAVLink parsing.
* the function will parse one byte at a time and return the complete packet once
* it could be successfully decoded. Checksum and other failures will be silently
* ignored.
*
* @param chan ID of the current channel. This allows to parse different channels with this function.
* a channel is not a physical message channel like a serial port, but a logic partition of
* the communication streams in this case. COMM_NB is the limit for the number of channels
* on MCU (e.g. ARM7), while COMM_NB_HIGH is the limit for the number of channels in Linux/Windows
* @param c The char to barse
*
* @param returnMsg NULL if no message could be decoded, the message data else
* @return 0 if no message could be decoded, 1 else
*
* A typical use scenario of this function call is:
*
* @code
* #include <inttypes.h> // For fixed-width uint8_t type
*
* mavlink_message_t msg;
* int chan = 0;
*
*
* while(serial.bytesAvailable > 0)
* {
* uint8_t byte = serial.getNextByte();
* if (mavlink_parse_char(chan, byte, &msg))
* {
* printf("Received message with ID %d, sequence: %d from component %d of system %d", msg.msgid, msg.seq, msg.compid, msg.sysid);
* }
* }
*
*
* @endcode
*/
MAVLINK_HELPER uint8_t mavlink_parse_char(uint8_t chan, uint8_t c, mavlink_message_t* r_message, mavlink_status_t* r_mavlink_status)
{
/*
default message crc function. You can override this per-system to
put this data in a different memory segment
*/
#if MAVLINK_CRC_EXTRA
#ifndef MAVLINK_MESSAGE_CRC
static const uint8_t mavlink_message_crcs[256] = MAVLINK_MESSAGE_CRCS;
#define MAVLINK_MESSAGE_CRC(msgid) mavlink_message_crcs[msgid]
#endif
#endif
 
mavlink_message_t* rxmsg = mavlink_get_channel_buffer(chan); ///< The currently decoded message
mavlink_status_t* status = mavlink_get_channel_status(chan); ///< The current decode status
int bufferIndex = 0;
 
status->msg_received = 0;
 
switch (status->parse_state)
{
case MAVLINK_PARSE_STATE_UNINIT:
case MAVLINK_PARSE_STATE_IDLE:
if (c == MAVLINK_STX)
{
status->parse_state = MAVLINK_PARSE_STATE_GOT_STX;
rxmsg->len = 0;
rxmsg->magic = c;
mavlink_start_checksum(rxmsg);
}
break;
 
case MAVLINK_PARSE_STATE_GOT_STX:
if (status->msg_received
/* Support shorter buffers than the
default maximum packet size */
#if (MAVLINK_MAX_PAYLOAD_LEN < 255)
|| c > MAVLINK_MAX_PAYLOAD_LEN
#endif
)
{
status->buffer_overrun++;
status->parse_error++;
status->msg_received = 0;
status->parse_state = MAVLINK_PARSE_STATE_IDLE;
}
else
{
// NOT counting STX, LENGTH, SEQ, SYSID, COMPID, MSGID, CRC1 and CRC2
rxmsg->len = c;
status->packet_idx = 0;
mavlink_update_checksum(rxmsg, c);
status->parse_state = MAVLINK_PARSE_STATE_GOT_LENGTH;
}
break;
 
case MAVLINK_PARSE_STATE_GOT_LENGTH:
rxmsg->seq = c;
mavlink_update_checksum(rxmsg, c);
status->parse_state = MAVLINK_PARSE_STATE_GOT_SEQ;
break;
 
case MAVLINK_PARSE_STATE_GOT_SEQ:
rxmsg->sysid = c;
mavlink_update_checksum(rxmsg, c);
status->parse_state = MAVLINK_PARSE_STATE_GOT_SYSID;
break;
 
case MAVLINK_PARSE_STATE_GOT_SYSID:
rxmsg->compid = c;
mavlink_update_checksum(rxmsg, c);
status->parse_state = MAVLINK_PARSE_STATE_GOT_COMPID;
break;
 
case MAVLINK_PARSE_STATE_GOT_COMPID:
rxmsg->msgid = c;
mavlink_update_checksum(rxmsg, c);
if (rxmsg->len == 0)
{
status->parse_state = MAVLINK_PARSE_STATE_GOT_PAYLOAD;
}
else
{
status->parse_state = MAVLINK_PARSE_STATE_GOT_MSGID;
}
break;
 
case MAVLINK_PARSE_STATE_GOT_MSGID:
_MAV_PAYLOAD_NON_CONST(rxmsg)[status->packet_idx++] = (char)c;
mavlink_update_checksum(rxmsg, c);
if (status->packet_idx == rxmsg->len)
{
status->parse_state = MAVLINK_PARSE_STATE_GOT_PAYLOAD;
}
break;
 
case MAVLINK_PARSE_STATE_GOT_PAYLOAD:
#if MAVLINK_CRC_EXTRA
mavlink_update_checksum(rxmsg, MAVLINK_MESSAGE_CRC(rxmsg->msgid));
#endif
if (c != (rxmsg->checksum & 0xFF)) {
// Check first checksum byte
status->parse_error++;
status->msg_received = 0;
status->parse_state = MAVLINK_PARSE_STATE_IDLE;
if (c == MAVLINK_STX)
{
status->parse_state = MAVLINK_PARSE_STATE_GOT_STX;
rxmsg->len = 0;
mavlink_start_checksum(rxmsg);
}
}
else
{
status->parse_state = MAVLINK_PARSE_STATE_GOT_CRC1;
_MAV_PAYLOAD_NON_CONST(rxmsg)[status->packet_idx] = (char)c;
}
break;
 
case MAVLINK_PARSE_STATE_GOT_CRC1:
if (c != (rxmsg->checksum >> 8)) {
// Check second checksum byte
status->parse_error++;
status->msg_received = 0;
status->parse_state = MAVLINK_PARSE_STATE_IDLE;
if (c == MAVLINK_STX)
{
status->parse_state = MAVLINK_PARSE_STATE_GOT_STX;
rxmsg->len = 0;
mavlink_start_checksum(rxmsg);
}
}
else
{
// Successfully got message
status->msg_received = 1;
status->parse_state = MAVLINK_PARSE_STATE_IDLE;
_MAV_PAYLOAD_NON_CONST(rxmsg)[status->packet_idx+1] = (char)c;
memcpy(r_message, rxmsg, sizeof(mavlink_message_t));
}
break;
}
 
bufferIndex++;
// If a message has been sucessfully decoded, check index
if (status->msg_received == 1)
{
//while(status->current_seq != rxmsg->seq)
//{
// status->packet_rx_drop_count++;
// status->current_seq++;
//}
status->current_rx_seq = rxmsg->seq;
// Initial condition: If no packet has been received so far, drop count is undefined
if (status->packet_rx_success_count == 0) status->packet_rx_drop_count = 0;
// Count this packet as received
status->packet_rx_success_count++;
}
 
r_mavlink_status->current_rx_seq = status->current_rx_seq+1;
r_mavlink_status->packet_rx_success_count = status->packet_rx_success_count;
r_mavlink_status->packet_rx_drop_count = status->parse_error;
status->parse_error = 0;
return status->msg_received;
}
 
/**
* @brief Put a bitfield of length 1-32 bit into the buffer
*
* @param b the value to add, will be encoded in the bitfield
* @param bits number of bits to use to encode b, e.g. 1 for boolean, 2, 3, etc.
* @param packet_index the position in the packet (the index of the first byte to use)
* @param bit_index the position in the byte (the index of the first bit to use)
* @param buffer packet buffer to write into
* @return new position of the last used byte in the buffer
*/
MAVLINK_HELPER uint8_t put_bitfield_n_by_index(int32_t b, uint8_t bits, uint8_t packet_index, uint8_t bit_index, uint8_t* r_bit_index, uint8_t* buffer)
{
uint16_t bits_remain = bits;
// Transform number into network order
int32_t v;
uint8_t i_bit_index, i_byte_index, curr_bits_n;
#if MAVLINK_NEED_BYTE_SWAP
union {
int32_t i;
uint8_t b[4];
} bin, bout;
bin.i = b;
bout.b[0] = bin.b[3];
bout.b[1] = bin.b[2];
bout.b[2] = bin.b[1];
bout.b[3] = bin.b[0];
v = bout.i;
#else
v = b;
#endif
 
// buffer in
// 01100000 01000000 00000000 11110001
// buffer out
// 11110001 00000000 01000000 01100000
 
// Existing partly filled byte (four free slots)
// 0111xxxx
 
// Mask n free bits
// 00001111 = 2^0 + 2^1 + 2^2 + 2^3 = 2^n - 1
// = ((uint32_t)(1 << n)) - 1; // = 2^n - 1
 
// Shift n bits into the right position
// out = in >> n;
 
// Mask and shift bytes
i_bit_index = bit_index;
i_byte_index = packet_index;
if (bit_index > 0)
{
// If bits were available at start, they were available
// in the byte before the current index
i_byte_index--;
}
 
// While bits have not been packed yet
while (bits_remain > 0)
{
// Bits still have to be packed
// there can be more than 8 bits, so
// we might have to pack them into more than one byte
 
// First pack everything we can into the current 'open' byte
//curr_bits_n = bits_remain << 3; // Equals bits_remain mod 8
//FIXME
if (bits_remain <= (uint8_t)(8 - i_bit_index))
{
// Enough space
curr_bits_n = (uint8_t)bits_remain;
}
else
{
curr_bits_n = (8 - i_bit_index);
}
// Pack these n bits into the current byte
// Mask out whatever was at that position with ones (xxx11111)
buffer[i_byte_index] &= (0xFF >> (8 - curr_bits_n));
// Put content to this position, by masking out the non-used part
buffer[i_byte_index] |= ((0x00 << curr_bits_n) & v);
// Increment the bit index
i_bit_index += curr_bits_n;
 
// Now proceed to the next byte, if necessary
bits_remain -= curr_bits_n;
if (bits_remain > 0)
{
// Offer another 8 bits / one byte
i_byte_index++;
i_bit_index = 0;
}
}
*r_bit_index = i_bit_index;
// If a partly filled byte is present, mark this as consumed
if (i_bit_index != 7) i_byte_index++;
return i_byte_index - packet_index;
}
 
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
// To make MAVLink work on your MCU, define comm_send_ch() if you wish
// to send 1 byte at a time, or MAVLINK_SEND_UART_BYTES() to send a
// whole packet at a time
 
/*
 
#include "mavlink_types.h"
 
void comm_send_ch(mavlink_channel_t chan, uint8_t ch)
{
if (chan == MAVLINK_COMM_0)
{
uart0_transmit(ch);
}
if (chan == MAVLINK_COMM_1)
{
uart1_transmit(ch);
}
}
*/
 
MAVLINK_HELPER void _mavlink_send_uart(mavlink_channel_t chan, const char *buf, uint16_t len)
{
#ifdef MAVLINK_SEND_UART_BYTES
/* this is the more efficient approach, if the platform
defines it */
MAVLINK_SEND_UART_BYTES(chan, (uint8_t *)buf, len);
#else
/* fallback to one byte at a time */
uint16_t i;
for (i = 0; i < len; i++) {
comm_send_ch(chan, (uint8_t)buf[i]);
}
#endif
}
#endif // MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
#endif /* _MAVLINK_HELPERS_H_ */
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v1.0/mavlink_protobuf_manager.hpp
0,0 → 1,377
#ifndef MAVLINKPROTOBUFMANAGER_HPP
#define MAVLINKPROTOBUFMANAGER_HPP
 
#include <deque>
#include <google/protobuf/message.h>
#include <iostream>
#include <tr1/memory>
 
#include <checksum.h>
#include <common/mavlink.h>
#include <mavlink_types.h>
#include <pixhawk/pixhawk.pb.h>
 
namespace mavlink
{
 
class ProtobufManager
{
public:
ProtobufManager()
: mRegisteredTypeCount(0)
, mStreamID(0)
, mVerbose(false)
, kExtendedHeaderSize(MAVLINK_EXTENDED_HEADER_LEN)
, kExtendedPayloadMaxSize(MAVLINK_MAX_EXTENDED_PAYLOAD_LEN)
{
// register GLOverlay
{
std::tr1::shared_ptr<px::GLOverlay> msg(new px::GLOverlay);
registerType(msg);
}
 
// register ObstacleList
{
std::tr1::shared_ptr<px::ObstacleList> msg(new px::ObstacleList);
registerType(msg);
}
 
// register ObstacleMap
{
std::tr1::shared_ptr<px::ObstacleMap> msg(new px::ObstacleMap);
registerType(msg);
}
 
// register Path
{
std::tr1::shared_ptr<px::Path> msg(new px::Path);
registerType(msg);
}
 
// register PointCloudXYZI
{
std::tr1::shared_ptr<px::PointCloudXYZI> msg(new px::PointCloudXYZI);
registerType(msg);
}
 
// register PointCloudXYZRGB
{
std::tr1::shared_ptr<px::PointCloudXYZRGB> msg(new px::PointCloudXYZRGB);
registerType(msg);
}
 
// register RGBDImage
{
std::tr1::shared_ptr<px::RGBDImage> msg(new px::RGBDImage);
registerType(msg);
}
 
srand(time(NULL));
mStreamID = rand() + 1;
}
 
bool fragmentMessage(uint8_t system_id, uint8_t component_id,
uint8_t target_system, uint8_t target_component,
const google::protobuf::Message& protobuf_msg,
std::vector<mavlink_extended_message_t>& fragments) const
{
TypeMap::const_iterator it = mTypeMap.find(protobuf_msg.GetTypeName());
if (it == mTypeMap.end())
{
std::cout << "# WARNING: Protobuf message with type "
<< protobuf_msg.GetTypeName() << " is not registered."
<< std::endl;
return false;
}
 
uint8_t typecode = it->second;
 
std::string data = protobuf_msg.SerializeAsString();
 
int fragmentCount = (protobuf_msg.ByteSize() + kExtendedPayloadMaxSize - 1) / kExtendedPayloadMaxSize;
unsigned int offset = 0;
 
for (int i = 0; i < fragmentCount; ++i)
{
mavlink_extended_message_t fragment;
 
// write extended header data
uint8_t* payload = reinterpret_cast<uint8_t*>(fragment.base_msg.payload64);
unsigned int length = 0;
uint8_t flags = 0;
 
if (i < fragmentCount - 1)
{
length = kExtendedPayloadMaxSize;
flags |= 0x1;
}
else
{
length = protobuf_msg.ByteSize() - kExtendedPayloadMaxSize * (fragmentCount - 1);
}
 
memcpy(payload, &target_system, 1);
memcpy(payload + 1, &target_component, 1);
memcpy(payload + 2, &typecode, 1);
memcpy(payload + 3, &length, 4);
memcpy(payload + 7, &mStreamID, 2);
memcpy(payload + 9, &offset, 4);
memcpy(payload + 13, &flags, 1);
 
fragment.base_msg.msgid = MAVLINK_MSG_ID_EXTENDED_MESSAGE;
mavlink_finalize_message(&fragment.base_msg, system_id, component_id, kExtendedHeaderSize, 0);
// write extended payload data
fragment.extended_payload_len = length;
memcpy(fragment.extended_payload, &data[offset], length);
 
fragments.push_back(fragment);
offset += length;
}
 
if (mVerbose)
{
std::cerr << "# INFO: Split extended message with size "
<< protobuf_msg.ByteSize() << " into "
<< fragmentCount << " fragments." << std::endl;
}
 
return true;
}
 
bool cacheFragment(mavlink_extended_message_t& msg)
{
if (!validFragment(msg))
{
if (mVerbose)
{
std::cerr << "# WARNING: Message is not a valid fragment. "
<< "Dropping message..." << std::endl;
}
return false;
}
 
// read extended header
uint8_t* payload = reinterpret_cast<uint8_t*>(msg.base_msg.payload64);
uint8_t typecode = 0;
unsigned int length = 0;
unsigned short streamID = 0;
unsigned int offset = 0;
uint8_t flags = 0;
 
memcpy(&typecode, payload + 2, 1);
memcpy(&length, payload + 3, 4);
memcpy(&streamID, payload + 7, 2);
memcpy(&offset, payload + 9, 4);
memcpy(&flags, payload + 13, 1);
 
if (typecode >= mTypeMap.size())
{
std::cout << "# WARNING: Protobuf message with type code "
<< static_cast<int>(typecode) << " is not registered." << std::endl;
return false;
}
 
bool reassemble = false;
 
FragmentQueue::iterator it = mFragmentQueue.find(streamID);
if (it == mFragmentQueue.end())
{
if (offset == 0)
{
mFragmentQueue[streamID].push_back(msg);
 
if ((flags & 0x1) != 0x1)
{
reassemble = true;
}
 
if (mVerbose)
{
std::cerr << "# INFO: Added fragment to new queue."
<< std::endl;
}
}
else
{
if (mVerbose)
{
std::cerr << "# WARNING: Message is not a valid fragment. "
<< "Dropping message..." << std::endl;
}
}
}
else
{
std::deque<mavlink_extended_message_t>& queue = it->second;
 
if (queue.empty())
{
if (offset == 0)
{
queue.push_back(msg);
 
if ((flags & 0x1) != 0x1)
{
reassemble = true;
}
}
else
{
if (mVerbose)
{
std::cerr << "# WARNING: Message is not a valid fragment. "
<< "Dropping message..." << std::endl;
}
}
}
else
{
if (fragmentDataSize(queue.back()) + fragmentOffset(queue.back()) != offset)
{
if (mVerbose)
{
std::cerr << "# WARNING: Previous fragment(s) have been lost. "
<< "Dropping message and clearing queue..." << std::endl;
}
queue.clear();
}
else
{
queue.push_back(msg);
 
if ((flags & 0x1) != 0x1)
{
reassemble = true;
}
}
}
}
 
if (reassemble)
{
std::deque<mavlink_extended_message_t>& queue = mFragmentQueue[streamID];
 
std::string data;
for (size_t i = 0; i < queue.size(); ++i)
{
mavlink_extended_message_t& mavlink_msg = queue.at(i);
 
data.append(reinterpret_cast<char*>(&mavlink_msg.extended_payload[0]),
static_cast<size_t>(mavlink_msg.extended_payload_len));
}
 
mMessages.at(typecode)->ParseFromString(data);
 
mMessageAvailable.at(typecode) = true;
 
queue.clear();
 
if (mVerbose)
{
std::cerr << "# INFO: Reassembled fragments for message with typename "
<< mMessages.at(typecode)->GetTypeName() << " and size "
<< mMessages.at(typecode)->ByteSize()
<< "." << std::endl;
}
}
 
return true;
}
 
bool getMessage(std::tr1::shared_ptr<google::protobuf::Message>& msg)
{
for (size_t i = 0; i < mMessageAvailable.size(); ++i)
{
if (mMessageAvailable.at(i))
{
msg = mMessages.at(i);
mMessageAvailable.at(i) = false;
 
return true;
}
}
 
return false;
}
 
private:
void registerType(const std::tr1::shared_ptr<google::protobuf::Message>& msg)
{
mTypeMap[msg->GetTypeName()] = mRegisteredTypeCount;
++mRegisteredTypeCount;
mMessages.push_back(msg);
mMessageAvailable.push_back(false);
}
 
bool validFragment(const mavlink_extended_message_t& msg) const
{
if (msg.base_msg.magic != MAVLINK_STX ||
msg.base_msg.len != kExtendedHeaderSize ||
msg.base_msg.msgid != MAVLINK_MSG_ID_EXTENDED_MESSAGE)
{
return false;
}
 
uint16_t checksum;
checksum = crc_calculate(reinterpret_cast<const uint8_t*>(&msg.base_msg.len), MAVLINK_CORE_HEADER_LEN);
crc_accumulate_buffer(&checksum, reinterpret_cast<const char*>(&msg.base_msg.payload64), kExtendedHeaderSize);
#if MAVLINK_CRC_EXTRA
static const uint8_t mavlink_message_crcs[256] = MAVLINK_MESSAGE_CRCS;
crc_accumulate(mavlink_message_crcs[msg.base_msg.msgid], &checksum);
#endif
 
if (mavlink_ck_a(&(msg.base_msg)) != (uint8_t)(checksum & 0xFF) &&
mavlink_ck_b(&(msg.base_msg)) != (uint8_t)(checksum >> 8))
{
return false;
}
 
return true;
}
 
unsigned int fragmentDataSize(const mavlink_extended_message_t& msg) const
{
const uint8_t* payload = reinterpret_cast<const uint8_t*>(msg.base_msg.payload64);
 
return *(reinterpret_cast<const unsigned int*>(payload + 3));
}
 
unsigned int fragmentOffset(const mavlink_extended_message_t& msg) const
{
const uint8_t* payload = reinterpret_cast<const uint8_t*>(msg.base_msg.payload64);
 
return *(reinterpret_cast<const unsigned int*>(payload + 9));
}
 
int mRegisteredTypeCount;
unsigned short mStreamID;
bool mVerbose;
 
typedef std::map<std::string, uint8_t> TypeMap;
TypeMap mTypeMap;
std::vector< std::tr1::shared_ptr<google::protobuf::Message> > mMessages;
std::vector<bool> mMessageAvailable;
 
typedef std::map<unsigned short, std::deque<mavlink_extended_message_t> > FragmentQueue;
FragmentQueue mFragmentQueue;
 
const int kExtendedHeaderSize;
/**
* Extended header structure
* =========================
* byte 0 - target_system
* byte 1 - target_component
* byte 2 - extended message id (type code)
* bytes 3-6 - extended payload size in bytes
* byte 7-8 - stream ID
* byte 9-12 - fragment offset
* byte 13 - fragment flags (bit 0 - 1=more fragments, 0=last fragment)
*/
 
const int kExtendedPayloadMaxSize;
};
 
}
 
#endif
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v1.0/mavlink_types.h
0,0 → 1,158
#ifndef MAVLINK_TYPES_H_
#define MAVLINK_TYPES_H_
 
#include <inttypes.h>
 
#ifndef MAVLINK_MAX_PAYLOAD_LEN
// it is possible to override this, but be careful!
#define MAVLINK_MAX_PAYLOAD_LEN 255 ///< Maximum payload length
#endif
 
#define MAVLINK_CORE_HEADER_LEN 5 ///< Length of core header (of the comm. layer): message length (1 byte) + message sequence (1 byte) + message system id (1 byte) + message component id (1 byte) + message type id (1 byte)
#define MAVLINK_NUM_HEADER_BYTES (MAVLINK_CORE_HEADER_LEN + 1) ///< Length of all header bytes, including core and checksum
#define MAVLINK_NUM_CHECKSUM_BYTES 2
#define MAVLINK_NUM_NON_PAYLOAD_BYTES (MAVLINK_NUM_HEADER_BYTES + MAVLINK_NUM_CHECKSUM_BYTES)
 
#define MAVLINK_MAX_PACKET_LEN (MAVLINK_MAX_PAYLOAD_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES) ///< Maximum packet length
 
#define MAVLINK_MSG_ID_EXTENDED_MESSAGE 255
#define MAVLINK_EXTENDED_HEADER_LEN 14
 
#if (defined _MSC_VER) | ((defined __APPLE__) & (defined __MACH__)) | (defined __linux__)
/* full fledged 32bit++ OS */
#define MAVLINK_MAX_EXTENDED_PACKET_LEN 65507
#else
/* small microcontrollers */
#define MAVLINK_MAX_EXTENDED_PACKET_LEN 2048
#endif
 
#define MAVLINK_MAX_EXTENDED_PAYLOAD_LEN (MAVLINK_MAX_EXTENDED_PACKET_LEN - MAVLINK_EXTENDED_HEADER_LEN - MAVLINK_NUM_NON_PAYLOAD_BYTES)
 
typedef struct param_union {
union {
float param_float;
int32_t param_int32;
uint32_t param_uint32;
uint8_t param_uint8;
uint8_t bytes[4];
};
uint8_t type;
} mavlink_param_union_t;
 
typedef struct __mavlink_system {
uint8_t sysid; ///< Used by the MAVLink message_xx_send() convenience function
uint8_t compid; ///< Used by the MAVLink message_xx_send() convenience function
uint8_t type; ///< Unused, can be used by user to store the system's type
uint8_t state; ///< Unused, can be used by user to store the system's state
uint8_t mode; ///< Unused, can be used by user to store the system's mode
uint8_t nav_mode; ///< Unused, can be used by user to store the system's navigation mode
} mavlink_system_t;
 
typedef struct __mavlink_message {
uint16_t checksum; /// sent at end of packet
uint8_t magic; ///< protocol magic marker
uint8_t len; ///< Length of payload
uint8_t seq; ///< Sequence of packet
uint8_t sysid; ///< ID of message sender system/aircraft
uint8_t compid; ///< ID of the message sender component
uint8_t msgid; ///< ID of message in payload
uint64_t payload64[(MAVLINK_MAX_PAYLOAD_LEN+MAVLINK_NUM_CHECKSUM_BYTES+7)/8];
} mavlink_message_t;
 
 
typedef struct __mavlink_extended_message {
mavlink_message_t base_msg;
int32_t extended_payload_len; ///< Length of extended payload if any
uint8_t extended_payload[MAVLINK_MAX_EXTENDED_PAYLOAD_LEN];
} mavlink_extended_message_t;
 
 
typedef enum {
MAVLINK_TYPE_CHAR = 0,
MAVLINK_TYPE_UINT8_T = 1,
MAVLINK_TYPE_INT8_T = 2,
MAVLINK_TYPE_UINT16_T = 3,
MAVLINK_TYPE_INT16_T = 4,
MAVLINK_TYPE_UINT32_T = 5,
MAVLINK_TYPE_INT32_T = 6,
MAVLINK_TYPE_UINT64_T = 7,
MAVLINK_TYPE_INT64_T = 8,
MAVLINK_TYPE_FLOAT = 9,
MAVLINK_TYPE_DOUBLE = 10
} mavlink_message_type_t;
 
#define MAVLINK_MAX_FIELDS 64
 
typedef struct __mavlink_field_info {
const char *name; // name of this field
const char *print_format; // printing format hint, or NULL
mavlink_message_type_t type; // type of this field
unsigned int array_length; // if non-zero, field is an array
unsigned int wire_offset; // offset of each field in the payload
unsigned int structure_offset; // offset in a C structure
} mavlink_field_info_t;
 
// note that in this structure the order of fields is the order
// in the XML file, not necessary the wire order
typedef struct __mavlink_message_info {
const char *name; // name of the message
unsigned num_fields; // how many fields in this message
mavlink_field_info_t fields[MAVLINK_MAX_FIELDS]; // field information
} mavlink_message_info_t;
 
#define _MAV_PAYLOAD(msg) ((const char *)(&((msg)->payload64[0])))
#define _MAV_PAYLOAD_NON_CONST(msg) ((char *)(&((msg)->payload64[0])))
 
// checksum is immediately after the payload bytes
#define mavlink_ck_a(msg) *((msg)->len + (uint8_t *)_MAV_PAYLOAD_NON_CONST(msg))
#define mavlink_ck_b(msg) *(((msg)->len+(uint16_t)1) + (uint8_t *)_MAV_PAYLOAD_NON_CONST(msg))
 
typedef enum {
MAVLINK_COMM_0,
MAVLINK_COMM_1,
MAVLINK_COMM_2,
MAVLINK_COMM_3
} mavlink_channel_t;
 
/*
* applications can set MAVLINK_COMM_NUM_BUFFERS to the maximum number
* of buffers they will use. If more are used, then the result will be
* a stack overrun
*/
#ifndef MAVLINK_COMM_NUM_BUFFERS
#if (defined linux) | (defined __linux) | (defined __MACH__) | (defined _WIN32)
# define MAVLINK_COMM_NUM_BUFFERS 16
#else
# define MAVLINK_COMM_NUM_BUFFERS 4
#endif
#endif
 
typedef enum {
MAVLINK_PARSE_STATE_UNINIT=0,
MAVLINK_PARSE_STATE_IDLE,
MAVLINK_PARSE_STATE_GOT_STX,
MAVLINK_PARSE_STATE_GOT_SEQ,
MAVLINK_PARSE_STATE_GOT_LENGTH,
MAVLINK_PARSE_STATE_GOT_SYSID,
MAVLINK_PARSE_STATE_GOT_COMPID,
MAVLINK_PARSE_STATE_GOT_MSGID,
MAVLINK_PARSE_STATE_GOT_PAYLOAD,
MAVLINK_PARSE_STATE_GOT_CRC1
} mavlink_parse_state_t; ///< The state machine for the comm parser
 
typedef struct __mavlink_status {
uint8_t msg_received; ///< Number of received messages
uint8_t buffer_overrun; ///< Number of buffer overruns
uint8_t parse_error; ///< Number of parse errors
mavlink_parse_state_t parse_state; ///< Parsing state machine
uint8_t packet_idx; ///< Index in current packet
uint8_t current_rx_seq; ///< Sequence number of last packet received
uint8_t current_tx_seq; ///< Sequence number of last packet sent
uint16_t packet_rx_success_count; ///< Received packets
uint16_t packet_rx_drop_count; ///< Number of packet drops
} mavlink_status_t;
 
#define MAVLINK_BIG_ENDIAN 0
#define MAVLINK_LITTLE_ENDIAN 1
 
#endif /* MAVLINK_TYPES_H_ */
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v1.0/protocol.h
0,0 → 1,322
#ifndef _MAVLINK_PROTOCOL_H_
#define _MAVLINK_PROTOCOL_H_
 
#include "string.h"
#include "mavlink_types.h"
 
/*
If you want MAVLink on a system that is native big-endian,
you need to define NATIVE_BIG_ENDIAN
*/
#ifdef NATIVE_BIG_ENDIAN
# define MAVLINK_NEED_BYTE_SWAP (MAVLINK_ENDIAN == MAVLINK_LITTLE_ENDIAN)
#else
# define MAVLINK_NEED_BYTE_SWAP (MAVLINK_ENDIAN != MAVLINK_LITTLE_ENDIAN)
#endif
 
#ifndef MAVLINK_STACK_BUFFER
#define MAVLINK_STACK_BUFFER 0
#endif
 
#ifndef MAVLINK_AVOID_GCC_STACK_BUG
# define MAVLINK_AVOID_GCC_STACK_BUG defined(__GNUC__)
#endif
 
#ifndef MAVLINK_ASSERT
#define MAVLINK_ASSERT(x)
#endif
 
#ifndef MAVLINK_START_UART_SEND
#define MAVLINK_START_UART_SEND(chan, length)
#endif
 
#ifndef MAVLINK_END_UART_SEND
#define MAVLINK_END_UART_SEND(chan, length)
#endif
 
#ifdef MAVLINK_SEPARATE_HELPERS
#define MAVLINK_HELPER
#else
#define MAVLINK_HELPER static inline
#include "mavlink_helpers.h"
#endif // MAVLINK_SEPARATE_HELPERS
 
/* always include the prototypes to ensure we don't get out of sync */
MAVLINK_HELPER mavlink_status_t* mavlink_get_channel_status(uint8_t chan);
#if MAVLINK_CRC_EXTRA
MAVLINK_HELPER uint16_t mavlink_finalize_message_chan(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id,
uint8_t chan, uint8_t length, uint8_t crc_extra);
MAVLINK_HELPER uint16_t mavlink_finalize_message(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id,
uint8_t length, uint8_t crc_extra);
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
MAVLINK_HELPER void _mav_finalize_message_chan_send(mavlink_channel_t chan, uint8_t msgid, const char *packet,
uint8_t length, uint8_t crc_extra);
#endif
#else
MAVLINK_HELPER uint16_t mavlink_finalize_message_chan(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id,
uint8_t chan, uint8_t length);
MAVLINK_HELPER uint16_t mavlink_finalize_message(mavlink_message_t* msg, uint8_t system_id, uint8_t component_id,
uint8_t length);
MAVLINK_HELPER void _mav_finalize_message_chan_send(mavlink_channel_t chan, uint8_t msgid, const char *packet, uint8_t length);
#endif // MAVLINK_CRC_EXTRA
MAVLINK_HELPER uint16_t mavlink_msg_to_send_buffer(uint8_t *buffer, const mavlink_message_t *msg);
MAVLINK_HELPER void mavlink_start_checksum(mavlink_message_t* msg);
MAVLINK_HELPER void mavlink_update_checksum(mavlink_message_t* msg, uint8_t c);
MAVLINK_HELPER uint8_t mavlink_parse_char(uint8_t chan, uint8_t c, mavlink_message_t* r_message, mavlink_status_t* r_mavlink_status);
MAVLINK_HELPER uint8_t put_bitfield_n_by_index(int32_t b, uint8_t bits, uint8_t packet_index, uint8_t bit_index,
uint8_t* r_bit_index, uint8_t* buffer);
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
MAVLINK_HELPER void _mavlink_send_uart(mavlink_channel_t chan, const char *buf, uint16_t len);
#endif
 
/**
* @brief Get the required buffer size for this message
*/
static inline uint16_t mavlink_msg_get_send_buffer_length(const mavlink_message_t* msg)
{
return msg->len + MAVLINK_NUM_NON_PAYLOAD_BYTES;
}
 
#if MAVLINK_NEED_BYTE_SWAP
static inline void byte_swap_2(char *dst, const char *src)
{
dst[0] = src[1];
dst[1] = src[0];
}
static inline void byte_swap_4(char *dst, const char *src)
{
dst[0] = src[3];
dst[1] = src[2];
dst[2] = src[1];
dst[3] = src[0];
}
static inline void byte_swap_8(char *dst, const char *src)
{
dst[0] = src[7];
dst[1] = src[6];
dst[2] = src[5];
dst[3] = src[4];
dst[4] = src[3];
dst[5] = src[2];
dst[6] = src[1];
dst[7] = src[0];
}
#elif !MAVLINK_ALIGNED_FIELDS
static inline void byte_copy_2(char *dst, const char *src)
{
dst[0] = src[0];
dst[1] = src[1];
}
static inline void byte_copy_4(char *dst, const char *src)
{
dst[0] = src[0];
dst[1] = src[1];
dst[2] = src[2];
dst[3] = src[3];
}
static inline void byte_copy_8(char *dst, const char *src)
{
memcpy(dst, src, 8);
}
#endif
 
#define _mav_put_uint8_t(buf, wire_offset, b) buf[wire_offset] = (uint8_t)b
#define _mav_put_int8_t(buf, wire_offset, b) buf[wire_offset] = (int8_t)b
#define _mav_put_char(buf, wire_offset, b) buf[wire_offset] = b
 
#if MAVLINK_NEED_BYTE_SWAP
#define _mav_put_uint16_t(buf, wire_offset, b) byte_swap_2(&buf[wire_offset], (const char *)&b)
#define _mav_put_int16_t(buf, wire_offset, b) byte_swap_2(&buf[wire_offset], (const char *)&b)
#define _mav_put_uint32_t(buf, wire_offset, b) byte_swap_4(&buf[wire_offset], (const char *)&b)
#define _mav_put_int32_t(buf, wire_offset, b) byte_swap_4(&buf[wire_offset], (const char *)&b)
#define _mav_put_uint64_t(buf, wire_offset, b) byte_swap_8(&buf[wire_offset], (const char *)&b)
#define _mav_put_int64_t(buf, wire_offset, b) byte_swap_8(&buf[wire_offset], (const char *)&b)
#define _mav_put_float(buf, wire_offset, b) byte_swap_4(&buf[wire_offset], (const char *)&b)
#define _mav_put_double(buf, wire_offset, b) byte_swap_8(&buf[wire_offset], (const char *)&b)
#elif !MAVLINK_ALIGNED_FIELDS
#define _mav_put_uint16_t(buf, wire_offset, b) byte_copy_2(&buf[wire_offset], (const char *)&b)
#define _mav_put_int16_t(buf, wire_offset, b) byte_copy_2(&buf[wire_offset], (const char *)&b)
#define _mav_put_uint32_t(buf, wire_offset, b) byte_copy_4(&buf[wire_offset], (const char *)&b)
#define _mav_put_int32_t(buf, wire_offset, b) byte_copy_4(&buf[wire_offset], (const char *)&b)
#define _mav_put_uint64_t(buf, wire_offset, b) byte_copy_8(&buf[wire_offset], (const char *)&b)
#define _mav_put_int64_t(buf, wire_offset, b) byte_copy_8(&buf[wire_offset], (const char *)&b)
#define _mav_put_float(buf, wire_offset, b) byte_copy_4(&buf[wire_offset], (const char *)&b)
#define _mav_put_double(buf, wire_offset, b) byte_copy_8(&buf[wire_offset], (const char *)&b)
#else
#define _mav_put_uint16_t(buf, wire_offset, b) *(uint16_t *)&buf[wire_offset] = b
#define _mav_put_int16_t(buf, wire_offset, b) *(int16_t *)&buf[wire_offset] = b
#define _mav_put_uint32_t(buf, wire_offset, b) *(uint32_t *)&buf[wire_offset] = b
#define _mav_put_int32_t(buf, wire_offset, b) *(int32_t *)&buf[wire_offset] = b
#define _mav_put_uint64_t(buf, wire_offset, b) *(uint64_t *)&buf[wire_offset] = b
#define _mav_put_int64_t(buf, wire_offset, b) *(int64_t *)&buf[wire_offset] = b
#define _mav_put_float(buf, wire_offset, b) *(float *)&buf[wire_offset] = b
#define _mav_put_double(buf, wire_offset, b) *(double *)&buf[wire_offset] = b
#endif
 
/*
like memcpy(), but if src is NULL, do a memset to zero
*/
static void mav_array_memcpy(void *dest, const void *src, size_t n)
{
if (src == NULL) {
memset(dest, 0, n);
} else {
memcpy(dest, src, n);
}
}
 
/*
* Place a char array into a buffer
*/
static inline void _mav_put_char_array(char *buf, uint8_t wire_offset, const char *b, uint8_t array_length)
{
mav_array_memcpy(&buf[wire_offset], b, array_length);
 
}
 
/*
* Place a uint8_t array into a buffer
*/
static inline void _mav_put_uint8_t_array(char *buf, uint8_t wire_offset, const uint8_t *b, uint8_t array_length)
{
mav_array_memcpy(&buf[wire_offset], b, array_length);
 
}
 
/*
* Place a int8_t array into a buffer
*/
static inline void _mav_put_int8_t_array(char *buf, uint8_t wire_offset, const int8_t *b, uint8_t array_length)
{
mav_array_memcpy(&buf[wire_offset], b, array_length);
 
}
 
#if MAVLINK_NEED_BYTE_SWAP
#define _MAV_PUT_ARRAY(TYPE, V) \
static inline void _mav_put_ ## TYPE ##_array(char *buf, uint8_t wire_offset, const TYPE *b, uint8_t array_length) \
{ \
if (b == NULL) { \
memset(&buf[wire_offset], 0, array_length*sizeof(TYPE)); \
} else { \
uint16_t i; \
for (i=0; i<array_length; i++) { \
_mav_put_## TYPE (buf, wire_offset+(i*sizeof(TYPE)), b[i]); \
} \
} \
}
#else
#define _MAV_PUT_ARRAY(TYPE, V) \
static inline void _mav_put_ ## TYPE ##_array(char *buf, uint8_t wire_offset, const TYPE *b, uint8_t array_length) \
{ \
mav_array_memcpy(&buf[wire_offset], b, array_length*sizeof(TYPE)); \
}
#endif
 
_MAV_PUT_ARRAY(uint16_t, u16)
_MAV_PUT_ARRAY(uint32_t, u32)
_MAV_PUT_ARRAY(uint64_t, u64)
_MAV_PUT_ARRAY(int16_t, i16)
_MAV_PUT_ARRAY(int32_t, i32)
_MAV_PUT_ARRAY(int64_t, i64)
_MAV_PUT_ARRAY(float, f)
_MAV_PUT_ARRAY(double, d)
 
#define _MAV_RETURN_char(msg, wire_offset) (const char)_MAV_PAYLOAD(msg)[wire_offset]
#define _MAV_RETURN_int8_t(msg, wire_offset) (const int8_t)_MAV_PAYLOAD(msg)[wire_offset]
#define _MAV_RETURN_uint8_t(msg, wire_offset) (const uint8_t)_MAV_PAYLOAD(msg)[wire_offset]
 
#if MAVLINK_NEED_BYTE_SWAP
#define _MAV_MSG_RETURN_TYPE(TYPE, SIZE) \
static inline TYPE _MAV_RETURN_## TYPE(const mavlink_message_t *msg, uint8_t ofs) \
{ TYPE r; byte_swap_## SIZE((char*)&r, &_MAV_PAYLOAD(msg)[ofs]); return r; }
 
_MAV_MSG_RETURN_TYPE(uint16_t, 2)
_MAV_MSG_RETURN_TYPE(int16_t, 2)
_MAV_MSG_RETURN_TYPE(uint32_t, 4)
_MAV_MSG_RETURN_TYPE(int32_t, 4)
_MAV_MSG_RETURN_TYPE(uint64_t, 8)
_MAV_MSG_RETURN_TYPE(int64_t, 8)
_MAV_MSG_RETURN_TYPE(float, 4)
_MAV_MSG_RETURN_TYPE(double, 8)
 
#elif !MAVLINK_ALIGNED_FIELDS
#define _MAV_MSG_RETURN_TYPE(TYPE, SIZE) \
static inline TYPE _MAV_RETURN_## TYPE(const mavlink_message_t *msg, uint8_t ofs) \
{ TYPE r; byte_copy_## SIZE((char*)&r, &_MAV_PAYLOAD(msg)[ofs]); return r; }
 
_MAV_MSG_RETURN_TYPE(uint16_t, 2)
_MAV_MSG_RETURN_TYPE(int16_t, 2)
_MAV_MSG_RETURN_TYPE(uint32_t, 4)
_MAV_MSG_RETURN_TYPE(int32_t, 4)
_MAV_MSG_RETURN_TYPE(uint64_t, 8)
_MAV_MSG_RETURN_TYPE(int64_t, 8)
_MAV_MSG_RETURN_TYPE(float, 4)
_MAV_MSG_RETURN_TYPE(double, 8)
#else // nicely aligned, no swap
#define _MAV_MSG_RETURN_TYPE(TYPE) \
static inline TYPE _MAV_RETURN_## TYPE(const mavlink_message_t *msg, uint8_t ofs) \
{ return *(const TYPE *)(&_MAV_PAYLOAD(msg)[ofs]);}
 
_MAV_MSG_RETURN_TYPE(uint16_t)
_MAV_MSG_RETURN_TYPE(int16_t)
_MAV_MSG_RETURN_TYPE(uint32_t)
_MAV_MSG_RETURN_TYPE(int32_t)
_MAV_MSG_RETURN_TYPE(uint64_t)
_MAV_MSG_RETURN_TYPE(int64_t)
_MAV_MSG_RETURN_TYPE(float)
_MAV_MSG_RETURN_TYPE(double)
#endif // MAVLINK_NEED_BYTE_SWAP
 
static inline uint16_t _MAV_RETURN_char_array(const mavlink_message_t *msg, char *value,
uint8_t array_length, uint8_t wire_offset)
{
memcpy(value, &_MAV_PAYLOAD(msg)[wire_offset], array_length);
return array_length;
}
 
static inline uint16_t _MAV_RETURN_uint8_t_array(const mavlink_message_t *msg, uint8_t *value,
uint8_t array_length, uint8_t wire_offset)
{
memcpy(value, &_MAV_PAYLOAD(msg)[wire_offset], array_length);
return array_length;
}
 
static inline uint16_t _MAV_RETURN_int8_t_array(const mavlink_message_t *msg, int8_t *value,
uint8_t array_length, uint8_t wire_offset)
{
memcpy(value, &_MAV_PAYLOAD(msg)[wire_offset], array_length);
return array_length;
}
 
#if MAVLINK_NEED_BYTE_SWAP
#define _MAV_RETURN_ARRAY(TYPE, V) \
static inline uint16_t _MAV_RETURN_## TYPE ##_array(const mavlink_message_t *msg, TYPE *value, \
uint8_t array_length, uint8_t wire_offset) \
{ \
uint16_t i; \
for (i=0; i<array_length; i++) { \
value[i] = _MAV_RETURN_## TYPE (msg, wire_offset+(i*sizeof(value[0]))); \
} \
return array_length*sizeof(value[0]); \
}
#else
#define _MAV_RETURN_ARRAY(TYPE, V) \
static inline uint16_t _MAV_RETURN_## TYPE ##_array(const mavlink_message_t *msg, TYPE *value, \
uint8_t array_length, uint8_t wire_offset) \
{ \
memcpy(value, &_MAV_PAYLOAD(msg)[wire_offset], array_length*sizeof(TYPE)); \
return array_length*sizeof(TYPE); \
}
#endif
 
_MAV_RETURN_ARRAY(uint16_t, u16)
_MAV_RETURN_ARRAY(uint32_t, u32)
_MAV_RETURN_ARRAY(uint64_t, u64)
_MAV_RETURN_ARRAY(int16_t, i16)
_MAV_RETURN_ARRAY(int32_t, i32)
_MAV_RETURN_ARRAY(int64_t, i64)
_MAV_RETURN_ARRAY(float, f)
_MAV_RETURN_ARRAY(double, d)
 
#endif // _MAVLINK_PROTOCOL_H_
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v1.0/sensesoar/mavlink.h
0,0 → 1,27
/** @file
* @brief MAVLink comm protocol built from sensesoar.xml
* @see http://pixhawk.ethz.ch/software/mavlink
*/
#ifndef MAVLINK_H
#define MAVLINK_H
 
#ifndef MAVLINK_STX
#define MAVLINK_STX 254
#endif
 
#ifndef MAVLINK_ENDIAN
#define MAVLINK_ENDIAN MAVLINK_LITTLE_ENDIAN
#endif
 
#ifndef MAVLINK_ALIGNED_FIELDS
#define MAVLINK_ALIGNED_FIELDS 1
#endif
 
#ifndef MAVLINK_CRC_EXTRA
#define MAVLINK_CRC_EXTRA 1
#endif
 
#include "version.h"
#include "sensesoar.h"
 
#endif // MAVLINK_H
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v1.0/sensesoar/mavlink_msg_cmd_airspeed_ack.h
0,0 → 1,166
// MESSAGE CMD_AIRSPEED_ACK PACKING
 
#define MAVLINK_MSG_ID_CMD_AIRSPEED_ACK 194
 
typedef struct __mavlink_cmd_airspeed_ack_t
{
float spCmd; ///< commanded airspeed
uint8_t ack; ///< 0:ack, 1:nack
} mavlink_cmd_airspeed_ack_t;
 
#define MAVLINK_MSG_ID_CMD_AIRSPEED_ACK_LEN 5
#define MAVLINK_MSG_ID_194_LEN 5
 
 
 
#define MAVLINK_MESSAGE_INFO_CMD_AIRSPEED_ACK { \
"CMD_AIRSPEED_ACK", \
2, \
{ { "spCmd", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_cmd_airspeed_ack_t, spCmd) }, \
{ "ack", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_cmd_airspeed_ack_t, ack) }, \
} \
}
 
 
/**
* @brief Pack a cmd_airspeed_ack message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param spCmd commanded airspeed
* @param ack 0:ack, 1:nack
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_cmd_airspeed_ack_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
float spCmd, uint8_t ack)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[5];
_mav_put_float(buf, 0, spCmd);
_mav_put_uint8_t(buf, 4, ack);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 5);
#else
mavlink_cmd_airspeed_ack_t packet;
packet.spCmd = spCmd;
packet.ack = ack;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 5);
#endif
 
msg->msgid = MAVLINK_MSG_ID_CMD_AIRSPEED_ACK;
return mavlink_finalize_message(msg, system_id, component_id, 5, 243);
}
 
/**
* @brief Pack a cmd_airspeed_ack message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param spCmd commanded airspeed
* @param ack 0:ack, 1:nack
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_cmd_airspeed_ack_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
float spCmd,uint8_t ack)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[5];
_mav_put_float(buf, 0, spCmd);
_mav_put_uint8_t(buf, 4, ack);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 5);
#else
mavlink_cmd_airspeed_ack_t packet;
packet.spCmd = spCmd;
packet.ack = ack;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 5);
#endif
 
msg->msgid = MAVLINK_MSG_ID_CMD_AIRSPEED_ACK;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 5, 243);
}
 
/**
* @brief Encode a cmd_airspeed_ack struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param cmd_airspeed_ack C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_cmd_airspeed_ack_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_cmd_airspeed_ack_t* cmd_airspeed_ack)
{
return mavlink_msg_cmd_airspeed_ack_pack(system_id, component_id, msg, cmd_airspeed_ack->spCmd, cmd_airspeed_ack->ack);
}
 
/**
* @brief Send a cmd_airspeed_ack message
* @param chan MAVLink channel to send the message
*
* @param spCmd commanded airspeed
* @param ack 0:ack, 1:nack
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_cmd_airspeed_ack_send(mavlink_channel_t chan, float spCmd, uint8_t ack)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[5];
_mav_put_float(buf, 0, spCmd);
_mav_put_uint8_t(buf, 4, ack);
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CMD_AIRSPEED_ACK, buf, 5, 243);
#else
mavlink_cmd_airspeed_ack_t packet;
packet.spCmd = spCmd;
packet.ack = ack;
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CMD_AIRSPEED_ACK, (const char *)&packet, 5, 243);
#endif
}
 
#endif
 
// MESSAGE CMD_AIRSPEED_ACK UNPACKING
 
 
/**
* @brief Get field spCmd from cmd_airspeed_ack message
*
* @return commanded airspeed
*/
static inline float mavlink_msg_cmd_airspeed_ack_get_spCmd(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 0);
}
 
/**
* @brief Get field ack from cmd_airspeed_ack message
*
* @return 0:ack, 1:nack
*/
static inline uint8_t mavlink_msg_cmd_airspeed_ack_get_ack(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 4);
}
 
/**
* @brief Decode a cmd_airspeed_ack message into a struct
*
* @param msg The message to decode
* @param cmd_airspeed_ack C-struct to decode the message contents into
*/
static inline void mavlink_msg_cmd_airspeed_ack_decode(const mavlink_message_t* msg, mavlink_cmd_airspeed_ack_t* cmd_airspeed_ack)
{
#if MAVLINK_NEED_BYTE_SWAP
cmd_airspeed_ack->spCmd = mavlink_msg_cmd_airspeed_ack_get_spCmd(msg);
cmd_airspeed_ack->ack = mavlink_msg_cmd_airspeed_ack_get_ack(msg);
#else
memcpy(cmd_airspeed_ack, _MAV_PAYLOAD(msg), 5);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v1.0/sensesoar/mavlink_msg_cmd_airspeed_chng.h
0,0 → 1,166
// MESSAGE CMD_AIRSPEED_CHNG PACKING
 
#define MAVLINK_MSG_ID_CMD_AIRSPEED_CHNG 192
 
typedef struct __mavlink_cmd_airspeed_chng_t
{
float spCmd; ///< commanded airspeed
uint8_t target; ///< Target ID
} mavlink_cmd_airspeed_chng_t;
 
#define MAVLINK_MSG_ID_CMD_AIRSPEED_CHNG_LEN 5
#define MAVLINK_MSG_ID_192_LEN 5
 
 
 
#define MAVLINK_MESSAGE_INFO_CMD_AIRSPEED_CHNG { \
"CMD_AIRSPEED_CHNG", \
2, \
{ { "spCmd", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_cmd_airspeed_chng_t, spCmd) }, \
{ "target", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_cmd_airspeed_chng_t, target) }, \
} \
}
 
 
/**
* @brief Pack a cmd_airspeed_chng message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param target Target ID
* @param spCmd commanded airspeed
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_cmd_airspeed_chng_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t target, float spCmd)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[5];
_mav_put_float(buf, 0, spCmd);
_mav_put_uint8_t(buf, 4, target);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 5);
#else
mavlink_cmd_airspeed_chng_t packet;
packet.spCmd = spCmd;
packet.target = target;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 5);
#endif
 
msg->msgid = MAVLINK_MSG_ID_CMD_AIRSPEED_CHNG;
return mavlink_finalize_message(msg, system_id, component_id, 5, 209);
}
 
/**
* @brief Pack a cmd_airspeed_chng message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param target Target ID
* @param spCmd commanded airspeed
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_cmd_airspeed_chng_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint8_t target,float spCmd)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[5];
_mav_put_float(buf, 0, spCmd);
_mav_put_uint8_t(buf, 4, target);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 5);
#else
mavlink_cmd_airspeed_chng_t packet;
packet.spCmd = spCmd;
packet.target = target;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 5);
#endif
 
msg->msgid = MAVLINK_MSG_ID_CMD_AIRSPEED_CHNG;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 5, 209);
}
 
/**
* @brief Encode a cmd_airspeed_chng struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param cmd_airspeed_chng C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_cmd_airspeed_chng_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_cmd_airspeed_chng_t* cmd_airspeed_chng)
{
return mavlink_msg_cmd_airspeed_chng_pack(system_id, component_id, msg, cmd_airspeed_chng->target, cmd_airspeed_chng->spCmd);
}
 
/**
* @brief Send a cmd_airspeed_chng message
* @param chan MAVLink channel to send the message
*
* @param target Target ID
* @param spCmd commanded airspeed
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_cmd_airspeed_chng_send(mavlink_channel_t chan, uint8_t target, float spCmd)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[5];
_mav_put_float(buf, 0, spCmd);
_mav_put_uint8_t(buf, 4, target);
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CMD_AIRSPEED_CHNG, buf, 5, 209);
#else
mavlink_cmd_airspeed_chng_t packet;
packet.spCmd = spCmd;
packet.target = target;
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CMD_AIRSPEED_CHNG, (const char *)&packet, 5, 209);
#endif
}
 
#endif
 
// MESSAGE CMD_AIRSPEED_CHNG UNPACKING
 
 
/**
* @brief Get field target from cmd_airspeed_chng message
*
* @return Target ID
*/
static inline uint8_t mavlink_msg_cmd_airspeed_chng_get_target(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 4);
}
 
/**
* @brief Get field spCmd from cmd_airspeed_chng message
*
* @return commanded airspeed
*/
static inline float mavlink_msg_cmd_airspeed_chng_get_spCmd(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 0);
}
 
/**
* @brief Decode a cmd_airspeed_chng message into a struct
*
* @param msg The message to decode
* @param cmd_airspeed_chng C-struct to decode the message contents into
*/
static inline void mavlink_msg_cmd_airspeed_chng_decode(const mavlink_message_t* msg, mavlink_cmd_airspeed_chng_t* cmd_airspeed_chng)
{
#if MAVLINK_NEED_BYTE_SWAP
cmd_airspeed_chng->spCmd = mavlink_msg_cmd_airspeed_chng_get_spCmd(msg);
cmd_airspeed_chng->target = mavlink_msg_cmd_airspeed_chng_get_target(msg);
#else
memcpy(cmd_airspeed_chng, _MAV_PAYLOAD(msg), 5);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v1.0/sensesoar/mavlink_msg_filt_rot_vel.h
0,0 → 1,144
// MESSAGE FILT_ROT_VEL PACKING
 
#define MAVLINK_MSG_ID_FILT_ROT_VEL 184
 
typedef struct __mavlink_filt_rot_vel_t
{
float rotVel[3]; ///< rotational velocity
} mavlink_filt_rot_vel_t;
 
#define MAVLINK_MSG_ID_FILT_ROT_VEL_LEN 12
#define MAVLINK_MSG_ID_184_LEN 12
 
#define MAVLINK_MSG_FILT_ROT_VEL_FIELD_ROTVEL_LEN 3
 
#define MAVLINK_MESSAGE_INFO_FILT_ROT_VEL { \
"FILT_ROT_VEL", \
1, \
{ { "rotVel", NULL, MAVLINK_TYPE_FLOAT, 3, 0, offsetof(mavlink_filt_rot_vel_t, rotVel) }, \
} \
}
 
 
/**
* @brief Pack a filt_rot_vel message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param rotVel rotational velocity
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_filt_rot_vel_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
const float *rotVel)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[12];
 
_mav_put_float_array(buf, 0, rotVel, 3);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 12);
#else
mavlink_filt_rot_vel_t packet;
 
mav_array_memcpy(packet.rotVel, rotVel, sizeof(float)*3);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 12);
#endif
 
msg->msgid = MAVLINK_MSG_ID_FILT_ROT_VEL;
return mavlink_finalize_message(msg, system_id, component_id, 12, 79);
}
 
/**
* @brief Pack a filt_rot_vel message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param rotVel rotational velocity
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_filt_rot_vel_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
const float *rotVel)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[12];
 
_mav_put_float_array(buf, 0, rotVel, 3);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 12);
#else
mavlink_filt_rot_vel_t packet;
 
mav_array_memcpy(packet.rotVel, rotVel, sizeof(float)*3);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 12);
#endif
 
msg->msgid = MAVLINK_MSG_ID_FILT_ROT_VEL;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 12, 79);
}
 
/**
* @brief Encode a filt_rot_vel struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param filt_rot_vel C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_filt_rot_vel_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_filt_rot_vel_t* filt_rot_vel)
{
return mavlink_msg_filt_rot_vel_pack(system_id, component_id, msg, filt_rot_vel->rotVel);
}
 
/**
* @brief Send a filt_rot_vel message
* @param chan MAVLink channel to send the message
*
* @param rotVel rotational velocity
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_filt_rot_vel_send(mavlink_channel_t chan, const float *rotVel)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[12];
 
_mav_put_float_array(buf, 0, rotVel, 3);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FILT_ROT_VEL, buf, 12, 79);
#else
mavlink_filt_rot_vel_t packet;
 
mav_array_memcpy(packet.rotVel, rotVel, sizeof(float)*3);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FILT_ROT_VEL, (const char *)&packet, 12, 79);
#endif
}
 
#endif
 
// MESSAGE FILT_ROT_VEL UNPACKING
 
 
/**
* @brief Get field rotVel from filt_rot_vel message
*
* @return rotational velocity
*/
static inline uint16_t mavlink_msg_filt_rot_vel_get_rotVel(const mavlink_message_t* msg, float *rotVel)
{
return _MAV_RETURN_float_array(msg, rotVel, 3, 0);
}
 
/**
* @brief Decode a filt_rot_vel message into a struct
*
* @param msg The message to decode
* @param filt_rot_vel C-struct to decode the message contents into
*/
static inline void mavlink_msg_filt_rot_vel_decode(const mavlink_message_t* msg, mavlink_filt_rot_vel_t* filt_rot_vel)
{
#if MAVLINK_NEED_BYTE_SWAP
mavlink_msg_filt_rot_vel_get_rotVel(msg, filt_rot_vel->rotVel);
#else
memcpy(filt_rot_vel, _MAV_PAYLOAD(msg), 12);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v1.0/sensesoar/mavlink_msg_llc_out.h
0,0 → 1,167
// MESSAGE LLC_OUT PACKING
 
#define MAVLINK_MSG_ID_LLC_OUT 186
 
typedef struct __mavlink_llc_out_t
{
int16_t servoOut[4]; ///< Servo signal
int16_t MotorOut[2]; ///< motor signal
} mavlink_llc_out_t;
 
#define MAVLINK_MSG_ID_LLC_OUT_LEN 12
#define MAVLINK_MSG_ID_186_LEN 12
 
#define MAVLINK_MSG_LLC_OUT_FIELD_SERVOOUT_LEN 4
#define MAVLINK_MSG_LLC_OUT_FIELD_MOTOROUT_LEN 2
 
#define MAVLINK_MESSAGE_INFO_LLC_OUT { \
"LLC_OUT", \
2, \
{ { "servoOut", NULL, MAVLINK_TYPE_INT16_T, 4, 0, offsetof(mavlink_llc_out_t, servoOut) }, \
{ "MotorOut", NULL, MAVLINK_TYPE_INT16_T, 2, 8, offsetof(mavlink_llc_out_t, MotorOut) }, \
} \
}
 
 
/**
* @brief Pack a llc_out message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param servoOut Servo signal
* @param MotorOut motor signal
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_llc_out_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
const int16_t *servoOut, const int16_t *MotorOut)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[12];
 
_mav_put_int16_t_array(buf, 0, servoOut, 4);
_mav_put_int16_t_array(buf, 8, MotorOut, 2);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 12);
#else
mavlink_llc_out_t packet;
 
mav_array_memcpy(packet.servoOut, servoOut, sizeof(int16_t)*4);
mav_array_memcpy(packet.MotorOut, MotorOut, sizeof(int16_t)*2);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 12);
#endif
 
msg->msgid = MAVLINK_MSG_ID_LLC_OUT;
return mavlink_finalize_message(msg, system_id, component_id, 12, 5);
}
 
/**
* @brief Pack a llc_out message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param servoOut Servo signal
* @param MotorOut motor signal
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_llc_out_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
const int16_t *servoOut,const int16_t *MotorOut)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[12];
 
_mav_put_int16_t_array(buf, 0, servoOut, 4);
_mav_put_int16_t_array(buf, 8, MotorOut, 2);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 12);
#else
mavlink_llc_out_t packet;
 
mav_array_memcpy(packet.servoOut, servoOut, sizeof(int16_t)*4);
mav_array_memcpy(packet.MotorOut, MotorOut, sizeof(int16_t)*2);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 12);
#endif
 
msg->msgid = MAVLINK_MSG_ID_LLC_OUT;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 12, 5);
}
 
/**
* @brief Encode a llc_out struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param llc_out C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_llc_out_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_llc_out_t* llc_out)
{
return mavlink_msg_llc_out_pack(system_id, component_id, msg, llc_out->servoOut, llc_out->MotorOut);
}
 
/**
* @brief Send a llc_out message
* @param chan MAVLink channel to send the message
*
* @param servoOut Servo signal
* @param MotorOut motor signal
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_llc_out_send(mavlink_channel_t chan, const int16_t *servoOut, const int16_t *MotorOut)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[12];
 
_mav_put_int16_t_array(buf, 0, servoOut, 4);
_mav_put_int16_t_array(buf, 8, MotorOut, 2);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LLC_OUT, buf, 12, 5);
#else
mavlink_llc_out_t packet;
 
mav_array_memcpy(packet.servoOut, servoOut, sizeof(int16_t)*4);
mav_array_memcpy(packet.MotorOut, MotorOut, sizeof(int16_t)*2);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LLC_OUT, (const char *)&packet, 12, 5);
#endif
}
 
#endif
 
// MESSAGE LLC_OUT UNPACKING
 
 
/**
* @brief Get field servoOut from llc_out message
*
* @return Servo signal
*/
static inline uint16_t mavlink_msg_llc_out_get_servoOut(const mavlink_message_t* msg, int16_t *servoOut)
{
return _MAV_RETURN_int16_t_array(msg, servoOut, 4, 0);
}
 
/**
* @brief Get field MotorOut from llc_out message
*
* @return motor signal
*/
static inline uint16_t mavlink_msg_llc_out_get_MotorOut(const mavlink_message_t* msg, int16_t *MotorOut)
{
return _MAV_RETURN_int16_t_array(msg, MotorOut, 2, 8);
}
 
/**
* @brief Decode a llc_out message into a struct
*
* @param msg The message to decode
* @param llc_out C-struct to decode the message contents into
*/
static inline void mavlink_msg_llc_out_decode(const mavlink_message_t* msg, mavlink_llc_out_t* llc_out)
{
#if MAVLINK_NEED_BYTE_SWAP
mavlink_msg_llc_out_get_servoOut(msg, llc_out->servoOut);
mavlink_msg_llc_out_get_MotorOut(msg, llc_out->MotorOut);
#else
memcpy(llc_out, _MAV_PAYLOAD(msg), 12);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v1.0/sensesoar/mavlink_msg_obs_air_temp.h
0,0 → 1,144
// MESSAGE OBS_AIR_TEMP PACKING
 
#define MAVLINK_MSG_ID_OBS_AIR_TEMP 183
 
typedef struct __mavlink_obs_air_temp_t
{
float airT; ///< Air Temperatur
} mavlink_obs_air_temp_t;
 
#define MAVLINK_MSG_ID_OBS_AIR_TEMP_LEN 4
#define MAVLINK_MSG_ID_183_LEN 4
 
 
 
#define MAVLINK_MESSAGE_INFO_OBS_AIR_TEMP { \
"OBS_AIR_TEMP", \
1, \
{ { "airT", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_obs_air_temp_t, airT) }, \
} \
}
 
 
/**
* @brief Pack a obs_air_temp message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param airT Air Temperatur
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_obs_air_temp_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
float airT)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[4];
_mav_put_float(buf, 0, airT);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 4);
#else
mavlink_obs_air_temp_t packet;
packet.airT = airT;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 4);
#endif
 
msg->msgid = MAVLINK_MSG_ID_OBS_AIR_TEMP;
return mavlink_finalize_message(msg, system_id, component_id, 4, 248);
}
 
/**
* @brief Pack a obs_air_temp message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param airT Air Temperatur
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_obs_air_temp_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
float airT)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[4];
_mav_put_float(buf, 0, airT);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 4);
#else
mavlink_obs_air_temp_t packet;
packet.airT = airT;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 4);
#endif
 
msg->msgid = MAVLINK_MSG_ID_OBS_AIR_TEMP;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 4, 248);
}
 
/**
* @brief Encode a obs_air_temp struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param obs_air_temp C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_obs_air_temp_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_obs_air_temp_t* obs_air_temp)
{
return mavlink_msg_obs_air_temp_pack(system_id, component_id, msg, obs_air_temp->airT);
}
 
/**
* @brief Send a obs_air_temp message
* @param chan MAVLink channel to send the message
*
* @param airT Air Temperatur
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_obs_air_temp_send(mavlink_channel_t chan, float airT)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[4];
_mav_put_float(buf, 0, airT);
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_AIR_TEMP, buf, 4, 248);
#else
mavlink_obs_air_temp_t packet;
packet.airT = airT;
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_AIR_TEMP, (const char *)&packet, 4, 248);
#endif
}
 
#endif
 
// MESSAGE OBS_AIR_TEMP UNPACKING
 
 
/**
* @brief Get field airT from obs_air_temp message
*
* @return Air Temperatur
*/
static inline float mavlink_msg_obs_air_temp_get_airT(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 0);
}
 
/**
* @brief Decode a obs_air_temp message into a struct
*
* @param msg The message to decode
* @param obs_air_temp C-struct to decode the message contents into
*/
static inline void mavlink_msg_obs_air_temp_decode(const mavlink_message_t* msg, mavlink_obs_air_temp_t* obs_air_temp)
{
#if MAVLINK_NEED_BYTE_SWAP
obs_air_temp->airT = mavlink_msg_obs_air_temp_get_airT(msg);
#else
memcpy(obs_air_temp, _MAV_PAYLOAD(msg), 4);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v1.0/sensesoar/mavlink_msg_obs_air_velocity.h
0,0 → 1,188
// MESSAGE OBS_AIR_VELOCITY PACKING
 
#define MAVLINK_MSG_ID_OBS_AIR_VELOCITY 178
 
typedef struct __mavlink_obs_air_velocity_t
{
float magnitude; ///< Air speed
float aoa; ///< angle of attack
float slip; ///< slip angle
} mavlink_obs_air_velocity_t;
 
#define MAVLINK_MSG_ID_OBS_AIR_VELOCITY_LEN 12
#define MAVLINK_MSG_ID_178_LEN 12
 
 
 
#define MAVLINK_MESSAGE_INFO_OBS_AIR_VELOCITY { \
"OBS_AIR_VELOCITY", \
3, \
{ { "magnitude", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_obs_air_velocity_t, magnitude) }, \
{ "aoa", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_obs_air_velocity_t, aoa) }, \
{ "slip", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_obs_air_velocity_t, slip) }, \
} \
}
 
 
/**
* @brief Pack a obs_air_velocity message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param magnitude Air speed
* @param aoa angle of attack
* @param slip slip angle
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_obs_air_velocity_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
float magnitude, float aoa, float slip)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[12];
_mav_put_float(buf, 0, magnitude);
_mav_put_float(buf, 4, aoa);
_mav_put_float(buf, 8, slip);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 12);
#else
mavlink_obs_air_velocity_t packet;
packet.magnitude = magnitude;
packet.aoa = aoa;
packet.slip = slip;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 12);
#endif
 
msg->msgid = MAVLINK_MSG_ID_OBS_AIR_VELOCITY;
return mavlink_finalize_message(msg, system_id, component_id, 12, 32);
}
 
/**
* @brief Pack a obs_air_velocity message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param magnitude Air speed
* @param aoa angle of attack
* @param slip slip angle
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_obs_air_velocity_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
float magnitude,float aoa,float slip)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[12];
_mav_put_float(buf, 0, magnitude);
_mav_put_float(buf, 4, aoa);
_mav_put_float(buf, 8, slip);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 12);
#else
mavlink_obs_air_velocity_t packet;
packet.magnitude = magnitude;
packet.aoa = aoa;
packet.slip = slip;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 12);
#endif
 
msg->msgid = MAVLINK_MSG_ID_OBS_AIR_VELOCITY;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 12, 32);
}
 
/**
* @brief Encode a obs_air_velocity struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param obs_air_velocity C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_obs_air_velocity_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_obs_air_velocity_t* obs_air_velocity)
{
return mavlink_msg_obs_air_velocity_pack(system_id, component_id, msg, obs_air_velocity->magnitude, obs_air_velocity->aoa, obs_air_velocity->slip);
}
 
/**
* @brief Send a obs_air_velocity message
* @param chan MAVLink channel to send the message
*
* @param magnitude Air speed
* @param aoa angle of attack
* @param slip slip angle
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_obs_air_velocity_send(mavlink_channel_t chan, float magnitude, float aoa, float slip)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[12];
_mav_put_float(buf, 0, magnitude);
_mav_put_float(buf, 4, aoa);
_mav_put_float(buf, 8, slip);
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_AIR_VELOCITY, buf, 12, 32);
#else
mavlink_obs_air_velocity_t packet;
packet.magnitude = magnitude;
packet.aoa = aoa;
packet.slip = slip;
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_AIR_VELOCITY, (const char *)&packet, 12, 32);
#endif
}
 
#endif
 
// MESSAGE OBS_AIR_VELOCITY UNPACKING
 
 
/**
* @brief Get field magnitude from obs_air_velocity message
*
* @return Air speed
*/
static inline float mavlink_msg_obs_air_velocity_get_magnitude(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 0);
}
 
/**
* @brief Get field aoa from obs_air_velocity message
*
* @return angle of attack
*/
static inline float mavlink_msg_obs_air_velocity_get_aoa(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 4);
}
 
/**
* @brief Get field slip from obs_air_velocity message
*
* @return slip angle
*/
static inline float mavlink_msg_obs_air_velocity_get_slip(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 8);
}
 
/**
* @brief Decode a obs_air_velocity message into a struct
*
* @param msg The message to decode
* @param obs_air_velocity C-struct to decode the message contents into
*/
static inline void mavlink_msg_obs_air_velocity_decode(const mavlink_message_t* msg, mavlink_obs_air_velocity_t* obs_air_velocity)
{
#if MAVLINK_NEED_BYTE_SWAP
obs_air_velocity->magnitude = mavlink_msg_obs_air_velocity_get_magnitude(msg);
obs_air_velocity->aoa = mavlink_msg_obs_air_velocity_get_aoa(msg);
obs_air_velocity->slip = mavlink_msg_obs_air_velocity_get_slip(msg);
#else
memcpy(obs_air_velocity, _MAV_PAYLOAD(msg), 12);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v1.0/sensesoar/mavlink_msg_obs_attitude.h
0,0 → 1,144
// MESSAGE OBS_ATTITUDE PACKING
 
#define MAVLINK_MSG_ID_OBS_ATTITUDE 174
 
typedef struct __mavlink_obs_attitude_t
{
double quat[4]; ///< Quaternion re;im
} mavlink_obs_attitude_t;
 
#define MAVLINK_MSG_ID_OBS_ATTITUDE_LEN 32
#define MAVLINK_MSG_ID_174_LEN 32
 
#define MAVLINK_MSG_OBS_ATTITUDE_FIELD_QUAT_LEN 4
 
#define MAVLINK_MESSAGE_INFO_OBS_ATTITUDE { \
"OBS_ATTITUDE", \
1, \
{ { "quat", NULL, MAVLINK_TYPE_DOUBLE, 4, 0, offsetof(mavlink_obs_attitude_t, quat) }, \
} \
}
 
 
/**
* @brief Pack a obs_attitude message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param quat Quaternion re;im
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_obs_attitude_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
const double *quat)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[32];
 
_mav_put_double_array(buf, 0, quat, 4);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 32);
#else
mavlink_obs_attitude_t packet;
 
mav_array_memcpy(packet.quat, quat, sizeof(double)*4);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 32);
#endif
 
msg->msgid = MAVLINK_MSG_ID_OBS_ATTITUDE;
return mavlink_finalize_message(msg, system_id, component_id, 32, 146);
}
 
/**
* @brief Pack a obs_attitude message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param quat Quaternion re;im
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_obs_attitude_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
const double *quat)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[32];
 
_mav_put_double_array(buf, 0, quat, 4);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 32);
#else
mavlink_obs_attitude_t packet;
 
mav_array_memcpy(packet.quat, quat, sizeof(double)*4);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 32);
#endif
 
msg->msgid = MAVLINK_MSG_ID_OBS_ATTITUDE;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 32, 146);
}
 
/**
* @brief Encode a obs_attitude struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param obs_attitude C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_obs_attitude_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_obs_attitude_t* obs_attitude)
{
return mavlink_msg_obs_attitude_pack(system_id, component_id, msg, obs_attitude->quat);
}
 
/**
* @brief Send a obs_attitude message
* @param chan MAVLink channel to send the message
*
* @param quat Quaternion re;im
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_obs_attitude_send(mavlink_channel_t chan, const double *quat)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[32];
 
_mav_put_double_array(buf, 0, quat, 4);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_ATTITUDE, buf, 32, 146);
#else
mavlink_obs_attitude_t packet;
 
mav_array_memcpy(packet.quat, quat, sizeof(double)*4);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_ATTITUDE, (const char *)&packet, 32, 146);
#endif
}
 
#endif
 
// MESSAGE OBS_ATTITUDE UNPACKING
 
 
/**
* @brief Get field quat from obs_attitude message
*
* @return Quaternion re;im
*/
static inline uint16_t mavlink_msg_obs_attitude_get_quat(const mavlink_message_t* msg, double *quat)
{
return _MAV_RETURN_double_array(msg, quat, 4, 0);
}
 
/**
* @brief Decode a obs_attitude message into a struct
*
* @param msg The message to decode
* @param obs_attitude C-struct to decode the message contents into
*/
static inline void mavlink_msg_obs_attitude_decode(const mavlink_message_t* msg, mavlink_obs_attitude_t* obs_attitude)
{
#if MAVLINK_NEED_BYTE_SWAP
mavlink_msg_obs_attitude_get_quat(msg, obs_attitude->quat);
#else
memcpy(obs_attitude, _MAV_PAYLOAD(msg), 32);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v1.0/sensesoar/mavlink_msg_obs_bias.h
0,0 → 1,167
// MESSAGE OBS_BIAS PACKING
 
#define MAVLINK_MSG_ID_OBS_BIAS 180
 
typedef struct __mavlink_obs_bias_t
{
float accBias[3]; ///< accelerometer bias
float gyroBias[3]; ///< gyroscope bias
} mavlink_obs_bias_t;
 
#define MAVLINK_MSG_ID_OBS_BIAS_LEN 24
#define MAVLINK_MSG_ID_180_LEN 24
 
#define MAVLINK_MSG_OBS_BIAS_FIELD_ACCBIAS_LEN 3
#define MAVLINK_MSG_OBS_BIAS_FIELD_GYROBIAS_LEN 3
 
#define MAVLINK_MESSAGE_INFO_OBS_BIAS { \
"OBS_BIAS", \
2, \
{ { "accBias", NULL, MAVLINK_TYPE_FLOAT, 3, 0, offsetof(mavlink_obs_bias_t, accBias) }, \
{ "gyroBias", NULL, MAVLINK_TYPE_FLOAT, 3, 12, offsetof(mavlink_obs_bias_t, gyroBias) }, \
} \
}
 
 
/**
* @brief Pack a obs_bias message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param accBias accelerometer bias
* @param gyroBias gyroscope bias
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_obs_bias_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
const float *accBias, const float *gyroBias)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[24];
 
_mav_put_float_array(buf, 0, accBias, 3);
_mav_put_float_array(buf, 12, gyroBias, 3);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 24);
#else
mavlink_obs_bias_t packet;
 
mav_array_memcpy(packet.accBias, accBias, sizeof(float)*3);
mav_array_memcpy(packet.gyroBias, gyroBias, sizeof(float)*3);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 24);
#endif
 
msg->msgid = MAVLINK_MSG_ID_OBS_BIAS;
return mavlink_finalize_message(msg, system_id, component_id, 24, 159);
}
 
/**
* @brief Pack a obs_bias message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param accBias accelerometer bias
* @param gyroBias gyroscope bias
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_obs_bias_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
const float *accBias,const float *gyroBias)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[24];
 
_mav_put_float_array(buf, 0, accBias, 3);
_mav_put_float_array(buf, 12, gyroBias, 3);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 24);
#else
mavlink_obs_bias_t packet;
 
mav_array_memcpy(packet.accBias, accBias, sizeof(float)*3);
mav_array_memcpy(packet.gyroBias, gyroBias, sizeof(float)*3);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 24);
#endif
 
msg->msgid = MAVLINK_MSG_ID_OBS_BIAS;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 24, 159);
}
 
/**
* @brief Encode a obs_bias struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param obs_bias C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_obs_bias_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_obs_bias_t* obs_bias)
{
return mavlink_msg_obs_bias_pack(system_id, component_id, msg, obs_bias->accBias, obs_bias->gyroBias);
}
 
/**
* @brief Send a obs_bias message
* @param chan MAVLink channel to send the message
*
* @param accBias accelerometer bias
* @param gyroBias gyroscope bias
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_obs_bias_send(mavlink_channel_t chan, const float *accBias, const float *gyroBias)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[24];
 
_mav_put_float_array(buf, 0, accBias, 3);
_mav_put_float_array(buf, 12, gyroBias, 3);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_BIAS, buf, 24, 159);
#else
mavlink_obs_bias_t packet;
 
mav_array_memcpy(packet.accBias, accBias, sizeof(float)*3);
mav_array_memcpy(packet.gyroBias, gyroBias, sizeof(float)*3);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_BIAS, (const char *)&packet, 24, 159);
#endif
}
 
#endif
 
// MESSAGE OBS_BIAS UNPACKING
 
 
/**
* @brief Get field accBias from obs_bias message
*
* @return accelerometer bias
*/
static inline uint16_t mavlink_msg_obs_bias_get_accBias(const mavlink_message_t* msg, float *accBias)
{
return _MAV_RETURN_float_array(msg, accBias, 3, 0);
}
 
/**
* @brief Get field gyroBias from obs_bias message
*
* @return gyroscope bias
*/
static inline uint16_t mavlink_msg_obs_bias_get_gyroBias(const mavlink_message_t* msg, float *gyroBias)
{
return _MAV_RETURN_float_array(msg, gyroBias, 3, 12);
}
 
/**
* @brief Decode a obs_bias message into a struct
*
* @param msg The message to decode
* @param obs_bias C-struct to decode the message contents into
*/
static inline void mavlink_msg_obs_bias_decode(const mavlink_message_t* msg, mavlink_obs_bias_t* obs_bias)
{
#if MAVLINK_NEED_BYTE_SWAP
mavlink_msg_obs_bias_get_accBias(msg, obs_bias->accBias);
mavlink_msg_obs_bias_get_gyroBias(msg, obs_bias->gyroBias);
#else
memcpy(obs_bias, _MAV_PAYLOAD(msg), 24);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v1.0/sensesoar/mavlink_msg_obs_position.h
0,0 → 1,188
// MESSAGE OBS_POSITION PACKING
 
#define MAVLINK_MSG_ID_OBS_POSITION 170
 
typedef struct __mavlink_obs_position_t
{
int32_t lon; ///< Longitude expressed in 1E7
int32_t lat; ///< Latitude expressed in 1E7
int32_t alt; ///< Altitude expressed in milimeters
} mavlink_obs_position_t;
 
#define MAVLINK_MSG_ID_OBS_POSITION_LEN 12
#define MAVLINK_MSG_ID_170_LEN 12
 
 
 
#define MAVLINK_MESSAGE_INFO_OBS_POSITION { \
"OBS_POSITION", \
3, \
{ { "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_obs_position_t, lon) }, \
{ "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_obs_position_t, lat) }, \
{ "alt", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_obs_position_t, alt) }, \
} \
}
 
 
/**
* @brief Pack a obs_position message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param lon Longitude expressed in 1E7
* @param lat Latitude expressed in 1E7
* @param alt Altitude expressed in milimeters
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_obs_position_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
int32_t lon, int32_t lat, int32_t alt)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[12];
_mav_put_int32_t(buf, 0, lon);
_mav_put_int32_t(buf, 4, lat);
_mav_put_int32_t(buf, 8, alt);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 12);
#else
mavlink_obs_position_t packet;
packet.lon = lon;
packet.lat = lat;
packet.alt = alt;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 12);
#endif
 
msg->msgid = MAVLINK_MSG_ID_OBS_POSITION;
return mavlink_finalize_message(msg, system_id, component_id, 12, 15);
}
 
/**
* @brief Pack a obs_position message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param lon Longitude expressed in 1E7
* @param lat Latitude expressed in 1E7
* @param alt Altitude expressed in milimeters
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_obs_position_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
int32_t lon,int32_t lat,int32_t alt)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[12];
_mav_put_int32_t(buf, 0, lon);
_mav_put_int32_t(buf, 4, lat);
_mav_put_int32_t(buf, 8, alt);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 12);
#else
mavlink_obs_position_t packet;
packet.lon = lon;
packet.lat = lat;
packet.alt = alt;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 12);
#endif
 
msg->msgid = MAVLINK_MSG_ID_OBS_POSITION;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 12, 15);
}
 
/**
* @brief Encode a obs_position struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param obs_position C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_obs_position_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_obs_position_t* obs_position)
{
return mavlink_msg_obs_position_pack(system_id, component_id, msg, obs_position->lon, obs_position->lat, obs_position->alt);
}
 
/**
* @brief Send a obs_position message
* @param chan MAVLink channel to send the message
*
* @param lon Longitude expressed in 1E7
* @param lat Latitude expressed in 1E7
* @param alt Altitude expressed in milimeters
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_obs_position_send(mavlink_channel_t chan, int32_t lon, int32_t lat, int32_t alt)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[12];
_mav_put_int32_t(buf, 0, lon);
_mav_put_int32_t(buf, 4, lat);
_mav_put_int32_t(buf, 8, alt);
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_POSITION, buf, 12, 15);
#else
mavlink_obs_position_t packet;
packet.lon = lon;
packet.lat = lat;
packet.alt = alt;
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_POSITION, (const char *)&packet, 12, 15);
#endif
}
 
#endif
 
// MESSAGE OBS_POSITION UNPACKING
 
 
/**
* @brief Get field lon from obs_position message
*
* @return Longitude expressed in 1E7
*/
static inline int32_t mavlink_msg_obs_position_get_lon(const mavlink_message_t* msg)
{
return _MAV_RETURN_int32_t(msg, 0);
}
 
/**
* @brief Get field lat from obs_position message
*
* @return Latitude expressed in 1E7
*/
static inline int32_t mavlink_msg_obs_position_get_lat(const mavlink_message_t* msg)
{
return _MAV_RETURN_int32_t(msg, 4);
}
 
/**
* @brief Get field alt from obs_position message
*
* @return Altitude expressed in milimeters
*/
static inline int32_t mavlink_msg_obs_position_get_alt(const mavlink_message_t* msg)
{
return _MAV_RETURN_int32_t(msg, 8);
}
 
/**
* @brief Decode a obs_position message into a struct
*
* @param msg The message to decode
* @param obs_position C-struct to decode the message contents into
*/
static inline void mavlink_msg_obs_position_decode(const mavlink_message_t* msg, mavlink_obs_position_t* obs_position)
{
#if MAVLINK_NEED_BYTE_SWAP
obs_position->lon = mavlink_msg_obs_position_get_lon(msg);
obs_position->lat = mavlink_msg_obs_position_get_lat(msg);
obs_position->alt = mavlink_msg_obs_position_get_alt(msg);
#else
memcpy(obs_position, _MAV_PAYLOAD(msg), 12);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v1.0/sensesoar/mavlink_msg_obs_qff.h
0,0 → 1,144
// MESSAGE OBS_QFF PACKING
 
#define MAVLINK_MSG_ID_OBS_QFF 182
 
typedef struct __mavlink_obs_qff_t
{
float qff; ///< Wind
} mavlink_obs_qff_t;
 
#define MAVLINK_MSG_ID_OBS_QFF_LEN 4
#define MAVLINK_MSG_ID_182_LEN 4
 
 
 
#define MAVLINK_MESSAGE_INFO_OBS_QFF { \
"OBS_QFF", \
1, \
{ { "qff", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_obs_qff_t, qff) }, \
} \
}
 
 
/**
* @brief Pack a obs_qff message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param qff Wind
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_obs_qff_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
float qff)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[4];
_mav_put_float(buf, 0, qff);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 4);
#else
mavlink_obs_qff_t packet;
packet.qff = qff;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 4);
#endif
 
msg->msgid = MAVLINK_MSG_ID_OBS_QFF;
return mavlink_finalize_message(msg, system_id, component_id, 4, 24);
}
 
/**
* @brief Pack a obs_qff message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param qff Wind
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_obs_qff_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
float qff)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[4];
_mav_put_float(buf, 0, qff);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 4);
#else
mavlink_obs_qff_t packet;
packet.qff = qff;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 4);
#endif
 
msg->msgid = MAVLINK_MSG_ID_OBS_QFF;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 4, 24);
}
 
/**
* @brief Encode a obs_qff struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param obs_qff C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_obs_qff_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_obs_qff_t* obs_qff)
{
return mavlink_msg_obs_qff_pack(system_id, component_id, msg, obs_qff->qff);
}
 
/**
* @brief Send a obs_qff message
* @param chan MAVLink channel to send the message
*
* @param qff Wind
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_obs_qff_send(mavlink_channel_t chan, float qff)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[4];
_mav_put_float(buf, 0, qff);
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_QFF, buf, 4, 24);
#else
mavlink_obs_qff_t packet;
packet.qff = qff;
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_QFF, (const char *)&packet, 4, 24);
#endif
}
 
#endif
 
// MESSAGE OBS_QFF UNPACKING
 
 
/**
* @brief Get field qff from obs_qff message
*
* @return Wind
*/
static inline float mavlink_msg_obs_qff_get_qff(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 0);
}
 
/**
* @brief Decode a obs_qff message into a struct
*
* @param msg The message to decode
* @param obs_qff C-struct to decode the message contents into
*/
static inline void mavlink_msg_obs_qff_decode(const mavlink_message_t* msg, mavlink_obs_qff_t* obs_qff)
{
#if MAVLINK_NEED_BYTE_SWAP
obs_qff->qff = mavlink_msg_obs_qff_get_qff(msg);
#else
memcpy(obs_qff, _MAV_PAYLOAD(msg), 4);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v1.0/sensesoar/mavlink_msg_obs_velocity.h
0,0 → 1,144
// MESSAGE OBS_VELOCITY PACKING
 
#define MAVLINK_MSG_ID_OBS_VELOCITY 172
 
typedef struct __mavlink_obs_velocity_t
{
float vel[3]; ///< Velocity
} mavlink_obs_velocity_t;
 
#define MAVLINK_MSG_ID_OBS_VELOCITY_LEN 12
#define MAVLINK_MSG_ID_172_LEN 12
 
#define MAVLINK_MSG_OBS_VELOCITY_FIELD_VEL_LEN 3
 
#define MAVLINK_MESSAGE_INFO_OBS_VELOCITY { \
"OBS_VELOCITY", \
1, \
{ { "vel", NULL, MAVLINK_TYPE_FLOAT, 3, 0, offsetof(mavlink_obs_velocity_t, vel) }, \
} \
}
 
 
/**
* @brief Pack a obs_velocity message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param vel Velocity
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_obs_velocity_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
const float *vel)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[12];
 
_mav_put_float_array(buf, 0, vel, 3);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 12);
#else
mavlink_obs_velocity_t packet;
 
mav_array_memcpy(packet.vel, vel, sizeof(float)*3);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 12);
#endif
 
msg->msgid = MAVLINK_MSG_ID_OBS_VELOCITY;
return mavlink_finalize_message(msg, system_id, component_id, 12, 108);
}
 
/**
* @brief Pack a obs_velocity message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param vel Velocity
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_obs_velocity_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
const float *vel)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[12];
 
_mav_put_float_array(buf, 0, vel, 3);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 12);
#else
mavlink_obs_velocity_t packet;
 
mav_array_memcpy(packet.vel, vel, sizeof(float)*3);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 12);
#endif
 
msg->msgid = MAVLINK_MSG_ID_OBS_VELOCITY;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 12, 108);
}
 
/**
* @brief Encode a obs_velocity struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param obs_velocity C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_obs_velocity_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_obs_velocity_t* obs_velocity)
{
return mavlink_msg_obs_velocity_pack(system_id, component_id, msg, obs_velocity->vel);
}
 
/**
* @brief Send a obs_velocity message
* @param chan MAVLink channel to send the message
*
* @param vel Velocity
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_obs_velocity_send(mavlink_channel_t chan, const float *vel)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[12];
 
_mav_put_float_array(buf, 0, vel, 3);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_VELOCITY, buf, 12, 108);
#else
mavlink_obs_velocity_t packet;
 
mav_array_memcpy(packet.vel, vel, sizeof(float)*3);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_VELOCITY, (const char *)&packet, 12, 108);
#endif
}
 
#endif
 
// MESSAGE OBS_VELOCITY UNPACKING
 
 
/**
* @brief Get field vel from obs_velocity message
*
* @return Velocity
*/
static inline uint16_t mavlink_msg_obs_velocity_get_vel(const mavlink_message_t* msg, float *vel)
{
return _MAV_RETURN_float_array(msg, vel, 3, 0);
}
 
/**
* @brief Decode a obs_velocity message into a struct
*
* @param msg The message to decode
* @param obs_velocity C-struct to decode the message contents into
*/
static inline void mavlink_msg_obs_velocity_decode(const mavlink_message_t* msg, mavlink_obs_velocity_t* obs_velocity)
{
#if MAVLINK_NEED_BYTE_SWAP
mavlink_msg_obs_velocity_get_vel(msg, obs_velocity->vel);
#else
memcpy(obs_velocity, _MAV_PAYLOAD(msg), 12);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v1.0/sensesoar/mavlink_msg_obs_wind.h
0,0 → 1,144
// MESSAGE OBS_WIND PACKING
 
#define MAVLINK_MSG_ID_OBS_WIND 176
 
typedef struct __mavlink_obs_wind_t
{
float wind[3]; ///< Wind
} mavlink_obs_wind_t;
 
#define MAVLINK_MSG_ID_OBS_WIND_LEN 12
#define MAVLINK_MSG_ID_176_LEN 12
 
#define MAVLINK_MSG_OBS_WIND_FIELD_WIND_LEN 3
 
#define MAVLINK_MESSAGE_INFO_OBS_WIND { \
"OBS_WIND", \
1, \
{ { "wind", NULL, MAVLINK_TYPE_FLOAT, 3, 0, offsetof(mavlink_obs_wind_t, wind) }, \
} \
}
 
 
/**
* @brief Pack a obs_wind message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param wind Wind
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_obs_wind_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
const float *wind)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[12];
 
_mav_put_float_array(buf, 0, wind, 3);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 12);
#else
mavlink_obs_wind_t packet;
 
mav_array_memcpy(packet.wind, wind, sizeof(float)*3);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 12);
#endif
 
msg->msgid = MAVLINK_MSG_ID_OBS_WIND;
return mavlink_finalize_message(msg, system_id, component_id, 12, 16);
}
 
/**
* @brief Pack a obs_wind message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param wind Wind
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_obs_wind_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
const float *wind)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[12];
 
_mav_put_float_array(buf, 0, wind, 3);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 12);
#else
mavlink_obs_wind_t packet;
 
mav_array_memcpy(packet.wind, wind, sizeof(float)*3);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 12);
#endif
 
msg->msgid = MAVLINK_MSG_ID_OBS_WIND;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 12, 16);
}
 
/**
* @brief Encode a obs_wind struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param obs_wind C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_obs_wind_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_obs_wind_t* obs_wind)
{
return mavlink_msg_obs_wind_pack(system_id, component_id, msg, obs_wind->wind);
}
 
/**
* @brief Send a obs_wind message
* @param chan MAVLink channel to send the message
*
* @param wind Wind
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_obs_wind_send(mavlink_channel_t chan, const float *wind)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[12];
 
_mav_put_float_array(buf, 0, wind, 3);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_WIND, buf, 12, 16);
#else
mavlink_obs_wind_t packet;
 
mav_array_memcpy(packet.wind, wind, sizeof(float)*3);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBS_WIND, (const char *)&packet, 12, 16);
#endif
}
 
#endif
 
// MESSAGE OBS_WIND UNPACKING
 
 
/**
* @brief Get field wind from obs_wind message
*
* @return Wind
*/
static inline uint16_t mavlink_msg_obs_wind_get_wind(const mavlink_message_t* msg, float *wind)
{
return _MAV_RETURN_float_array(msg, wind, 3, 0);
}
 
/**
* @brief Decode a obs_wind message into a struct
*
* @param msg The message to decode
* @param obs_wind C-struct to decode the message contents into
*/
static inline void mavlink_msg_obs_wind_decode(const mavlink_message_t* msg, mavlink_obs_wind_t* obs_wind)
{
#if MAVLINK_NEED_BYTE_SWAP
mavlink_msg_obs_wind_get_wind(msg, obs_wind->wind);
#else
memcpy(obs_wind, _MAV_PAYLOAD(msg), 12);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v1.0/sensesoar/mavlink_msg_pm_elec.h
0,0 → 1,182
// MESSAGE PM_ELEC PACKING
 
#define MAVLINK_MSG_ID_PM_ELEC 188
 
typedef struct __mavlink_pm_elec_t
{
float PwCons; ///< current power consumption
float BatStat; ///< battery status
float PwGen[3]; ///< Power generation from each module
} mavlink_pm_elec_t;
 
#define MAVLINK_MSG_ID_PM_ELEC_LEN 20
#define MAVLINK_MSG_ID_188_LEN 20
 
#define MAVLINK_MSG_PM_ELEC_FIELD_PWGEN_LEN 3
 
#define MAVLINK_MESSAGE_INFO_PM_ELEC { \
"PM_ELEC", \
3, \
{ { "PwCons", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_pm_elec_t, PwCons) }, \
{ "BatStat", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_pm_elec_t, BatStat) }, \
{ "PwGen", NULL, MAVLINK_TYPE_FLOAT, 3, 8, offsetof(mavlink_pm_elec_t, PwGen) }, \
} \
}
 
 
/**
* @brief Pack a pm_elec message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param PwCons current power consumption
* @param BatStat battery status
* @param PwGen Power generation from each module
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_pm_elec_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
float PwCons, float BatStat, const float *PwGen)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[20];
_mav_put_float(buf, 0, PwCons);
_mav_put_float(buf, 4, BatStat);
_mav_put_float_array(buf, 8, PwGen, 3);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 20);
#else
mavlink_pm_elec_t packet;
packet.PwCons = PwCons;
packet.BatStat = BatStat;
mav_array_memcpy(packet.PwGen, PwGen, sizeof(float)*3);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 20);
#endif
 
msg->msgid = MAVLINK_MSG_ID_PM_ELEC;
return mavlink_finalize_message(msg, system_id, component_id, 20, 170);
}
 
/**
* @brief Pack a pm_elec message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param PwCons current power consumption
* @param BatStat battery status
* @param PwGen Power generation from each module
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_pm_elec_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
float PwCons,float BatStat,const float *PwGen)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[20];
_mav_put_float(buf, 0, PwCons);
_mav_put_float(buf, 4, BatStat);
_mav_put_float_array(buf, 8, PwGen, 3);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 20);
#else
mavlink_pm_elec_t packet;
packet.PwCons = PwCons;
packet.BatStat = BatStat;
mav_array_memcpy(packet.PwGen, PwGen, sizeof(float)*3);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 20);
#endif
 
msg->msgid = MAVLINK_MSG_ID_PM_ELEC;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 20, 170);
}
 
/**
* @brief Encode a pm_elec struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param pm_elec C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_pm_elec_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_pm_elec_t* pm_elec)
{
return mavlink_msg_pm_elec_pack(system_id, component_id, msg, pm_elec->PwCons, pm_elec->BatStat, pm_elec->PwGen);
}
 
/**
* @brief Send a pm_elec message
* @param chan MAVLink channel to send the message
*
* @param PwCons current power consumption
* @param BatStat battery status
* @param PwGen Power generation from each module
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_pm_elec_send(mavlink_channel_t chan, float PwCons, float BatStat, const float *PwGen)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[20];
_mav_put_float(buf, 0, PwCons);
_mav_put_float(buf, 4, BatStat);
_mav_put_float_array(buf, 8, PwGen, 3);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PM_ELEC, buf, 20, 170);
#else
mavlink_pm_elec_t packet;
packet.PwCons = PwCons;
packet.BatStat = BatStat;
mav_array_memcpy(packet.PwGen, PwGen, sizeof(float)*3);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PM_ELEC, (const char *)&packet, 20, 170);
#endif
}
 
#endif
 
// MESSAGE PM_ELEC UNPACKING
 
 
/**
* @brief Get field PwCons from pm_elec message
*
* @return current power consumption
*/
static inline float mavlink_msg_pm_elec_get_PwCons(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 0);
}
 
/**
* @brief Get field BatStat from pm_elec message
*
* @return battery status
*/
static inline float mavlink_msg_pm_elec_get_BatStat(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 4);
}
 
/**
* @brief Get field PwGen from pm_elec message
*
* @return Power generation from each module
*/
static inline uint16_t mavlink_msg_pm_elec_get_PwGen(const mavlink_message_t* msg, float *PwGen)
{
return _MAV_RETURN_float_array(msg, PwGen, 3, 8);
}
 
/**
* @brief Decode a pm_elec message into a struct
*
* @param msg The message to decode
* @param pm_elec C-struct to decode the message contents into
*/
static inline void mavlink_msg_pm_elec_decode(const mavlink_message_t* msg, mavlink_pm_elec_t* pm_elec)
{
#if MAVLINK_NEED_BYTE_SWAP
pm_elec->PwCons = mavlink_msg_pm_elec_get_PwCons(msg);
pm_elec->BatStat = mavlink_msg_pm_elec_get_BatStat(msg);
mavlink_msg_pm_elec_get_PwGen(msg, pm_elec->PwGen);
#else
memcpy(pm_elec, _MAV_PAYLOAD(msg), 20);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v1.0/sensesoar/mavlink_msg_sys_stat.h
0,0 → 1,210
// MESSAGE SYS_Stat PACKING
 
#define MAVLINK_MSG_ID_SYS_Stat 190
 
typedef struct __mavlink_sys_stat_t
{
uint8_t gps; ///< gps status
uint8_t act; ///< actuator status
uint8_t mod; ///< module status
uint8_t commRssi; ///< module status
} mavlink_sys_stat_t;
 
#define MAVLINK_MSG_ID_SYS_Stat_LEN 4
#define MAVLINK_MSG_ID_190_LEN 4
 
 
 
#define MAVLINK_MESSAGE_INFO_SYS_Stat { \
"SYS_Stat", \
4, \
{ { "gps", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_sys_stat_t, gps) }, \
{ "act", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_sys_stat_t, act) }, \
{ "mod", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_sys_stat_t, mod) }, \
{ "commRssi", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_sys_stat_t, commRssi) }, \
} \
}
 
 
/**
* @brief Pack a sys_stat message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param gps gps status
* @param act actuator status
* @param mod module status
* @param commRssi module status
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_sys_stat_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t gps, uint8_t act, uint8_t mod, uint8_t commRssi)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[4];
_mav_put_uint8_t(buf, 0, gps);
_mav_put_uint8_t(buf, 1, act);
_mav_put_uint8_t(buf, 2, mod);
_mav_put_uint8_t(buf, 3, commRssi);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 4);
#else
mavlink_sys_stat_t packet;
packet.gps = gps;
packet.act = act;
packet.mod = mod;
packet.commRssi = commRssi;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 4);
#endif
 
msg->msgid = MAVLINK_MSG_ID_SYS_Stat;
return mavlink_finalize_message(msg, system_id, component_id, 4, 157);
}
 
/**
* @brief Pack a sys_stat message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message was sent over
* @param msg The MAVLink message to compress the data into
* @param gps gps status
* @param act actuator status
* @param mod module status
* @param commRssi module status
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_sys_stat_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint8_t gps,uint8_t act,uint8_t mod,uint8_t commRssi)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[4];
_mav_put_uint8_t(buf, 0, gps);
_mav_put_uint8_t(buf, 1, act);
_mav_put_uint8_t(buf, 2, mod);
_mav_put_uint8_t(buf, 3, commRssi);
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, 4);
#else
mavlink_sys_stat_t packet;
packet.gps = gps;
packet.act = act;
packet.mod = mod;
packet.commRssi = commRssi;
 
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, 4);
#endif
 
msg->msgid = MAVLINK_MSG_ID_SYS_Stat;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, 4, 157);
}
 
/**
* @brief Encode a sys_stat struct into a message
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param sys_stat C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_sys_stat_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_sys_stat_t* sys_stat)
{
return mavlink_msg_sys_stat_pack(system_id, component_id, msg, sys_stat->gps, sys_stat->act, sys_stat->mod, sys_stat->commRssi);
}
 
/**
* @brief Send a sys_stat message
* @param chan MAVLink channel to send the message
*
* @param gps gps status
* @param act actuator status
* @param mod module status
* @param commRssi module status
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
 
static inline void mavlink_msg_sys_stat_send(mavlink_channel_t chan, uint8_t gps, uint8_t act, uint8_t mod, uint8_t commRssi)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[4];
_mav_put_uint8_t(buf, 0, gps);
_mav_put_uint8_t(buf, 1, act);
_mav_put_uint8_t(buf, 2, mod);
_mav_put_uint8_t(buf, 3, commRssi);
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYS_Stat, buf, 4, 157);
#else
mavlink_sys_stat_t packet;
packet.gps = gps;
packet.act = act;
packet.mod = mod;
packet.commRssi = commRssi;
 
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SYS_Stat, (const char *)&packet, 4, 157);
#endif
}
 
#endif
 
// MESSAGE SYS_Stat UNPACKING
 
 
/**
* @brief Get field gps from sys_stat message
*
* @return gps status
*/
static inline uint8_t mavlink_msg_sys_stat_get_gps(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 0);
}
 
/**
* @brief Get field act from sys_stat message
*
* @return actuator status
*/
static inline uint8_t mavlink_msg_sys_stat_get_act(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 1);
}
 
/**
* @brief Get field mod from sys_stat message
*
* @return module status
*/
static inline uint8_t mavlink_msg_sys_stat_get_mod(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 2);
}
 
/**
* @brief Get field commRssi from sys_stat message
*
* @return module status
*/
static inline uint8_t mavlink_msg_sys_stat_get_commRssi(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 3);
}
 
/**
* @brief Decode a sys_stat message into a struct
*
* @param msg The message to decode
* @param sys_stat C-struct to decode the message contents into
*/
static inline void mavlink_msg_sys_stat_decode(const mavlink_message_t* msg, mavlink_sys_stat_t* sys_stat)
{
#if MAVLINK_NEED_BYTE_SWAP
sys_stat->gps = mavlink_msg_sys_stat_get_gps(msg);
sys_stat->act = mavlink_msg_sys_stat_get_act(msg);
sys_stat->mod = mavlink_msg_sys_stat_get_mod(msg);
sys_stat->commRssi = mavlink_msg_sys_stat_get_commRssi(msg);
#else
memcpy(sys_stat, _MAV_PAYLOAD(msg), 4);
#endif
}
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v1.0/sensesoar/sensesoar.h
0,0 → 1,77
/** @file
* @brief MAVLink comm protocol generated from sensesoar.xml
* @see http://qgroundcontrol.org/mavlink/
*/
#ifndef SENSESOAR_H
#define SENSESOAR_H
 
#ifdef __cplusplus
extern "C" {
#endif
 
// MESSAGE LENGTHS AND CRCS
 
#ifndef MAVLINK_MESSAGE_LENGTHS
#define MAVLINK_MESSAGE_LENGTHS {9, 31, 12, 0, 14, 28, 3, 32, 0, 0, 0, 6, 0, 0, 0, 0, 0, 0, 0, 0, 20, 2, 25, 23, 30, 101, 22, 26, 16, 14, 28, 32, 28, 28, 22, 22, 21, 6, 6, 37, 4, 4, 2, 2, 4, 2, 2, 3, 13, 12, 19, 17, 15, 15, 27, 25, 18, 18, 20, 20, 9, 54, 26, 0, 36, 0, 6, 4, 0, 21, 18, 0, 0, 0, 20, 0, 33, 3, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 28, 56, 42, 33, 0, 0, 0, 0, 0, 0, 0, 26, 32, 32, 20, 32, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 12, 0, 12, 0, 32, 0, 12, 0, 12, 0, 24, 0, 4, 4, 12, 0, 12, 0, 20, 0, 4, 0, 5, 0, 5, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 36, 30, 18, 18, 51, 9, 0}
#endif
 
#ifndef MAVLINK_MESSAGE_CRCS
#define MAVLINK_MESSAGE_CRCS {50, 124, 137, 0, 237, 217, 104, 119, 0, 0, 0, 89, 0, 0, 0, 0, 0, 0, 0, 0, 214, 159, 220, 168, 24, 23, 170, 144, 67, 115, 39, 246, 185, 104, 237, 244, 222, 212, 9, 254, 230, 28, 28, 132, 221, 232, 11, 153, 41, 39, 214, 223, 141, 33, 15, 3, 100, 24, 239, 238, 30, 200, 183, 0, 130, 0, 148, 21, 0, 52, 124, 0, 0, 0, 20, 0, 152, 143, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 231, 183, 63, 54, 0, 0, 0, 0, 0, 0, 0, 175, 102, 158, 208, 56, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 15, 0, 108, 0, 146, 0, 16, 0, 32, 0, 159, 0, 24, 248, 79, 0, 5, 0, 170, 0, 157, 0, 209, 0, 243, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 204, 49, 170, 44, 83, 46, 0}
#endif
 
#ifndef MAVLINK_MESSAGE_INFO
#define MAVLINK_MESSAGE_INFO {MAVLINK_MESSAGE_INFO_HEARTBEAT, MAVLINK_MESSAGE_INFO_SYS_STATUS, MAVLINK_MESSAGE_INFO_SYSTEM_TIME, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_PING, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL, MAVLINK_MESSAGE_INFO_CHANGE_OPERATOR_CONTROL_ACK, MAVLINK_MESSAGE_INFO_AUTH_KEY, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_SET_MODE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_READ, MAVLINK_MESSAGE_INFO_PARAM_REQUEST_LIST, MAVLINK_MESSAGE_INFO_PARAM_VALUE, MAVLINK_MESSAGE_INFO_PARAM_SET, MAVLINK_MESSAGE_INFO_GPS_RAW_INT, MAVLINK_MESSAGE_INFO_GPS_STATUS, MAVLINK_MESSAGE_INFO_SCALED_IMU, MAVLINK_MESSAGE_INFO_RAW_IMU, MAVLINK_MESSAGE_INFO_RAW_PRESSURE, MAVLINK_MESSAGE_INFO_SCALED_PRESSURE, MAVLINK_MESSAGE_INFO_ATTITUDE, MAVLINK_MESSAGE_INFO_ATTITUDE_QUATERNION, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_INT, MAVLINK_MESSAGE_INFO_RC_CHANNELS_SCALED, MAVLINK_MESSAGE_INFO_RC_CHANNELS_RAW, MAVLINK_MESSAGE_INFO_SERVO_OUTPUT_RAW, MAVLINK_MESSAGE_INFO_MISSION_REQUEST_PARTIAL_LIST, MAVLINK_MESSAGE_INFO_MISSION_WRITE_PARTIAL_LIST, MAVLINK_MESSAGE_INFO_MISSION_ITEM, MAVLINK_MESSAGE_INFO_MISSION_REQUEST, MAVLINK_MESSAGE_INFO_MISSION_SET_CURRENT, MAVLINK_MESSAGE_INFO_MISSION_CURRENT, MAVLINK_MESSAGE_INFO_MISSION_REQUEST_LIST, MAVLINK_MESSAGE_INFO_MISSION_COUNT, MAVLINK_MESSAGE_INFO_MISSION_CLEAR_ALL, MAVLINK_MESSAGE_INFO_MISSION_ITEM_REACHED, MAVLINK_MESSAGE_INFO_MISSION_ACK, MAVLINK_MESSAGE_INFO_SET_GPS_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_GPS_GLOBAL_ORIGIN, MAVLINK_MESSAGE_INFO_SET_LOCAL_POSITION_SETPOINT, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_SETPOINT, MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_SETPOINT_INT, MAVLINK_MESSAGE_INFO_SET_GLOBAL_POSITION_SETPOINT_INT, MAVLINK_MESSAGE_INFO_SAFETY_SET_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SAFETY_ALLOWED_AREA, MAVLINK_MESSAGE_INFO_SET_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_SET_ROLL_PITCH_YAW_SPEED_THRUST, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT, MAVLINK_MESSAGE_INFO_SET_QUAD_MOTORS_SETPOINT, MAVLINK_MESSAGE_INFO_SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST, MAVLINK_MESSAGE_INFO_NAV_CONTROLLER_OUTPUT, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_STATE_CORRECTION, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_REQUEST_DATA_STREAM, MAVLINK_MESSAGE_INFO_DATA_STREAM, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_MANUAL_CONTROL, MAVLINK_MESSAGE_INFO_RC_CHANNELS_OVERRIDE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_VFR_HUD, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_COMMAND_LONG, MAVLINK_MESSAGE_INFO_COMMAND_ACK, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET, MAVLINK_MESSAGE_INFO_HIL_STATE, MAVLINK_MESSAGE_INFO_HIL_CONTROLS, MAVLINK_MESSAGE_INFO_HIL_RC_INPUTS_RAW, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_OPTICAL_FLOW, MAVLINK_MESSAGE_INFO_GLOBAL_VISION_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_VISION_POSITION_ESTIMATE, MAVLINK_MESSAGE_INFO_VISION_SPEED_ESTIMATE, MAVLINK_MESSAGE_INFO_VICON_POSITION_ESTIMATE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_OBS_POSITION, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_OBS_VELOCITY, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_OBS_ATTITUDE, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_OBS_WIND, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_OBS_AIR_VELOCITY, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_OBS_BIAS, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_OBS_QFF, MAVLINK_MESSAGE_INFO_OBS_AIR_TEMP, MAVLINK_MESSAGE_INFO_FILT_ROT_VEL, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_LLC_OUT, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_PM_ELEC, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_SYS_Stat, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_CMD_AIRSPEED_CHNG, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_CMD_AIRSPEED_ACK, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}, MAVLINK_MESSAGE_INFO_MEMORY_VECT, MAVLINK_MESSAGE_INFO_DEBUG_VECT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_FLOAT, MAVLINK_MESSAGE_INFO_NAMED_VALUE_INT, MAVLINK_MESSAGE_INFO_STATUSTEXT, MAVLINK_MESSAGE_INFO_DEBUG, {"EMPTY",0,{{"","",MAVLINK_TYPE_CHAR,0,0,0}}}}
#endif
 
#include "../protocol.h"
 
#define MAVLINK_ENABLED_SENSESOAR
 
#include "../common/common.h"
 
// MAVLINK VERSION
 
#ifndef MAVLINK_VERSION
#define MAVLINK_VERSION 2
#endif
 
#if (MAVLINK_VERSION == 0)
#undef MAVLINK_VERSION
#define MAVLINK_VERSION 2
#endif
 
// ENUM DEFINITIONS
 
 
/** @brief Different flight modes */
#ifndef HAVE_ENUM_SENSESOAR_MODE
#define HAVE_ENUM_SENSESOAR_MODE
enum SENSESOAR_MODE
{
SENSESOAR_MODE_GLIDING=1, /* | */
SENSESOAR_MODE_AUTONOMOUS=2, /* | */
SENSESOAR_MODE_MANUAL=3, /* | */
SENSESOAR_MODE_ENUM_END=4, /* | */
};
#endif
 
// MESSAGE DEFINITIONS
#include "./mavlink_msg_obs_position.h"
#include "./mavlink_msg_obs_velocity.h"
#include "./mavlink_msg_obs_attitude.h"
#include "./mavlink_msg_obs_wind.h"
#include "./mavlink_msg_obs_air_velocity.h"
#include "./mavlink_msg_obs_bias.h"
#include "./mavlink_msg_obs_qff.h"
#include "./mavlink_msg_obs_air_temp.h"
#include "./mavlink_msg_filt_rot_vel.h"
#include "./mavlink_msg_llc_out.h"
#include "./mavlink_msg_pm_elec.h"
#include "./mavlink_msg_sys_stat.h"
#include "./mavlink_msg_cmd_airspeed_chng.h"
#include "./mavlink_msg_cmd_airspeed_ack.h"
 
#ifdef __cplusplus
}
#endif // __cplusplus
#endif // SENSESOAR_H
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v1.0/sensesoar/testsuite.h
0,0 → 1,676
/** @file
* @brief MAVLink comm protocol testsuite generated from sensesoar.xml
* @see http://qgroundcontrol.org/mavlink/
*/
#ifndef SENSESOAR_TESTSUITE_H
#define SENSESOAR_TESTSUITE_H
 
#ifdef __cplusplus
extern "C" {
#endif
 
#ifndef MAVLINK_TEST_ALL
#define MAVLINK_TEST_ALL
static void mavlink_test_common(uint8_t, uint8_t, mavlink_message_t *last_msg);
static void mavlink_test_sensesoar(uint8_t, uint8_t, mavlink_message_t *last_msg);
 
static void mavlink_test_all(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_test_common(system_id, component_id, last_msg);
mavlink_test_sensesoar(system_id, component_id, last_msg);
}
#endif
 
#include "../common/testsuite.h"
 
 
static void mavlink_test_obs_position(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_obs_position_t packet_in = {
963497464,
963497672,
963497880,
};
mavlink_obs_position_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.lon = packet_in.lon;
packet1.lat = packet_in.lat;
packet1.alt = packet_in.alt;
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_obs_position_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_obs_position_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_obs_position_pack(system_id, component_id, &msg , packet1.lon , packet1.lat , packet1.alt );
mavlink_msg_obs_position_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_obs_position_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.lon , packet1.lat , packet1.alt );
mavlink_msg_obs_position_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_obs_position_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_obs_position_send(MAVLINK_COMM_1 , packet1.lon , packet1.lat , packet1.alt );
mavlink_msg_obs_position_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_obs_velocity(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_obs_velocity_t packet_in = {
{ 17.0, 18.0, 19.0 },
};
mavlink_obs_velocity_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
mav_array_memcpy(packet1.vel, packet_in.vel, sizeof(float)*3);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_obs_velocity_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_obs_velocity_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_obs_velocity_pack(system_id, component_id, &msg , packet1.vel );
mavlink_msg_obs_velocity_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_obs_velocity_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.vel );
mavlink_msg_obs_velocity_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_obs_velocity_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_obs_velocity_send(MAVLINK_COMM_1 , packet1.vel );
mavlink_msg_obs_velocity_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_obs_attitude(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_obs_attitude_t packet_in = {
{ 123.0, 124.0, 125.0, 126.0 },
};
mavlink_obs_attitude_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
mav_array_memcpy(packet1.quat, packet_in.quat, sizeof(double)*4);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_obs_attitude_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_obs_attitude_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_obs_attitude_pack(system_id, component_id, &msg , packet1.quat );
mavlink_msg_obs_attitude_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_obs_attitude_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.quat );
mavlink_msg_obs_attitude_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_obs_attitude_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_obs_attitude_send(MAVLINK_COMM_1 , packet1.quat );
mavlink_msg_obs_attitude_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_obs_wind(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_obs_wind_t packet_in = {
{ 17.0, 18.0, 19.0 },
};
mavlink_obs_wind_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
mav_array_memcpy(packet1.wind, packet_in.wind, sizeof(float)*3);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_obs_wind_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_obs_wind_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_obs_wind_pack(system_id, component_id, &msg , packet1.wind );
mavlink_msg_obs_wind_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_obs_wind_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.wind );
mavlink_msg_obs_wind_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_obs_wind_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_obs_wind_send(MAVLINK_COMM_1 , packet1.wind );
mavlink_msg_obs_wind_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_obs_air_velocity(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_obs_air_velocity_t packet_in = {
17.0,
45.0,
73.0,
};
mavlink_obs_air_velocity_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.magnitude = packet_in.magnitude;
packet1.aoa = packet_in.aoa;
packet1.slip = packet_in.slip;
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_obs_air_velocity_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_obs_air_velocity_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_obs_air_velocity_pack(system_id, component_id, &msg , packet1.magnitude , packet1.aoa , packet1.slip );
mavlink_msg_obs_air_velocity_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_obs_air_velocity_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.magnitude , packet1.aoa , packet1.slip );
mavlink_msg_obs_air_velocity_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_obs_air_velocity_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_obs_air_velocity_send(MAVLINK_COMM_1 , packet1.magnitude , packet1.aoa , packet1.slip );
mavlink_msg_obs_air_velocity_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_obs_bias(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_obs_bias_t packet_in = {
{ 17.0, 18.0, 19.0 },
{ 101.0, 102.0, 103.0 },
};
mavlink_obs_bias_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
mav_array_memcpy(packet1.accBias, packet_in.accBias, sizeof(float)*3);
mav_array_memcpy(packet1.gyroBias, packet_in.gyroBias, sizeof(float)*3);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_obs_bias_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_obs_bias_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_obs_bias_pack(system_id, component_id, &msg , packet1.accBias , packet1.gyroBias );
mavlink_msg_obs_bias_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_obs_bias_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.accBias , packet1.gyroBias );
mavlink_msg_obs_bias_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_obs_bias_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_obs_bias_send(MAVLINK_COMM_1 , packet1.accBias , packet1.gyroBias );
mavlink_msg_obs_bias_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_obs_qff(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_obs_qff_t packet_in = {
17.0,
};
mavlink_obs_qff_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.qff = packet_in.qff;
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_obs_qff_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_obs_qff_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_obs_qff_pack(system_id, component_id, &msg , packet1.qff );
mavlink_msg_obs_qff_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_obs_qff_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.qff );
mavlink_msg_obs_qff_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_obs_qff_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_obs_qff_send(MAVLINK_COMM_1 , packet1.qff );
mavlink_msg_obs_qff_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_obs_air_temp(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_obs_air_temp_t packet_in = {
17.0,
};
mavlink_obs_air_temp_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.airT = packet_in.airT;
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_obs_air_temp_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_obs_air_temp_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_obs_air_temp_pack(system_id, component_id, &msg , packet1.airT );
mavlink_msg_obs_air_temp_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_obs_air_temp_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.airT );
mavlink_msg_obs_air_temp_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_obs_air_temp_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_obs_air_temp_send(MAVLINK_COMM_1 , packet1.airT );
mavlink_msg_obs_air_temp_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_filt_rot_vel(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_filt_rot_vel_t packet_in = {
{ 17.0, 18.0, 19.0 },
};
mavlink_filt_rot_vel_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
mav_array_memcpy(packet1.rotVel, packet_in.rotVel, sizeof(float)*3);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_filt_rot_vel_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_filt_rot_vel_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_filt_rot_vel_pack(system_id, component_id, &msg , packet1.rotVel );
mavlink_msg_filt_rot_vel_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_filt_rot_vel_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.rotVel );
mavlink_msg_filt_rot_vel_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_filt_rot_vel_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_filt_rot_vel_send(MAVLINK_COMM_1 , packet1.rotVel );
mavlink_msg_filt_rot_vel_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_llc_out(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_llc_out_t packet_in = {
{ 17235, 17236, 17237, 17238 },
{ 17651, 17652 },
};
mavlink_llc_out_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
mav_array_memcpy(packet1.servoOut, packet_in.servoOut, sizeof(int16_t)*4);
mav_array_memcpy(packet1.MotorOut, packet_in.MotorOut, sizeof(int16_t)*2);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_llc_out_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_llc_out_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_llc_out_pack(system_id, component_id, &msg , packet1.servoOut , packet1.MotorOut );
mavlink_msg_llc_out_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_llc_out_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.servoOut , packet1.MotorOut );
mavlink_msg_llc_out_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_llc_out_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_llc_out_send(MAVLINK_COMM_1 , packet1.servoOut , packet1.MotorOut );
mavlink_msg_llc_out_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_pm_elec(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_pm_elec_t packet_in = {
17.0,
45.0,
{ 73.0, 74.0, 75.0 },
};
mavlink_pm_elec_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.PwCons = packet_in.PwCons;
packet1.BatStat = packet_in.BatStat;
mav_array_memcpy(packet1.PwGen, packet_in.PwGen, sizeof(float)*3);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_pm_elec_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_pm_elec_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_pm_elec_pack(system_id, component_id, &msg , packet1.PwCons , packet1.BatStat , packet1.PwGen );
mavlink_msg_pm_elec_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_pm_elec_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.PwCons , packet1.BatStat , packet1.PwGen );
mavlink_msg_pm_elec_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_pm_elec_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_pm_elec_send(MAVLINK_COMM_1 , packet1.PwCons , packet1.BatStat , packet1.PwGen );
mavlink_msg_pm_elec_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_sys_stat(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_sys_stat_t packet_in = {
5,
72,
139,
206,
};
mavlink_sys_stat_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.gps = packet_in.gps;
packet1.act = packet_in.act;
packet1.mod = packet_in.mod;
packet1.commRssi = packet_in.commRssi;
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_sys_stat_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_sys_stat_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_sys_stat_pack(system_id, component_id, &msg , packet1.gps , packet1.act , packet1.mod , packet1.commRssi );
mavlink_msg_sys_stat_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_sys_stat_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.gps , packet1.act , packet1.mod , packet1.commRssi );
mavlink_msg_sys_stat_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_sys_stat_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_sys_stat_send(MAVLINK_COMM_1 , packet1.gps , packet1.act , packet1.mod , packet1.commRssi );
mavlink_msg_sys_stat_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_cmd_airspeed_chng(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_cmd_airspeed_chng_t packet_in = {
17.0,
17,
};
mavlink_cmd_airspeed_chng_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.spCmd = packet_in.spCmd;
packet1.target = packet_in.target;
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_cmd_airspeed_chng_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_cmd_airspeed_chng_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_cmd_airspeed_chng_pack(system_id, component_id, &msg , packet1.target , packet1.spCmd );
mavlink_msg_cmd_airspeed_chng_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_cmd_airspeed_chng_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.target , packet1.spCmd );
mavlink_msg_cmd_airspeed_chng_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_cmd_airspeed_chng_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_cmd_airspeed_chng_send(MAVLINK_COMM_1 , packet1.target , packet1.spCmd );
mavlink_msg_cmd_airspeed_chng_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_cmd_airspeed_ack(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_message_t msg;
uint8_t buffer[MAVLINK_MAX_PACKET_LEN];
uint16_t i;
mavlink_cmd_airspeed_ack_t packet_in = {
17.0,
17,
};
mavlink_cmd_airspeed_ack_t packet1, packet2;
memset(&packet1, 0, sizeof(packet1));
packet1.spCmd = packet_in.spCmd;
packet1.ack = packet_in.ack;
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_cmd_airspeed_ack_encode(system_id, component_id, &msg, &packet1);
mavlink_msg_cmd_airspeed_ack_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_cmd_airspeed_ack_pack(system_id, component_id, &msg , packet1.spCmd , packet1.ack );
mavlink_msg_cmd_airspeed_ack_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_cmd_airspeed_ack_pack_chan(system_id, component_id, MAVLINK_COMM_0, &msg , packet1.spCmd , packet1.ack );
mavlink_msg_cmd_airspeed_ack_decode(&msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
 
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_to_send_buffer(buffer, &msg);
for (i=0; i<mavlink_msg_get_send_buffer_length(&msg); i++) {
comm_send_ch(MAVLINK_COMM_0, buffer[i]);
}
mavlink_msg_cmd_airspeed_ack_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
memset(&packet2, 0, sizeof(packet2));
mavlink_msg_cmd_airspeed_ack_send(MAVLINK_COMM_1 , packet1.spCmd , packet1.ack );
mavlink_msg_cmd_airspeed_ack_decode(last_msg, &packet2);
MAVLINK_ASSERT(memcmp(&packet1, &packet2, sizeof(packet1)) == 0);
}
 
static void mavlink_test_sensesoar(uint8_t system_id, uint8_t component_id, mavlink_message_t *last_msg)
{
mavlink_test_obs_position(system_id, component_id, last_msg);
mavlink_test_obs_velocity(system_id, component_id, last_msg);
mavlink_test_obs_attitude(system_id, component_id, last_msg);
mavlink_test_obs_wind(system_id, component_id, last_msg);
mavlink_test_obs_air_velocity(system_id, component_id, last_msg);
mavlink_test_obs_bias(system_id, component_id, last_msg);
mavlink_test_obs_qff(system_id, component_id, last_msg);
mavlink_test_obs_air_temp(system_id, component_id, last_msg);
mavlink_test_filt_rot_vel(system_id, component_id, last_msg);
mavlink_test_llc_out(system_id, component_id, last_msg);
mavlink_test_pm_elec(system_id, component_id, last_msg);
mavlink_test_sys_stat(system_id, component_id, last_msg);
mavlink_test_cmd_airspeed_chng(system_id, component_id, last_msg);
mavlink_test_cmd_airspeed_ack(system_id, component_id, last_msg);
}
 
#ifdef __cplusplus
}
#endif // __cplusplus
#endif // SENSESOAR_TESTSUITE_H
/C-OSD/arducam-osd/libraries/GCS_MAVLink/include/mavlink/v1.0/sensesoar/version.h
0,0 → 1,12
/** @file
* @brief MAVLink comm protocol built from sensesoar.xml
* @see http://pixhawk.ethz.ch/software/mavlink
*/
#ifndef MAVLINK_VERSION_H
#define MAVLINK_VERSION_H
 
#define MAVLINK_BUILD_DATE "Fri Apr 20 12:22:51 2012"
#define MAVLINK_WIRE_PROTOCOL_VERSION "1.0"
#define MAVLINK_MAX_DIALECT_PAYLOAD_SIZE 101
#endif // MAVLINK_VERSION_H
/C-OSD/arducam-osd/libraries/GCS_MAVLink/message_definitions/ardupilotmega.xml
0,0 → 1,270
<?xml version='1.0'?>
<mavlink>
<include>common.xml</include>
<!-- note that APM specific messages should use the command id
range from 150 to 250, to leave plenty of room for growth
of common.xml
 
If you prototype a message here, then you should consider if it
is general enough to move into common.xml later
-->
 
 
<enums>
<!-- Camera Mount mode Enumeration -->
<enum name="MAV_MOUNT_MODE">
<description>Enumeration of possible mount operation modes</description>
<entry name="MAV_MOUNT_MODE_RETRACT" value="0"><description>Load and keep safe position (Roll,Pitch,Yaw) from EEPROM and stop stabilization</description></entry>
<entry name="MAV_MOUNT_MODE_NEUTRAL" value="1"><description>Load and keep neutral position (Roll,Pitch,Yaw) from EEPROM.</description></entry>
<entry name="MAV_MOUNT_MODE_MAVLINK_TARGETING" value="2"><description>Load neutral position and start MAVLink Roll,Pitch,Yaw control with stabilization</description></entry>
<entry name="MAV_MOUNT_MODE_RC_TARGETING" value="3"><description>Load neutral position and start RC Roll,Pitch,Yaw control with stabilization</description></entry>
<entry name="MAV_MOUNT_MODE_GPS_POINT" value="4"><description>Load neutral position and start to point to Lat,Lon,Alt</description></entry>
</enum>
 
<enum name="MAV_CMD" >
<!-- Camera Controller Mission Commands Enumeration -->
<entry name="MAV_CMD_DO_DIGICAM_CONFIGURE" value="202">
<description>Mission command to configure an on-board camera controller system.</description>
<param index="1">Modes: P, TV, AV, M, Etc</param>
<param index="2">Shutter speed: Divisor number for one second</param>
<param index="3">Aperture: F stop number</param>
<param index="4">ISO number e.g. 80, 100, 200, Etc</param>
<param index="5">Exposure type enumerator</param>
<param index="6">Command Identity</param>
<param index="7">Main engine cut-off time before camera trigger in seconds/10 (0 means no cut-off)</param>
</entry>
 
<entry name="MAV_CMD_DO_DIGICAM_CONTROL" value="203">
<description>Mission command to control an on-board camera controller system.</description>
<param index="1">Session control e.g. show/hide lens</param>
<param index="2">Zoom's absolute position</param>
<param index="3">Zooming step value to offset zoom from the current position</param>
<param index="4">Focus Locking, Unlocking or Re-locking</param>
<param index="5">Shooting Command</param>
<param index="6">Command Identity</param>
<param index="7">Empty</param>
</entry>
 
<!-- Camera Mount Mission Commands Enumeration -->
<entry name="MAV_CMD_DO_MOUNT_CONFIGURE" value="204">
<description>Mission command to configure a camera or antenna mount</description>
<param index="1">Mount operation mode (see MAV_MOUNT_MODE enum)</param>
<param index="2">stabilize roll? (1 = yes, 0 = no)</param>
<param index="3">stabilize pitch? (1 = yes, 0 = no)</param>
<param index="4">stabilize yaw? (1 = yes, 0 = no)</param>
<param index="5">Empty</param>
<param index="6">Empty</param>
<param index="7">Empty</param>
</entry>
 
<entry name="MAV_CMD_DO_MOUNT_CONTROL" value="205">
<description>Mission command to control a camera or antenna mount</description>
<param index="1">pitch(deg*100) or lat, depending on mount mode.</param>
<param index="2">roll(deg*100) or lon depending on mount mode</param>
<param index="3">yaw(deg*100) or alt (in cm) depending on mount mode</param>
<param index="4">Empty</param>
<param index="5">Empty</param>
<param index="6">Empty</param>
<param index="7">Empty</param>
</entry>
</enum>
 
<!-- fenced mode enums -->
<enum name="FENCE_ACTION">
<entry name="FENCE_ACTION_NONE" value="0">
<description>Disable fenced mode</description>
</entry>
<entry name="FENCE_ACTION_GUIDED" value="1">
<description>Switched to guided mode to return point (fence point 0)</description>
</entry>
</enum>
 
<enum name="FENCE_BREACH">
<entry name="FENCE_BREACH_NONE" value="0">
<description>No last fence breach</description>
</entry>
<entry name="FENCE_BREACH_MINALT" value="1">
<description>Breached minimum altitude</description>
</entry>
<entry name="FENCE_BREACH_MAXALT" value="2">
<description>Breached maximum altitude</description>
</entry>
<entry name="FENCE_BREACH_BOUNDARY" value="3">
<description>Breached fence boundary</description>
</entry>
</enum>
</enums>
 
<messages>
<message id="150" name="SENSOR_OFFSETS">
<description>Offsets and calibrations values for hardware
sensors. This makes it easier to debug the calibration process.</description>
<field type="int16_t" name="mag_ofs_x">magnetometer X offset</field>
<field type="int16_t" name="mag_ofs_y">magnetometer Y offset</field>
<field type="int16_t" name="mag_ofs_z">magnetometer Z offset</field>
<field type="float" name="mag_declination">magnetic declination (radians)</field>
<field type="int32_t" name="raw_press">raw pressure from barometer</field>
<field type="int32_t" name="raw_temp">raw temperature from barometer</field>
<field type="float" name="gyro_cal_x">gyro X calibration</field>
<field type="float" name="gyro_cal_y">gyro Y calibration</field>
<field type="float" name="gyro_cal_z">gyro Z calibration</field>
<field type="float" name="accel_cal_x">accel X calibration</field>
<field type="float" name="accel_cal_y">accel Y calibration</field>
<field type="float" name="accel_cal_z">accel Z calibration</field>
</message>
 
<message id="151" name="SET_MAG_OFFSETS">
<description>set the magnetometer offsets</description>
<field type="uint8_t" name="target_system">System ID</field>
<field type="uint8_t" name="target_component">Component ID</field>
<field type="int16_t" name="mag_ofs_x">magnetometer X offset</field>
<field type="int16_t" name="mag_ofs_y">magnetometer Y offset</field>
<field type="int16_t" name="mag_ofs_z">magnetometer Z offset</field>
</message>
 
<message id="152" name="MEMINFO">
<description>state of APM memory</description>
<field type="uint16_t" name="brkval">heap top</field>
<field type="uint16_t" name="freemem">free memory</field>
</message>
 
<message id="153" name="AP_ADC">
<description>raw ADC output</description>
<field type="uint16_t" name="adc1">ADC output 1</field>
<field type="uint16_t" name="adc2">ADC output 2</field>
<field type="uint16_t" name="adc3">ADC output 3</field>
<field type="uint16_t" name="adc4">ADC output 4</field>
<field type="uint16_t" name="adc5">ADC output 5</field>
<field type="uint16_t" name="adc6">ADC output 6</field>
</message>
 
<!-- Camera Controller Messages -->
<message name="DIGICAM_CONFIGURE" id="154">
<description>Configure on-board Camera Control System.</description>
<field name="target_system" type="uint8_t">System ID</field>
<field name="target_component" type="uint8_t">Component ID</field>
<field name="mode" type="uint8_t">Mode enumeration from 1 to N //P, TV, AV, M, Etc (0 means ignore)</field>
<field name="shutter_speed" type="uint16_t">Divisor number //e.g. 1000 means 1/1000 (0 means ignore)</field>
<field name="aperture" type="uint8_t">F stop number x 10 //e.g. 28 means 2.8 (0 means ignore)</field>
<field name="iso" type="uint8_t">ISO enumeration from 1 to N //e.g. 80, 100, 200, Etc (0 means ignore)</field>
<field name="exposure_type" type="uint8_t">Exposure type enumeration from 1 to N (0 means ignore)</field>
<field name="command_id" type="uint8_t">Command Identity (incremental loop: 0 to 255)//A command sent multiple times will be executed or pooled just once</field>
<field name="engine_cut_off" type="uint8_t">Main engine cut-off time before camera trigger in seconds/10 (0 means no cut-off)</field>
<field name="extra_param" type="uint8_t">Extra parameters enumeration (0 means ignore)</field>
<field name="extra_value" type="float">Correspondent value to given extra_param</field>
</message>
 
<message name="DIGICAM_CONTROL" id="155">
<description>Control on-board Camera Control System to take shots.</description>
<field name="target_system" type="uint8_t">System ID</field>
<field name="target_component" type="uint8_t">Component ID</field>
<field name="session" type="uint8_t">0: stop, 1: start or keep it up //Session control e.g. show/hide lens</field>
<field name="zoom_pos" type="uint8_t">1 to N //Zoom's absolute position (0 means ignore)</field>
<field name="zoom_step" type="int8_t">-100 to 100 //Zooming step value to offset zoom from the current position</field>
<field name="focus_lock" type="uint8_t">0: unlock focus or keep unlocked, 1: lock focus or keep locked, 3: re-lock focus</field>
<field name="shot" type="uint8_t">0: ignore, 1: shot or start filming</field>
<field name="command_id" type="uint8_t">Command Identity (incremental loop: 0 to 255)//A command sent multiple times will be executed or pooled just once</field>
<field name="extra_param" type="uint8_t">Extra parameters enumeration (0 means ignore)</field>
<field name="extra_value" type="float">Correspondent value to given extra_param</field>
</message>
 
<!-- Camera Mount Messages -->
<message name="MOUNT_CONFIGURE" id="156">
<description>Message to configure a camera mount, directional antenna, etc.</description>
<field name="target_system" type="uint8_t">System ID</field>
<field name="target_component" type="uint8_t">Component ID</field>
<field name="mount_mode" type="uint8_t">mount operating mode (see MAV_MOUNT_MODE enum)</field>
<field name="stab_roll" type="uint8_t">(1 = yes, 0 = no)</field>
<field name="stab_pitch" type="uint8_t">(1 = yes, 0 = no)</field>
<field name="stab_yaw" type="uint8_t">(1 = yes, 0 = no)</field>
</message>
 
<message name="MOUNT_CONTROL" id="157">
<description>Message to control a camera mount, directional antenna, etc.</description>
<field name="target_system" type="uint8_t">System ID</field>
<field name="target_component" type="uint8_t">Component ID</field>
<field name="input_a" type="int32_t">pitch(deg*100) or lat, depending on mount mode</field>
<field name="input_b" type="int32_t">roll(deg*100) or lon depending on mount mode</field>
<field name="input_c" type="int32_t">yaw(deg*100) or alt (in cm) depending on mount mode</field>
<field name="save_position" type="uint8_t">if "1" it will save current trimmed position on EEPROM (just valid for NEUTRAL and LANDING)</field>
</message>
 
<message name="MOUNT_STATUS" id="158">
<description>Message with some status from APM to GCS about camera or antenna mount</description>
<field name="target_system" type="uint8_t">System ID</field>
<field name="target_component" type="uint8_t">Component ID</field>
<field name="pointing_a" type="int32_t">pitch(deg*100) or lat, depending on mount mode</field>
<field name="pointing_b" type="int32_t">roll(deg*100) or lon depending on mount mode</field>
<field name="pointing_c" type="int32_t">yaw(deg*100) or alt (in cm) depending on mount mode</field>
</message>
 
<!-- geo-fence messages -->
<message name="FENCE_POINT" id="160">
<description>A fence point. Used to set a point when from
GCS -> MAV. Also used to return a point from MAV -> GCS</description>
<field name="target_system" type="uint8_t">System ID</field>
<field name="target_component" type="uint8_t">Component ID</field>
<field name="idx" type="uint8_t">point index (first point is 1, 0 is for return point)</field>
<field name="count" type="uint8_t">total number of points (for sanity checking)</field>
<field name="lat" type="float">Latitude of point</field>
<field name="lng" type="float">Longitude of point</field>
</message>
 
<message name="FENCE_FETCH_POINT" id="161">
<description>Request a current fence point from MAV</description>
<field name="target_system" type="uint8_t">System ID</field>
<field name="target_component" type="uint8_t">Component ID</field>
<field name="idx" type="uint8_t">point index (first point is 1, 0 is for return point)</field>
</message>
 
<message name="FENCE_STATUS" id="162">
<description>Status of geo-fencing. Sent in extended
status stream when fencing enabled</description>
<field name="breach_status" type="uint8_t">0 if currently inside fence, 1 if outside</field>
<field name="breach_count" type="uint16_t">number of fence breaches</field>
<field name="breach_type" type="uint8_t">last breach type (see FENCE_BREACH_* enum)</field>
<field name="breach_time" type="uint32_t">time of last breach in milliseconds since boot</field>
</message>
 
<message name="AHRS" id="163">
<description>Status of DCM attitude estimator</description>
<field type="float" name="omegaIx">X gyro drift estimate rad/s</field>
<field type="float" name="omegaIy">Y gyro drift estimate rad/s</field>
<field type="float" name="omegaIz">Z gyro drift estimate rad/s</field>
<field type="float" name="accel_weight">average accel_weight</field>
<field type="float" name="renorm_val">average renormalisation value</field>
<field type="float" name="error_rp">average error_roll_pitch value</field>
<field type="float" name="error_yaw">average error_yaw value</field>
</message>
 
<message name="SIMSTATE" id="164">
<description>Status of simulation environment, if used</description>
<field type="float" name="roll">Roll angle (rad)</field>
<field type="float" name="pitch">Pitch angle (rad)</field>
<field type="float" name="yaw">Yaw angle (rad)</field>
<field type="float" name="xacc">X acceleration m/s/s</field>
<field type="float" name="yacc">Y acceleration m/s/s</field>
<field type="float" name="zacc">Z acceleration m/s/s</field>
<field type="float" name="xgyro">Angular speed around X axis rad/s</field>
<field type="float" name="ygyro">Angular speed around Y axis rad/s</field>
<field type="float" name="zgyro">Angular speed around Z axis rad/s</field>
</message>
 
<message name="HWSTATUS" id="165">
<description>Status of key hardware</description>
<field type="uint16_t" name="Vcc">board voltage (mV)</field>
<field type="uint8_t" name="I2Cerr">I2C error count</field>
</message>
 
<message name="RADIO" id="166">
<description>Status generated by radio</description>
<field type="uint8_t" name="rssi">local signal strength</field>
<field type="uint8_t" name="remrssi">remote signal strength</field>
<field type="uint8_t" name="txbuf">how full the tx buffer is as a percentage</field>
<field type="uint8_t" name="noise">background noise level</field>
<field type="uint8_t" name="remnoise">remote background noise level</field>
<field type="uint16_t" name="rxerrors">receive errors</field>
<field type="uint16_t" name="fixed">count of error corrected packets</field>
</message>
</messages>
</mavlink>
/C-OSD/arducam-osd/libraries/GCS_MAVLink/message_definitions/common.xml
0,0 → 1,941
<?xml version='1.0'?>
<mavlink>
<version>2</version>
<enums>
<enum name="MAV_CMD">
<description>Commands to be executed by the MAV. They can be executed on user request,
or as part of a mission script. If the action is used in a mission, the parameter mapping
to the waypoint/mission message is as follows:
Param 1, Param 2, Param 3, Param 4, X: Param 5, Y:Param 6, Z:Param 7. This command list is similar what
ARINC 424 is for commercial aircraft: A data format how to interpret waypoint/mission data.</description>
<entry value="16" name="MAV_CMD_NAV_WAYPOINT">
<description>Navigate to waypoint.</description>
<param index="1">Hold time in decimal seconds. (ignored by fixed wing, time to stay at waypoint for rotary wing)</param>
<param index="2">Acceptance radius in meters (if the sphere with this radius is hit, the waypoint counts as reached)</param>
<param index="3">0 to pass through the WP, if > 0 radius in meters to pass by WP. Positive value for clockwise orbit, negative value for counter-clockwise orbit. Allows trajectory control.</param>
<param index="4">Desired yaw angle at waypoint (rotary wing)</param>
<param index="5">Latitude</param>
<param index="6">Longitude</param>
<param index="7">Altitude</param>
</entry>
<entry value="17" name="MAV_CMD_NAV_LOITER_UNLIM">
<description>Loiter around this waypoint an unlimited amount of time</description>
<param index="1">Empty</param>
<param index="2">Empty</param>
<param index="3">Radius around waypoint, in meters. If positive loiter clockwise, else counter-clockwise</param>
<param index="4">Desired yaw angle.</param>
<param index="5">Latitude</param>
<param index="6">Longitude</param>
<param index="7">Altitude</param>
</entry>
<entry value="18" name="MAV_CMD_NAV_LOITER_TURNS">
<description>Loiter around this waypoint for X turns</description>
<param index="1">Turns</param>
<param index="2">Empty</param>
<param index="3">Radius around waypoint, in meters. If positive loiter clockwise, else counter-clockwise</param>
<param index="4">Desired yaw angle.</param>
<param index="5">Latitude</param>
<param index="6">Longitude</param>
<param index="7">Altitude</param>
</entry>
<entry value="19" name="MAV_CMD_NAV_LOITER_TIME">
<description>Loiter around this waypoint for X seconds</description>
<param index="1">Seconds (decimal)</param>
<param index="2">Empty</param>
<param index="3">Radius around waypoint, in meters. If positive loiter clockwise, else counter-clockwise</param>
<param index="4">Desired yaw angle.</param>
<param index="5">Latitude</param>
<param index="6">Longitude</param>
<param index="7">Altitude</param>
</entry>
<entry value="20" name="MAV_CMD_NAV_RETURN_TO_LAUNCH">
<description>Return to launch location</description>
<param index="1">Empty</param>
<param index="2">Empty</param>
<param index="3">Empty</param>
<param index="4">Empty</param>
<param index="5">Empty</param>
<param index="6">Empty</param>
<param index="7">Empty</param>
</entry>
<entry value="21" name="MAV_CMD_NAV_LAND">
<description>Land at location</description>
<param index="1">Empty</param>
<param index="2">Empty</param>
<param index="3">Empty</param>
<param index="4">Desired yaw angle.</param>
<param index="5">Latitude</param>
<param index="6">Longitude</param>
<param index="7">Altitude</param>
</entry>
<entry value="22" name="MAV_CMD_NAV_TAKEOFF">
<description>Takeoff from ground / hand</description>
<param index="1">Minimum pitch (if airspeed sensor present), desired pitch without sensor</param>
<param index="2">Empty</param>
<param index="3">Empty</param>
<param index="4">Yaw angle (if magnetometer present), ignored without magnetometer</param>
<param index="5">Latitude</param>
<param index="6">Longitude</param>
<param index="7">Altitude</param>
</entry>
<entry value="80" name="MAV_CMD_NAV_ROI">
<description>Sets the region of interest (ROI) for a sensor set or the
vehicle itself. This can then be used by the vehicles control
system to control the vehicle attitude and the attitude of various
sensors such as cameras.</description>
<param index="1">Region of intereset mode. (see MAV_ROI enum)</param>
<param index="2">Waypoint index/ target ID. (see MAV_ROI enum)</param>
<param index="3">ROI index (allows a vehicle to manage multiple ROI's)</param>
<param index="4">Empty</param>
<param index="5">x the location of the fixed ROI (see MAV_FRAME)</param>
<param index="6">y</param>
<param index="7">z</param>
</entry>
<entry value="81" name="MAV_CMD_NAV_PATHPLANNING">
<description>Control autonomous path planning on the MAV.</description>
<param index="1">0: Disable local obstacle avoidance / local path planning (without resetting map), 1: Enable local path planning, 2: Enable and reset local path planning</param>
<param index="2">0: Disable full path planning (without resetting map), 1: Enable, 2: Enable and reset map/occupancy grid, 3: Enable and reset planned route, but not occupancy grid</param>
<param index="3">Empty</param>
<param index="4">Yaw angle at goal, in compass degrees, [0..360]</param>
<param index="5">Latitude/X of goal</param>
<param index="6">Longitude/Y of goal</param>
<param index="7">Altitude/Z of goal</param>
</entry>
<entry value="95" name="MAV_CMD_NAV_LAST">
<description>NOP - This command is only used to mark the upper limit of the NAV/ACTION commands in the enumeration</description>
<param index="1">Empty</param>
<param index="2">Empty</param>
<param index="3">Empty</param>
<param index="4">Empty</param>
<param index="5">Empty</param>
<param index="6">Empty</param>
<param index="7">Empty</param>
</entry>
<entry value="112" name="MAV_CMD_CONDITION_DELAY">
<description>Delay mission state machine.</description>
<param index="1">Delay in seconds (decimal)</param>
<param index="2">Empty</param>
<param index="3">Empty</param>
<param index="4">Empty</param>
<param index="5">Empty</param>
<param index="6">Empty</param>
<param index="7">Empty</param>
</entry>
<entry value="113" name="MAV_CMD_CONDITION_CHANGE_ALT">
<description>Ascend/descend at rate. Delay mission state machine until desired altitude reached.</description>
<param index="1">Descent / Ascend rate (m/s)</param>
<param index="2">Empty</param>
<param index="3">Empty</param>
<param index="4">Empty</param>
<param index="5">Empty</param>
<param index="6">Empty</param>
<param index="7">Finish Altitude</param>
</entry>
<entry value="114" name="MAV_CMD_CONDITION_DISTANCE">
<description>Delay mission state machine until within desired distance of next NAV point.</description>
<param index="1">Distance (meters)</param>
<param index="2">Empty</param>
<param index="3">Empty</param>
<param index="4">Empty</param>
<param index="5">Empty</param>
<param index="6">Empty</param>
<param index="7">Empty</param>
</entry>
<entry value="115" name="MAV_CMD_CONDITION_YAW">
<description>Reach a certain target angle.</description>
<param index="1">target angle: [0-360], 0 is north</param>
<param index="2">speed during yaw change:[deg per second]</param>
<param index="3">direction: negative: counter clockwise, positive: clockwise [-1,1]</param>
<param index="4">relative offset or absolute angle: [ 1,0]</param>
<param index="5">Empty</param>
<param index="6">Empty</param>
<param index="7">Empty</param>
</entry>
<entry value="159" name="MAV_CMD_CONDITION_LAST">
<description>NOP - This command is only used to mark the upper limit of the CONDITION commands in the enumeration</description>
<param index="1">Empty</param>
<param index="2">Empty</param>
<param index="3">Empty</param>
<param index="4">Empty</param>
<param index="5">Empty</param>
<param index="6">Empty</param>
<param index="7">Empty</param>
</entry>
<entry value="176" name="MAV_CMD_DO_SET_MODE">
<description>Set system mode.</description>
<param index="1">Mode, as defined by ENUM MAV_MODE</param>
<param index="2">Empty</param>
<param index="3">Empty</param>
<param index="4">Empty</param>
<param index="5">Empty</param>
<param index="6">Empty</param>
<param index="7">Empty</param>
</entry>
<entry value="177" name="MAV_CMD_DO_JUMP">
<description>Jump to the desired command in the mission list. Repeat this action only the specified number of times</description>
<param index="1">Sequence number</param>
<param index="2">Repeat count</param>
<param index="3">Empty</param>
<param index="4">Empty</param>
<param index="5">Empty</param>
<param index="6">Empty</param>
<param index="7">Empty</param>
</entry>
<entry value="178" name="MAV_CMD_DO_CHANGE_SPEED">
<description>Change speed and/or throttle set points.</description>
<param index="1">Speed type (0=Airspeed, 1=Ground Speed)</param>
<param index="2">Speed (m/s, -1 indicates no change)</param>
<param index="3">Throttle ( Percent, -1 indicates no change)</param>
<param index="4">Empty</param>
<param index="5">Empty</param>
<param index="6">Empty</param>
<param index="7">Empty</param>
</entry>
<entry value="179" name="MAV_CMD_DO_SET_HOME">
<description>Changes the home location either to the current location or a specified location.</description>
<param index="1">Use current (1=use current location, 0=use specified location)</param>
<param index="2">Empty</param>
<param index="3">Empty</param>
<param index="4">Empty</param>
<param index="5">Latitude</param>
<param index="6">Longitude</param>
<param index="7">Altitude</param>
</entry>
<entry value="180" name="MAV_CMD_DO_SET_PARAMETER">
<description>Set a system parameter. Caution! Use of this command requires knowledge of the numeric enumeration value of the parameter.</description>
<param index="1">Parameter number</param>
<param index="2">Parameter value</param>
<param index="3">Empty</param>
<param index="4">Empty</param>
<param index="5">Empty</param>
<param index="6">Empty</param>
<param index="7">Empty</param>
</entry>
<entry value="181" name="MAV_CMD_DO_SET_RELAY">
<description>Set a relay to a condition.</description>
<param index="1">Relay number</param>
<param index="2">Setting (1=on, 0=off, others possible depending on system hardware)</param>
<param index="3">Empty</param>
<param index="4">Empty</param>
<param index="5">Empty</param>
<param index="6">Empty</param>
<param index="7">Empty</param>
</entry>
<entry value="182" name="MAV_CMD_DO_REPEAT_RELAY">
<description>Cycle a relay on and off for a desired number of cyles with a desired period.</description>
<param index="1">Relay number</param>
<param index="2">Cycle count</param>
<param index="3">Cycle time (seconds, decimal)</param>
<param index="4">Empty</param>
<param index="5">Empty</param>
<param index="6">Empty</param>
<param index="7">Empty</param>
</entry>
<entry value="183" name="MAV_CMD_DO_SET_SERVO">
<description>Set a servo to a desired PWM value.</description>
<param index="1">Servo number</param>
<param index="2">PWM (microseconds, 1000 to 2000 typical)</param>
<param index="3">Empty</param>
<param index="4">Empty</param>
<param index="5">Empty</param>
<param index="6">Empty</param>
<param index="7">Empty</param>
</entry>
<entry value="184" name="MAV_CMD_DO_REPEAT_SERVO">
<description>Cycle a between its nominal setting and a desired PWM for a desired number of cycles with a desired period.</description>
<param index="1">Servo number</param>
<param index="2">PWM (microseconds, 1000 to 2000 typical)</param>
<param index="3">Cycle count</param>
<param index="4">Cycle time (seconds)</param>
<param index="5">Empty</param>
<param index="6">Empty</param>
<param index="7">Empty</param>
</entry>
<entry value="200" name="MAV_CMD_DO_CONTROL_VIDEO">
<description>Control onboard camera capturing.</description>
<param index="1">Camera ID (-1 for all)</param>
<param index="2">Transmission: 0: disabled, 1: enabled compressed, 2: enabled raw</param>
<param index="3">Transmission mode: 0: video stream, >0: single images every n seconds (decimal)</param>
<param index="4">Recording: 0: disabled, 1: enabled compressed, 2: enabled raw</param>
<param index="5">Empty</param>
<param index="6">Empty</param>
<param index="7">Empty</param>
</entry>
<entry value="201" name="MAV_CMD_DO_SET_ROI">
<description>Sets the region of interest (ROI) for a sensor set or the
vehicle itself. This can then be used by the vehicles control
system to control the vehicle attitude and the attitude of various
devices such as cameras.
</description>
<param index="1">Region of interest mode. (see MAV_ROI enum)</param>
<param index="2">Waypoint index/ target ID. (see MAV_ROI enum)</param>
<param index="3">ROI index (allows a vehicle to manage multiple cameras etc.)</param>
<param index="4">Empty</param>
<param index="5">x the location of the fixed ROI (see MAV_FRAME)</param>
<param index="6">y</param>
<param index="7">z</param>
</entry>
<entry value="240" name="MAV_CMD_DO_LAST">
<description>NOP - This command is only used to mark the upper limit of the DO commands in the enumeration</description>
<param index="1">Empty</param>
<param index="2">Empty</param>
<param index="3">Empty</param>
<param index="4">Empty</param>
<param index="5">Empty</param>
<param index="6">Empty</param>
<param index="7">Empty</param>
</entry>
<entry value="241" name="MAV_CMD_PREFLIGHT_CALIBRATION">
<description>Trigger calibration. This command will be only accepted if in pre-flight mode.</description>
<param index="1">Gyro calibration: 0: no, 1: yes</param>
<param index="2">Magnetometer calibration: 0: no, 1: yes</param>
<param index="3">Ground pressure: 0: no, 1: yes</param>
<param index="4">Radio calibration: 0: no, 1: yes</param>
<param index="5">Empty</param>
<param index="6">Empty</param>
<param index="7">Empty</param>
</entry>
<entry value="245" name="MAV_CMD_PREFLIGHT_STORAGE">
<description>Request storage of different parameter values and logs. This command will be only accepted if in pre-flight mode.</description>
<param index="1">Parameter storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM</param>
<param index="2">Mission storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM</param>
<param index="3">Reserved</param>
<param index="4">Reserved</param>
<param index="5">Empty</param>
<param index="6">Empty</param>
<param index="7">Empty</param>
</entry>
</enum>
<enum name="MAV_DATA_STREAM">
<description>Data stream IDs. A data stream is not a fixed set of messages, but rather a
recommendation to the autopilot software. Individual autopilots may or may not obey
the recommended messages.
</description>
<entry value="0" name="MAV_DATA_STREAM_ALL">
<description>Enable all data streams</description>
</entry>
<entry value="1" name="MAV_DATA_STREAM_RAW_SENSORS">
<description>Enable IMU_RAW, GPS_RAW, GPS_STATUS packets.</description>
</entry>
<entry value="2" name="MAV_DATA_STREAM_EXTENDED_STATUS">
<description>Enable GPS_STATUS, CONTROL_STATUS, AUX_STATUS</description>
</entry>
<entry value="3" name="MAV_DATA_STREAM_RC_CHANNELS">
<description>Enable RC_CHANNELS_SCALED, RC_CHANNELS_RAW, SERVO_OUTPUT_RAW</description>
</entry>
<entry value="4" name="MAV_DATA_STREAM_RAW_CONTROLLER">
<description>Enable ATTITUDE_CONTROLLER_OUTPUT, POSITION_CONTROLLER_OUTPUT, NAV_CONTROLLER_OUTPUT.</description>
</entry>
<entry value="6" name="MAV_DATA_STREAM_POSITION">
<description>Enable LOCAL_POSITION, GLOBAL_POSITION/GLOBAL_POSITION_INT messages.</description>
</entry>
<entry value="10" name="MAV_DATA_STREAM_EXTRA1">
<description>Dependent on the autopilot</description>
</entry>
<entry value="11" name="MAV_DATA_STREAM_EXTRA2">
<description>Dependent on the autopilot</description>
</entry>
<entry value="12" name="MAV_DATA_STREAM_EXTRA3">
<description>Dependent on the autopilot</description>
</entry>
</enum>
<enum name="MAV_ROI">
<description> The ROI (region of interest) for the vehicle. This can be
be used by the vehicle for camera/vehicle attitude alignment (see
MAV_CMD_NAV_ROI).
</description>
<entry value="0" name="MAV_ROI_NONE">
<description>No region of interest.</description>
</entry>
<entry value="1" name="MAV_ROI_WPNEXT">
<description>Point toward next waypoint.</description>
</entry>
<entry value="2" name="MAV_ROI_WPINDEX">
<description>Point toward given waypoint.</description>
</entry>
<entry value="3" name="MAV_ROI_LOCATION">
<description>Point toward fixed location.</description>
</entry>
<entry value="4" name="MAV_ROI_TARGET">
<description>Point toward of given id.</description>
</entry>
</enum>
</enums>
<messages>
<message id="0" name="HEARTBEAT">
<description>The heartbeat message shows that a system is present and responding. The type of the MAV and Autopilot hardware allow the receiving system to treat further messages from this system appropriate (e.g. by laying out the user interface based on the autopilot).</description>
<field type="uint8_t" name="type">Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM)</field>
<field type="uint8_t" name="autopilot">Type of the Autopilot: 0: Generic, 1: PIXHAWK, 2: SLUGS, 3: Ardupilot (up to 15 types), defined in MAV_AUTOPILOT_TYPE ENUM</field>
<field type="uint8_t_mavlink_version" name="mavlink_version">MAVLink version</field>
</message>
<message id="1" name="BOOT">
<description>The boot message indicates that a system is starting. The onboard software version allows to keep track of onboard soft/firmware revisions.</description>
<field type="uint32_t" name="version">The onboard software version</field>
</message>
<message id="2" name="SYSTEM_TIME">
<description>The system time is the time of the master clock, typically the computer clock of the main onboard computer.</description>
<field type="uint64_t" name="time_usec">Timestamp of the master clock in microseconds since UNIX epoch.</field>
</message>
<message id="3" name="PING">
<description>A ping message either requesting or responding to a ping. This allows to measure the system latencies, including serial port, radio modem and UDP connections.</description>
<field type="uint32_t" name="seq">PING sequence</field>
<field type="uint8_t" name="target_system">0: request ping from all receiving systems, if greater than 0: message is a ping response and number is the system id of the requesting system</field>
<field type="uint8_t" name="target_component">0: request ping from all receiving components, if greater than 0: message is a ping response and number is the system id of the requesting system</field>
<field type="uint64_t" name="time">Unix timestamp in microseconds</field>
</message>
<message id="4" name="SYSTEM_TIME_UTC">
<description>UTC date and time from GPS module</description>
<field type="uint32_t" name="utc_date">GPS UTC date ddmmyy</field>
<field type="uint32_t" name="utc_time">GPS UTC time hhmmss</field>
</message>
<message id="5" name="CHANGE_OPERATOR_CONTROL">
<description>Request to control this MAV</description>
<field type="uint8_t" name="target_system">System the GCS requests control for</field>
<field type="uint8_t" name="control_request">0: request control of this MAV, 1: Release control of this MAV</field>
<field type="uint8_t" name="version">0: key as plaintext, 1-255: future, different hashing/encryption variants. The GCS should in general use the safest mode possible initially and then gradually move down the encryption level if it gets a NACK message indicating an encryption mismatch.</field>
<field type="char[25]" name="passkey">Password / Key, depending on version plaintext or encrypted. 25 or less characters, NULL terminated. The characters may involve A-Z, a-z, 0-9, and "!?,.-"</field>
</message>
<message id="6" name="CHANGE_OPERATOR_CONTROL_ACK">
<description>Accept / deny control of this MAV</description>
<field type="uint8_t" name="gcs_system_id">ID of the GCS this message </field>
<field type="uint8_t" name="control_request">0: request control of this MAV, 1: Release control of this MAV</field>
<field type="uint8_t" name="ack">0: ACK, 1: NACK: Wrong passkey, 2: NACK: Unsupported passkey encryption method, 3: NACK: Already under control</field>
</message>
<message id="7" name="AUTH_KEY">
<description>Emit an encrypted signature / key identifying this system. PLEASE NOTE: This protocol has been kept simple, so transmitting the key requires an encrypted channel for true safety.</description>
<field type="char[32]" name="key">key</field>
</message>
<message id="9" name="ACTION_ACK">
<description>This message acknowledges an action. IMPORTANT: The acknowledgement can be also negative, e.g. the MAV rejects a reset message because it is in-flight. The action ids are defined in ENUM MAV_ACTION in mavlink/include/mavlink_types.h</description>
<field type="uint8_t" name="action">The action id</field>
<field type="uint8_t" name="result">0: Action DENIED, 1: Action executed</field>
</message>
<message id="10" name="ACTION">
<description>An action message allows to execute a certain onboard action. These include liftoff, land, storing parameters too EEPROM, shutddown, etc. The action ids are defined in ENUM MAV_ACTION in mavlink/include/mavlink_types.h</description>
<field type="uint8_t" name="target">The system executing the action</field>
<field type="uint8_t" name="target_component">The component executing the action</field>
<field type="uint8_t" name="action">The action id</field>
</message>
<message id="11" name="SET_MODE">
<description>Set the system mode, as defined by enum MAV_MODE in mavlink/include/mavlink_types.h. There is no target component id as the mode is by definition for the overall aircraft, not only for one component.</description>
<field type="uint8_t" name="target">The system setting the mode</field>
<field type="uint8_t" name="mode">The new mode</field>
</message>
<message id="12" name="SET_NAV_MODE">
<description>Set the system navigation mode, as defined by enum MAV_NAV_MODE in mavlink/include/mavlink_types.h. The navigation mode applies to the whole aircraft and thus all components.</description>
<field type="uint8_t" name="target">The system setting the mode</field>
<field type="uint8_t" name="nav_mode">The new navigation mode</field>
</message>
<message id="20" name="PARAM_REQUEST_READ">
<description>Request to read the onboard parameter with the param_id string id. Onboard parameters are stored as key[const char*] -> value[float]. This allows to send a parameter to any other component (such as the GCS) without the need of previous knowledge of possible parameter names. Thus the same GCS can store different parameters for different autopilots. See also http://qgroundcontrol.org/parameter_interface for a full documentation of QGroundControl and IMU code.</description>
<field type="uint8_t" name="target_system">System ID</field>
<field type="uint8_t" name="target_component">Component ID</field>
<field type="array[15]" name="param_id">Onboard parameter id</field>
<field type="int16_t" name="param_index">Parameter index. Send -1 to use the param ID field as identifier</field>
</message>
<message id="21" name="PARAM_REQUEST_LIST">
<description>Request all parameters of this component. After his request, all parameters are emitted.</description>
<field type="uint8_t" name="target_system">System ID</field>
<field type="uint8_t" name="target_component">Component ID</field>
</message>
<message id="22" name="PARAM_VALUE">
<description>Emit the value of a onboard parameter. The inclusion of param_count and param_index in the message allows the recipient to keep track of received parameters and allows him to re-request missing parameters after a loss or timeout.</description>
<field type="array[15]" name="param_id">Onboard parameter id</field>
<field type="float" name="param_value">Onboard parameter value</field>
<field type="uint16_t" name="param_count">Total number of onboard parameters</field>
<field type="uint16_t" name="param_index">Index of this onboard parameter</field>
</message>
<message id="23" name="PARAM_SET">
<description>Set a parameter value TEMPORARILY to RAM. It will be reset to default on system reboot. Send the ACTION MAV_ACTION_STORAGE_WRITE to PERMANENTLY write the RAM contents to EEPROM. IMPORTANT: The receiving component should acknowledge the new parameter value by sending a param_value message to all communication partners. This will also ensure that multiple GCS all have an up-to-date list of all parameters. If the sending GCS did not receive a PARAM_VALUE message within its timeout time, it should re-send the PARAM_SET message.</description>
<field type="uint8_t" name="target_system">System ID</field>
<field type="uint8_t" name="target_component">Component ID</field>
<field type="array[15]" name="param_id">Onboard parameter id</field>
<field type="float" name="param_value">Onboard parameter value</field>
</message>
<message id="25" name="GPS_RAW_INT">
<description>The global position, as returned by the Global Positioning System (GPS). This is
NOT the global position estimate of the sytem, but rather a RAW sensor value. See message GLOBAL_POSITION for the global position estimate. Coordinate frame is right-handed, Z-axis up (GPS frame)</description>
<field type="uint64_t" name="usec">Timestamp (microseconds since UNIX epoch or microseconds since system boot)</field>
<field type="uint8_t" name="fix_type">0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix.</field>
<field type="int32_t" name="lat">Latitude in 1E7 degrees</field>
<field type="int32_t" name="lon">Longitude in 1E7 degrees</field>
<field type="int32_t" name="alt">Altitude in 1E3 meters (millimeters)</field>
<field type="float" name="eph">GPS HDOP</field>
<field type="float" name="epv">GPS VDOP</field>
<field type="float" name="v">GPS ground speed (m/s)</field>
<field type="float" name="hdg">Compass heading in degrees, 0..360 degrees</field>
</message>
<message id="26" name="SCALED_IMU">
<description>The RAW IMU readings for the usual 9DOF sensor setup. This message should contain the scaled values to the described units</description>
<field type="uint64_t" name="usec">Timestamp (microseconds since UNIX epoch or microseconds since system boot)</field>
<field type="int16_t" name="xacc">X acceleration (mg)</field>
<field type="int16_t" name="yacc">Y acceleration (mg)</field>
<field type="int16_t" name="zacc">Z acceleration (mg)</field>
<field type="int16_t" name="xgyro">Angular speed around X axis (millirad /sec)</field>
<field type="int16_t" name="ygyro">Angular speed around Y axis (millirad /sec)</field>
<field type="int16_t" name="zgyro">Angular speed around Z axis (millirad /sec)</field>
<field type="int16_t" name="xmag">X Magnetic field (milli tesla)</field>
<field type="int16_t" name="ymag">Y Magnetic field (milli tesla)</field>
<field type="int16_t" name="zmag">Z Magnetic field (milli tesla)</field>
</message>
<message id="27" name="GPS_STATUS">
<description>The positioning status, as reported by GPS. This message is intended to display status information about each satellite visible to the receiver. See message GLOBAL_POSITION for the global position estimate. This message can contain information for up to 20 satellites.</description>
<field type="uint8_t" name="satellites_visible">Number of satellites visible</field>
<field type="array[20]" name="satellite_prn">Global satellite ID</field>
<field type="array[20]" name="satellite_used">0: Satellite not used, 1: used for localization</field>
<field type="array[20]" name="satellite_elevation">Elevation (0: right on top of receiver, 90: on the horizon) of satellite</field>
<field type="array[20]" name="satellite_azimuth">Direction of satellite, 0: 0 deg, 255: 360 deg.</field>
<field type="array[20]" name="satellite_snr">Signal to noise ratio of satellite</field>
</message>
<message id="28" name="RAW_IMU">
<description>The RAW IMU readings for the usual 9DOF sensor setup. This message should always contain the true raw values without any scaling to allow data capture and system debugging.</description>
<field type="uint64_t" name="usec">Timestamp (microseconds since UNIX epoch or microseconds since system boot)</field>
<field type="int16_t" name="xacc">X acceleration (raw)</field>
<field type="int16_t" name="yacc">Y acceleration (raw)</field>
<field type="int16_t" name="zacc">Z acceleration (raw)</field>
<field type="int16_t" name="xgyro">Angular speed around X axis (raw)</field>
<field type="int16_t" name="ygyro">Angular speed around Y axis (raw)</field>
<field type="int16_t" name="zgyro">Angular speed around Z axis (raw)</field>
<field type="int16_t" name="xmag">X Magnetic field (raw)</field>
<field type="int16_t" name="ymag">Y Magnetic field (raw)</field>
<field type="int16_t" name="zmag">Z Magnetic field (raw)</field>
</message>
<message id="29" name="RAW_PRESSURE">
<description>The RAW pressure readings for the typical setup of one absolute pressure and one differential pressure sensor. The sensor values should be the raw, UNSCALED ADC values.</description>
<field type="uint64_t" name="usec">Timestamp (microseconds since UNIX epoch or microseconds since system boot)</field>
<field type="int16_t" name="press_abs">Absolute pressure (raw)</field>
<field type="int16_t" name="press_diff1">Differential pressure 1 (raw)</field>
<field type="int16_t" name="press_diff2">Differential pressure 2 (raw)</field>
<field type="int16_t" name="temperature">Raw Temperature measurement (raw)</field>
</message>
<message id="38" name="SCALED_PRESSURE">
<description>The pressure readings for the typical setup of one absolute and differential pressure sensor. The units are as specified in each field.</description>
<field type="uint64_t" name="usec">Timestamp (microseconds since UNIX epoch or microseconds since system boot)</field>
<field type="float" name="press_abs">Absolute pressure (hectopascal)</field>
<field type="float" name="press_diff">Differential pressure 1 (hectopascal)</field>
<field type="int16_t" name="temperature">Temperature measurement (0.01 degrees celsius)</field>
</message>
<message id="30" name="ATTITUDE">
<description>The attitude in the aeronautical frame (right-handed, Z-down, X-front, Y-right).</description>
<field type="uint64_t" name="usec">Timestamp (microseconds since UNIX epoch or microseconds since system boot)</field>
<field type="float" name="roll">Roll angle (rad)</field>
<field type="float" name="pitch">Pitch angle (rad)</field>
<field type="float" name="yaw">Yaw angle (rad)</field>
<field type="float" name="rollspeed">Roll angular speed (rad/s)</field>
<field type="float" name="pitchspeed">Pitch angular speed (rad/s)</field>
<field type="float" name="yawspeed">Yaw angular speed (rad/s)</field>
</message>
<message id="31" name="LOCAL_POSITION">
<description>The filtered local position (e.g. fused computer vision and accelerometers). Coordinate frame is right-handed, Z-axis down (aeronautical frame)</description>
<field type="uint64_t" name="usec">Timestamp (microseconds since UNIX epoch or microseconds since system boot)</field>
<field type="float" name="x">X Position</field>
<field type="float" name="y">Y Position</field>
<field type="float" name="z">Z Position</field>
<field type="float" name="vx">X Speed</field>
<field type="float" name="vy">Y Speed</field>
<field type="float" name="vz">Z Speed</field>
</message>
<message id="33" name="GLOBAL_POSITION">
<description>The filtered global position (e.g. fused GPS and accelerometers). Coordinate frame is right-handed, Z-axis up (GPS frame)</description>
<field type="uint64_t" name="usec">Timestamp (microseconds since unix epoch)</field>
<field type="float" name="lat">Latitude, in degrees</field>
<field type="float" name="lon">Longitude, in degrees</field>
<field type="float" name="alt">Absolute altitude, in meters</field>
<field type="float" name="vx">X Speed (in Latitude direction, positive: going north)</field>
<field type="float" name="vy">Y Speed (in Longitude direction, positive: going east)</field>
<field type="float" name="vz">Z Speed (in Altitude direction, positive: going up)</field>
</message>
<message id="32" name="GPS_RAW">
<description>The global position, as returned by the Global Positioning System (GPS). This is
NOT the global position estimate of the sytem, but rather a RAW sensor value. See message GLOBAL_POSITION for the global position estimate. Coordinate frame is right-handed, Z-axis up (GPS frame)</description>
<field type="uint64_t" name="usec">Timestamp (microseconds since UNIX epoch or microseconds since system boot)</field>
<field type="uint8_t" name="fix_type">0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix.</field>
<field type="float" name="lat">Latitude in degrees</field>
<field type="float" name="lon">Longitude in degrees</field>
<field type="float" name="alt">Altitude in meters</field>
<field type="float" name="eph">GPS HDOP</field>
<field type="float" name="epv">GPS VDOP</field>
<field type="float" name="v">GPS ground speed</field>
<field type="float" name="hdg">Compass heading in degrees, 0..360 degrees</field>
</message>
<message id="34" name="SYS_STATUS">
<description>The general system state. If the system is following the MAVLink standard, the system state is mainly defined by three orthogonal states/modes: The system mode, which is either LOCKED (motors shut down and locked), MANUAL (system under RC control), GUIDED (system with autonomous position control, position setpoint controlled manually) or AUTO (system guided by path/waypoint planner). The NAV_MODE defined the current flight state: LIFTOFF (often an open-loop maneuver), LANDING, WAYPOINTS or VECTOR. This represents the internal navigation state machine. The system status shows wether the system is currently active or not and if an emergency occured. During the CRITICAL and EMERGENCY states the MAV is still considered to be active, but should start emergency procedures autonomously. After a failure occured it should first move from active to critical to allow manual intervention and then move to emergency after a certain timeout.</description>
<field type="uint8_t" name="mode">System mode, see MAV_MODE ENUM in mavlink/include/mavlink_types.h</field>
<field type="uint8_t" name="nav_mode">Navigation mode, see MAV_NAV_MODE ENUM</field>
<field type="uint8_t" name="status">System status flag, see MAV_STATUS ENUM</field>
<field type="uint16_t" name="load">Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000</field>
<field type="uint16_t" name="vbat">Battery voltage, in millivolts (1 = 1 millivolt)</field>
<field type="uint16_t" name="battery_remaining">Remaining battery energy: (0%: 0, 100%: 1000)</field>
<field type="uint16_t" name="packet_drop">Dropped packets (packets that were corrupted on reception on the MAV)</field>
</message>
<message id="35" name="RC_CHANNELS_RAW">
<description>The RAW values of the RC channels received. The standard PPM modulation is as follows: 1000 microseconds: 0%, 2000 microseconds: 100%. Individual receivers/transmitters might violate this specification.</description>
<field type="uint16_t" name="chan1_raw">RC channel 1 value, in microseconds</field>
<field type="uint16_t" name="chan2_raw">RC channel 2 value, in microseconds</field>
<field type="uint16_t" name="chan3_raw">RC channel 3 value, in microseconds</field>
<field type="uint16_t" name="chan4_raw">RC channel 4 value, in microseconds</field>
<field type="uint16_t" name="chan5_raw">RC channel 5 value, in microseconds</field>
<field type="uint16_t" name="chan6_raw">RC channel 6 value, in microseconds</field>
<field type="uint16_t" name="chan7_raw">RC channel 7 value, in microseconds</field>
<field type="uint16_t" name="chan8_raw">RC channel 8 value, in microseconds</field>
<field type="uint8_t" name="rssi">Receive signal strength indicator, 0: 0%, 255: 100%</field>
</message>
<message id="36" name="RC_CHANNELS_SCALED">
<description>The scaled values of the RC channels received. (-100%) -10000, (0%) 0, (100%) 10000</description>
<field type="int16_t" name="chan1_scaled">RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000</field>
<field type="int16_t" name="chan2_scaled">RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000</field>
<field type="int16_t" name="chan3_scaled">RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000</field>
<field type="int16_t" name="chan4_scaled">RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000</field>
<field type="int16_t" name="chan5_scaled">RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000</field>
<field type="int16_t" name="chan6_scaled">RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000</field>
<field type="int16_t" name="chan7_scaled">RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000</field>
<field type="int16_t" name="chan8_scaled">RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000</field>
<field type="uint8_t" name="rssi">Receive signal strength indicator, 0: 0%, 255: 100%</field>
</message>
<message id="37" name="SERVO_OUTPUT_RAW">
<description>The RAW values of the servo outputs (for RC input from the remote, use the RC_CHANNELS messages). The standard PPM modulation is as follows: 1000 microseconds: 0%, 2000 microseconds: 100%.</description>
<field type="uint16_t" name="servo1_raw">Servo output 1 value, in microseconds</field>
<field type="uint16_t" name="servo2_raw">Servo output 2 value, in microseconds</field>
<field type="uint16_t" name="servo3_raw">Servo output 3 value, in microseconds</field>
<field type="uint16_t" name="servo4_raw">Servo output 4 value, in microseconds</field>
<field type="uint16_t" name="servo5_raw">Servo output 5 value, in microseconds</field>
<field type="uint16_t" name="servo6_raw">Servo output 6 value, in microseconds</field>
<field type="uint16_t" name="servo7_raw">Servo output 7 value, in microseconds</field>
<field type="uint16_t" name="servo8_raw">Servo output 8 value, in microseconds</field>
</message>
<message id="39" name="WAYPOINT">
<description>Message encoding a waypoint. This message is emitted to announce
the presence of a waypoint and to set a waypoint on the system. The waypoint can be either in x, y, z meters (type: LOCAL) or x:lat, y:lon, z:altitude. Local frame is Z-down, right handed, global frame is Z-up, right handed</description>
<field type="uint8_t" name="target_system">System ID</field>
<field type="uint8_t" name="target_component">Component ID</field>
<field type="uint16_t" name="seq">Sequence</field>
<field type="uint8_t" name="frame">The coordinate system of the waypoint. see MAV_FRAME in mavlink_types.h</field>
<field type="uint8_t" name="command">The scheduled action for the waypoint. see MAV_COMMAND in common.xml MAVLink specs</field>
<field type="uint8_t" name="current">false:0, true:1</field>
<field type="uint8_t" name="autocontinue">autocontinue to next wp</field>
<field type="float" name="param1">PARAM1 / For NAV command waypoints: Radius in which the waypoint is accepted as reached, in meters</field>
<field type="float" name="param2">PARAM2 / For NAV command waypoints: Time that the MAV should stay inside the PARAM1 radius before advancing, in milliseconds</field>
<field type="float" name="param3">PARAM3 / For LOITER command waypoints: Orbit to circle around the waypoint, in meters. If positive the orbit direction should be clockwise, if negative the orbit direction should be counter-clockwise.</field>
<field type="float" name="param4">PARAM4 / For NAV and LOITER command waypoints: Yaw orientation in degrees, [0..360] 0 = NORTH</field>
<field type="float" name="x">PARAM5 / local: x position, global: latitude</field>
<field type="float" name="y">PARAM6 / y position: global: longitude</field>
<field type="float" name="z">PARAM7 / z position: global: altitude</field>
</message>
<message id="40" name="WAYPOINT_REQUEST">
<description>Request the information of the waypoint with the sequence number seq. The response of the system to this message should be a WAYPOINT message.</description>
<field type="uint8_t" name="target_system">System ID</field>
<field type="uint8_t" name="target_component">Component ID</field>
<field type="uint16_t" name="seq">Sequence</field>
</message>
<message id="41" name="WAYPOINT_SET_CURRENT">
<description>Set the waypoint with sequence number seq as current waypoint. This means that the MAV will continue to this waypoint on the shortest path (not following the waypoints in-between).</description>
<field type="uint8_t" name="target_system">System ID</field>
<field type="uint8_t" name="target_component">Component ID</field>
<field type="uint16_t" name="seq">Sequence</field>
</message>
<message id="42" name="WAYPOINT_CURRENT">
<description>Message that announces the sequence number of the current active waypoint. The MAV will fly towards this waypoint.</description>
<field type="uint16_t" name="seq">Sequence</field>
</message>
<message id="43" name="WAYPOINT_REQUEST_LIST">
<description>Request the overall list of waypoints from the system/component.</description>
<field type="uint8_t" name="target_system">System ID</field>
<field type="uint8_t" name="target_component">Component ID</field>
</message>
<message id="44" name="WAYPOINT_COUNT">
<description>This message is emitted as response to WAYPOINT_REQUEST_LIST by the MAV. The GCS can then request the individual waypoints based on the knowledge of the total number of waypoints.</description>
<field type="uint8_t" name="target_system">System ID</field>
<field type="uint8_t" name="target_component">Component ID</field>
<field type="uint16_t" name="count">Number of Waypoints in the Sequence</field>
</message>
<message id="45" name="WAYPOINT_CLEAR_ALL">
<description>Delete all waypoints at once.</description>
<field type="uint8_t" name="target_system">System ID</field>
<field type="uint8_t" name="target_component">Component ID</field>
</message>
<message id="46" name="WAYPOINT_REACHED">
<description>A certain waypoint has been reached. The system will either hold this position (or circle on the orbit) or (if the autocontinue on the WP was set) continue to the next waypoint.</description>
<field type="uint16_t" name="seq">Sequence</field>
</message>
<message id="47" name="WAYPOINT_ACK">
<description>Ack message during waypoint handling. The type field states if this message is a positive ack (type=0) or if an error happened (type=non-zero).</description>
<field type="uint8_t" name="target_system">System ID</field>
<field type="uint8_t" name="target_component">Component ID</field>
<field type="uint8_t" name="type">0: OK, 1: Error</field>
</message>
<message id="48" name="GPS_SET_GLOBAL_ORIGIN">
<description>As local waypoints exist, the global waypoint reference allows to transform between the local coordinate frame and the global (GPS) coordinate frame. This can be necessary when e.g. in- and outdoor settings are connected and the MAV should move from in- to outdoor.</description>
<field type="uint8_t" name="target_system">System ID</field>
<field type="uint8_t" name="target_component">Component ID</field>
<field type="int32_t" name="latitude">global position * 1E7</field>
<field type="int32_t" name="longitude">global position * 1E7</field>
<field type="int32_t" name="altitude">global position * 1000</field>
</message>
<message id="49" name="GPS_LOCAL_ORIGIN_SET">
<description>Once the MAV sets a new GPS-Local correspondence, this message announces the origin (0,0,0) position</description>
<field type="int32_t" name="latitude">Latitude (WGS84), expressed as * 1E7</field>
<field type="int32_t" name="longitude">Longitude (WGS84), expressed as * 1E7</field>
<field type="int32_t" name="altitude">Altitude(WGS84), expressed as * 1000</field>
</message>
<message id="50" name="LOCAL_POSITION_SETPOINT_SET">
<description>Set the setpoint for a local position controller. This is the position in local coordinates the MAV should fly to. This message is sent by the path/waypoint planner to the onboard position controller. As some MAVs have a degree of freedom in yaw (e.g. all helicopters/quadrotors), the desired yaw angle is part of the message.</description>
<field type="uint8_t" name="target_system">System ID</field>
<field type="uint8_t" name="target_component">Component ID</field>
<field type="float" name="x">x position</field>
<field type="float" name="y">y position</field>
<field type="float" name="z">z position</field>
<field type="float" name="yaw">Desired yaw angle</field>
</message>
<message id="51" name="LOCAL_POSITION_SETPOINT">
<description>Transmit the current local setpoint of the controller to other MAVs (collision avoidance) and to the GCS.</description>
<field type="float" name="x">x position</field>
<field type="float" name="y">y position</field>
<field type="float" name="z">z position</field>
<field type="float" name="yaw">Desired yaw angle</field>
</message>
<message id="52" name="CONTROL_STATUS">
<field type="uint8_t" name="position_fix">Position fix: 0: lost, 2: 2D position fix, 3: 3D position fix </field>
<field type="uint8_t" name="vision_fix">Vision position fix: 0: lost, 1: 2D local position hold, 2: 2D global position fix, 3: 3D global position fix </field>
<field type="uint8_t" name="gps_fix">GPS position fix: 0: no reception, 1: Minimum 1 satellite, but no position fix, 2: 2D position fix, 3: 3D position fix </field>
<field type="uint8_t" name="ahrs_health">Attitude estimation health: 0: poor, 255: excellent</field>
<field type="uint8_t" name="control_att">0: Attitude control disabled, 1: enabled</field>
<field type="uint8_t" name="control_pos_xy">0: X, Y position control disabled, 1: enabled</field>
<field type="uint8_t" name="control_pos_z">0: Z position control disabled, 1: enabled</field>
<field type="uint8_t" name="control_pos_yaw">0: Yaw angle control disabled, 1: enabled</field>
</message>
<message id="53" name="SAFETY_SET_ALLOWED_AREA">
<description>Set a safety zone (volume), which is defined by two corners of a cube. This message can be used to tell the MAV which setpoints/waypoints to accept and which to reject. Safety areas are often enforced by national or competition regulations.</description>
<field type="uint8_t" name="target_system">System ID</field>
<field type="uint8_t" name="target_component">Component ID</field>
<field type="uint8_t" name="frame">Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down.</field>
<field type="float" name="p1x">x position 1 / Latitude 1</field>
<field type="float" name="p1y">y position 1 / Longitude 1</field>
<field type="float" name="p1z">z position 1 / Altitude 1</field>
<field type="float" name="p2x">x position 2 / Latitude 2</field>
<field type="float" name="p2y">y position 2 / Longitude 2</field>
<field type="float" name="p2z">z position 2 / Altitude 2</field>
</message>
<message id="54" name="SAFETY_ALLOWED_AREA">
<description>Read out the safety zone the MAV currently assumes.</description>
<field type="uint8_t" name="frame">Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down.</field>
<field type="float" name="p1x">x position 1 / Latitude 1</field>
<field type="float" name="p1y">y position 1 / Longitude 1</field>
<field type="float" name="p1z">z position 1 / Altitude 1</field>
<field type="float" name="p2x">x position 2 / Latitude 2</field>
<field type="float" name="p2y">y position 2 / Longitude 2</field>
<field type="float" name="p2z">z position 2 / Altitude 2</field>
</message>
<message id="55" name="SET_ROLL_PITCH_YAW_THRUST">
<description>Set roll, pitch and yaw.</description>
<field type="uint8_t" name="target_system">System ID</field>
<field type="uint8_t" name="target_component">Component ID</field>
<field type="float" name="roll">Desired roll angle in radians</field>
<field type="float" name="pitch">Desired pitch angle in radians</field>
<field type="float" name="yaw">Desired yaw angle in radians</field>
<field type="float" name="thrust">Collective thrust, normalized to 0 .. 1</field>
</message>
<message id="56" name="SET_ROLL_PITCH_YAW_SPEED_THRUST">
<description>Set roll, pitch and yaw.</description>
<field type="uint8_t" name="target_system">System ID</field>
<field type="uint8_t" name="target_component">Component ID</field>
<field type="float" name="roll_speed">Desired roll angular speed in rad/s</field>
<field type="float" name="pitch_speed">Desired pitch angular speed in rad/s</field>
<field type="float" name="yaw_speed">Desired yaw angular speed in rad/s</field>
<field type="float" name="thrust">Collective thrust, normalized to 0 .. 1</field>
</message>
<message id="57" name="ROLL_PITCH_YAW_THRUST_SETPOINT">
<description>Setpoint in roll, pitch, yaw currently active on the system.</description>
<field type="uint64_t" name="time_us">Timestamp in micro seconds since unix epoch</field>
<field type="float" name="roll">Desired roll angle in radians</field>
<field type="float" name="pitch">Desired pitch angle in radians</field>
<field type="float" name="yaw">Desired yaw angle in radians</field>
<field type="float" name="thrust">Collective thrust, normalized to 0 .. 1</field>
</message>
<message id="58" name="ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT">
<description>Setpoint in rollspeed, pitchspeed, yawspeed currently active on the system.</description>
<field type="uint64_t" name="time_us">Timestamp in micro seconds since unix epoch</field>
<field type="float" name="roll_speed">Desired roll angular speed in rad/s</field>
<field type="float" name="pitch_speed">Desired pitch angular speed in rad/s</field>
<field type="float" name="yaw_speed">Desired yaw angular speed in rad/s</field>
<field type="float" name="thrust">Collective thrust, normalized to 0 .. 1</field>
</message>
<message id="62" name="NAV_CONTROLLER_OUTPUT">
<description>Outputs of the APM navigation controller. The primary use of this message is to check the response and signs
of the controller before actual flight and to assist with tuning controller parameters </description>
<field type="float" name="nav_roll">Current desired roll in degrees</field>
<field type="float" name="nav_pitch">Current desired pitch in degrees</field>
<field type="int16_t" name="nav_bearing">Current desired heading in degrees</field>
<field type="int16_t" name="target_bearing">Bearing to current waypoint/target in degrees</field>
<field type="uint16_t" name="wp_dist">Distance to active waypoint in meters</field>
<field type="float" name="alt_error">Current altitude error in meters</field>
<field type="float" name="aspd_error">Current airspeed error in meters/second</field>
<field type="float" name="xtrack_error">Current crosstrack error on x-y plane in meters</field>
</message>
<message id="63" name="POSITION_TARGET">
<description>The goal position of the system. This position is the input to any navigation or path planning algorithm and does NOT represent the current controller setpoint.</description>
<field type="float" name="x">x position</field>
<field type="float" name="y">y position</field>
<field type="float" name="z">z position</field>
<field type="float" name="yaw">yaw orientation in radians, 0 = NORTH</field>
</message>
<message id="64" name="STATE_CORRECTION">
<description>Corrects the systems state by adding an error correction term to the position and velocity, and by rotating the attitude by a correction angle.</description>
<field type="float" name="xErr">x position error</field>
<field type="float" name="yErr">y position error</field>
<field type="float" name="zErr">z position error</field>
<field type="float" name="rollErr">roll error (radians)</field>
<field type="float" name="pitchErr">pitch error (radians)</field>
<field type="float" name="yawErr">yaw error (radians)</field>
<field type="float" name="vxErr">x velocity</field>
<field type="float" name="vyErr">y velocity</field>
<field type="float" name="vzErr">z velocity</field>
</message>
<message id="65" name="SET_ALTITUDE">
<field type="uint8_t" name="target">The system setting the altitude</field>
<field type="uint32_t" name="mode">The new altitude in meters</field>
</message>
<message id="66" name="REQUEST_DATA_STREAM">
<field type="uint8_t" name="target_system">The target requested to send the message stream.</field>
<field type="uint8_t" name="target_component">The target requested to send the message stream.</field>
<field type="uint8_t" name="req_stream_id">The ID of the requested message type</field>
<field type="uint16_t" name="req_message_rate">Update rate in Hertz</field>
<field type="uint8_t" name="start_stop">1 to start sending, 0 to stop sending.</field>
</message>
<message id="67" name="HIL_STATE">
<description>This packet is useful for high throughput
applications such as hardware in the loop simulations.
</description>
<field type="uint64_t" name="usec">Timestamp (microseconds since UNIX epoch or microseconds since system boot)</field>
<field type="float" name="roll">Roll angle (rad)</field>
<field type="float" name="pitch">Pitch angle (rad)</field>
<field type="float" name="yaw">Yaw angle (rad)</field>
<field type="float" name="rollspeed">Roll angular speed (rad/s)</field>
<field type="float" name="pitchspeed">Pitch angular speed (rad/s)</field>
<field type="float" name="yawspeed">Yaw angular speed (rad/s)</field>
<field type="int32_t" name="lat">Latitude, expressed as * 1E7</field>
<field type="int32_t" name="lon">Longitude, expressed as * 1E7</field>
<field type="int32_t" name="alt">Altitude in meters, expressed as * 1000 (millimeters)</field>
<field type="int16_t" name="vx">Ground X Speed (Latitude), expressed as m/s * 100</field>
<field type="int16_t" name="vy">Ground Y Speed (Longitude), expressed as m/s * 100</field>
<field type="int16_t" name="vz">Ground Z Speed (Altitude), expressed as m/s * 100</field>
<field type="int16_t" name="xacc">X acceleration (mg)</field>
<field type="int16_t" name="yacc">Y acceleration (mg)</field>
<field type="int16_t" name="zacc">Z acceleration (mg)</field>
</message>
<message id="68" name="HIL_CONTROLS">
<description>Hardware in the loop control outputs</description>
<field type="uint64_t" name="time_us">Timestamp (microseconds since UNIX epoch or microseconds since system boot)</field>
<field type="float" name="roll_ailerons">Control output -3 .. 1</field>
<field type="float" name="pitch_elevator">Control output -1 .. 1</field>
<field type="float" name="yaw_rudder">Control output -1 .. 1</field>
<field type="float" name="throttle">Throttle 0 .. 1</field>
<field type="uint8_t" name="mode">System mode (MAV_MODE)</field>
<field type="uint8_t" name="nav_mode">Navigation mode (MAV_NAV_MODE)</field>
</message>
<message id="69" name="MANUAL_CONTROL">
<field type="uint8_t" name="target">The system to be controlled</field>
<field type="float" name="roll">roll</field>
<field type="float" name="pitch">pitch</field>
<field type="float" name="yaw">yaw</field>
<field type="float" name="thrust">thrust</field>
<field type="uint8_t" name="roll_manual">roll control enabled auto:0, manual:1</field>
<field type="uint8_t" name="pitch_manual">pitch auto:0, manual:1</field>
<field type="uint8_t" name="yaw_manual">yaw auto:0, manual:1</field>
<field type="uint8_t" name="thrust_manual">thrust auto:0, manual:1</field>
</message>
<message id="70" name="RC_CHANNELS_OVERRIDE">
<description>The RAW values of the RC channels sent to the MAV to override info received from the RC radio. A value of -1 means no change to that channel. A value of 0 means control of that channel should be released back to the RC radio. The standard PPM modulation is as follows: 1000 microseconds: 0%, 2000 microseconds: 100%. Individual receivers/transmitters might violate this specification.</description>
<field type="uint8_t" name="target_system">System ID</field>
<field type="uint8_t" name="target_component">Component ID</field>
<field type="uint16_t" name="chan1_raw">RC channel 1 value, in microseconds</field>
<field type="uint16_t" name="chan2_raw">RC channel 2 value, in microseconds</field>
<field type="uint16_t" name="chan3_raw">RC channel 3 value, in microseconds</field>
<field type="uint16_t" name="chan4_raw">RC channel 4 value, in microseconds</field>
<field type="uint16_t" name="chan5_raw">RC channel 5 value, in microseconds</field>
<field type="uint16_t" name="chan6_raw">RC channel 6 value, in microseconds</field>
<field type="uint16_t" name="chan7_raw">RC channel 7 value, in microseconds</field>
<field type="uint16_t" name="chan8_raw">RC channel 8 value, in microseconds</field>
</message>
<message id="73" name="GLOBAL_POSITION_INT">
<description>The filtered global position (e.g. fused GPS and accelerometers). The position is in GPS-frame (right-handed, Z-up)</description>
<field type="int32_t" name="lat">Latitude, expressed as * 1E7</field>
<field type="int32_t" name="lon">Longitude, expressed as * 1E7</field>
<field type="int32_t" name="alt">Altitude in meters, expressed as * 1000 (millimeters)</field>
<field type="int16_t" name="vx">Ground X Speed (Latitude), expressed as m/s * 100</field>
<field type="int16_t" name="vy">Ground Y Speed (Longitude), expressed as m/s * 100</field>
<field type="int16_t" name="vz">Ground Z Speed (Altitude), expressed as m/s * 100</field>
</message>
<message id="74" name="VFR_HUD">
<description>Metrics typically displayed on a HUD for fixed wing aircraft</description>
<field type="float" name="airspeed">Current airspeed in m/s</field>
<field type="float" name="groundspeed">Current ground speed in m/s</field>
<field type="int16_t" name="heading">Current heading in degrees, in compass units (0..360, 0=north)</field>
<field type="uint16_t" name="throttle">Current throttle setting in integer percent, 0 to 100</field>
<field type="float" name="alt">Current altitude (MSL), in meters</field>
<field type="float" name="climb">Current climb rate in meters/second</field>
</message>
<message id="75" name="COMMAND">
<description>Send a command with up to four parameters to the MAV</description>
<field type="uint8_t" name="target_system">System which should execute the command</field>
<field type="uint8_t" name="target_component">Component which should execute the command, 0 for all components</field>
<field type="uint8_t" name="command">Command ID, as defined by MAV_CMD enum.</field>
<field type="uint8_t" name="confirmation">0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command)</field>
<field type="float" name="param1">Parameter 1, as defined by MAV_CMD enum.</field>
<field type="float" name="param2">Parameter 2, as defined by MAV_CMD enum.</field>
<field type="float" name="param3">Parameter 3, as defined by MAV_CMD enum.</field>
<field type="float" name="param4">Parameter 4, as defined by MAV_CMD enum.</field>
</message>
<message id="76" name="COMMAND_ACK">
<description>Report status of a command. Includes feedback wether the command was executed</description>
<field type="float" name="command">Current airspeed in m/s</field>
<field type="float" name="result">1: Action ACCEPTED and EXECUTED, 1: Action TEMPORARY REJECTED/DENIED, 2: Action PERMANENTLY DENIED, 3: Action UNKNOWN/UNSUPPORTED, 4: Requesting CONFIRMATION</field>
</message>
<message id="100" name="OPTICAL_FLOW">
<description>Optical flow from a flow sensor (e.g. optical mouse sensor)</description>
<field type="uint64_t" name="time">Timestamp (UNIX)</field>
<field type="uint8_t" name="sensor_id">Sensor ID</field>
<field type="int16_t" name="flow_x">Flow in pixels in x-sensor direction</field>
<field type="int16_t" name="flow_y">Flow in pixels in y-sensor direction</field>
<field type="uint8_t" name="quality">Optical flow quality / confidence. 0: bad, 255: maximum quality</field>
<field type="float" name="ground_distance">Ground distance in meters</field>
</message>
<message id="140" name="OBJECT_DETECTION_EVENT">
<description>Object has been detected</description>
<field type="uint32_t" name="time">Timestamp in milliseconds since system boot</field>
<field type="uint16_t" name="object_id">Object ID</field>
<field type="uint8_t" name="type">Object type: 0: image, 1: letter, 2: ground vehicle, 3: air vehicle, 4: surface vehicle, 5: sub-surface vehicle, 6: human, 7: animal</field>
<field type="char[20]" name="name">Name of the object as defined by the detector</field>
<field type="uint8_t" name="quality">Detection quality / confidence. 0: bad, 255: maximum confidence</field>
<field type="float" name="bearing">Angle of the object with respect to the body frame in NED coordinates in radians. 0: front</field>
<field type="float" name="distance">Ground distance in meters</field>
</message>
<!-- MESSAGE IDs 80 - 250: Space for custom messages in individual projectname_messages.xml files -->
<message id="251" name="DEBUG_VECT">
<field type="char[10]" name="name">Name</field>
<field type="uint64_t" name="usec">Timestamp</field>
<field type="float" name="x">x</field>
<field type="float" name="y">y</field>
<field type="float" name="z">z</field>
</message>
<message id="252" name="NAMED_VALUE_FLOAT">
<description>Send a key-value pair as float. The use of this message is discouraged for normal packets, but a quite efficient way for testing new messages and getting experimental debug output.</description>
<field type="char[10]" name="name">Name of the debug variable</field>
<field type="float" name="value">Floating point value</field>
</message>
<message id="253" name="NAMED_VALUE_INT">
<description>Send a key-value pair as integer. The use of this message is discouraged for normal packets, but a quite efficient way for testing new messages and getting experimental debug output.</description>
<field type="char[10]" name="name">Name of the debug variable</field>
<field type="int32_t" name="value">Signed integer value</field>
</message>
<message id="254" name="STATUSTEXT">
<description>Status text message. These messages are printed in yellow in the COMM console of QGroundControl. WARNING: They consume quite some bandwidth, so use only for important status and error messages. If implemented wisely, these messages are buffered on the MCU and sent only at a limited rate (e.g. 10 Hz).</description>
<field type="uint8_t" name="severity">Severity of status, 0 = info message, 255 = critical fault</field>
<field type="int8_t[50]" name="text">Status text message, without null termination character</field>
</message>
<message id="255" name="DEBUG">
<description>Send a debug value. The index is used to discriminate between values. These values show up in the plot of QGroundControl as DEBUG N.</description>
<field type="uint8_t" name="ind">index of debug variable</field>
<field type="float" name="value">DEBUG value</field>
</message>
</messages>
</mavlink>
/C-OSD/arducam-osd/libraries/GCS_MAVLink/message_definitions/minimal.xml
0,0 → 1,13
<?xml version='1.0'?>
<mavlink>
<version>2</version>
<enums/>
<messages>
<message id="0" name="HEARTBEAT">
<description>The heartbeat message shows that a system is present and responding. The type of the MAV and Autopilot hardware allow the receiving system to treat further messages from this system appropriate (e.g. by laying out the user interface based on the autopilot).</description>
<field type="uint8_t" name="type">Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM)</field>
<field type="uint8_t" name="autopilot">Type of the Autopilot: 0: Generic, 1: PIXHAWK, 2: SLUGS, 3: Ardupilot (up to 15 types), defined in MAV_AUTOPILOT_TYPE ENUM</field>
<field type="uint8_t_mavlink_version" name="mavlink_version">MAVLink version</field>
</message>
</messages>
</mavlink>
/C-OSD/arducam-osd/libraries/GCS_MAVLink/message_definitions/pixhawk.xml
0,0 → 1,227
<?xml version='1.0'?>
<mavlink>
<include>common.xml</include>
<enums>
<enum name="DATA_TYPES">
<description>Content Types for data transmission handshake</description>
<entry value="1" name="DATA_TYPE_JPEG_IMAGE"/>
<entry value="2" name="DATA_TYPE_RAW_IMAGE"/>
<entry value="3" name="DATA_TYPE_KINECT"/>
</enum>
</enums>
<messages>
<message id="151" name="SET_CAM_SHUTTER">
<field type="uint8_t" name="cam_no">Camera id</field>
<field type="uint8_t" name="cam_mode">Camera mode: 0 = auto, 1 = manual</field>
<field type="uint8_t" name="trigger_pin">Trigger pin, 0-3 for PtGrey FireFly</field>
<field type="uint16_t" name="interval">Shutter interval, in microseconds</field>
<field type="uint16_t" name="exposure">Exposure time, in microseconds</field>
<field type="float" name="gain">Camera gain</field>
</message>
<message id="152" name="IMAGE_TRIGGERED">
<field type="uint64_t" name="timestamp">Timestamp</field>
<field type="uint32_t" name="seq">IMU seq</field>
<field type="float" name="roll">Roll angle in rad</field>
<field type="float" name="pitch">Pitch angle in rad</field>
<field type="float" name="yaw">Yaw angle in rad</field>
<field type="float" name="local_z">Local frame Z coordinate (height over ground)</field>
<field type="float" name="lat">GPS X coordinate</field>
<field type="float" name="lon">GPS Y coordinate</field>
<field type="float" name="alt">Global frame altitude</field>
<field type="float" name="ground_x">Ground truth X</field>
<field type="float" name="ground_y">Ground truth Y</field>
<field type="float" name="ground_z">Ground truth Z</field>
</message>
<message id="153" name="IMAGE_TRIGGER_CONTROL">
<field type="uint8_t" name="enable">0 to disable, 1 to enable</field>
</message>
<message id="154" name="IMAGE_AVAILABLE">
<field type="uint64_t" name="cam_id">Camera id</field>
<field type="uint8_t" name="cam_no">Camera # (starts with 0)</field>
<field type="uint64_t" name="timestamp">Timestamp</field>
<field type="uint64_t" name="valid_until">Until which timestamp this buffer will stay valid</field>
<field type="uint32_t" name="img_seq">The image sequence number</field>
<field type="uint32_t" name="img_buf_index">Position of the image in the buffer, starts with 0</field>
<field type="uint16_t" name="width">Image width</field>
<field type="uint16_t" name="height">Image height</field>
<field type="uint16_t" name="depth">Image depth</field>
<field type="uint8_t" name="channels">Image channels</field>
<field type="uint32_t" name="key">Shared memory area key</field>
<field type="uint32_t" name="exposure">Exposure time, in microseconds</field>
<field type="float" name="gain">Camera gain</field>
<field type="float" name="roll">Roll angle in rad</field>
<field type="float" name="pitch">Pitch angle in rad</field>
<field type="float" name="yaw">Yaw angle in rad</field>
<field type="float" name="local_z">Local frame Z coordinate (height over ground)</field>
<field type="float" name="lat">GPS X coordinate</field>
<field type="float" name="lon">GPS Y coordinate</field>
<field type="float" name="alt">Global frame altitude</field>
<field type="float" name="ground_x">Ground truth X</field>
<field type="float" name="ground_y">Ground truth Y</field>
<field type="float" name="ground_z">Ground truth Z</field>
</message>
<message id="156" name="VISION_POSITION_ESTIMATE">
<field type="uint64_t" name="usec">Timestamp (milliseconds)</field>
<field type="float" name="x">Global X position</field>
<field type="float" name="y">Global Y position</field>
<field type="float" name="z">Global Z position</field>
<field type="float" name="roll">Roll angle in rad</field>
<field type="float" name="pitch">Pitch angle in rad</field>
<field type="float" name="yaw">Yaw angle in rad</field>
</message>
<message id="157" name="VICON_POSITION_ESTIMATE">
<field type="uint64_t" name="usec">Timestamp (milliseconds)</field>
<field type="float" name="x">Global X position</field>
<field type="float" name="y">Global Y position</field>
<field type="float" name="z">Global Z position</field>
<field type="float" name="roll">Roll angle in rad</field>
<field type="float" name="pitch">Pitch angle in rad</field>
<field type="float" name="yaw">Yaw angle in rad</field>
</message>
<message id="158" name="VISION_SPEED_ESTIMATE">
<field type="uint64_t" name="usec">Timestamp (milliseconds)</field>
<field type="float" name="x">Global X speed</field>
<field type="float" name="y">Global Y speed</field>
<field type="float" name="z">Global Z speed</field>
</message>
<message id="159" name="POSITION_CONTROL_SETPOINT_SET">
<description>Message sent to the MAV to set a new position as reference for the controller</description>
<field type="uint8_t" name="target_system">System ID</field>
<field type="uint8_t" name="target_component">Component ID</field>
<field type="uint16_t" name="id">ID of waypoint, 0 for plain position</field>
<field type="float" name="x">x position</field>
<field type="float" name="y">y position</field>
<field type="float" name="z">z position</field>
<field type="float" name="yaw">yaw orientation in radians, 0 = NORTH</field>
</message>
<message id="160" name="POSITION_CONTROL_OFFSET_SET">
<description>Message sent to the MAV to set a new offset from the currently controlled position</description>
<field type="uint8_t" name="target_system">System ID</field>
<field type="uint8_t" name="target_component">Component ID</field>
<field type="float" name="x">x position offset</field>
<field type="float" name="y">y position offset</field>
<field type="float" name="z">z position offset</field>
<field type="float" name="yaw">yaw orientation offset in radians, 0 = NORTH</field>
</message>
<!-- Message sent by the MAV once it sets a new position as reference in the controller -->
<message id="170" name="POSITION_CONTROL_SETPOINT">
<field type="uint16_t" name="id">ID of waypoint, 0 for plain position</field>
<field type="float" name="x">x position</field>
<field type="float" name="y">y position</field>
<field type="float" name="z">z position</field>
<field type="float" name="yaw">yaw orientation in radians, 0 = NORTH</field>
</message>
<message id="171" name="MARKER">
<field type="uint16_t" name="id">ID</field>
<field type="float" name="x">x position</field>
<field type="float" name="y">y position</field>
<field type="float" name="z">z position</field>
<field type="float" name="roll">roll orientation</field>
<field type="float" name="pitch">pitch orientation</field>
<field type="float" name="yaw">yaw orientation</field>
</message>
<message id="172" name="RAW_AUX">
<field type="uint16_t" name="adc1">ADC1 (J405 ADC3, LPC2148 AD0.6)</field>
<field type="uint16_t" name="adc2">ADC2 (J405 ADC5, LPC2148 AD0.2)</field>
<field type="uint16_t" name="adc3">ADC3 (J405 ADC6, LPC2148 AD0.1)</field>
<field type="uint16_t" name="adc4">ADC4 (J405 ADC7, LPC2148 AD1.3)</field>
<field type="uint16_t" name="vbat">Battery voltage</field>
<field type="int16_t" name="temp">Temperature (degrees celcius)</field>
<field type="int32_t" name="baro">Barometric pressure (hecto Pascal)</field>
</message>
<message id="180" name="WATCHDOG_HEARTBEAT">
<field type="uint16_t" name="watchdog_id">Watchdog ID</field>
<field type="uint16_t" name="process_count">Number of processes</field>
</message>
<message id="181" name="WATCHDOG_PROCESS_INFO">
<field type="uint16_t" name="watchdog_id">Watchdog ID</field>
<field type="uint16_t" name="process_id">Process ID</field>
<field type="char[100]" name="name">Process name</field>
<field type="char[147]" name="arguments">Process arguments</field>
<field type="int32_t" name="timeout">Timeout (seconds)</field>
</message>
<message id="182" name="WATCHDOG_PROCESS_STATUS">
<field type="uint16_t" name="watchdog_id">Watchdog ID</field>
<field type="uint16_t" name="process_id">Process ID</field>
<field type="uint8_t" name="state">Is running / finished / suspended / crashed</field>
<field type="uint8_t" name="muted">Is muted</field>
<field type="int32_t" name="pid">PID</field>
<field type="uint16_t" name="crashes">Number of crashes</field>
</message>
<message id="183" name="WATCHDOG_COMMAND">
<field type="uint8_t" name="target_system_id">Target system ID</field>
<field type="uint16_t" name="watchdog_id">Watchdog ID</field>
<field type="uint16_t" name="process_id">Process ID</field>
<field type="uint8_t" name="command_id">Command ID</field>
</message>
<message id="190" name="PATTERN_DETECTED">
<field type="uint8_t" name="type">0: Pattern, 1: Letter</field>
<field type="float" name="confidence">Confidence of detection</field>
<field type="char[100]" name="file">Pattern file name</field>
<field type="uint8_t" name="detected">Accepted as true detection, 0 no, 1 yes</field>
</message>
<message id="191" name="POINT_OF_INTEREST">
<description>Notifies the operator about a point of interest (POI). This can be anything detected by the
system. This generic message is intented to help interfacing to generic visualizations and to display
the POI on a map.
</description>
<field type="uint8_t" name="type">0: Notice, 1: Warning, 2: Critical, 3: Emergency, 4: Debug</field>
<field type="uint8_t" name="color">0: blue, 1: yellow, 2: red, 3: orange, 4: green, 5: magenta</field>
<field type="uint8_t" name="coordinate_system">0: global, 1:local</field>
<field type="uint16_t" name="timeout">0: no timeout, >1: timeout in seconds</field>
<field type="float" name="x">X Position</field>
<field type="float" name="y">Y Position</field>
<field type="float" name="z">Z Position</field>
<field type="char[26]" name="name">POI name</field>
</message>
<message id="192" name="POINT_OF_INTEREST_CONNECTION">
<description>Notifies the operator about the connection of two point of interests (POI). This can be anything detected by the
system. This generic message is intented to help interfacing to generic visualizations and to display
the POI on a map.
</description>
<field type="uint8_t" name="type">0: Notice, 1: Warning, 2: Critical, 3: Emergency, 4: Debug</field>
<field type="uint8_t" name="color">0: blue, 1: yellow, 2: red, 3: orange, 4: green, 5: magenta</field>
<field type="uint8_t" name="coordinate_system">0: global, 1:local</field>
<field type="uint16_t" name="timeout">0: no timeout, >1: timeout in seconds</field>
<field type="float" name="xp1">X1 Position</field>
<field type="float" name="yp1">Y1 Position</field>
<field type="float" name="zp1">Z1 Position</field>
<field type="float" name="xp2">X2 Position</field>
<field type="float" name="yp2">Y2 Position</field>
<field type="float" name="zp2">Z2 Position</field>
<field type="char[26]" name="name">POI connection name</field>
</message>
<message id="193" name="DATA_TRANSMISSION_HANDSHAKE">
<field type="uint8_t" name="type">type of requested/acknowledged data (as defined in ENUM DATA_TYPES in mavlink/include/mavlink_types.h)</field>
<field type="uint32_t" name="size">total data size in bytes (set on ACK only)</field>
<field type="uint8_t" name="packets">number of packets beeing sent (set on ACK only)</field>
<field type="uint8_t" name="payload">payload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only)</field>
<field type="uint8_t" name="jpg_quality">JPEG quality out of [1,100]</field>
</message>
<message id="194" name="ENCAPSULATED_DATA">
<field type="uint16_t" name="seqnr">sequence number (starting with 0 on every transmission)</field>
<field type="uint8_t[253]" name="data">image data bytes</field>
</message>
<message id="195" name="BRIEF_FEATURE">
<field type="float" name="x">x position in m</field>
<field type="float" name="y">y position in m</field>
<field type="float" name="z">z position in m</field>
<field type="uint8_t" name="orientation_assignment">Orientation assignment 0: false, 1:true</field>
<field type="uint16_t" name="size">Size in pixels</field>
<field type="uint16_t" name="orientation">Orientation</field>
<field type="uint8_t[32]" name="descriptor">Descriptor</field>
<field type="float" name="response">Harris operator response at this location</field>
</message>
<message id="200" name="ATTITUDE_CONTROL">
<field type="uint8_t" name="target">The system to be controlled</field>
<field type="float" name="roll">roll</field>
<field type="float" name="pitch">pitch</field>
<field type="float" name="yaw">yaw</field>
<field type="float" name="thrust">thrust</field>
<field type="uint8_t" name="roll_manual">roll control enabled auto:0, manual:1</field>
<field type="uint8_t" name="pitch_manual">pitch auto:0, manual:1</field>
<field type="uint8_t" name="yaw_manual">yaw auto:0, manual:1</field>
<field type="uint8_t" name="thrust_manual">thrust auto:0, manual:1</field>
</message>
</messages>
</mavlink>
/C-OSD/arducam-osd/libraries/GCS_MAVLink/message_definitions/slugs.xml
0,0 → 1,144
<?xml version="1.0"?>
<mavlink>
<include>common.xml</include>
 
<!-- <enums>
<enum name="SLUGS_ACTION" >
<description> Slugs Actions </description>
<entry name = "SLUGS_ACTION_NONE">
<entry name = "SLUGS_ACTION_SUCCESS">
<entry name = "SLUGS_ACTION_FAIL">
<entry name = "SLUGS_ACTION_EEPROM">
<entry name = "SLUGS_ACTION_MODE_CHANGE">
<entry name = "SLUGS_ACTION_MODE_REPORT">
<entry name = "SLUGS_ACTION_PT_CHANGE">
<entry name = "SLUGS_ACTION_PT_REPORT">
<entry name = "SLUGS_ACTION_PID_CHANGE">
<entry name = "SLUGS_ACTION_PID_REPORT">
<entry name = "SLUGS_ACTION_WP_CHANGE">
<entry name = "SLUGS_ACTION_WP_REPORT">
<entry name = "SLUGS_ACTION_MLC_CHANGE">
<entry name = "SLUGS_ACTION_MLC_REPORT">
</enum>
 
<enum name="WP_PROTOCOL_STATE" >
<description> Waypoint Protocol States </description>
<entry name = "WP_PROT_IDLE">
<entry name = "WP_PROT_LIST_REQUESTED">
<entry name = "WP_PROT_NUM_SENT">
<entry name = "WP_PROT_TX_WP">
<entry name = "WP_PROT_RX_WP">
<entry name = "WP_PROT_SENDING_WP_IDLE">
<entry name = "WP_PROT_GETTING_WP_IDLE">
</enum>
 
</enums> -->
 
<messages>
 
<message name="CPU_LOAD" id="170">
Sensor and DSC control loads.
<field name="sensLoad" type="uint8_t">Sensor DSC Load</field>
<field name="ctrlLoad" type="uint8_t">Control DSC Load</field>
<field name="batVolt" type="uint16_t">Battery Voltage in millivolts</field>
</message>
 
<message name="AIR_DATA" id="171">
Air data for altitude and airspeed computation.
<field name="dynamicPressure" type="float">Dynamic pressure (Pa)</field>
<field name="staticPressure" type="float">Static pressure (Pa)</field>
<field name="temperature" type="uint16_t">Board temperature</field>
</message>
 
<message name="SENSOR_BIAS" id="172">
Accelerometer and gyro biases.
<field name="axBias" type="float">Accelerometer X bias (m/s)</field>
<field name="ayBias" type="float">Accelerometer Y bias (m/s)</field>
<field name="azBias" type="float">Accelerometer Z bias (m/s)</field>
<field name="gxBias" type="float">Gyro X bias (rad/s)</field>
<field name="gyBias" type="float">Gyro Y bias (rad/s)</field>
<field name="gzBias" type="float">Gyro Z bias (rad/s)</field>
</message>
 
<message name="DIAGNOSTIC" id="173">
Configurable diagnostic messages.
<field name="diagFl1" type="float">Diagnostic float 1</field>
<field name="diagFl2" type="float">Diagnostic float 2</field>
<field name="diagFl3" type="float">Diagnostic float 3</field>
<field name="diagSh1" type="int16_t">Diagnostic short 1</field>
<field name="diagSh2" type="int16_t">Diagnostic short 2</field>
<field name="diagSh3" type="int16_t">Diagnostic short 3</field>
</message>
 
<message name="SLUGS_NAVIGATION" id="176">
Data used in the navigation algorithm.
<field name="u_m" type="float">Measured Airspeed prior to the Nav Filter</field>
<field name="phi_c" type="float">Commanded Roll</field>
<field name="theta_c" type="float">Commanded Pitch</field>
<field name="psiDot_c" type="float">Commanded Turn rate</field>
<field name="ay_body" type="float">Y component of the body acceleration</field>
<field name="totalDist" type="float">Total Distance to Run on this leg of Navigation</field>
<field name="dist2Go" type="float">Remaining distance to Run on this leg of Navigation</field>
<field name="fromWP" type="uint8_t">Origin WP</field>
<field name="toWP" type="uint8_t">Destination WP</field>
</message>
 
<message name="DATA_LOG" id="177">
Configurable data log probes to be used inside Simulink
<field name="fl_1" type="float">Log value 1 </field>
<field name="fl_2" type="float">Log value 2 </field>
<field name="fl_3" type="float">Log value 3 </field>
<field name="fl_4" type="float">Log value 4 </field>
<field name="fl_5" type="float">Log value 5 </field>
<field name="fl_6" type="float">Log value 6 </field>
</message>
 
<message name="GPS_DATE_TIME" id="179">
Pilot console PWM messges.
<field name="year" type="uint8_t">Year reported by Gps </field>
<field name="month" type="uint8_t">Month reported by Gps </field>
<field name="day" type="uint8_t">Day reported by Gps </field>
<field name="hour" type="uint8_t">Hour reported by Gps </field>
<field name="min" type="uint8_t">Min reported by Gps </field>
<field name="sec" type="uint8_t">Sec reported by Gps </field>
<field name="visSat" type="uint8_t">Visible sattelites reported by Gps </field>
</message>
 
<message name="MID_LVL_CMDS" id="180">
Mid Level commands sent from the GS to the autopilot. These are only sent when being opperated in mid-level commands mode from the ground; for periodic report of these commands generated from the autopilot see message XXXX.
<field name="target" type="uint8_t">The system setting the commands</field>
<field name="hCommand" type="float">Commanded Airspeed</field>
<field name="uCommand" type="float">Log value 2 </field>
<field name="rCommand" type="float">Log value 3 </field>
</message>
 
 
<message name="CTRL_SRFC_PT" id="181">
This message configures the Selective Passthrough mode. it allows to select which control surfaces the Pilot can control from his console. It is implemented as a bitfield as follows:
Position Bit Code
=================================
15-8 Reserved
7 dt_pass 128
6 dla_pass 64
5 dra_pass 32
4 dr_pass 16
3 dle_pass 8
2 dre_pass 4
1 dlf_pass 2
0 drf_pass 1
Where Bit 15 is the MSb. 0 = AP has control of the surface; 1 = Pilot Console has control of the surface.
<field name="target" type="uint8_t">The system setting the commands</field>
<field name="bitfieldPt" type="uint16_t">Bitfield containing the PT configuration</field>
</message>
 
 
 
<message name="SLUGS_ACTION" id="183">
Action messages focused on the SLUGS AP.
<field name="target" type="uint8_t">The system reporting the action</field>
<field name="actionId" type="uint8_t">Action ID. See apDefinitions.h in the SLUGS /clib directory for the ID names</field>
<field name="actionVal" type="uint16_t">Value associated with the action</field>
</message>
 
</messages>
</mavlink>
/C-OSD/arducam-osd/libraries/GCS_MAVLink/message_definitions/test.xml
0,0 → 1,31
<?xml version='1.0'?>
<mavlink>
<version>3</version>
<messages>
<message id="0" name="TEST_TYPES">
<description>Test all field types</description>
<field type="char" name="c">char</field>
<field type="char[10]" name="s">string</field>
<field type="uint8_t" name="u8">uint8_t</field>
<field type="uint16_t" name="u16">uint16_t</field>
<field type="uint32_t" name="u32" print_format="0x%08x">uint32_t</field>
<field type="uint64_t" name="u64">uint64_t</field>
<field type="int8_t" name="s8">int8_t</field>
<field type="int16_t" name="s16">int16_t</field>
<field type="int32_t" name="s32">int32_t</field>
<field type="int64_t" name="s64">int64_t</field>
<field type="float" name="f">float</field>
<field type="double" name="d">double</field>
<field type="uint8_t[3]" name="u8_array">uint8_t_array</field>
<field type="uint16_t[3]" name="u16_array">uint16_t_array</field>
<field type="uint32_t[3]" name="u32_array">uint32_t_array</field>
<field type="uint64_t[3]" name="u64_array">uint64_t_array</field>
<field type="int8_t[3]" name="s8_array">int8_t_array</field>
<field type="int16_t[3]" name="s16_array">int16_t_array</field>
<field type="int32_t[3]" name="s32_array">int32_t_array</field>
<field type="int64_t[3]" name="s64_array">int64_t_array</field>
<field type="float[3]" name="f_array">float_array</field>
<field type="double[3]" name="d_array">double_array</field>
</message>
</messages>
</mavlink>
/C-OSD/arducam-osd/libraries/GCS_MAVLink/message_definitions/ualberta.xml
0,0 → 1,54
<?xml version='1.0'?>
<mavlink>
<include>common.xml</include>
<enums>
<enum name="UALBERTA_AUTOPILOT_MODE">
<description>Available autopilot modes for ualberta uav</description>
<entry name="MODE_MANUAL_DIRECT">Raw input pulse widts sent to output</entry>
<entry name="MODE_MANUAL_SCALED">Inputs are normalized using calibration, the converted back to raw pulse widths for output</entry>
<entry name="MODE_AUTO_PID_ATT"> dfsdfs</entry>
<entry name="MODE_AUTO_PID_VEL"> dfsfds</entry>
<entry name="MODE_AUTO_PID_POS"> dfsdfsdfs</entry>
</enum>
<enum name="UALBERTA_NAV_MODE">
<description>Navigation filter mode</description>
<entry name="NAV_AHRS_INIT" />
<entry name="NAV_AHRS">AHRS mode</entry>
<entry name="NAV_INS_GPS_INIT">INS/GPS initialization mode</entry>
<entry name="NAV_INS_GPS">INS/GPS mode</entry>
</enum>
<enum name="UALBERTA_PILOT_MODE">
<description>Mode currently commanded by pilot</description>
<entry name="PILOT_MANUAL"> sdf</entry>
<entry name="PILOT_AUTO"> dfs</entry>
<entry name="PILOT_ROTO"> Rotomotion mode </entry>
</enum>
</enums>
<messages>
<message id="220" name="NAV_FILTER_BIAS">
<description>Accelerometer and Gyro biases from the navigation filter</description>
<field type="uint64_t" name="usec">Timestamp (microseconds)</field>
<field type="float" name="accel_0">b_f[0]</field>
<field type="float" name="accel_1">b_f[1]</field>
<field type="float" name="accel_2">b_f[2]</field>
<field type="float" name="gyro_0">b_f[0]</field>
<field type="float" name="gyro_1">b_f[1]</field>
<field type="float" name="gyro_2">b_f[2]</field>
</message>
<message id="221" name="RADIO_CALIBRATION">
<description>Complete set of calibration parameters for the radio</description>
<field type="uint16_t[3]" name="aileron">Aileron setpoints: left, center, right</field>
<field type="uint16_t[3]" name="elevator">Elevator setpoints: nose down, center, nose up</field>
<field type="uint16_t[3]" name="rudder">Rudder setpoints: nose left, center, nose right</field>
<field type="uint16_t[2]" name="gyro">Tail gyro mode/gain setpoints: heading hold, rate mode</field>
<field type="uint16_t[5]" name="pitch">Pitch curve setpoints (every 25%)</field>
<field type="uint16_t[5]" name="throttle">Throttle curve setpoints (every 25%)</field>
</message>
<message id="222" name="UALBERTA_SYS_STATUS">
<description>System status specific to ualberta uav</description>
<field type="uint8_t" name="mode">System mode, see UALBERTA_AUTOPILOT_MODE ENUM</field>
<field type="uint8_t" name="nav_mode">Navigation mode, see UALBERTA_NAV_MODE ENUM</field>
<field type="uint8_t" name="pilot">Pilot mode, see UALBERTA_PILOT_MODE</field>
</message>
</messages>
</mavlink>
/C-OSD/arducam-osd/libraries/GCS_MAVLink/message_definitions_v1.0/ardupilotmega.xml
0,0 → 1,270
<?xml version='1.0'?>
<mavlink>
<include>common.xml</include>
<!-- note that APM specific messages should use the command id
range from 150 to 250, to leave plenty of room for growth
of common.xml
 
If you prototype a message here, then you should consider if it
is general enough to move into common.xml later
-->
 
 
<enums>
<!-- Camera Mount mode Enumeration -->
<enum name="MAV_MOUNT_MODE">
<description>Enumeration of possible mount operation modes</description>
<entry name="MAV_MOUNT_MODE_RETRACT" value="0"><description>Load and keep safe position (Roll,Pitch,Yaw) from EEPROM and stop stabilization</description></entry>
<entry name="MAV_MOUNT_MODE_NEUTRAL" value="1"><description>Load and keep neutral position (Roll,Pitch,Yaw) from EEPROM.</description></entry>
<entry name="MAV_MOUNT_MODE_MAVLINK_TARGETING" value="2"><description>Load neutral position and start MAVLink Roll,Pitch,Yaw control with stabilization</description></entry>
<entry name="MAV_MOUNT_MODE_RC_TARGETING" value="3"><description>Load neutral position and start RC Roll,Pitch,Yaw control with stabilization</description></entry>
<entry name="MAV_MOUNT_MODE_GPS_POINT" value="4"><description>Load neutral position and start to point to Lat,Lon,Alt</description></entry>
</enum>
 
<enum name="MAV_CMD" >
<!-- Camera Controller Mission Commands Enumeration -->
<entry name="MAV_CMD_DO_DIGICAM_CONFIGURE" value="202">
<description>Mission command to configure an on-board camera controller system.</description>
<param index="1">Modes: P, TV, AV, M, Etc</param>
<param index="2">Shutter speed: Divisor number for one second</param>
<param index="3">Aperture: F stop number</param>
<param index="4">ISO number e.g. 80, 100, 200, Etc</param>
<param index="5">Exposure type enumerator</param>
<param index="6">Command Identity</param>
<param index="7">Main engine cut-off time before camera trigger in seconds/10 (0 means no cut-off)</param>
</entry>
 
<entry name="MAV_CMD_DO_DIGICAM_CONTROL" value="203">
<description>Mission command to control an on-board camera controller system.</description>
<param index="1">Session control e.g. show/hide lens</param>
<param index="2">Zoom's absolute position</param>
<param index="3">Zooming step value to offset zoom from the current position</param>
<param index="4">Focus Locking, Unlocking or Re-locking</param>
<param index="5">Shooting Command</param>
<param index="6">Command Identity</param>
<param index="7">Empty</param>
</entry>
 
<!-- Camera Mount Mission Commands Enumeration -->
<entry name="MAV_CMD_DO_MOUNT_CONFIGURE" value="204">
<description>Mission command to configure a camera or antenna mount</description>
<param index="1">Mount operation mode (see MAV_MOUNT_MODE enum)</param>
<param index="2">stabilize roll? (1 = yes, 0 = no)</param>
<param index="3">stabilize pitch? (1 = yes, 0 = no)</param>
<param index="4">stabilize yaw? (1 = yes, 0 = no)</param>
<param index="5">Empty</param>
<param index="6">Empty</param>
<param index="7">Empty</param>
</entry>
 
<entry name="MAV_CMD_DO_MOUNT_CONTROL" value="205">
<description>Mission command to control a camera or antenna mount</description>
<param index="1">pitch(deg*100) or lat, depending on mount mode.</param>
<param index="2">roll(deg*100) or lon depending on mount mode</param>
<param index="3">yaw(deg*100) or alt (in cm) depending on mount mode</param>
<param index="4">Empty</param>
<param index="5">Empty</param>
<param index="6">Empty</param>
<param index="7">Empty</param>
</entry>
</enum>
 
<!-- fenced mode enums -->
<enum name="FENCE_ACTION">
<entry name="FENCE_ACTION_NONE" value="0">
<description>Disable fenced mode</description>
</entry>
<entry name="FENCE_ACTION_GUIDED" value="1">
<description>Switched to guided mode to return point (fence point 0)</description>
</entry>
</enum>
 
<enum name="FENCE_BREACH">
<entry name="FENCE_BREACH_NONE" value="0">
<description>No last fence breach</description>
</entry>
<entry name="FENCE_BREACH_MINALT" value="1">
<description>Breached minimum altitude</description>
</entry>
<entry name="FENCE_BREACH_MAXALT" value="2">
<description>Breached minimum altitude</description>
</entry>
<entry name="FENCE_BREACH_BOUNDARY" value="3">
<description>Breached fence boundary</description>
</entry>
</enum>
</enums>
 
<messages>
<message id="150" name="SENSOR_OFFSETS">
<description>Offsets and calibrations values for hardware
sensors. This makes it easier to debug the calibration process.</description>
<field type="int16_t" name="mag_ofs_x">magnetometer X offset</field>
<field type="int16_t" name="mag_ofs_y">magnetometer Y offset</field>
<field type="int16_t" name="mag_ofs_z">magnetometer Z offset</field>
<field type="float" name="mag_declination">magnetic declination (radians)</field>
<field type="int32_t" name="raw_press">raw pressure from barometer</field>
<field type="int32_t" name="raw_temp">raw temperature from barometer</field>
<field type="float" name="gyro_cal_x">gyro X calibration</field>
<field type="float" name="gyro_cal_y">gyro Y calibration</field>
<field type="float" name="gyro_cal_z">gyro Z calibration</field>
<field type="float" name="accel_cal_x">accel X calibration</field>
<field type="float" name="accel_cal_y">accel Y calibration</field>
<field type="float" name="accel_cal_z">accel Z calibration</field>
</message>
 
<message id="151" name="SET_MAG_OFFSETS">
<description>set the magnetometer offsets</description>
<field type="uint8_t" name="target_system">System ID</field>
<field type="uint8_t" name="target_component">Component ID</field>
<field type="int16_t" name="mag_ofs_x">magnetometer X offset</field>
<field type="int16_t" name="mag_ofs_y">magnetometer Y offset</field>
<field type="int16_t" name="mag_ofs_z">magnetometer Z offset</field>
</message>
 
<message id="152" name="MEMINFO">
<description>state of APM memory</description>
<field type="uint16_t" name="brkval">heap top</field>
<field type="uint16_t" name="freemem">free memory</field>
</message>
 
<message id="153" name="AP_ADC">
<description>raw ADC output</description>
<field type="uint16_t" name="adc1">ADC output 1</field>
<field type="uint16_t" name="adc2">ADC output 2</field>
<field type="uint16_t" name="adc3">ADC output 3</field>
<field type="uint16_t" name="adc4">ADC output 4</field>
<field type="uint16_t" name="adc5">ADC output 5</field>
<field type="uint16_t" name="adc6">ADC output 6</field>
</message>
 
<!-- Camera Controller Messages -->
<message name="DIGICAM_CONFIGURE" id="154">
<description>Configure on-board Camera Control System.</description>
<field name="target_system" type="uint8_t">System ID</field>
<field name="target_component" type="uint8_t">Component ID</field>
<field name="mode" type="uint8_t">Mode enumeration from 1 to N //P, TV, AV, M, Etc (0 means ignore)</field>
<field name="shutter_speed" type="uint16_t">Divisor number //e.g. 1000 means 1/1000 (0 means ignore)</field>
<field name="aperture" type="uint8_t">F stop number x 10 //e.g. 28 means 2.8 (0 means ignore)</field>
<field name="iso" type="uint8_t">ISO enumeration from 1 to N //e.g. 80, 100, 200, Etc (0 means ignore)</field>
<field name="exposure_type" type="uint8_t">Exposure type enumeration from 1 to N (0 means ignore)</field>
<field name="command_id" type="uint8_t">Command Identity (incremental loop: 0 to 255)//A command sent multiple times will be executed or pooled just once</field>
<field name="engine_cut_off" type="uint8_t">Main engine cut-off time before camera trigger in seconds/10 (0 means no cut-off)</field>
<field name="extra_param" type="uint8_t">Extra parameters enumeration (0 means ignore)</field>
<field name="extra_value" type="float">Correspondent value to given extra_param</field>
</message>
 
<message name="DIGICAM_CONTROL" id="155">
<description>Control on-board Camera Control System to take shots.</description>
<field name="target_system" type="uint8_t">System ID</field>
<field name="target_component" type="uint8_t">Component ID</field>
<field name="session" type="uint8_t">0: stop, 1: start or keep it up //Session control e.g. show/hide lens</field>
<field name="zoom_pos" type="uint8_t">1 to N //Zoom's absolute position (0 means ignore)</field>
<field name="zoom_step" type="int8_t">-100 to 100 //Zooming step value to offset zoom from the current position</field>
<field name="focus_lock" type="uint8_t">0: unlock focus or keep unlocked, 1: lock focus or keep locked, 3: re-lock focus</field>
<field name="shot" type="uint8_t">0: ignore, 1: shot or start filming</field>
<field name="command_id" type="uint8_t">Command Identity (incremental loop: 0 to 255)//A command sent multiple times will be executed or pooled just once</field>
<field name="extra_param" type="uint8_t">Extra parameters enumeration (0 means ignore)</field>
<field name="extra_value" type="float">Correspondent value to given extra_param</field>
</message>
 
<!-- Camera Mount Messages -->
<message name="MOUNT_CONFIGURE" id="156">
<description>Message to configure a camera mount, directional antenna, etc.</description>
<field name="target_system" type="uint8_t">System ID</field>
<field name="target_component" type="uint8_t">Component ID</field>
<field name="mount_mode" type="uint8_t">mount operating mode (see MAV_MOUNT_MODE enum)</field>
<field name="stab_roll" type="uint8_t">(1 = yes, 0 = no)</field>
<field name="stab_pitch" type="uint8_t">(1 = yes, 0 = no)</field>
<field name="stab_yaw" type="uint8_t">(1 = yes, 0 = no)</field>
</message>
 
<message name="MOUNT_CONTROL" id="157">
<description>Message to control a camera mount, directional antenna, etc.</description>
<field name="target_system" type="uint8_t">System ID</field>
<field name="target_component" type="uint8_t">Component ID</field>
<field name="input_a" type="int32_t">pitch(deg*100) or lat, depending on mount mode</field>
<field name="input_b" type="int32_t">roll(deg*100) or lon depending on mount mode</field>
<field name="input_c" type="int32_t">yaw(deg*100) or alt (in cm) depending on mount mode</field>
<field name="save_position" type="uint8_t">if "1" it will save current trimmed position on EEPROM (just valid for NEUTRAL and LANDING)</field>
</message>
 
<message name="MOUNT_STATUS" id="158">
<description>Message with some status from APM to GCS about camera or antenna mount</description>
<field name="target_system" type="uint8_t">System ID</field>
<field name="target_component" type="uint8_t">Component ID</field>
<field name="pointing_a" type="int32_t">pitch(deg*100) or lat, depending on mount mode</field>
<field name="pointing_b" type="int32_t">roll(deg*100) or lon depending on mount mode</field>
<field name="pointing_c" type="int32_t">yaw(deg*100) or alt (in cm) depending on mount mode</field>
</message>
 
<!-- geo-fence messages -->
<message name="FENCE_POINT" id="160">
<description>A fence point. Used to set a point when from
GCS -> MAV. Also used to return a point from MAV -> GCS</description>
<field name="target_system" type="uint8_t">System ID</field>
<field name="target_component" type="uint8_t">Component ID</field>
<field name="idx" type="uint8_t">point index (first point is 1, 0 is for return point)</field>
<field name="count" type="uint8_t">total number of points (for sanity checking)</field>
<field name="lat" type="float">Latitude of point</field>
<field name="lng" type="float">Longitude of point</field>
</message>
 
<message name="FENCE_FETCH_POINT" id="161">
<description>Request a current fence point from MAV</description>
<field name="target_system" type="uint8_t">System ID</field>
<field name="target_component" type="uint8_t">Component ID</field>
<field name="idx" type="uint8_t">point index (first point is 1, 0 is for return point)</field>
</message>
 
<message name="FENCE_STATUS" id="162">
<description>Status of geo-fencing. Sent in extended
status stream when fencing enabled</description>
<field name="breach_status" type="uint8_t">0 if currently inside fence, 1 if outside</field>
<field name="breach_count" type="uint16_t">number of fence breaches</field>
<field name="breach_type" type="uint8_t">last breach type (see FENCE_BREACH_* enum)</field>
<field name="breach_time" type="uint32_t">time of last breach in milliseconds since boot</field>
</message>
 
<message name="AHRS" id="163">
<description>Status of DCM attitude estimator</description>
<field type="float" name="omegaIx">X gyro drift estimate rad/s</field>
<field type="float" name="omegaIy">Y gyro drift estimate rad/s</field>
<field type="float" name="omegaIz">Z gyro drift estimate rad/s</field>
<field type="float" name="accel_weight">average accel_weight</field>
<field type="float" name="renorm_val">average renormalisation value</field>
<field type="float" name="error_rp">average error_roll_pitch value</field>
<field type="float" name="error_yaw">average error_yaw value</field>
</message>
 
<message name="SIMSTATE" id="164">
<description>Status of simulation environment, if used</description>
<field type="float" name="roll">Roll angle (rad)</field>
<field type="float" name="pitch">Pitch angle (rad)</field>
<field type="float" name="yaw">Yaw angle (rad)</field>
<field type="float" name="xacc">X acceleration m/s/s</field>
<field type="float" name="yacc">Y acceleration m/s/s</field>
<field type="float" name="zacc">Z acceleration m/s/s</field>
<field type="float" name="xgyro">Angular speed around X axis rad/s</field>
<field type="float" name="ygyro">Angular speed around Y axis rad/s</field>
<field type="float" name="zgyro">Angular speed around Z axis rad/s</field>
</message>
 
<message name="HWSTATUS" id="165">
<description>Status of key hardware</description>
<field type="uint16_t" name="Vcc">board voltage (mV)</field>
<field type="uint8_t" name="I2Cerr">I2C error count</field>
</message>
 
<message name="RADIO" id="166">
<description>Status generated by radio</description>
<field type="uint8_t" name="rssi">local signal strength</field>
<field type="uint8_t" name="remrssi">remote signal strength</field>
<field type="uint8_t" name="txbuf">how full the tx buffer is as a percentage</field>
<field type="uint8_t" name="noise">background noise level</field>
<field type="uint8_t" name="remnoise">remote background noise level</field>
<field type="uint16_t" name="rxerrors">receive errors</field>
<field type="uint16_t" name="fixed">count of error corrected packets</field>
</message>
</messages>
</mavlink>
/C-OSD/arducam-osd/libraries/GCS_MAVLink/message_definitions_v1.0/common.xml
0,0 → 1,1531
<?xml version='1.0'?>
<mavlink>
<version>3</version>
<enums>
<enum name="MAV_AUTOPILOT">
<description>Micro air vehicle / autopilot classes. This identifies the individual model.</description>
<entry value="0" name="MAV_AUTOPILOT_GENERIC">
<description>Generic autopilot, full support for everything</description>
</entry>
<entry value="1" name="MAV_AUTOPILOT_PIXHAWK">
<description>PIXHAWK autopilot, http://pixhawk.ethz.ch</description>
</entry>
<entry value="2" name="MAV_AUTOPILOT_SLUGS">
<description>SLUGS autopilot, http://slugsuav.soe.ucsc.edu</description>
</entry>
<entry value="3" name="MAV_AUTOPILOT_ARDUPILOTMEGA">
<description>ArduPilotMega / ArduCopter, http://diydrones.com</description>
</entry>
<entry value="4" name="MAV_AUTOPILOT_OPENPILOT">
<description>OpenPilot, http://openpilot.org</description>
</entry>
<entry value="5" name="MAV_AUTOPILOT_GENERIC_WAYPOINTS_ONLY">
<description>Generic autopilot only supporting simple waypoints</description>
</entry>
<entry value="6" name="MAV_AUTOPILOT_GENERIC_WAYPOINTS_AND_SIMPLE_NAVIGATION_ONLY">
<description>Generic autopilot supporting waypoints and other simple navigation commands</description>
</entry>
<entry value="7" name="MAV_AUTOPILOT_GENERIC_MISSION_FULL">
<description>Generic autopilot supporting the full mission command set</description>
</entry>
<entry value="8" name="MAV_AUTOPILOT_INVALID">
<description>No valid autopilot, e.g. a GCS or other MAVLink component</description>
</entry>
<entry value="9" name="MAV_AUTOPILOT_PPZ">
<description>PPZ UAV - http://nongnu.org/paparazzi</description>
</entry>
<entry value="10" name="MAV_AUTOPILOT_UDB">
<description>UAV Dev Board</description>
</entry>
<entry value="11" name="MAV_AUTOPILOT_FP">
<description>FlexiPilot</description>
</entry>
</enum>
<enum name="MAV_TYPE">
<entry value="0" name="MAV_TYPE_GENERIC">
<description>Generic micro air vehicle.</description>
</entry>
<entry value="1" name="MAV_TYPE_FIXED_WING">
<description>Fixed wing aircraft.</description>
</entry>
<entry value="2" name="MAV_TYPE_QUADROTOR">
<description>Quadrotor</description>
</entry>
<entry value="3" name="MAV_TYPE_COAXIAL">
<description>Coaxial helicopter</description>
</entry>
<entry value="4" name="MAV_TYPE_HELICOPTER">
<description>Normal helicopter with tail rotor.</description>
</entry>
<entry value="5" name="MAV_TYPE_ANTENNA_TRACKER">
<description>Ground installation</description>
</entry>
<entry value="6" name="MAV_TYPE_GCS">
<description>Operator control unit / ground control station</description>
</entry>
<entry value="7" name="MAV_TYPE_AIRSHIP">
<description>Airship, controlled</description>
</entry>
<entry value="8" name="MAV_TYPE_FREE_BALLOON">
<description>Free balloon, uncontrolled</description>
</entry>
<entry value="9" name="MAV_TYPE_ROCKET">
<description>Rocket</description>
</entry>
<entry value="10" name="MAV_TYPE_GROUND_ROVER">
<description>Ground rover</description>
</entry>
<entry value="11" name="MAV_TYPE_SURFACE_BOAT">
<description>Surface vessel, boat, ship</description>
</entry>
<entry value="12" name="MAV_TYPE_SUBMARINE">
<description>Submarine</description>
</entry>
<entry value="13" name="MAV_TYPE_HEXAROTOR">
<description>Hexarotor</description>
</entry>
<entry value="14" name="MAV_TYPE_OCTOROTOR">
<description>Octorotor</description>
</entry>
<entry value="15" name="MAV_TYPE_TRICOPTER">
<description>Octorotor</description>
</entry>
<entry value="16" name="MAV_TYPE_FLAPPING_WING">
<description>Flapping wing</description>
</entry>
</enum>
<!-- WARNING: MAV_ACTION Enum is no longer supported - has been removed. Please use MAV_CMD -->
<enum name="MAV_MODE_FLAG">
<description>These flags encode the MAV mode.</description>
<entry value="128" name="MAV_MODE_FLAG_SAFETY_ARMED">
<description>0b10000000 MAV safety set to armed. Motors are enabled / running / can start. Ready to fly.</description>
</entry>
<entry value="64" name="MAV_MODE_FLAG_MANUAL_INPUT_ENABLED">
<description>0b01000000 remote control input is enabled.</description>
</entry>
<entry value="32" name="MAV_MODE_FLAG_HIL_ENABLED">
<description>0b00100000 hardware in the loop simulation. All motors / actuators are blocked, but internal software is full operational.</description>
</entry>
<entry value="16" name="MAV_MODE_FLAG_STABILIZE_ENABLED">
<description>0b00010000 system stabilizes electronically its attitude (and optionally position). It needs however further control inputs to move around.</description>
</entry>
<entry value="8" name="MAV_MODE_FLAG_GUIDED_ENABLED">
<description>0b00001000 guided mode enabled, system flies MISSIONs / mission items.</description>
</entry>
<entry value="4" name="MAV_MODE_FLAG_AUTO_ENABLED">
<description>0b00000100 autonomous mode enabled, system finds its own goal positions. Guided flag can be set or not, depends on the actual implementation.</description>
</entry>
<entry value="2" name="MAV_MODE_FLAG_TEST_ENABLED">
<description>0b00000010 system has a test mode enabled. This flag is intended for temporary system tests and should not be used for stable implementations.</description>
</entry>
<entry value="1" name="MAV_MODE_FLAG_CUSTOM_MODE_ENABLED">
<description>0b00000001 Reserved for future use.</description>
</entry>
</enum>
<enum name="MAV_MODE_FLAG_DECODE_POSITION">
<description>These values encode the bit positions of the decode position. These values can be used to read the value of a flag bit by combining the base_mode variable with AND with the flag position value. The result will be either 0 or 1, depending on if the flag is set or not.</description>
<entry value="128" name="MAV_MODE_FLAG_DECODE_POSITION_SAFETY">
<description>First bit: 10000000</description>
</entry>
<entry value="64" name="MAV_MODE_FLAG_DECODE_POSITION_MANUAL">
<description>Second bit: 01000000</description>
</entry>
<entry value="32" name="MAV_MODE_FLAG_DECODE_POSITION_HIL">
<description>Third bit: 00100000</description>
</entry>
<entry value="16" name="MAV_MODE_FLAG_DECODE_POSITION_STABILIZE">
<description>Fourth bit: 00010000</description>
</entry>
<entry value="8" name="MAV_MODE_FLAG_DECODE_POSITION_GUIDED">
<description>Fifth bit: 00001000</description>
</entry>
<entry value="4" name="MAV_MODE_FLAG_DECODE_POSITION_AUTO">
<description>Sixt bit: 00000100</description>
</entry>
<entry value="2" name="MAV_MODE_FLAG_DECODE_POSITION_TEST">
<description>Seventh bit: 00000010</description>
</entry>
<entry value="1" name="MAV_MODE_FLAG_DECODE_POSITION_CUSTOM_MODE">
<description>Eighth bit: 00000001</description>
</entry>
</enum>
<enum name="MAV_GOTO">
<description>Override command, pauses current mission execution and moves immediately to a position</description>
<entry value="0" name="MAV_GOTO_DO_HOLD">
<description>Hold at the current position.</description>
</entry>
<entry value="1" name="MAV_GOTO_DO_CONTINUE">
<description>Continue with the next item in mission execution.</description>
</entry>
<entry value="2" name="MAV_GOTO_HOLD_AT_CURRENT_POSITION">
<description>Hold at the current position of the system</description>
</entry>
<entry value="3" name="MAV_GOTO_HOLD_AT_SPECIFIED_POSITION">
<description>Hold at the position specified in the parameters of the DO_HOLD action</description>
</entry>
</enum>
<enum name="MAV_MODE">
<description>These defines are predefined OR-combined mode flags. There is no need to use values from this enum, but it
simplifies the use of the mode flags. Note that manual input is enabled in all modes as a safety override.</description>
<entry value="0" name="MAV_MODE_PREFLIGHT">
<description>System is not ready to fly, booting, calibrating, etc. No flag is set.</description>
</entry>
<entry value="80" name="MAV_MODE_STABILIZE_DISARMED">
<description>System is allowed to be active, under assisted RC control.</description>
</entry>
<entry value="208" name="MAV_MODE_STABILIZE_ARMED">
<description>System is allowed to be active, under assisted RC control.</description>
</entry>
<entry value="64" name="MAV_MODE_MANUAL_DISARMED">
<description>System is allowed to be active, under manual (RC) control, no stabilization</description>
</entry>
<entry value="192" name="MAV_MODE_MANUAL_ARMED">
<description>System is allowed to be active, under manual (RC) control, no stabilization</description>
</entry>
<entry value="88" name="MAV_MODE_GUIDED_DISARMED">
<description>System is allowed to be active, under autonomous control, manual setpoint</description>
</entry>
<entry value="216" name="MAV_MODE_GUIDED_ARMED">
<description>System is allowed to be active, under autonomous control, manual setpoint</description>
</entry>
<entry value="92" name="MAV_MODE_AUTO_DISARMED">
<description>System is allowed to be active, under autonomous control and navigation (the trajectory is decided onboard and not pre-programmed by MISSIONs)</description>
</entry>
<entry value="220" name="MAV_MODE_AUTO_ARMED">
<description>System is allowed to be active, under autonomous control and navigation (the trajectory is decided onboard and not pre-programmed by MISSIONs)</description>
</entry>
<entry value="66" name="MAV_MODE_TEST_DISARMED">
<description>UNDEFINED mode. This solely depends on the autopilot - use with caution, intended for developers only.</description>
</entry>
<entry value="194" name="MAV_MODE_TEST_ARMED">
<description>UNDEFINED mode. This solely depends on the autopilot - use with caution, intended for developers only.</description>
</entry>
</enum>
<enum name="MAV_STATE">
<entry value="0" name="MAV_STATE_UNINIT">
<description>Uninitialized system, state is unknown.</description>
</entry>
<entry name="MAV_STATE_BOOT">
<description>System is booting up.</description>
</entry>
<entry name="MAV_STATE_CALIBRATING">
<description>System is calibrating and not flight-ready.</description>
</entry>
<entry name="MAV_STATE_STANDBY">
<description>System is grounded and on standby. It can be launched any time.</description>
</entry>
<entry name="MAV_STATE_ACTIVE">
<description>System is active and might be already airborne. Motors are engaged.</description>
</entry>
<entry name="MAV_STATE_CRITICAL">
<description>System is in a non-normal flight mode. It can however still navigate.</description>
</entry>
<entry name="MAV_STATE_EMERGENCY">
<description>System is in a non-normal flight mode. It lost control over parts or over the whole airframe. It is in mayday and going down.</description>
</entry>
<entry name="MAV_STATE_POWEROFF">
<description>System just initialized its power-down sequence, will shut down now.</description>
</entry>
</enum>
<enum name="MAV_COMPONENT">
<entry value="0" name="MAV_COMP_ID_ALL">
<description/>
</entry>
<entry value="220" name="MAV_COMP_ID_GPS">
<description/>
</entry>
<entry value="190" name="MAV_COMP_ID_MISSIONPLANNER">
<description/>
</entry>
<entry value="195" name="MAV_COMP_ID_PATHPLANNER">
<description/>
</entry>
<entry value="180" name="MAV_COMP_ID_MAPPER">
<description/>
</entry>
<entry value="100" name="MAV_COMP_ID_CAMERA">
<description/>
</entry>
<entry value="200" name="MAV_COMP_ID_IMU">
<description/>
</entry>
<entry value="201" name="MAV_COMP_ID_IMU_2">
<description/>
</entry>
<entry value="202" name="MAV_COMP_ID_IMU_3">
<description/>
</entry>
<entry value="240" name="MAV_COMP_ID_UDP_BRIDGE">
<description/>
</entry>
<entry value="241" name="MAV_COMP_ID_UART_BRIDGE">
<description/>
</entry>
<entry value="250" name="MAV_COMP_ID_SYSTEM_CONTROL">
<description/>
</entry>
<entry value="140" name="MAV_COMP_ID_SERVO1">
<description/>
</entry>
<entry value="141" name="MAV_COMP_ID_SERVO2">
<description/>
</entry>
<entry value="142" name="MAV_COMP_ID_SERVO3">
<description/>
</entry>
<entry value="143" name="MAV_COMP_ID_SERVO4">
<description/>
</entry>
<entry value="144" name="MAV_COMP_ID_SERVO5">
<description/>
</entry>
<entry value="145" name="MAV_COMP_ID_SERVO6">
<description/>
</entry>
<entry value="146" name="MAV_COMP_ID_SERVO7">
<description/>
</entry>
<entry value="147" name="MAV_COMP_ID_SERVO8">
<description/>
</entry>
<entry value="148" name="MAV_COMP_ID_SERVO9">
<description/>
</entry>
<entry value="149" name="MAV_COMP_ID_SERVO10">
<description/>
</entry>
<entry value="150" name="MAV_COMP_ID_SERVO11">
<description/>
</entry>
<entry value="151" name="MAV_COMP_ID_SERVO12">
<description/>
</entry>
<entry value="152" name="MAV_COMP_ID_SERVO13">
<description/>
</entry>
<entry value="153" name="MAV_COMP_ID_SERVO14">
<description/>
</entry>
</enum>
<enum name="MAV_FRAME">
<entry value="0" name="MAV_FRAME_GLOBAL">
<description>Global coordinate frame, WGS84 coordinate system. First value / x: latitude, second value / y: longitude, third value / z: positive altitude over mean sea level (MSL)</description>
</entry>
<entry value="1" name="MAV_FRAME_LOCAL_NED">
<description>Local coordinate frame, Z-up (x: north, y: east, z: down).</description>
</entry>
<entry value="2" name="MAV_FRAME_MISSION">
<description>NOT a coordinate frame, indicates a mission command.</description>
</entry>
<entry value="3" name="MAV_FRAME_GLOBAL_RELATIVE_ALT">
<description>Global coordinate frame, WGS84 coordinate system, relative altitude over ground with respect to the home position. First value / x: latitude, second value / y: longitude, third value / z: positive altitude with 0 being at the altitude of the home location.</description>
</entry>
<entry value="4" name="MAV_FRAME_LOCAL_ENU">
<description>Local coordinate frame, Z-down (x: east, y: north, z: up)</description>
</entry>
</enum>
<enum name="MAVLINK_DATA_STREAM_TYPE">
<entry name="MAVLINK_DATA_STREAM_IMG_JPEG">
<description/>
</entry>
<entry name="MAVLINK_DATA_STREAM_IMG_BMP">
<description/>
</entry>
<entry name="MAVLINK_DATA_STREAM_IMG_RAW8U">
<description/>
</entry>
<entry name="MAVLINK_DATA_STREAM_IMG_RAW32U">
<description/>
</entry>
<entry name="MAVLINK_DATA_STREAM_IMG_PGM">
<description/>
</entry>
<entry name="MAVLINK_DATA_STREAM_IMG_PNG">
<description/>
</entry>
</enum>
<enum name="MAV_CMD">
<description>Commands to be executed by the MAV. They can be executed on user request, or as part of a mission script. If the action is used in a mission, the parameter mapping to the waypoint/mission message is as follows: Param 1, Param 2, Param 3, Param 4, X: Param 5, Y:Param 6, Z:Param 7. This command list is similar what ARINC 424 is for commercial aircraft: A data format how to interpret waypoint/mission data.</description>
<entry value="16" name="MAV_CMD_NAV_WAYPOINT">
<description>Navigate to MISSION.</description>
<param index="1">Hold time in decimal seconds. (ignored by fixed wing, time to stay at MISSION for rotary wing)</param>
<param index="2">Acceptance radius in meters (if the sphere with this radius is hit, the MISSION counts as reached)</param>
<param index="3">0 to pass through the WP, if > 0 radius in meters to pass by WP. Positive value for clockwise orbit, negative value for counter-clockwise orbit. Allows trajectory control.</param>
<param index="4">Desired yaw angle at MISSION (rotary wing)</param>
<param index="5">Latitude</param>
<param index="6">Longitude</param>
<param index="7">Altitude</param>
</entry>
<entry value="17" name="MAV_CMD_NAV_LOITER_UNLIM">
<description>Loiter around this MISSION an unlimited amount of time</description>
<param index="1">Empty</param>
<param index="2">Empty</param>
<param index="3">Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise</param>
<param index="4">Desired yaw angle.</param>
<param index="5">Latitude</param>
<param index="6">Longitude</param>
<param index="7">Altitude</param>
</entry>
<entry value="18" name="MAV_CMD_NAV_LOITER_TURNS">
<description>Loiter around this MISSION for X turns</description>
<param index="1">Turns</param>
<param index="2">Empty</param>
<param index="3">Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise</param>
<param index="4">Desired yaw angle.</param>
<param index="5">Latitude</param>
<param index="6">Longitude</param>
<param index="7">Altitude</param>
</entry>
<entry value="19" name="MAV_CMD_NAV_LOITER_TIME">
<description>Loiter around this MISSION for X seconds</description>
<param index="1">Seconds (decimal)</param>
<param index="2">Empty</param>
<param index="3">Radius around MISSION, in meters. If positive loiter clockwise, else counter-clockwise</param>
<param index="4">Desired yaw angle.</param>
<param index="5">Latitude</param>
<param index="6">Longitude</param>
<param index="7">Altitude</param>
</entry>
<entry value="20" name="MAV_CMD_NAV_RETURN_TO_LAUNCH">
<description>Return to launch location</description>
<param index="1">Empty</param>
<param index="2">Empty</param>
<param index="3">Empty</param>
<param index="4">Empty</param>
<param index="5">Empty</param>
<param index="6">Empty</param>
<param index="7">Empty</param>
</entry>
<entry value="21" name="MAV_CMD_NAV_LAND">
<description>Land at location</description>
<param index="1">Empty</param>
<param index="2">Empty</param>
<param index="3">Empty</param>
<param index="4">Desired yaw angle.</param>
<param index="5">Latitude</param>
<param index="6">Longitude</param>
<param index="7">Altitude</param>
</entry>
<entry value="22" name="MAV_CMD_NAV_TAKEOFF">
<description>Takeoff from ground / hand</description>
<param index="1">Minimum pitch (if airspeed sensor present), desired pitch without sensor</param>
<param index="2">Empty</param>
<param index="3">Empty</param>
<param index="4">Yaw angle (if magnetometer present), ignored without magnetometer</param>
<param index="5">Latitude</param>
<param index="6">Longitude</param>
<param index="7">Altitude</param>
</entry>
<entry value="80" name="MAV_CMD_NAV_ROI">
<description>Sets the region of interest (ROI) for a sensor set or the vehicle itself. This can then be used by the vehicles control system to control the vehicle attitude and the attitude of various sensors such as cameras.</description>
<param index="1">Region of intereset mode. (see MAV_ROI enum)</param>
<param index="2">MISSION index/ target ID. (see MAV_ROI enum)</param>
<param index="3">ROI index (allows a vehicle to manage multiple ROI's)</param>
<param index="4">Empty</param>
<param index="5">x the location of the fixed ROI (see MAV_FRAME)</param>
<param index="6">y</param>
<param index="7">z</param>
</entry>
<entry value="81" name="MAV_CMD_NAV_PATHPLANNING">
<description>Control autonomous path planning on the MAV.</description>
<param index="1">0: Disable local obstacle avoidance / local path planning (without resetting map), 1: Enable local path planning, 2: Enable and reset local path planning</param>
<param index="2">0: Disable full path planning (without resetting map), 1: Enable, 2: Enable and reset map/occupancy grid, 3: Enable and reset planned route, but not occupancy grid</param>
<param index="3">Empty</param>
<param index="4">Yaw angle at goal, in compass degrees, [0..360]</param>
<param index="5">Latitude/X of goal</param>
<param index="6">Longitude/Y of goal</param>
<param index="7">Altitude/Z of goal</param>
</entry>
<entry value="95" name="MAV_CMD_NAV_LAST">
<description>NOP - This command is only used to mark the upper limit of the NAV/ACTION commands in the enumeration</description>
<param index="1">Empty</param>
<param index="2">Empty</param>
<param index="3">Empty</param>
<param index="4">Empty</param>
<param index="5">Empty</param>
<param index="6">Empty</param>
<param index="7">Empty</param>
</entry>
<entry value="112" name="MAV_CMD_CONDITION_DELAY">
<description>Delay mission state machine.</description>
<param index="1">Delay in seconds (decimal)</param>
<param index="2">Empty</param>
<param index="3">Empty</param>
<param index="4">Empty</param>
<param index="5">Empty</param>
<param index="6">Empty</param>
<param index="7">Empty</param>
</entry>
<entry value="113" name="MAV_CMD_CONDITION_CHANGE_ALT">
<description>Ascend/descend at rate. Delay mission state machine until desired altitude reached.</description>
<param index="1">Descent / Ascend rate (m/s)</param>
<param index="2">Empty</param>
<param index="3">Empty</param>
<param index="4">Empty</param>
<param index="5">Empty</param>
<param index="6">Empty</param>
<param index="7">Finish Altitude</param>
</entry>
<entry value="114" name="MAV_CMD_CONDITION_DISTANCE">
<description>Delay mission state machine until within desired distance of next NAV point.</description>
<param index="1">Distance (meters)</param>
<param index="2">Empty</param>
<param index="3">Empty</param>
<param index="4">Empty</param>
<param index="5">Empty</param>
<param index="6">Empty</param>
<param index="7">Empty</param>
</entry>
<entry value="115" name="MAV_CMD_CONDITION_YAW">
<description>Reach a certain target angle.</description>
<param index="1">target angle: [0-360], 0 is north</param>
<param index="2">speed during yaw change:[deg per second]</param>
<param index="3">direction: negative: counter clockwise, positive: clockwise [-1,1]</param>
<param index="4">relative offset or absolute angle: [ 1,0]</param>
<param index="5">Empty</param>
<param index="6">Empty</param>
<param index="7">Empty</param>
</entry>
<entry value="159" name="MAV_CMD_CONDITION_LAST">
<description>NOP - This command is only used to mark the upper limit of the CONDITION commands in the enumeration</description>
<param index="1">Empty</param>
<param index="2">Empty</param>
<param index="3">Empty</param>
<param index="4">Empty</param>
<param index="5">Empty</param>
<param index="6">Empty</param>
<param index="7">Empty</param>
</entry>
<entry value="176" name="MAV_CMD_DO_SET_MODE">
<description>Set system mode.</description>
<param index="1">Mode, as defined by ENUM MAV_MODE</param>
<param index="2">Empty</param>
<param index="3">Empty</param>
<param index="4">Empty</param>
<param index="5">Empty</param>
<param index="6">Empty</param>
<param index="7">Empty</param>
</entry>
<entry value="177" name="MAV_CMD_DO_JUMP">
<description>Jump to the desired command in the mission list. Repeat this action only the specified number of times</description>
<param index="1">Sequence number</param>
<param index="2">Repeat count</param>
<param index="3">Empty</param>
<param index="4">Empty</param>
<param index="5">Empty</param>
<param index="6">Empty</param>
<param index="7">Empty</param>
</entry>
<entry value="178" name="MAV_CMD_DO_CHANGE_SPEED">
<description>Change speed and/or throttle set points.</description>
<param index="1">Speed type (0=Airspeed, 1=Ground Speed)</param>
<param index="2">Speed (m/s, -1 indicates no change)</param>
<param index="3">Throttle ( Percent, -1 indicates no change)</param>
<param index="4">Empty</param>
<param index="5">Empty</param>
<param index="6">Empty</param>
<param index="7">Empty</param>
</entry>
<entry value="179" name="MAV_CMD_DO_SET_HOME">
<description>Changes the home location either to the current location or a specified location.</description>
<param index="1">Use current (1=use current location, 0=use specified location)</param>
<param index="2">Empty</param>
<param index="3">Empty</param>
<param index="4">Empty</param>
<param index="5">Latitude</param>
<param index="6">Longitude</param>
<param index="7">Altitude</param>
</entry>
<entry value="180" name="MAV_CMD_DO_SET_PARAMETER">
<description>Set a system parameter. Caution! Use of this command requires knowledge of the numeric enumeration value of the parameter.</description>
<param index="1">Parameter number</param>
<param index="2">Parameter value</param>
<param index="3">Empty</param>
<param index="4">Empty</param>
<param index="5">Empty</param>
<param index="6">Empty</param>
<param index="7">Empty</param>
</entry>
<entry value="181" name="MAV_CMD_DO_SET_RELAY">
<description>Set a relay to a condition.</description>
<param index="1">Relay number</param>
<param index="2">Setting (1=on, 0=off, others possible depending on system hardware)</param>
<param index="3">Empty</param>
<param index="4">Empty</param>
<param index="5">Empty</param>
<param index="6">Empty</param>
<param index="7">Empty</param>
</entry>
<entry value="182" name="MAV_CMD_DO_REPEAT_RELAY">
<description>Cycle a relay on and off for a desired number of cyles with a desired period.</description>
<param index="1">Relay number</param>
<param index="2">Cycle count</param>
<param index="3">Cycle time (seconds, decimal)</param>
<param index="4">Empty</param>
<param index="5">Empty</param>
<param index="6">Empty</param>
<param index="7">Empty</param>
</entry>
<entry value="183" name="MAV_CMD_DO_SET_SERVO">
<description>Set a servo to a desired PWM value.</description>
<param index="1">Servo number</param>
<param index="2">PWM (microseconds, 1000 to 2000 typical)</param>
<param index="3">Empty</param>
<param index="4">Empty</param>
<param index="5">Empty</param>
<param index="6">Empty</param>
<param index="7">Empty</param>
</entry>
<entry value="184" name="MAV_CMD_DO_REPEAT_SERVO">
<description>Cycle a between its nominal setting and a desired PWM for a desired number of cycles with a desired period.</description>
<param index="1">Servo number</param>
<param index="2">PWM (microseconds, 1000 to 2000 typical)</param>
<param index="3">Cycle count</param>
<param index="4">Cycle time (seconds)</param>
<param index="5">Empty</param>
<param index="6">Empty</param>
<param index="7">Empty</param>
</entry>
<entry value="200" name="MAV_CMD_DO_CONTROL_VIDEO">
<description>Control onboard camera system.</description>
<param index="1">Camera ID (-1 for all)</param>
<param index="2">Transmission: 0: disabled, 1: enabled compressed, 2: enabled raw</param>
<param index="3">Transmission mode: 0: video stream, >0: single images every n seconds (decimal)</param>
<param index="4">Recording: 0: disabled, 1: enabled compressed, 2: enabled raw</param>
<param index="5">Empty</param>
<param index="6">Empty</param>
<param index="7">Empty</param>
</entry>
<entry value="240" name="MAV_CMD_DO_LAST">
<description>NOP - This command is only used to mark the upper limit of the DO commands in the enumeration</description>
<param index="1">Empty</param>
<param index="2">Empty</param>
<param index="3">Empty</param>
<param index="4">Empty</param>
<param index="5">Empty</param>
<param index="6">Empty</param>
<param index="7">Empty</param>
</entry>
<entry value="241" name="MAV_CMD_PREFLIGHT_CALIBRATION">
<description>Trigger calibration. This command will be only accepted if in pre-flight mode.</description>
<param index="1">Gyro calibration: 0: no, 1: yes</param>
<param index="2">Magnetometer calibration: 0: no, 1: yes</param>
<param index="3">Ground pressure: 0: no, 1: yes</param>
<param index="4">Radio calibration: 0: no, 1: yes</param>
<param index="5">Empty</param>
<param index="6">Empty</param>
<param index="7">Empty</param>
</entry>
<entry value="242" name="MAV_CMD_PREFLIGHT_SET_SENSOR_OFFSETS">
<description>Set sensor offsets. This command will be only accepted if in pre-flight mode.</description>
<param index="1">Sensor to adjust the offsets for: 0: gyros, 1: accelerometer, 2: magnetometer, 3: barometer, 4: optical flow</param>
<param index="2">X axis offset (or generic dimension 1), in the sensor's raw units</param>
<param index="3">Y axis offset (or generic dimension 2), in the sensor's raw units</param>
<param index="4">Z axis offset (or generic dimension 3), in the sensor's raw units</param>
<param index="5">Generic dimension 4, in the sensor's raw units</param>
<param index="6">Generic dimension 5, in the sensor's raw units</param>
<param index="7">Generic dimension 6, in the sensor's raw units</param>
</entry>
<entry value="245" name="MAV_CMD_PREFLIGHT_STORAGE">
<description>Request storage of different parameter values and logs. This command will be only accepted if in pre-flight mode.</description>
<param index="1">Parameter storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM</param>
<param index="2">Mission storage: 0: READ FROM FLASH/EEPROM, 1: WRITE CURRENT TO FLASH/EEPROM</param>
<param index="3">Reserved</param>
<param index="4">Reserved</param>
<param index="5">Empty</param>
<param index="6">Empty</param>
<param index="7">Empty</param>
</entry>
<entry value="246" name="MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN">
<description>Request the reboot or shutdown of system components.</description>
<param index="1">0: Do nothing for autopilot, 1: Reboot autopilot, 2: Shutdown autopilot.</param>
<param index="2">0: Do nothing for onboard computer, 1: Reboot onboard computer, 2: Shutdown onboard computer.</param>
<param index="3">Reserved</param>
<param index="4">Reserved</param>
<param index="5">Empty</param>
<param index="6">Empty</param>
<param index="7">Empty</param>
</entry>
<entry value="252" name="MAV_CMD_OVERRIDE_GOTO">
<description>Hold / continue the current action</description>
<param index="1">MAV_GOTO_DO_HOLD: hold MAV_GOTO_DO_CONTINUE: continue with next item in mission plan</param>
<param index="2">MAV_GOTO_HOLD_AT_CURRENT_POSITION: Hold at current position MAV_GOTO_HOLD_AT_SPECIFIED_POSITION: hold at specified position</param>
<param index="3">MAV_FRAME coordinate frame of hold point</param>
<param index="4">Desired yaw angle in degrees</param>
<param index="5">Latitude / X position</param>
<param index="6">Longitude / Y position</param>
<param index="7">Altitude / Z position</param>
</entry>
<entry value="300" name="MAV_CMD_MISSION_START">
<description>start running a mission</description>
<param index="1">first_item: the first mission item to run</param>
<param index="2">last_item: the last mission item to run (after this item is run, the mission ends)</param>
</entry>
<entry value="400" name="MAV_CMD_COMPONENT_ARM_DISARM">
<description>Arms / Disarms a component</description>
<param index="1">1 to arm, 0 to disarm</param>
</entry>
</enum>
<enum name="MAV_DATA_STREAM">
<description>Data stream IDs. A data stream is not a fixed set of messages, but rather a
recommendation to the autopilot software. Individual autopilots may or may not obey
the recommended messages.</description>
<entry value="0" name="MAV_DATA_STREAM_ALL">
<description>Enable all data streams</description>
</entry>
<entry value="1" name="MAV_DATA_STREAM_RAW_SENSORS">
<description>Enable IMU_RAW, GPS_RAW, GPS_STATUS packets.</description>
</entry>
<entry value="2" name="MAV_DATA_STREAM_EXTENDED_STATUS">
<description>Enable GPS_STATUS, CONTROL_STATUS, AUX_STATUS</description>
</entry>
<entry value="3" name="MAV_DATA_STREAM_RC_CHANNELS">
<description>Enable RC_CHANNELS_SCALED, RC_CHANNELS_RAW, SERVO_OUTPUT_RAW</description>
</entry>
<entry value="4" name="MAV_DATA_STREAM_RAW_CONTROLLER">
<description>Enable ATTITUDE_CONTROLLER_OUTPUT, POSITION_CONTROLLER_OUTPUT, NAV_CONTROLLER_OUTPUT.</description>
</entry>
<entry value="6" name="MAV_DATA_STREAM_POSITION">
<description>Enable LOCAL_POSITION, GLOBAL_POSITION/GLOBAL_POSITION_INT messages.</description>
</entry>
<entry value="10" name="MAV_DATA_STREAM_EXTRA1">
<description>Dependent on the autopilot</description>
</entry>
<entry value="11" name="MAV_DATA_STREAM_EXTRA2">
<description>Dependent on the autopilot</description>
</entry>
<entry value="12" name="MAV_DATA_STREAM_EXTRA3">
<description>Dependent on the autopilot</description>
</entry>
</enum>
<enum name="MAV_ROI">
<description> The ROI (region of interest) for the vehicle. This can be
be used by the vehicle for camera/vehicle attitude alignment (see
MAV_CMD_NAV_ROI).</description>
<entry value="0" name="MAV_ROI_NONE">
<description>No region of interest.</description>
</entry>
<entry value="1" name="MAV_ROI_WPNEXT">
<description>Point toward next MISSION.</description>
</entry>
<entry value="2" name="MAV_ROI_WPINDEX">
<description>Point toward given MISSION.</description>
</entry>
<entry value="3" name="MAV_ROI_LOCATION">
<description>Point toward fixed location.</description>
</entry>
<entry value="4" name="MAV_ROI_TARGET">
<description>Point toward of given id.</description>
</entry>
</enum>
<enum name="MAV_CMD_ACK">
<description>ACK / NACK / ERROR values as a result of MAV_CMDs and for mission item transmission.</description>
<entry name="MAV_CMD_ACK_OK">
<description>Command / mission item is ok.</description>
</entry>
<entry name="MAV_CMD_ACK_ERR_FAIL">
<description>Generic error message if none of the other reasons fails or if no detailed error reporting is implemented.</description>
</entry>
<entry name="MAV_CMD_ACK_ERR_ACCESS_DENIED">
<description>The system is refusing to accept this command from this source / communication partner.</description>
</entry>
<entry name="MAV_CMD_ACK_ERR_NOT_SUPPORTED">
<description>Command or mission item is not supported, other commands would be accepted.</description>
</entry>
<entry name="MAV_CMD_ACK_ERR_COORDINATE_FRAME_NOT_SUPPORTED">
<description>The coordinate frame of this command / mission item is not supported.</description>
</entry>
<entry name="MAV_CMD_ACK_ERR_COORDINATES_OUT_OF_RANGE">
<description>The coordinate frame of this command is ok, but he coordinate values exceed the safety limits of this system. This is a generic error, please use the more specific error messages below if possible.</description>
</entry>
<entry name="MAV_CMD_ACK_ERR_X_LAT_OUT_OF_RANGE">
<description>The X or latitude value is out of range.</description>
</entry>
<entry name="MAV_CMD_ACK_ERR_Y_LON_OUT_OF_RANGE">
<description>The Y or longitude value is out of range.</description>
</entry>
<entry name="MAV_CMD_ACK_ERR_Z_ALT_OUT_OF_RANGE">
<description>The Z or altitude value is out of range.</description>
</entry>
</enum>
<enum name="MAV_VAR">
<description>type of a mavlink parameter</description>
<entry value="0" name="MAV_VAR_FLOAT">
<description>32 bit float</description>
</entry>
<entry value="1" name="MAV_VAR_UINT8">
<description>8 bit unsigned integer</description>
</entry>
<entry value="2" name="MAV_VAR_INT8">
<description>8 bit signed integer</description>
</entry>
<entry value="3" name="MAV_VAR_UINT16">
<description>16 bit unsigned integer</description>
</entry>
<entry value="4" name="MAV_VAR_INT16">
<description>16 bit signed integer</description>
</entry>
<entry value="5" name="MAV_VAR_UINT32">
<description>32 bit unsigned integer</description>
</entry>
<entry value="6" name="MAV_VAR_INT32">
<description>32 bit signed integer</description>
</entry>
</enum>
<enum name="MAV_RESULT">
<description>result from a mavlink command</description>
<entry value="0" name="MAV_RESULT_ACCEPTED">
<description>Command ACCEPTED and EXECUTED</description>
</entry>
<entry value="1" name="MAV_RESULT_TEMPORARILY_REJECTED">
<description>Command TEMPORARY REJECTED/DENIED</description>
</entry>
<entry value="2" name="MAV_RESULT_DENIED">
<description>Command PERMANENTLY DENIED</description>
</entry>
<entry value="3" name="MAV_RESULT_UNSUPPORTED">
<description>Command UNKNOWN/UNSUPPORTED</description>
</entry>
<entry value="4" name="MAV_RESULT_FAILED">
<description>Command executed, but failed</description>
</entry>
</enum>
<enum name="MAV_MISSION_RESULT">
<description>result in a mavlink mission ack</description>
<entry value="0" name="MAV_MISSION_ACCEPTED">
<description>mission accepted OK</description>
</entry>
<entry value="1" name="MAV_MISSION_ERROR">
<description>generic error / not accepting mission commands at all right now</description>
</entry>
<entry value="2" name="MAV_MISSION_UNSUPPORTED_FRAME">
<description>coordinate frame is not supported</description>
</entry>
<entry value="3" name="MAV_MISSION_UNSUPPORTED">
<description>command is not supported</description>
</entry>
<entry value="4" name="MAV_MISSION_NO_SPACE">
<description>mission item exceeds storage space</description>
</entry>
<entry value="5" name="MAV_MISSION_INVALID">
<description>one of the parameters has an invalid value</description>
</entry>
<entry value="6" name="MAV_MISSION_INVALID_PARAM1">
<description>param1 has an invalid value</description>
</entry>
<entry value="7" name="MAV_MISSION_INVALID_PARAM2">
<description>param2 has an invalid value</description>
</entry>
<entry value="8" name="MAV_MISSION_INVALID_PARAM3">
<description>param3 has an invalid value</description>
</entry>
<entry value="9" name="MAV_MISSION_INVALID_PARAM4">
<description>param4 has an invalid value</description>
</entry>
<entry value="10" name="MAV_MISSION_INVALID_PARAM5_X">
<description>x/param5 has an invalid value</description>
</entry>
<entry value="11" name="MAV_MISSION_INVALID_PARAM6_Y">
<description>y/param6 has an invalid value</description>
</entry>
<entry value="12" name="MAV_MISSION_INVALID_PARAM7">
<description>param7 has an invalid value</description>
</entry>
<entry value="13" name="MAV_MISSION_INVALID_SEQUENCE">
<description>received waypoint out of sequence</description>
</entry>
<entry value="14" name="MAV_MISSION_DENIED">
<description>not accepting any mission commands from this communication partner</description>
</entry>
</enum>
<enum name="MAV_SEVERITY">
<description>Indicates the severity level, generally used for status messages to indicate their relative urgency. Based on RFC-5424 using expanded definitions at: http://www.kiwisyslog.com/kb/info:-syslog-message-levels/.</description>
<entry value="0" name="MAV_SEVERITY_EMERGENCY">
<description>System is unusable. This is a "panic" condition.</description>
</entry>
<entry value="1" name="MAV_SEVERITY_ALERT">
<description>Action should be taken immediately. Indicates error in non-critical systems.</description>
</entry>
<entry value="2" name="MAV_SEVERITY_CRITICAL">
<description>Action must be taken immediately. Indicates failure in a primary system.</description>
</entry>
<entry value="3" name="MAV_SEVERITY_ERROR">
<description>Indicates an error in secondary/redundant systems.</description>
</entry>
<entry value="4" name="MAV_SEVERITY_WARNING">
<description>Indicates about a possible future error if this is not resolved within a given timeframe. Example would be a low battery warning.</description>
</entry>
<entry value="5" name="MAV_SEVERITY_NOTICE">
<description>An unusual event has occured, though not an error condition. This should be investigated for the root cause.</description>
</entry>
<entry value="6" name="MAV_SEVERITY_INFO">
<description>Normal operational messages. Useful for logging. No action is required for these messages.</description>
</entry>
<entry value="7" name="MAV_SEVERITY_DEBUG">
<description>Useful non-operational messages that can assist in debugging. These should not occur during normal operation.</description>
</entry>
</enum>
</enums>
<messages>
<message id="0" name="HEARTBEAT">
<description>The heartbeat message shows that a system is present and responding. The type of the MAV and Autopilot hardware allow the receiving system to treat further messages from this system appropriate (e.g. by laying out the user interface based on the autopilot).</description>
<field type="uint8_t" name="type">Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM)</field>
<field type="uint8_t" name="autopilot">Autopilot type / class. defined in MAV_AUTOPILOT ENUM</field>
<field type="uint8_t" name="base_mode">System mode bitfield, see MAV_MODE_FLAGS ENUM in mavlink/include/mavlink_types.h</field>
<field type="uint32_t" name="custom_mode">A bitfield for use for autopilot-specific flags.</field>
<field type="uint8_t" name="system_status">System status flag, see MAV_STATE ENUM</field>
<field type="uint8_t_mavlink_version" name="mavlink_version">MAVLink version, not writable by user, gets added by protocol because of magic data type: uint8_t_mavlink_version</field>
</message>
<message id="1" name="SYS_STATUS">
<description>The general system state. If the system is following the MAVLink standard, the system state is mainly defined by three orthogonal states/modes: The system mode, which is either LOCKED (motors shut down and locked), MANUAL (system under RC control), GUIDED (system with autonomous position control, position setpoint controlled manually) or AUTO (system guided by path/waypoint planner). The NAV_MODE defined the current flight state: LIFTOFF (often an open-loop maneuver), LANDING, WAYPOINTS or VECTOR. This represents the internal navigation state machine. The system status shows wether the system is currently active or not and if an emergency occured. During the CRITICAL and EMERGENCY states the MAV is still considered to be active, but should start emergency procedures autonomously. After a failure occured it should first move from active to critical to allow manual intervention and then move to emergency after a certain timeout.</description>
<field type="uint32_t" name="onboard_control_sensors_present" print_format="0x%04x">Bitmask showing which onboard controllers and sensors are present. Value of 0: not present. Value of 1: present. Indices: 0: 3D gyro, 1: 3D acc, 2: 3D mag, 3: absolute pressure, 4: differential pressure, 5: GPS, 6: optical flow, 7: computer vision position, 8: laser based position, 9: external ground-truth (Vicon or Leica). Controllers: 10: 3D angular rate control 11: attitude stabilization, 12: yaw position, 13: z/altitude control, 14: x/y position control, 15: motor outputs / control</field>
<field type="uint32_t" name="onboard_control_sensors_enabled" print_format="0x%04x">Bitmask showing which onboard controllers and sensors are enabled: Value of 0: not enabled. Value of 1: enabled. Indices: 0: 3D gyro, 1: 3D acc, 2: 3D mag, 3: absolute pressure, 4: differential pressure, 5: GPS, 6: optical flow, 7: computer vision position, 8: laser based position, 9: external ground-truth (Vicon or Leica). Controllers: 10: 3D angular rate control 11: attitude stabilization, 12: yaw position, 13: z/altitude control, 14: x/y position control, 15: motor outputs / control</field>
<field type="uint32_t" name="onboard_control_sensors_health" print_format="0x%04x">Bitmask showing which onboard controllers and sensors are operational or have an error: Value of 0: not enabled. Value of 1: enabled. Indices: 0: 3D gyro, 1: 3D acc, 2: 3D mag, 3: absolute pressure, 4: differential pressure, 5: GPS, 6: optical flow, 7: computer vision position, 8: laser based position, 9: external ground-truth (Vicon or Leica). Controllers: 10: 3D angular rate control 11: attitude stabilization, 12: yaw position, 13: z/altitude control, 14: x/y position control, 15: motor outputs / control</field>
<field type="uint16_t" name="load">Maximum usage in percent of the mainloop time, (0%: 0, 100%: 1000) should be always below 1000</field>
<field type="uint16_t" name="voltage_battery">Battery voltage, in millivolts (1 = 1 millivolt)</field>
<field type="int16_t" name="current_battery">Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current</field>
<field type="int8_t" name="battery_remaining">Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot estimate the remaining battery</field>
<field type="uint16_t" name="drop_rate_comm">Communication drops in percent, (0%: 0, 100%: 10'000), (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV)</field>
<field type="uint16_t" name="errors_comm">Communication errors (UART, I2C, SPI, CAN), dropped packets on all links (packets that were corrupted on reception on the MAV)</field>
<field type="uint16_t" name="errors_count1">Autopilot-specific errors</field>
<field type="uint16_t" name="errors_count2">Autopilot-specific errors</field>
<field type="uint16_t" name="errors_count3">Autopilot-specific errors</field>
<field type="uint16_t" name="errors_count4">Autopilot-specific errors</field>
</message>
<message id="2" name="SYSTEM_TIME">
<description>The system time is the time of the master clock, typically the computer clock of the main onboard computer.</description>
<field type="uint64_t" name="time_unix_usec">Timestamp of the master clock in microseconds since UNIX epoch.</field>
<field type="uint32_t" name="time_boot_ms">Timestamp of the component clock since boot time in milliseconds.</field>
</message>
<!-- FIXME to be removed / merged with SYSTEM_TIME -->
<message id="4" name="PING">
<description>A ping message either requesting or responding to a ping. This allows to measure the system latencies, including serial port, radio modem and UDP connections.</description>
<field type="uint64_t" name="time_usec">Unix timestamp in microseconds</field>
<field type="uint32_t" name="seq">PING sequence</field>
<field type="uint8_t" name="target_system">0: request ping from all receiving systems, if greater than 0: message is a ping response and number is the system id of the requesting system</field>
<field type="uint8_t" name="target_component">0: request ping from all receiving components, if greater than 0: message is a ping response and number is the system id of the requesting system</field>
</message>
<message id="5" name="CHANGE_OPERATOR_CONTROL">
<description>Request to control this MAV</description>
<field type="uint8_t" name="target_system">System the GCS requests control for</field>
<field type="uint8_t" name="control_request">0: request control of this MAV, 1: Release control of this MAV</field>
<field type="uint8_t" name="version">0: key as plaintext, 1-255: future, different hashing/encryption variants. The GCS should in general use the safest mode possible initially and then gradually move down the encryption level if it gets a NACK message indicating an encryption mismatch.</field>
<field type="char[25]" name="passkey">Password / Key, depending on version plaintext or encrypted. 25 or less characters, NULL terminated. The characters may involve A-Z, a-z, 0-9, and "!?,.-"</field>
</message>
<message id="6" name="CHANGE_OPERATOR_CONTROL_ACK">
<description>Accept / deny control of this MAV</description>
<field type="uint8_t" name="gcs_system_id">ID of the GCS this message </field>
<field type="uint8_t" name="control_request">0: request control of this MAV, 1: Release control of this MAV</field>
<field type="uint8_t" name="ack">0: ACK, 1: NACK: Wrong passkey, 2: NACK: Unsupported passkey encryption method, 3: NACK: Already under control</field>
</message>
<message id="7" name="AUTH_KEY">
<description>Emit an encrypted signature / key identifying this system. PLEASE NOTE: This protocol has been kept simple, so transmitting the key requires an encrypted channel for true safety.</description>
<field type="char[32]" name="key">key</field>
</message>
<message id="11" name="SET_MODE">
<description>Set the system mode, as defined by enum MAV_MODE. There is no target component id as the mode is by definition for the overall aircraft, not only for one component.</description>
<field type="uint8_t" name="target_system">The system setting the mode</field>
<field type="uint8_t" name="base_mode">The new base mode</field>
<field type="uint32_t" name="custom_mode">The new autopilot-specific mode. This field can be ignored by an autopilot.</field>
</message>
<message id="20" name="PARAM_REQUEST_READ">
<description>Request to read the onboard parameter with the param_id string id. Onboard parameters are stored as key[const char*] -> value[float]. This allows to send a parameter to any other component (such as the GCS) without the need of previous knowledge of possible parameter names. Thus the same GCS can store different parameters for different autopilots. See also http://qgroundcontrol.org/parameter_interface for a full documentation of QGroundControl and IMU code.</description>
<field type="uint8_t" name="target_system">System ID</field>
<field type="uint8_t" name="target_component">Component ID</field>
<field type="char[16]" name="param_id">Onboard parameter id</field>
<field type="int16_t" name="param_index">Parameter index. Send -1 to use the param ID field as identifier</field>
</message>
<message id="21" name="PARAM_REQUEST_LIST">
<description>Request all parameters of this component. After his request, all parameters are emitted.</description>
<field type="uint8_t" name="target_system">System ID</field>
<field type="uint8_t" name="target_component">Component ID</field>
</message>
<message id="22" name="PARAM_VALUE">
<description>Emit the value of a onboard parameter. The inclusion of param_count and param_index in the message allows the recipient to keep track of received parameters and allows him to re-request missing parameters after a loss or timeout.</description>
<field type="char[16]" name="param_id">Onboard parameter id</field>
<field type="float" name="param_value">Onboard parameter value</field>
<field type="uint8_t" name="param_type">Onboard parameter type: see MAV_VAR enum</field>
<field type="uint16_t" name="param_count">Total number of onboard parameters</field>
<field type="uint16_t" name="param_index">Index of this onboard parameter</field>
</message>
<message id="23" name="PARAM_SET">
<description>Set a parameter value TEMPORARILY to RAM. It will be reset to default on system reboot. Send the ACTION MAV_ACTION_STORAGE_WRITE to PERMANENTLY write the RAM contents to EEPROM. IMPORTANT: The receiving component should acknowledge the new parameter value by sending a param_value message to all communication partners. This will also ensure that multiple GCS all have an up-to-date list of all parameters. If the sending GCS did not receive a PARAM_VALUE message within its timeout time, it should re-send the PARAM_SET message.</description>
<field type="uint8_t" name="target_system">System ID</field>
<field type="uint8_t" name="target_component">Component ID</field>
<field type="char[16]" name="param_id">Onboard parameter id</field>
<field type="float" name="param_value">Onboard parameter value</field>
<field type="uint8_t" name="param_type">Onboard parameter type: see MAV_VAR enum</field>
</message>
<message id="24" name="GPS_RAW_INT">
<description>The global position, as returned by the Global Positioning System (GPS). This is
NOT the global position estimate of the sytem, but rather a RAW sensor value. See message GLOBAL_POSITION for the global position estimate. Coordinate frame is right-handed, Z-axis up (GPS frame).</description>
<field type="uint64_t" name="time_usec">Timestamp (microseconds since UNIX epoch or microseconds since system boot)</field>
<field type="uint8_t" name="fix_type">0-1: no fix, 2: 2D fix, 3: 3D fix. Some applications will not use the value of this field unless it is at least two, so always correctly fill in the fix.</field>
<field type="int32_t" name="lat">Latitude in 1E7 degrees</field>
<field type="int32_t" name="lon">Longitude in 1E7 degrees</field>
<field type="int32_t" name="alt">Altitude in 1E3 meters (millimeters) above MSL</field>
<field type="uint16_t" name="eph">GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535</field>
<field type="uint16_t" name="epv">GPS VDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535</field>
<field type="uint16_t" name="vel">GPS ground speed (m/s * 100). If unknown, set to: 65535</field>
<field type="uint16_t" name="cog">Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535</field>
<field type="uint8_t" name="satellites_visible">Number of satellites visible. If unknown, set to 255</field>
</message>
<message id="25" name="GPS_STATUS">
<description>The positioning status, as reported by GPS. This message is intended to display status information about each satellite visible to the receiver. See message GLOBAL_POSITION for the global position estimate. This message can contain information for up to 20 satellites.</description>
<field type="uint8_t" name="satellites_visible">Number of satellites visible</field>
<field type="uint8_t[20]" name="satellite_prn">Global satellite ID</field>
<field type="uint8_t[20]" name="satellite_used">0: Satellite not used, 1: used for localization</field>
<field type="uint8_t[20]" name="satellite_elevation">Elevation (0: right on top of receiver, 90: on the horizon) of satellite</field>
<field type="uint8_t[20]" name="satellite_azimuth">Direction of satellite, 0: 0 deg, 255: 360 deg.</field>
<field type="uint8_t[20]" name="satellite_snr">Signal to noise ratio of satellite</field>
</message>
<message id="26" name="SCALED_IMU">
<description>The RAW IMU readings for the usual 9DOF sensor setup. This message should contain the scaled values to the described units</description>
<field type="uint32_t" name="time_boot_ms">Timestamp (milliseconds since system boot)</field>
<field type="int16_t" name="xacc">X acceleration (mg)</field>
<field type="int16_t" name="yacc">Y acceleration (mg)</field>
<field type="int16_t" name="zacc">Z acceleration (mg)</field>
<field type="int16_t" name="xgyro">Angular speed around X axis (millirad /sec)</field>
<field type="int16_t" name="ygyro">Angular speed around Y axis (millirad /sec)</field>
<field type="int16_t" name="zgyro">Angular speed around Z axis (millirad /sec)</field>
<field type="int16_t" name="xmag">X Magnetic field (milli tesla)</field>
<field type="int16_t" name="ymag">Y Magnetic field (milli tesla)</field>
<field type="int16_t" name="zmag">Z Magnetic field (milli tesla)</field>
</message>
<message id="27" name="RAW_IMU">
<description>The RAW IMU readings for the usual 9DOF sensor setup. This message should always contain the true raw values without any scaling to allow data capture and system debugging.</description>
<field type="uint64_t" name="time_usec">Timestamp (microseconds since UNIX epoch or microseconds since system boot)</field>
<field type="int16_t" name="xacc">X acceleration (raw)</field>
<field type="int16_t" name="yacc">Y acceleration (raw)</field>
<field type="int16_t" name="zacc">Z acceleration (raw)</field>
<field type="int16_t" name="xgyro">Angular speed around X axis (raw)</field>
<field type="int16_t" name="ygyro">Angular speed around Y axis (raw)</field>
<field type="int16_t" name="zgyro">Angular speed around Z axis (raw)</field>
<field type="int16_t" name="xmag">X Magnetic field (raw)</field>
<field type="int16_t" name="ymag">Y Magnetic field (raw)</field>
<field type="int16_t" name="zmag">Z Magnetic field (raw)</field>
</message>
<message id="28" name="RAW_PRESSURE">
<description>The RAW pressure readings for the typical setup of one absolute pressure and one differential pressure sensor. The sensor values should be the raw, UNSCALED ADC values.</description>
<field type="uint64_t" name="time_usec">Timestamp (microseconds since UNIX epoch or microseconds since system boot)</field>
<field type="int16_t" name="press_abs">Absolute pressure (raw)</field>
<field type="int16_t" name="press_diff1">Differential pressure 1 (raw)</field>
<field type="int16_t" name="press_diff2">Differential pressure 2 (raw)</field>
<field type="int16_t" name="temperature">Raw Temperature measurement (raw)</field>
</message>
<message id="29" name="SCALED_PRESSURE">
<description>The pressure readings for the typical setup of one absolute and differential pressure sensor. The units are as specified in each field.</description>
<field type="uint32_t" name="time_boot_ms">Timestamp (microseconds since UNIX epoch or microseconds since system boot)</field>
<field type="float" name="press_abs">Absolute pressure (hectopascal)</field>
<field type="float" name="press_diff">Differential pressure 1 (hectopascal)</field>
<field type="int16_t" name="temperature">Temperature measurement (0.01 degrees celsius)</field>
</message>
<message id="30" name="ATTITUDE">
<description>The attitude in the aeronautical frame (right-handed, Z-down, X-front, Y-right).</description>
<field type="uint32_t" name="time_boot_ms">Timestamp (milliseconds since system boot)</field>
<field type="float" name="roll">Roll angle (rad)</field>
<field type="float" name="pitch">Pitch angle (rad)</field>
<field type="float" name="yaw">Yaw angle (rad)</field>
<field type="float" name="rollspeed">Roll angular speed (rad/s)</field>
<field type="float" name="pitchspeed">Pitch angular speed (rad/s)</field>
<field type="float" name="yawspeed">Yaw angular speed (rad/s)</field>
</message>
<message id="31" name="ATTITUDE_QUATERNION">
<description>The attitude in the aeronautical frame (right-handed, Z-down, X-front, Y-right), expressed as quaternion.</description>
<field type="uint32_t" name="time_boot_ms">Timestamp (milliseconds since system boot)</field>
<field type="float" name="q1">Quaternion component 1</field>
<field type="float" name="q2">Quaternion component 2</field>
<field type="float" name="q3">Quaternion component 3</field>
<field type="float" name="q4">Quaternion component 4</field>
<field type="float" name="rollspeed">Roll angular speed (rad/s)</field>
<field type="float" name="pitchspeed">Pitch angular speed (rad/s)</field>
<field type="float" name="yawspeed">Yaw angular speed (rad/s)</field>
</message>
<message id="32" name="LOCAL_POSITION_NED">
<description>The filtered local position (e.g. fused computer vision and accelerometers). Coordinate frame is right-handed, Z-axis down (aeronautical frame, NED / north-east-down convention)</description>
<field type="uint32_t" name="time_boot_ms">Timestamp (milliseconds since system boot)</field>
<field type="float" name="x">X Position</field>
<field type="float" name="y">Y Position</field>
<field type="float" name="z">Z Position</field>
<field type="float" name="vx">X Speed</field>
<field type="float" name="vy">Y Speed</field>
<field type="float" name="vz">Z Speed</field>
</message>
<message id="33" name="GLOBAL_POSITION_INT">
<description>The filtered global position (e.g. fused GPS and accelerometers). The position is in GPS-frame (right-handed, Z-up). It
is designed as scaled integer message since the resolution of float is not sufficient.</description>
<field type="uint32_t" name="time_boot_ms">Timestamp (milliseconds since system boot)</field>
<field type="int32_t" name="lat">Latitude, expressed as * 1E7</field>
<field type="int32_t" name="lon">Longitude, expressed as * 1E7</field>
<field type="int32_t" name="alt">Altitude in meters, expressed as * 1000 (millimeters), above MSL</field>
<field type="int32_t" name="relative_alt">Altitude above ground in meters, expressed as * 1000 (millimeters)</field>
<field type="int16_t" name="vx">Ground X Speed (Latitude), expressed as m/s * 100</field>
<field type="int16_t" name="vy">Ground Y Speed (Longitude), expressed as m/s * 100</field>
<field type="int16_t" name="vz">Ground Z Speed (Altitude), expressed as m/s * 100</field>
<field type="uint16_t" name="hdg">Compass heading in degrees * 100, 0.0..359.99 degrees. If unknown, set to: 65535</field>
</message>
<message id="34" name="RC_CHANNELS_SCALED">
<description>The scaled values of the RC channels received. (-100%) -10000, (0%) 0, (100%) 10000</description>
<field type="uint32_t" name="time_boot_ms">Timestamp (milliseconds since system boot)</field>
<field type="uint8_t" name="port">Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos.</field>
<field type="int16_t" name="chan1_scaled">RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000</field>
<field type="int16_t" name="chan2_scaled">RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000</field>
<field type="int16_t" name="chan3_scaled">RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000</field>
<field type="int16_t" name="chan4_scaled">RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000</field>
<field type="int16_t" name="chan5_scaled">RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000</field>
<field type="int16_t" name="chan6_scaled">RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000</field>
<field type="int16_t" name="chan7_scaled">RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000</field>
<field type="int16_t" name="chan8_scaled">RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000</field>
<field type="uint8_t" name="rssi">Receive signal strength indicator, 0: 0%, 255: 100%</field>
</message>
<message id="35" name="RC_CHANNELS_RAW">
<description>The RAW values of the RC channels received. The standard PPM modulation is as follows: 1000 microseconds: 0%, 2000 microseconds: 100%. Individual receivers/transmitters might violate this specification.</description>
<field type="uint32_t" name="time_boot_ms">Timestamp (milliseconds since system boot)</field>
<field type="uint8_t" name="port">Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos.</field>
<field type="uint16_t" name="chan1_raw">RC channel 1 value, in microseconds</field>
<field type="uint16_t" name="chan2_raw">RC channel 2 value, in microseconds</field>
<field type="uint16_t" name="chan3_raw">RC channel 3 value, in microseconds</field>
<field type="uint16_t" name="chan4_raw">RC channel 4 value, in microseconds</field>
<field type="uint16_t" name="chan5_raw">RC channel 5 value, in microseconds</field>
<field type="uint16_t" name="chan6_raw">RC channel 6 value, in microseconds</field>
<field type="uint16_t" name="chan7_raw">RC channel 7 value, in microseconds</field>
<field type="uint16_t" name="chan8_raw">RC channel 8 value, in microseconds</field>
<field type="uint8_t" name="rssi">Receive signal strength indicator, 0: 0%, 255: 100%</field>
</message>
<message id="36" name="SERVO_OUTPUT_RAW">
<description>The RAW values of the servo outputs (for RC input from the remote, use the RC_CHANNELS messages). The standard PPM modulation is as follows: 1000 microseconds: 0%, 2000 microseconds: 100%.</description>
<field type="uint32_t" name="time_usec">Timestamp (since UNIX epoch or microseconds since system boot)</field>
<field type="uint8_t" name="port">Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos.</field>
<field type="uint16_t" name="servo1_raw">Servo output 1 value, in microseconds</field>
<field type="uint16_t" name="servo2_raw">Servo output 2 value, in microseconds</field>
<field type="uint16_t" name="servo3_raw">Servo output 3 value, in microseconds</field>
<field type="uint16_t" name="servo4_raw">Servo output 4 value, in microseconds</field>
<field type="uint16_t" name="servo5_raw">Servo output 5 value, in microseconds</field>
<field type="uint16_t" name="servo6_raw">Servo output 6 value, in microseconds</field>
<field type="uint16_t" name="servo7_raw">Servo output 7 value, in microseconds</field>
<field type="uint16_t" name="servo8_raw">Servo output 8 value, in microseconds</field>
</message>
<message id="37" name="MISSION_REQUEST_PARTIAL_LIST">
<description>Request the overall list of MISSIONs from the system/component. http://qgroundcontrol.org/mavlink/waypoint_protocol</description>
<field type="uint8_t" name="target_system">System ID</field>
<field type="uint8_t" name="target_component">Component ID</field>
<field type="int16_t" name="start_index">Start index, 0 by default</field>
<field type="int16_t" name="end_index">End index, -1 by default (-1: send list to end). Else a valid index of the list</field>
</message>
<message id="38" name="MISSION_WRITE_PARTIAL_LIST">
<description>This message is sent to the MAV to write a partial list. If start index == end index, only one item will be transmitted / updated. If the start index is NOT 0 and above the current list size, this request should be REJECTED!</description>
<field type="uint8_t" name="target_system">System ID</field>
<field type="uint8_t" name="target_component">Component ID</field>
<field type="int16_t" name="start_index">Start index, 0 by default and smaller / equal to the largest index of the current onboard list.</field>
<field type="int16_t" name="end_index">End index, equal or greater than start index.</field>
</message>
<message id="39" name="MISSION_ITEM">
<description>Message encoding a mission item. This message is emitted to announce
the presence of a mission item and to set a mission item on the system. The mission item can be either in x, y, z meters (type: LOCAL) or x:lat, y:lon, z:altitude. Local frame is Z-down, right handed (NED), global frame is Z-up, right handed (ENU). See also http://qgroundcontrol.org/mavlink/waypoint_protocol.</description>
<field type="uint8_t" name="target_system">System ID</field>
<field type="uint8_t" name="target_component">Component ID</field>
<field type="uint16_t" name="seq">Sequence</field>
<field type="uint8_t" name="frame">The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h</field>
<field type="uint16_t" name="command">The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs</field>
<field type="uint8_t" name="current">false:0, true:1</field>
<field type="uint8_t" name="autocontinue">autocontinue to next wp</field>
<field type="float" name="param1">PARAM1 / For NAV command MISSIONs: Radius in which the MISSION is accepted as reached, in meters</field>
<field type="float" name="param2">PARAM2 / For NAV command MISSIONs: Time that the MAV should stay inside the PARAM1 radius before advancing, in milliseconds</field>
<field type="float" name="param3">PARAM3 / For LOITER command MISSIONs: Orbit to circle around the MISSION, in meters. If positive the orbit direction should be clockwise, if negative the orbit direction should be counter-clockwise.</field>
<field type="float" name="param4">PARAM4 / For NAV and LOITER command MISSIONs: Yaw orientation in degrees, [0..360] 0 = NORTH</field>
<field type="float" name="x">PARAM5 / local: x position, global: latitude</field>
<field type="float" name="y">PARAM6 / y position: global: longitude</field>
<field type="float" name="z">PARAM7 / z position: global: altitude</field>
</message>
<message id="40" name="MISSION_REQUEST">
<description>Request the information of the mission item with the sequence number seq. The response of the system to this message should be a MISSION_ITEM message. http://qgroundcontrol.org/mavlink/waypoint_protocol</description>
<field type="uint8_t" name="target_system">System ID</field>
<field type="uint8_t" name="target_component">Component ID</field>
<field type="uint16_t" name="seq">Sequence</field>
</message>
<message id="41" name="MISSION_SET_CURRENT">
<description>Set the mission item with sequence number seq as current item. This means that the MAV will continue to this mission item on the shortest path (not following the mission items in-between).</description>
<field type="uint8_t" name="target_system">System ID</field>
<field type="uint8_t" name="target_component">Component ID</field>
<field type="uint16_t" name="seq">Sequence</field>
</message>
<message id="42" name="MISSION_CURRENT">
<description>Message that announces the sequence number of the current active mission item. The MAV will fly towards this mission item.</description>
<field type="uint16_t" name="seq">Sequence</field>
</message>
<message id="43" name="MISSION_REQUEST_LIST">
<description>Request the overall list of mission items from the system/component.</description>
<field type="uint8_t" name="target_system">System ID</field>
<field type="uint8_t" name="target_component">Component ID</field>
</message>
<message id="44" name="MISSION_COUNT">
<description>This message is emitted as response to MISSION_REQUEST_LIST by the MAV and to initiate a write transaction. The GCS can then request the individual mission item based on the knowledge of the total number of MISSIONs.</description>
<field type="uint8_t" name="target_system">System ID</field>
<field type="uint8_t" name="target_component">Component ID</field>
<field type="uint16_t" name="count">Number of mission items in the sequence</field>
</message>
<message id="45" name="MISSION_CLEAR_ALL">
<description>Delete all mission items at once.</description>
<field type="uint8_t" name="target_system">System ID</field>
<field type="uint8_t" name="target_component">Component ID</field>
</message>
<message id="46" name="MISSION_ITEM_REACHED">
<description>A certain mission item has been reached. The system will either hold this position (or circle on the orbit) or (if the autocontinue on the WP was set) continue to the next MISSION.</description>
<field type="uint16_t" name="seq">Sequence</field>
</message>
<message id="47" name="MISSION_ACK">
<description>Ack message during MISSION handling. The type field states if this message is a positive ack (type=0) or if an error happened (type=non-zero).</description>
<field type="uint8_t" name="target_system">System ID</field>
<field type="uint8_t" name="target_component">Component ID</field>
<field type="uint8_t" name="type">See MAV_MISSION_RESULT enum</field>
</message>
<message id="48" name="SET_GPS_GLOBAL_ORIGIN">
<description>As local MISSIONs exist, the global MISSION reference allows to transform between the local coordinate frame and the global (GPS) coordinate frame. This can be necessary when e.g. in- and outdoor settings are connected and the MAV should move from in- to outdoor.</description>
<field type="uint8_t" name="target_system">System ID</field>
<field type="int32_t" name="latitude">global position * 1E7</field>
<field type="int32_t" name="longitude">global position * 1E7</field>
<field type="int32_t" name="altitude">global position * 1000</field>
</message>
<message id="49" name="GPS_GLOBAL_ORIGIN">
<description>Once the MAV sets a new GPS-Local correspondence, this message announces the origin (0,0,0) position</description>
<field type="int32_t" name="latitude">Latitude (WGS84), expressed as * 1E7</field>
<field type="int32_t" name="longitude">Longitude (WGS84), expressed as * 1E7</field>
<field type="int32_t" name="altitude">Altitude(WGS84), expressed as * 1000</field>
</message>
<message id="50" name="SET_LOCAL_POSITION_SETPOINT">
<description>Set the setpoint for a local position controller. This is the position in local coordinates the MAV should fly to. This message is sent by the path/MISSION planner to the onboard position controller. As some MAVs have a degree of freedom in yaw (e.g. all helicopters/quadrotors), the desired yaw angle is part of the message.</description>
<field type="uint8_t" name="target_system">System ID</field>
<field type="uint8_t" name="target_component">Component ID</field>
<field type="uint8_t" name="coordinate_frame">Coordinate frame - valid values are only MAV_FRAME_LOCAL_NED or MAV_FRAME_LOCAL_ENU</field>
<field type="float" name="x">x position</field>
<field type="float" name="y">y position</field>
<field type="float" name="z">z position</field>
<field type="float" name="yaw">Desired yaw angle</field>
</message>
<message id="51" name="LOCAL_POSITION_SETPOINT">
<description>Transmit the current local setpoint of the controller to other MAVs (collision avoidance) and to the GCS.</description>
<field type="uint8_t" name="coordinate_frame">Coordinate frame - valid values are only MAV_FRAME_LOCAL_NED or MAV_FRAME_LOCAL_ENU</field>
<field type="float" name="x">x position</field>
<field type="float" name="y">y position</field>
<field type="float" name="z">z position</field>
<field type="float" name="yaw">Desired yaw angle</field>
</message>
<message id="52" name="GLOBAL_POSITION_SETPOINT_INT">
<description>Transmit the current local setpoint of the controller to other MAVs (collision avoidance) and to the GCS.</description>
<field type="uint8_t" name="coordinate_frame">Coordinate frame - valid values are only MAV_FRAME_GLOBAL or MAV_FRAME_GLOBAL_RELATIVE_ALT</field>
<field type="int32_t" name="latitude">WGS84 Latitude position in degrees * 1E7</field>
<field type="int32_t" name="longitude">WGS84 Longitude position in degrees * 1E7</field>
<field type="int32_t" name="altitude">WGS84 Altitude in meters * 1000 (positive for up)</field>
<field type="int16_t" name="yaw">Desired yaw angle in degrees * 100</field>
</message>
<message id="53" name="SET_GLOBAL_POSITION_SETPOINT_INT">
<description>Set the current global position setpoint.</description>
<field type="uint8_t" name="coordinate_frame">Coordinate frame - valid values are only MAV_FRAME_GLOBAL or MAV_FRAME_GLOBAL_RELATIVE_ALT</field>
<field type="int32_t" name="latitude">WGS84 Latitude position in degrees * 1E7</field>
<field type="int32_t" name="longitude">WGS84 Longitude position in degrees * 1E7</field>
<field type="int32_t" name="altitude">WGS84 Altitude in meters * 1000 (positive for up)</field>
<field type="int16_t" name="yaw">Desired yaw angle in degrees * 100</field>
</message>
<message id="54" name="SAFETY_SET_ALLOWED_AREA">
<description>Set a safety zone (volume), which is defined by two corners of a cube. This message can be used to tell the MAV which setpoints/MISSIONs to accept and which to reject. Safety areas are often enforced by national or competition regulations.</description>
<field type="uint8_t" name="target_system">System ID</field>
<field type="uint8_t" name="target_component">Component ID</field>
<field type="uint8_t" name="frame">Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down.</field>
<field type="float" name="p1x">x position 1 / Latitude 1</field>
<field type="float" name="p1y">y position 1 / Longitude 1</field>
<field type="float" name="p1z">z position 1 / Altitude 1</field>
<field type="float" name="p2x">x position 2 / Latitude 2</field>
<field type="float" name="p2y">y position 2 / Longitude 2</field>
<field type="float" name="p2z">z position 2 / Altitude 2</field>
</message>
<message id="55" name="SAFETY_ALLOWED_AREA">
<description>Read out the safety zone the MAV currently assumes.</description>
<field type="uint8_t" name="frame">Coordinate frame, as defined by MAV_FRAME enum in mavlink_types.h. Can be either global, GPS, right-handed with Z axis up or local, right handed, Z axis down.</field>
<field type="float" name="p1x">x position 1 / Latitude 1</field>
<field type="float" name="p1y">y position 1 / Longitude 1</field>
<field type="float" name="p1z">z position 1 / Altitude 1</field>
<field type="float" name="p2x">x position 2 / Latitude 2</field>
<field type="float" name="p2y">y position 2 / Longitude 2</field>
<field type="float" name="p2z">z position 2 / Altitude 2</field>
</message>
<message id="56" name="SET_ROLL_PITCH_YAW_THRUST">
<description>Set roll, pitch and yaw.</description>
<field type="uint8_t" name="target_system">System ID</field>
<field type="uint8_t" name="target_component">Component ID</field>
<field type="float" name="roll">Desired roll angle in radians</field>
<field type="float" name="pitch">Desired pitch angle in radians</field>
<field type="float" name="yaw">Desired yaw angle in radians</field>
<field type="float" name="thrust">Collective thrust, normalized to 0 .. 1</field>
</message>
<message id="57" name="SET_ROLL_PITCH_YAW_SPEED_THRUST">
<description>Set roll, pitch and yaw.</description>
<field type="uint8_t" name="target_system">System ID</field>
<field type="uint8_t" name="target_component">Component ID</field>
<field type="float" name="roll_speed">Desired roll angular speed in rad/s</field>
<field type="float" name="pitch_speed">Desired pitch angular speed in rad/s</field>
<field type="float" name="yaw_speed">Desired yaw angular speed in rad/s</field>
<field type="float" name="thrust">Collective thrust, normalized to 0 .. 1</field>
</message>
<message id="58" name="ROLL_PITCH_YAW_THRUST_SETPOINT">
<description>Setpoint in roll, pitch, yaw currently active on the system.</description>
<field type="uint32_t" name="time_boot_ms">Timestamp in milliseconds since system boot</field>
<field type="float" name="roll">Desired roll angle in radians</field>
<field type="float" name="pitch">Desired pitch angle in radians</field>
<field type="float" name="yaw">Desired yaw angle in radians</field>
<field type="float" name="thrust">Collective thrust, normalized to 0 .. 1</field>
</message>
<message id="59" name="ROLL_PITCH_YAW_SPEED_THRUST_SETPOINT">
<description>Setpoint in rollspeed, pitchspeed, yawspeed currently active on the system.</description>
<field type="uint32_t" name="time_boot_ms">Timestamp in milliseconds since system boot</field>
<field type="float" name="roll_speed">Desired roll angular speed in rad/s</field>
<field type="float" name="pitch_speed">Desired pitch angular speed in rad/s</field>
<field type="float" name="yaw_speed">Desired yaw angular speed in rad/s</field>
<field type="float" name="thrust">Collective thrust, normalized to 0 .. 1</field>
</message>
<message id="60" name="SET_QUAD_MOTORS_SETPOINT">
<description>Setpoint in the four motor speeds</description>
<field type="uint8_t" name="target_system">System ID of the system that should set these motor commands</field>
<field type="uint16_t" name="motor_front_nw">Front motor in + configuration, front left motor in x configuration</field>
<field type="uint16_t" name="motor_right_ne">Right motor in + configuration, front right motor in x configuration</field>
<field type="uint16_t" name="motor_back_se">Back motor in + configuration, back right motor in x configuration</field>
<field type="uint16_t" name="motor_left_sw">Left motor in + configuration, back left motor in x configuration</field>
</message>
<message id="61" name="SET_QUAD_SWARM_ROLL_PITCH_YAW_THRUST">
<description></description>
<field type="uint8_t[6]" name="target_systems">System IDs for 6 quadrotors: 0..5, the ID's are the MAVLink IDs</field>
<field type="int16_t[6]" name="roll">Desired roll angle in radians, scaled to int16 for 6 quadrotors: 0..5</field>
<field type="int16_t[6]" name="pitch">Desired pitch angle in radians, scaled to int16 for 6 quadrotors: 0..5</field>
<field type="int16_t[6]" name="yaw">Desired yaw angle in radians, scaled to int16 for 6 quadrotors: 0..5</field>
<field type="uint16_t[6]" name="thrust">Collective thrust, scaled to uint16 for 6 quadrotors: 0..5</field>
</message>
<message id="62" name="NAV_CONTROLLER_OUTPUT">
<description>Outputs of the APM navigation controller. The primary use of this message is to check the response and signs of the controller before actual flight and to assist with tuning controller parameters.</description>
<field type="float" name="nav_roll">Current desired roll in degrees</field>
<field type="float" name="nav_pitch">Current desired pitch in degrees</field>
<field type="int16_t" name="nav_bearing">Current desired heading in degrees</field>
<field type="int16_t" name="target_bearing">Bearing to current MISSION/target in degrees</field>
<field type="uint16_t" name="wp_dist">Distance to active MISSION in meters</field>
<field type="float" name="alt_error">Current altitude error in meters</field>
<field type="float" name="aspd_error">Current airspeed error in meters/second</field>
<field type="float" name="xtrack_error">Current crosstrack error on x-y plane in meters</field>
</message>
<message id="64" name="STATE_CORRECTION">
<description>Corrects the systems state by adding an error correction term to the position and velocity, and by rotating the attitude by a correction angle.</description>
<field type="float" name="xErr">x position error</field>
<field type="float" name="yErr">y position error</field>
<field type="float" name="zErr">z position error</field>
<field type="float" name="rollErr">roll error (radians)</field>
<field type="float" name="pitchErr">pitch error (radians)</field>
<field type="float" name="yawErr">yaw error (radians)</field>
<field type="float" name="vxErr">x velocity</field>
<field type="float" name="vyErr">y velocity</field>
<field type="float" name="vzErr">z velocity</field>
</message>
<message id="66" name="REQUEST_DATA_STREAM">
<field type="uint8_t" name="target_system">The target requested to send the message stream.</field>
<field type="uint8_t" name="target_component">The target requested to send the message stream.</field>
<field type="uint8_t" name="req_stream_id">The ID of the requested data stream</field>
<field type="uint16_t" name="req_message_rate">The requested interval between two messages of this type</field>
<field type="uint8_t" name="start_stop">1 to start sending, 0 to stop sending.</field>
</message>
<message id="67" name="DATA_STREAM">
<field type="uint8_t" name="stream_id">The ID of the requested data stream</field>
<field type="uint16_t" name="message_rate">The requested interval between two messages of this type</field>
<field type="uint8_t" name="on_off">1 stream is enabled, 0 stream is stopped.</field>
</message>
<message id="69" name="MANUAL_CONTROL">
<field type="uint8_t" name="target">The system to be controlled</field>
<field type="float" name="roll">roll</field>
<field type="float" name="pitch">pitch</field>
<field type="float" name="yaw">yaw</field>
<field type="float" name="thrust">thrust</field>
<field type="uint8_t" name="roll_manual">roll control enabled auto:0, manual:1</field>
<field type="uint8_t" name="pitch_manual">pitch auto:0, manual:1</field>
<field type="uint8_t" name="yaw_manual">yaw auto:0, manual:1</field>
<field type="uint8_t" name="thrust_manual">thrust auto:0, manual:1</field>
</message>
<message id="70" name="RC_CHANNELS_OVERRIDE">
<description>The RAW values of the RC channels sent to the MAV to override info received from the RC radio. A value of -1 means no change to that channel. A value of 0 means control of that channel should be released back to the RC radio. The standard PPM modulation is as follows: 1000 microseconds: 0%, 2000 microseconds: 100%. Individual receivers/transmitters might violate this specification.</description>
<field type="uint8_t" name="target_system">System ID</field>
<field type="uint8_t" name="target_component">Component ID</field>
<field type="uint16_t" name="chan1_raw">RC channel 1 value, in microseconds</field>
<field type="uint16_t" name="chan2_raw">RC channel 2 value, in microseconds</field>
<field type="uint16_t" name="chan3_raw">RC channel 3 value, in microseconds</field>
<field type="uint16_t" name="chan4_raw">RC channel 4 value, in microseconds</field>
<field type="uint16_t" name="chan5_raw">RC channel 5 value, in microseconds</field>
<field type="uint16_t" name="chan6_raw">RC channel 6 value, in microseconds</field>
<field type="uint16_t" name="chan7_raw">RC channel 7 value, in microseconds</field>
<field type="uint16_t" name="chan8_raw">RC channel 8 value, in microseconds</field>
</message>
<message id="74" name="VFR_HUD">
<description>Metrics typically displayed on a HUD for fixed wing aircraft</description>
<field type="float" name="airspeed">Current airspeed in m/s</field>
<field type="float" name="groundspeed">Current ground speed in m/s</field>
<field type="int16_t" name="heading">Current heading in degrees, in compass units (0..360, 0=north)</field>
<field type="uint16_t" name="throttle">Current throttle setting in integer percent, 0 to 100</field>
<field type="float" name="alt">Current altitude (MSL), in meters</field>
<field type="float" name="climb">Current climb rate in meters/second</field>
</message>
<message id="76" name="COMMAND_LONG">
<description>Send a command with up to four parameters to the MAV</description>
<field type="uint8_t" name="target_system">System which should execute the command</field>
<field type="uint8_t" name="target_component">Component which should execute the command, 0 for all components</field>
<field type="uint16_t" name="command">Command ID, as defined by MAV_CMD enum.</field>
<field type="uint8_t" name="confirmation">0: First transmission of this command. 1-255: Confirmation transmissions (e.g. for kill command)</field>
<field type="float" name="param1">Parameter 1, as defined by MAV_CMD enum.</field>
<field type="float" name="param2">Parameter 2, as defined by MAV_CMD enum.</field>
<field type="float" name="param3">Parameter 3, as defined by MAV_CMD enum.</field>
<field type="float" name="param4">Parameter 4, as defined by MAV_CMD enum.</field>
<field type="float" name="param5">Parameter 5, as defined by MAV_CMD enum.</field>
<field type="float" name="param6">Parameter 6, as defined by MAV_CMD enum.</field>
<field type="float" name="param7">Parameter 7, as defined by MAV_CMD enum.</field>
</message>
<message id="77" name="COMMAND_ACK">
<description>Report status of a command. Includes feedback wether the command was executed.</description>
<field type="uint16_t" name="command">Command ID, as defined by MAV_CMD enum.</field>
<field type="uint8_t" name="result">See MAV_RESULT enum</field>
</message>
<message id="89" name="LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET">
<description>The offset in X, Y, Z and yaw between the LOCAL_POSITION_NED messages of MAV X and the global coordinate frame in NED coordinates. Coordinate frame is right-handed, Z-axis down (aeronautical frame, NED / north-east-down convention)</description>
<field type="uint32_t" name="time_boot_ms">Timestamp (milliseconds since system boot)</field>
<field type="float" name="x">X Position</field>
<field type="float" name="y">Y Position</field>
<field type="float" name="z">Z Position</field>
<field type="float" name="roll">Roll</field>
<field type="float" name="pitch">Pitch</field>
<field type="float" name="yaw">Yaw</field>
</message>
<message id="90" name="HIL_STATE">
<description>Sent from simulation to autopilot. This packet is useful for high throughput applications such as hardware in the loop simulations.</description>
<field type="uint64_t" name="time_usec">Timestamp (microseconds since UNIX epoch or microseconds since system boot)</field>
<field type="float" name="roll">Roll angle (rad)</field>
<field type="float" name="pitch">Pitch angle (rad)</field>
<field type="float" name="yaw">Yaw angle (rad)</field>
<field type="float" name="rollspeed">Roll angular speed (rad/s)</field>
<field type="float" name="pitchspeed">Pitch angular speed (rad/s)</field>
<field type="float" name="yawspeed">Yaw angular speed (rad/s)</field>
<field type="int32_t" name="lat">Latitude, expressed as * 1E7</field>
<field type="int32_t" name="lon">Longitude, expressed as * 1E7</field>
<field type="int32_t" name="alt">Altitude in meters, expressed as * 1000 (millimeters)</field>
<field type="int16_t" name="vx">Ground X Speed (Latitude), expressed as m/s * 100</field>
<field type="int16_t" name="vy">Ground Y Speed (Longitude), expressed as m/s * 100</field>
<field type="int16_t" name="vz">Ground Z Speed (Altitude), expressed as m/s * 100</field>
<field type="int16_t" name="xacc">X acceleration (mg)</field>
<field type="int16_t" name="yacc">Y acceleration (mg)</field>
<field type="int16_t" name="zacc">Z acceleration (mg)</field>
</message>
<message id="91" name="HIL_CONTROLS">
<description>Sent from autopilot to simulation. Hardware in the loop control outputs</description>
<field name="time_usec" type="uint64_t">Timestamp (microseconds since UNIX epoch or microseconds since system boot)</field>
<field name="roll_ailerons" type="float">Control output -1 .. 1</field>
<field name="pitch_elevator" type="float">Control output -1 .. 1</field>
<field name="yaw_rudder" type="float">Control output -1 .. 1</field>
<field name="throttle" type="float">Throttle 0 .. 1</field>
<field name="aux1" type="float">Aux 1, -1 .. 1</field>
<field name="aux2" type="float">Aux 2, -1 .. 1</field>
<field name="aux3" type="float">Aux 3, -1 .. 1</field>
<field name="aux4" type="float">Aux 4, -1 .. 1</field>
<field name="mode" type="uint8_t">System mode (MAV_MODE)</field>
<field name="nav_mode" type="uint8_t">Navigation mode (MAV_NAV_MODE)</field>
</message>
<message id="92" name="HIL_RC_INPUTS_RAW">
<description>Sent from simulation to autopilot. The RAW values of the RC channels received. The standard PPM modulation is as follows: 1000 microseconds: 0%, 2000 microseconds: 100%. Individual receivers/transmitters might violate this specification.</description>
<field type="uint64_t" name="time_usec">Timestamp (microseconds since UNIX epoch or microseconds since system boot)</field>
<field type="uint16_t" name="chan1_raw">RC channel 1 value, in microseconds</field>
<field type="uint16_t" name="chan2_raw">RC channel 2 value, in microseconds</field>
<field type="uint16_t" name="chan3_raw">RC channel 3 value, in microseconds</field>
<field type="uint16_t" name="chan4_raw">RC channel 4 value, in microseconds</field>
<field type="uint16_t" name="chan5_raw">RC channel 5 value, in microseconds</field>
<field type="uint16_t" name="chan6_raw">RC channel 6 value, in microseconds</field>
<field type="uint16_t" name="chan7_raw">RC channel 7 value, in microseconds</field>
<field type="uint16_t" name="chan8_raw">RC channel 8 value, in microseconds</field>
<field type="uint16_t" name="chan9_raw">RC channel 9 value, in microseconds</field>
<field type="uint16_t" name="chan10_raw">RC channel 10 value, in microseconds</field>
<field type="uint16_t" name="chan11_raw">RC channel 11 value, in microseconds</field>
<field type="uint16_t" name="chan12_raw">RC channel 12 value, in microseconds</field>
<field type="uint8_t" name="rssi">Receive signal strength indicator, 0: 0%, 255: 100%</field>
</message>
<message id="100" name="OPTICAL_FLOW">
<description>Optical flow from a flow sensor (e.g. optical mouse sensor)</description>
<field type="uint64_t" name="time_usec">Timestamp (UNIX)</field>
<field type="uint8_t" name="sensor_id">Sensor ID</field>
<field type="int16_t" name="flow_x">Flow in pixels in x-sensor direction</field>
<field type="int16_t" name="flow_y">Flow in pixels in y-sensor direction</field>
<field type="float" name="flow_comp_m_x">Flow in meters in x-sensor direction, angular-speed compensated</field>
<field type="float" name="flow_comp_m_y">Flow in meters in y-sensor direction, angular-speed compensated</field>
<field type="uint8_t" name="quality">Optical flow quality / confidence. 0: bad, 255: maximum quality</field>
<field type="float" name="ground_distance">Ground distance in meters. Positive value: distance known. Negative value: Unknown distance</field>
</message>
<message id="101" name="GLOBAL_VISION_POSITION_ESTIMATE">
<field type="uint64_t" name="usec">Timestamp (milliseconds)</field>
<field type="float" name="x">Global X position</field>
<field type="float" name="y">Global Y position</field>
<field type="float" name="z">Global Z position</field>
<field type="float" name="roll">Roll angle in rad</field>
<field type="float" name="pitch">Pitch angle in rad</field>
<field type="float" name="yaw">Yaw angle in rad</field>
</message>
<message id="102" name="VISION_POSITION_ESTIMATE">
<field type="uint64_t" name="usec">Timestamp (milliseconds)</field>
<field type="float" name="x">Global X position</field>
<field type="float" name="y">Global Y position</field>
<field type="float" name="z">Global Z position</field>
<field type="float" name="roll">Roll angle in rad</field>
<field type="float" name="pitch">Pitch angle in rad</field>
<field type="float" name="yaw">Yaw angle in rad</field>
</message>
<message id="103" name="VISION_SPEED_ESTIMATE">
<field type="uint64_t" name="usec">Timestamp (milliseconds)</field>
<field type="float" name="x">Global X speed</field>
<field type="float" name="y">Global Y speed</field>
<field type="float" name="z">Global Z speed</field>
</message>
<message id="104" name="VICON_POSITION_ESTIMATE">
<field type="uint64_t" name="usec">Timestamp (milliseconds)</field>
<field type="float" name="x">Global X position</field>
<field type="float" name="y">Global Y position</field>
<field type="float" name="z">Global Z position</field>
<field type="float" name="roll">Roll angle in rad</field>
<field type="float" name="pitch">Pitch angle in rad</field>
<field type="float" name="yaw">Yaw angle in rad</field>
</message>
<!-- MESSAGE IDs 150 - 240: Space for custom messages in individual projectname_messages.xml files -->
<message id="249" name="MEMORY_VECT">
<description>Send raw controller memory. The use of this message is discouraged for normal packets, but a quite efficient way for testing new messages and getting experimental debug output.</description>
<field type="uint16_t" name="address">Starting address of the debug variables</field>
<field type="uint8_t" name="ver">Version code of the type variable. 0=unknown, type ignored and assumed int16_t. 1=as below</field>
<field type="uint8_t" name="type">Type code of the memory variables. for ver = 1: 0=16 x int16_t, 1=16 x uint16_t, 2=16 x Q15, 3=16 x 1Q14</field>
<field type="int8_t[32]" name="value">Memory contents at specified address</field>
</message>
<message id="250" name="DEBUG_VECT">
<field type="char[10]" name="name">Name</field>
<field type="uint64_t" name="time_usec">Timestamp</field>
<field type="float" name="x">x</field>
<field type="float" name="y">y</field>
<field type="float" name="z">z</field>
</message>
<message id="251" name="NAMED_VALUE_FLOAT">
<description>Send a key-value pair as float. The use of this message is discouraged for normal packets, but a quite efficient way for testing new messages and getting experimental debug output.</description>
<field type="uint32_t" name="time_boot_ms">Timestamp (milliseconds since system boot)</field>
<field type="char[10]" name="name">Name of the debug variable</field>
<field type="float" name="value">Floating point value</field>
</message>
<message id="252" name="NAMED_VALUE_INT">
<description>Send a key-value pair as integer. The use of this message is discouraged for normal packets, but a quite efficient way for testing new messages and getting experimental debug output.</description>
<field type="uint32_t" name="time_boot_ms">Timestamp (milliseconds since system boot)</field>
<field type="char[10]" name="name">Name of the debug variable</field>
<field type="int32_t" name="value">Signed integer value</field>
</message>
<message id="253" name="STATUSTEXT">
<description>Status text message. These messages are printed in yellow in the COMM console of QGroundControl. WARNING: They consume quite some bandwidth, so use only for important status and error messages. If implemented wisely, these messages are buffered on the MCU and sent only at a limited rate (e.g. 10 Hz).</description>
<field type="uint8_t" name="severity">Severity of status. Relies on the definitions within RFC-5424. See enum MAV_SEVERITY.</field>
<field type="char[50]" name="text">Status text message, without null termination character</field>
</message>
<message id="254" name="DEBUG">
<description>Send a debug value. The index is used to discriminate between values. These values show up in the plot of QGroundControl as DEBUG N.</description>
<field type="uint32_t" name="time_boot_ms">Timestamp (milliseconds since system boot)</field>
<field type="uint8_t" name="ind">index of debug variable</field>
<field type="float" name="value">DEBUG value</field>
</message>
</messages>
</mavlink>
/C-OSD/arducam-osd/libraries/GCS_MAVLink/message_definitions_v1.0/matrixpilot.xml
0,0 → 1,14
<?xml version='1.0'?>
<mavlink>
<include>common.xml</include>
<!-- note that MatrixPilot specific messages should use the command id
range from 150 to 250, to leave plenty of room for growth
of common.xml
 
If you prototype a message here, then you should consider if it
is general enough to move into common.xml later
-->
<messages>
 
</messages>
</mavlink>
/C-OSD/arducam-osd/libraries/GCS_MAVLink/message_definitions_v1.0/minimal.xml
0,0 → 1,189
<?xml version='1.0'?>
<mavlink>
<version>2</version>
<enums>
<enum name="MAV_AUTOPILOT">
<description>Micro air vehicle / autopilot classes. This identifies the individual model.</description>
<entry value="0" name="MAV_AUTOPILOT_GENERIC">
<description>Generic autopilot, full support for everything</description>
</entry>
<entry value="1" name="MAV_AUTOPILOT_PIXHAWK">
<description>PIXHAWK autopilot, http://pixhawk.ethz.ch</description>
</entry>
<entry value="2" name="MAV_AUTOPILOT_SLUGS">
<description>SLUGS autopilot, http://slugsuav.soe.ucsc.edu</description>
</entry>
<entry value="3" name="MAV_AUTOPILOT_ARDUPILOTMEGA">
<description>ArduPilotMega / ArduCopter, http://diydrones.com</description>
</entry>
<entry value="4" name="MAV_AUTOPILOT_OPENPILOT">
<description>OpenPilot, http://openpilot.org</description>
</entry>
<entry value="5" name="MAV_AUTOPILOT_GENERIC_WAYPOINTS_ONLY">
<description>Generic autopilot only supporting simple waypoints</description>
</entry>
<entry value="6" name="MAV_AUTOPILOT_GENERIC_WAYPOINTS_AND_SIMPLE_NAVIGATION_ONLY">
<description>Generic autopilot supporting waypoints and other simple navigation commands</description>
</entry>
<entry value="7" name="MAV_AUTOPILOT_GENERIC_MISSION_FULL">
<description>Generic autopilot supporting the full mission command set</description>
</entry>
<entry value="8" name="MAV_AUTOPILOT_INVALID">
<description>No valid autopilot, e.g. a GCS or other MAVLink component</description>
</entry>
<entry value="9" name="MAV_AUTOPILOT_PPZ">
<description>PPZ UAV - http://nongnu.org/paparazzi</description>
</entry>
<entry value="10" name="MAV_AUTOPILOT_UDB">
<description>UAV Dev Board</description>
</entry>
<entry value="11" name="MAV_AUTOPILOT_FP">
<description>FlexiPilot</description>
</entry>
</enum>
<enum name="MAV_TYPE">
<entry value="0" name="MAV_TYPE_GENERIC">
<description>Generic micro air vehicle.</description>
</entry>
<entry value="1" name="MAV_TYPE_FIXED_WING">
<description>Fixed wing aircraft.</description>
</entry>
<entry value="2" name="MAV_TYPE_QUADROTOR">
<description>Quadrotor</description>
</entry>
<entry value="3" name="MAV_TYPE_COAXIAL">
<description>Coaxial helicopter</description>
</entry>
<entry value="4" name="MAV_TYPE_HELICOPTER">
<description>Normal helicopter with tail rotor.</description>
</entry>
<entry value="5" name="MAV_TYPE_ANTENNA_TRACKER">
<description>Ground installation</description>
</entry>
<entry value="6" name="MAV_TYPE_GCS">
<description>Operator control unit / ground control station</description>
</entry>
<entry value="7" name="MAV_TYPE_AIRSHIP">
<description>Airship, controlled</description>
</entry>
<entry value="8" name="MAV_TYPE_FREE_BALLOON">
<description>Free balloon, uncontrolled</description>
</entry>
<entry value="9" name="MAV_TYPE_ROCKET">
<description>Rocket</description>
</entry>
<entry value="10" name="MAV_TYPE_GROUND_ROVER">
<description>Ground rover</description>
</entry>
<entry value="11" name="MAV_TYPE_SURFACE_BOAT">
<description>Surface vessel, boat, ship</description>
</entry>
<entry value="12" name="MAV_TYPE_SUBMARINE">
<description>Submarine</description>
</entry>
<entry value="13" name="MAV_TYPE_HEXAROTOR">
<description>Hexarotor</description>
</entry>
<entry value="14" name="MAV_TYPE_OCTOROTOR">
<description>Octorotor</description>
</entry>
<entry value="15" name="MAV_TYPE_TRICOPTER">
<description>Octorotor</description>
</entry>
<entry value="16" name="MAV_TYPE_FLAPPING_WING">
<description>Flapping wing</description>
</entry>
</enum>
<enum name="MAV_MODE_FLAG">
<description>These flags encode the MAV mode.</description>
<entry value="128" name="MAV_MODE_FLAG_SAFETY_ARMED">
<description>0b10000000 MAV safety set to armed. Motors are enabled / running / can start. Ready to fly.</description>
</entry>
<entry value="64" name="MAV_MODE_FLAG_MANUAL_INPUT_ENABLED">
<description>0b01000000 remote control input is enabled.</description>
</entry>
<entry value="32" name="MAV_MODE_FLAG_HIL_ENABLED">
<description>0b00100000 hardware in the loop simulation. All motors / actuators are blocked, but internal software is full operational.</description>
</entry>
<entry value="16" name="MAV_MODE_FLAG_STABILIZE_ENABLED">
<description>0b00010000 system stabilizes electronically its attitude (and optionally position). It needs however further control inputs to move around.</description>
</entry>
<entry value="8" name="MAV_MODE_FLAG_GUIDED_ENABLED">
<description>0b00001000 guided mode enabled, system flies MISSIONs / mission items.</description>
</entry>
<entry value="4" name="MAV_MODE_FLAG_AUTO_ENABLED">
<description>0b00000100 autonomous mode enabled, system finds its own goal positions. Guided flag can be set or not, depends on the actual implementation.</description>
</entry>
<entry value="2" name="MAV_MODE_FLAG_TEST_ENABLED">
<description>0b00000010 system has a test mode enabled. This flag is intended for temporary system tests and should not be used for stable implementations.</description>
</entry>
<entry value="1" name="MAV_MODE_FLAG_CUSTOM_MODE_ENABLED">
<description>0b00000001 Reserved for future use.</description>
</entry>
</enum>
<enum name="MAV_MODE_FLAG_DECODE_POSITION">
<description>These values encode the bit positions of the decode position. These values can be used to read the value of a flag bit by combining the base_mode variable with AND with the flag position value. The result will be either 0 or 1, depending on if the flag is set or not.</description>
<entry value="128" name="MAV_MODE_FLAG_DECODE_POSITION_SAFETY">
<description>First bit: 10000000</description>
</entry>
<entry value="64" name="MAV_MODE_FLAG_DECODE_POSITION_MANUAL">
<description>Second bit: 01000000</description>
</entry>
<entry value="32" name="MAV_MODE_FLAG_DECODE_POSITION_HIL">
<description>Third bit: 00100000</description>
</entry>
<entry value="16" name="MAV_MODE_FLAG_DECODE_POSITION_STABILIZE">
<description>Fourth bit: 00010000</description>
</entry>
<entry value="8" name="MAV_MODE_FLAG_DECODE_POSITION_GUIDED">
<description>Fifth bit: 00001000</description>
</entry>
<entry value="4" name="MAV_MODE_FLAG_DECODE_POSITION_AUTO">
<description>Sixt bit: 00000100</description>
</entry>
<entry value="2" name="MAV_MODE_FLAG_DECODE_POSITION_TEST">
<description>Seventh bit: 00000010</description>
</entry>
<entry value="1" name="MAV_MODE_FLAG_DECODE_POSITION_CUSTOM_MODE">
<description>Eighth bit: 00000001</description>
</entry>
</enum>
<enum name="MAV_STATE">
<entry value="0" name="MAV_STATE_UNINIT">
<description>Uninitialized system, state is unknown.</description>
</entry>
<entry name="MAV_STATE_BOOT">
<description>System is booting up.</description>
</entry>
<entry name="MAV_STATE_CALIBRATING">
<description>System is calibrating and not flight-ready.</description>
</entry>
<entry name="MAV_STATE_STANDBY">
<description>System is grounded and on standby. It can be launched any time.</description>
</entry>
<entry name="MAV_STATE_ACTIVE">
<description>System is active and might be already airborne. Motors are engaged.</description>
</entry>
<entry name="MAV_STATE_CRITICAL">
<description>System is in a non-normal flight mode. It can however still navigate.</description>
</entry>
<entry name="MAV_STATE_EMERGENCY">
<description>System is in a non-normal flight mode. It lost control over parts or over the whole airframe. It is in mayday and going down.</description>
</entry>
<entry name="MAV_STATE_POWEROFF">
<description>System just initialized its power-down sequence, will shut down now.</description>
</entry>
</enum>
</enums>
<messages>
<message id="0" name="HEARTBEAT">
<description>The heartbeat message shows that a system is present and responding. The type of the MAV and Autopilot hardware allow the receiving system to treat further messages from this system appropriate (e.g. by laying out the user interface based on the autopilot).</description>
<field type="uint8_t" name="type">Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM)</field>
<field type="uint8_t" name="autopilot">Autopilot type / class. defined in MAV_AUTOPILOT ENUM</field>
<field type="uint8_t" name="base_mode">System mode bitfield, see MAV_MODE_FLAGS ENUM in mavlink/include/mavlink_types.h</field>
<field type="uint32_t" name="custom_mode">A bitfield for use for autopilot-specific flags.</field>
<field type="uint8_t" name="system_status">System status flag, see MAV_STATE ENUM</field>
<field type="uint8_t_mavlink_version" name="mavlink_version">MAVLink version</field>
</message>
</messages>
</mavlink>
/C-OSD/arducam-osd/libraries/GCS_MAVLink/message_definitions_v1.0/pixhawk.xml
0,0 → 1,195
<?xml version='1.0'?>
<mavlink>
<include>common.xml</include>
<enums>
<enum name="DATA_TYPES">
<description>Content Types for data transmission handshake</description>
<entry value="1" name="DATA_TYPE_JPEG_IMAGE"/>
<entry value="2" name="DATA_TYPE_RAW_IMAGE"/>
<entry value="3" name="DATA_TYPE_KINECT"/>
</enum>
</enums>
<messages>
<message id="151" name="SET_CAM_SHUTTER">
<field type="uint8_t" name="cam_no">Camera id</field>
<field type="uint8_t" name="cam_mode">Camera mode: 0 = auto, 1 = manual</field>
<field type="uint8_t" name="trigger_pin">Trigger pin, 0-3 for PtGrey FireFly</field>
<field type="uint16_t" name="interval">Shutter interval, in microseconds</field>
<field type="uint16_t" name="exposure">Exposure time, in microseconds</field>
<field type="float" name="gain">Camera gain</field>
</message>
<message id="152" name="IMAGE_TRIGGERED">
<field type="uint64_t" name="timestamp">Timestamp</field>
<field type="uint32_t" name="seq">IMU seq</field>
<field type="float" name="roll">Roll angle in rad</field>
<field type="float" name="pitch">Pitch angle in rad</field>
<field type="float" name="yaw">Yaw angle in rad</field>
<field type="float" name="local_z">Local frame Z coordinate (height over ground)</field>
<field type="float" name="lat">GPS X coordinate</field>
<field type="float" name="lon">GPS Y coordinate</field>
<field type="float" name="alt">Global frame altitude</field>
<field type="float" name="ground_x">Ground truth X</field>
<field type="float" name="ground_y">Ground truth Y</field>
<field type="float" name="ground_z">Ground truth Z</field>
</message>
<message id="153" name="IMAGE_TRIGGER_CONTROL">
<field type="uint8_t" name="enable">0 to disable, 1 to enable</field>
</message>
<message id="154" name="IMAGE_AVAILABLE">
<field type="uint64_t" name="cam_id">Camera id</field>
<field type="uint8_t" name="cam_no">Camera # (starts with 0)</field>
<field type="uint64_t" name="timestamp">Timestamp</field>
<field type="uint64_t" name="valid_until">Until which timestamp this buffer will stay valid</field>
<field type="uint32_t" name="img_seq">The image sequence number</field>
<field type="uint32_t" name="img_buf_index">Position of the image in the buffer, starts with 0</field>
<field type="uint16_t" name="width">Image width</field>
<field type="uint16_t" name="height">Image height</field>
<field type="uint16_t" name="depth">Image depth</field>
<field type="uint8_t" name="channels">Image channels</field>
<field type="uint32_t" name="key">Shared memory area key</field>
<field type="uint32_t" name="exposure">Exposure time, in microseconds</field>
<field type="float" name="gain">Camera gain</field>
<field type="float" name="roll">Roll angle in rad</field>
<field type="float" name="pitch">Pitch angle in rad</field>
<field type="float" name="yaw">Yaw angle in rad</field>
<field type="float" name="local_z">Local frame Z coordinate (height over ground)</field>
<field type="float" name="lat">GPS X coordinate</field>
<field type="float" name="lon">GPS Y coordinate</field>
<field type="float" name="alt">Global frame altitude</field>
<field type="float" name="ground_x">Ground truth X</field>
<field type="float" name="ground_y">Ground truth Y</field>
<field type="float" name="ground_z">Ground truth Z</field>
</message>
<message id="160" name="SET_POSITION_CONTROL_OFFSET">
<description>Message sent to the MAV to set a new offset from the currently controlled position</description>
<field type="uint8_t" name="target_system">System ID</field>
<field type="uint8_t" name="target_component">Component ID</field>
<field type="float" name="x">x position offset</field>
<field type="float" name="y">y position offset</field>
<field type="float" name="z">z position offset</field>
<field type="float" name="yaw">yaw orientation offset in radians, 0 = NORTH</field>
</message>
<!-- Message sent by the MAV once it sets a new position as reference in the controller -->
<message id="170" name="POSITION_CONTROL_SETPOINT">
<field type="uint16_t" name="id">ID of waypoint, 0 for plain position</field>
<field type="float" name="x">x position</field>
<field type="float" name="y">y position</field>
<field type="float" name="z">z position</field>
<field type="float" name="yaw">yaw orientation in radians, 0 = NORTH</field>
</message>
<message id="171" name="MARKER">
<field type="uint16_t" name="id">ID</field>
<field type="float" name="x">x position</field>
<field type="float" name="y">y position</field>
<field type="float" name="z">z position</field>
<field type="float" name="roll">roll orientation</field>
<field type="float" name="pitch">pitch orientation</field>
<field type="float" name="yaw">yaw orientation</field>
</message>
<message id="172" name="RAW_AUX">
<field type="uint16_t" name="adc1">ADC1 (J405 ADC3, LPC2148 AD0.6)</field>
<field type="uint16_t" name="adc2">ADC2 (J405 ADC5, LPC2148 AD0.2)</field>
<field type="uint16_t" name="adc3">ADC3 (J405 ADC6, LPC2148 AD0.1)</field>
<field type="uint16_t" name="adc4">ADC4 (J405 ADC7, LPC2148 AD1.3)</field>
<field type="uint16_t" name="vbat">Battery voltage</field>
<field type="int16_t" name="temp">Temperature (degrees celcius)</field>
<field type="int32_t" name="baro">Barometric pressure (hecto Pascal)</field>
</message>
<message id="180" name="WATCHDOG_HEARTBEAT">
<field type="uint16_t" name="watchdog_id">Watchdog ID</field>
<field type="uint16_t" name="process_count">Number of processes</field>
</message>
<message id="181" name="WATCHDOG_PROCESS_INFO">
<field type="uint16_t" name="watchdog_id">Watchdog ID</field>
<field type="uint16_t" name="process_id">Process ID</field>
<field type="char[100]" name="name">Process name</field>
<field type="char[147]" name="arguments">Process arguments</field>
<field type="int32_t" name="timeout">Timeout (seconds)</field>
</message>
<message id="182" name="WATCHDOG_PROCESS_STATUS">
<field type="uint16_t" name="watchdog_id">Watchdog ID</field>
<field type="uint16_t" name="process_id">Process ID</field>
<field type="uint8_t" name="state">Is running / finished / suspended / crashed</field>
<field type="uint8_t" name="muted">Is muted</field>
<field type="int32_t" name="pid">PID</field>
<field type="uint16_t" name="crashes">Number of crashes</field>
</message>
<message id="183" name="WATCHDOG_COMMAND">
<field type="uint8_t" name="target_system_id">Target system ID</field>
<field type="uint16_t" name="watchdog_id">Watchdog ID</field>
<field type="uint16_t" name="process_id">Process ID</field>
<field type="uint8_t" name="command_id">Command ID</field>
</message>
<message id="190" name="PATTERN_DETECTED">
<field type="uint8_t" name="type">0: Pattern, 1: Letter</field>
<field type="float" name="confidence">Confidence of detection</field>
<field type="char[100]" name="file">Pattern file name</field>
<field type="uint8_t" name="detected">Accepted as true detection, 0 no, 1 yes</field>
</message>
<message id="191" name="POINT_OF_INTEREST">
<description>Notifies the operator about a point of interest (POI). This can be anything detected by the
system. This generic message is intented to help interfacing to generic visualizations and to display
the POI on a map.
</description>
<field type="uint8_t" name="type">0: Notice, 1: Warning, 2: Critical, 3: Emergency, 4: Debug</field>
<field type="uint8_t" name="color">0: blue, 1: yellow, 2: red, 3: orange, 4: green, 5: magenta</field>
<field type="uint8_t" name="coordinate_system">0: global, 1:local</field>
<field type="uint16_t" name="timeout">0: no timeout, >1: timeout in seconds</field>
<field type="float" name="x">X Position</field>
<field type="float" name="y">Y Position</field>
<field type="float" name="z">Z Position</field>
<field type="char[26]" name="name">POI name</field>
</message>
<message id="192" name="POINT_OF_INTEREST_CONNECTION">
<description>Notifies the operator about the connection of two point of interests (POI). This can be anything detected by the
system. This generic message is intented to help interfacing to generic visualizations and to display
the POI on a map.
</description>
<field type="uint8_t" name="type">0: Notice, 1: Warning, 2: Critical, 3: Emergency, 4: Debug</field>
<field type="uint8_t" name="color">0: blue, 1: yellow, 2: red, 3: orange, 4: green, 5: magenta</field>
<field type="uint8_t" name="coordinate_system">0: global, 1:local</field>
<field type="uint16_t" name="timeout">0: no timeout, >1: timeout in seconds</field>
<field type="float" name="xp1">X1 Position</field>
<field type="float" name="yp1">Y1 Position</field>
<field type="float" name="zp1">Z1 Position</field>
<field type="float" name="xp2">X2 Position</field>
<field type="float" name="yp2">Y2 Position</field>
<field type="float" name="zp2">Z2 Position</field>
<field type="char[26]" name="name">POI connection name</field>
</message>
<message id="193" name="DATA_TRANSMISSION_HANDSHAKE">
<field type="uint8_t" name="type">type of requested/acknowledged data (as defined in ENUM DATA_TYPES in mavlink/include/mavlink_types.h)</field>
<field type="uint32_t" name="size">total data size in bytes (set on ACK only)</field>
<field type="uint16_t" name="width">Width of a matrix or image</field>
<field type="uint16_t" name="height">Height of a matrix or image</field>
<field type="uint8_t" name="packets">number of packets beeing sent (set on ACK only)</field>
<field type="uint8_t" name="payload">payload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only)</field>
<field type="uint8_t" name="jpg_quality">JPEG quality out of [1,100]</field>
</message>
<message id="194" name="ENCAPSULATED_DATA">
<field type="uint16_t" name="seqnr">sequence number (starting with 0 on every transmission)</field>
<field type="uint8_t[253]" name="data">image data bytes</field>
</message>
<message id="195" name="BRIEF_FEATURE">
<field type="float" name="x">x position in m</field>
<field type="float" name="y">y position in m</field>
<field type="float" name="z">z position in m</field>
<field type="uint8_t" name="orientation_assignment">Orientation assignment 0: false, 1:true</field>
<field type="uint16_t" name="size">Size in pixels</field>
<field type="uint16_t" name="orientation">Orientation</field>
<field type="uint8_t[32]" name="descriptor">Descriptor</field>
<field type="float" name="response">Harris operator response at this location</field>
</message>
<message id="200" name="ATTITUDE_CONTROL">
<field type="uint8_t" name="target">The system to be controlled</field>
<field type="float" name="roll">roll</field>
<field type="float" name="pitch">pitch</field>
<field type="float" name="yaw">yaw</field>
<field type="float" name="thrust">thrust</field>
<field type="uint8_t" name="roll_manual">roll control enabled auto:0, manual:1</field>
<field type="uint8_t" name="pitch_manual">pitch auto:0, manual:1</field>
<field type="uint8_t" name="yaw_manual">yaw auto:0, manual:1</field>
<field type="uint8_t" name="thrust_manual">thrust auto:0, manual:1</field>
</message>
</messages>
</mavlink>
/C-OSD/arducam-osd/libraries/GCS_MAVLink/message_definitions_v1.0/sensesoar.xml
0,0 → 1,83
<?xml version='1.0'?>
<mavlink>
<include>common.xml</include>
<enums>
<enum name="SENSESOAR_MODE">
<description> Different flight modes </description>
<entry name="SENSESOAR_MODE_GLIDING"> Gliding mode with motors off</entry>
<entry name="SENSESOAR_MODE_AUTONOMOUS"> Autonomous flight</entry>
<entry name="SENSESOAR_MODE_MANUAL"> RC controlled</entry>
</enum>
</enums>
<messages>
<message id="170" name="OBS_POSITION">
Position estimate of the observer in global frame
<field type="int32_t" name="lon">Longitude expressed in 1E7</field>
<field type="int32_t" name="lat">Latitude expressed in 1E7</field>
<field type="int32_t" name="alt">Altitude expressed in milimeters</field>
</message>
<message id="172" name="OBS_VELOCITY">
velocity estimate of the observer in NED inertial frame
<field type="float[3]" name="vel">Velocity</field>
</message>
<message id="174" name="OBS_ATTITUDE">
attitude estimate of the observer
<field type="double[4]" name="quat">Quaternion re;im</field>
</message>
<message id="176" name="OBS_WIND">
Wind estimate in NED inertial frame
<field type="float[3]" name="wind">Wind</field>
</message>
<message id="178" name="OBS_AIR_VELOCITY">
Estimate of the air velocity
<field type="float" name="magnitude">Air speed</field>
<field type="float" name="aoa">angle of attack</field>
<field type="float" name="slip">slip angle</field>
</message>
<message id="180" name="OBS_BIAS">
IMU biases
<field type="float[3]" name="accBias">accelerometer bias</field>
<field type="float[3]" name="gyroBias">gyroscope bias</field>
</message>
<message id="182" name="OBS_QFF">
estimate of the pressure at sea level
<field type="float" name="qff">Wind</field>
</message>
<message id="183" name="OBS_AIR_TEMP">
ambient air temperature
<field type="float" name="airT">Air Temperatur</field>
</message>
<message id="184" name="FILT_ROT_VEL">
filtered rotational velocity
<field type="float[3]" name="rotVel">rotational velocity</field>
</message>
<message id="186" name="LLC_OUT">
low level control output
<field type="int16_t[4]" name="servoOut">Servo signal</field>
<field type="int16_t[2]" name="MotorOut">motor signal</field>
</message>
<message id="188" name="PM_ELEC">
Power managment
<field type="float" name="PwCons">current power consumption</field>
<field type="float" name="BatStat">battery status</field>
<field type="float[3]" name="PwGen">Power generation from each module</field>
</message>
<message id="190" name="SYS_Stat">
system status
<field type="uint8_t" name="gps">gps status</field>
<field type="uint8_t" name="act">actuator status</field>
<field type="uint8_t" name="mod">module status</field>
<field type="uint8_t" name="commRssi">module status</field>
</message>
<message id="192" name="CMD_AIRSPEED_CHNG">
change commanded air speed
<field type="uint8_t" name="target">Target ID</field>
<field type="float" name="spCmd">commanded airspeed</field>
</message>
<message id="194" name="CMD_AIRSPEED_ACK">
accept change of airspeed
<field type="float" name="spCmd">commanded airspeed</field>
<field type="uint8_t" name="ack">0:ack, 1:nack</field>
</message>
</messages>
</mavlink>
/C-OSD/arducam-osd/libraries/GCS_MAVLink/message_definitions_v1.0/slugs.xml
0,0 → 1,144
<?xml version="1.0"?>
<mavlink>
<include>common.xml</include>
 
<!-- <enums>
<enum name="SLUGS_ACTION" >
<description> Slugs Actions </description>
<entry name = "SLUGS_ACTION_NONE">
<entry name = "SLUGS_ACTION_SUCCESS">
<entry name = "SLUGS_ACTION_FAIL">
<entry name = "SLUGS_ACTION_EEPROM">
<entry name = "SLUGS_ACTION_MODE_CHANGE">
<entry name = "SLUGS_ACTION_MODE_REPORT">
<entry name = "SLUGS_ACTION_PT_CHANGE">
<entry name = "SLUGS_ACTION_PT_REPORT">
<entry name = "SLUGS_ACTION_PID_CHANGE">
<entry name = "SLUGS_ACTION_PID_REPORT">
<entry name = "SLUGS_ACTION_WP_CHANGE">
<entry name = "SLUGS_ACTION_WP_REPORT">
<entry name = "SLUGS_ACTION_MLC_CHANGE">
<entry name = "SLUGS_ACTION_MLC_REPORT">
</enum>
 
<enum name="WP_PROTOCOL_STATE" >
<description> Waypoint Protocol States </description>
<entry name = "WP_PROT_IDLE">
<entry name = "WP_PROT_LIST_REQUESTED">
<entry name = "WP_PROT_NUM_SENT">
<entry name = "WP_PROT_TX_WP">
<entry name = "WP_PROT_RX_WP">
<entry name = "WP_PROT_SENDING_WP_IDLE">
<entry name = "WP_PROT_GETTING_WP_IDLE">
</enum>
 
</enums> -->
 
<messages>
 
<message name="CPU_LOAD" id="170">
Sensor and DSC control loads.
<field name="sensLoad" type="uint8_t">Sensor DSC Load</field>
<field name="ctrlLoad" type="uint8_t">Control DSC Load</field>
<field name="batVolt" type="uint16_t">Battery Voltage in millivolts</field>
</message>
 
<message name="AIR_DATA" id="171">
Air data for altitude and airspeed computation.
<field name="dynamicPressure" type="float">Dynamic pressure (Pa)</field>
<field name="staticPressure" type="float">Static pressure (Pa)</field>
<field name="temperature" type="uint16_t">Board temperature</field>
</message>
 
<message name="SENSOR_BIAS" id="172">
Accelerometer and gyro biases.
<field name="axBias" type="float">Accelerometer X bias (m/s)</field>
<field name="ayBias" type="float">Accelerometer Y bias (m/s)</field>
<field name="azBias" type="float">Accelerometer Z bias (m/s)</field>
<field name="gxBias" type="float">Gyro X bias (rad/s)</field>
<field name="gyBias" type="float">Gyro Y bias (rad/s)</field>
<field name="gzBias" type="float">Gyro Z bias (rad/s)</field>
</message>
 
<message name="DIAGNOSTIC" id="173">
Configurable diagnostic messages.
<field name="diagFl1" type="float">Diagnostic float 1</field>
<field name="diagFl2" type="float">Diagnostic float 2</field>
<field name="diagFl3" type="float">Diagnostic float 3</field>
<field name="diagSh1" type="int16_t">Diagnostic short 1</field>
<field name="diagSh2" type="int16_t">Diagnostic short 2</field>
<field name="diagSh3" type="int16_t">Diagnostic short 3</field>
</message>
 
<message name="SLUGS_NAVIGATION" id="176">
Data used in the navigation algorithm.
<field name="u_m" type="float">Measured Airspeed prior to the Nav Filter</field>
<field name="phi_c" type="float">Commanded Roll</field>
<field name="theta_c" type="float">Commanded Pitch</field>
<field name="psiDot_c" type="float">Commanded Turn rate</field>
<field name="ay_body" type="float">Y component of the body acceleration</field>
<field name="totalDist" type="float">Total Distance to Run on this leg of Navigation</field>
<field name="dist2Go" type="float">Remaining distance to Run on this leg of Navigation</field>
<field name="fromWP" type="uint8_t">Origin WP</field>
<field name="toWP" type="uint8_t">Destination WP</field>
</message>
 
<message name="DATA_LOG" id="177">
Configurable data log probes to be used inside Simulink
<field name="fl_1" type="float">Log value 1 </field>
<field name="fl_2" type="float">Log value 2 </field>
<field name="fl_3" type="float">Log value 3 </field>
<field name="fl_4" type="float">Log value 4 </field>
<field name="fl_5" type="float">Log value 5 </field>
<field name="fl_6" type="float">Log value 6 </field>
</message>
 
<message name="GPS_DATE_TIME" id="179">
Pilot console PWM messges.
<field name="year" type="uint8_t">Year reported by Gps </field>
<field name="month" type="uint8_t">Month reported by Gps </field>
<field name="day" type="uint8_t">Day reported by Gps </field>
<field name="hour" type="uint8_t">Hour reported by Gps </field>
<field name="min" type="uint8_t">Min reported by Gps </field>
<field name="sec" type="uint8_t">Sec reported by Gps </field>
<field name="visSat" type="uint8_t">Visible sattelites reported by Gps </field>
</message>
 
<message name="MID_LVL_CMDS" id="180">
Mid Level commands sent from the GS to the autopilot. These are only sent when being opperated in mid-level commands mode from the ground; for periodic report of these commands generated from the autopilot see message XXXX.
<field name="target" type="uint8_t">The system setting the commands</field>
<field name="hCommand" type="float">Commanded Airspeed</field>
<field name="uCommand" type="float">Log value 2 </field>
<field name="rCommand" type="float">Log value 3 </field>
</message>
 
 
<message name="CTRL_SRFC_PT" id="181">
This message configures the Selective Passthrough mode. it allows to select which control surfaces the Pilot can control from his console. It is implemented as a bitfield as follows:
Position Bit Code
=================================
15-8 Reserved
7 dt_pass 128
6 dla_pass 64
5 dra_pass 32
4 dr_pass 16
3 dle_pass 8
2 dre_pass 4
1 dlf_pass 2
0 drf_pass 1
Where Bit 15 is the MSb. 0 = AP has control of the surface; 1 = Pilot Console has control of the surface.
<field name="target" type="uint8_t">The system setting the commands</field>
<field name="bitfieldPt" type="uint16_t">Bitfield containing the PT configuration</field>
</message>
 
 
 
<message name="SLUGS_ACTION" id="183">
Action messages focused on the SLUGS AP.
<field name="target" type="uint8_t">The system reporting the action</field>
<field name="actionId" type="uint8_t">Action ID. See apDefinitions.h in the SLUGS /clib directory for the ID names</field>
<field name="actionVal" type="uint16_t">Value associated with the action</field>
</message>
 
</messages>
</mavlink>
/C-OSD/arducam-osd/libraries/GCS_MAVLink/message_definitions_v1.0/test.xml
0,0 → 1,31
<?xml version='1.0'?>
<mavlink>
<version>3</version>
<messages>
<message id="0" name="TEST_TYPES">
<description>Test all field types</description>
<field type="char" name="c">char</field>
<field type="char[10]" name="s">string</field>
<field type="uint8_t" name="u8">uint8_t</field>
<field type="uint16_t" name="u16">uint16_t</field>
<field print_format="0x%08x" type="uint32_t" name="u32">uint32_t</field>
<field type="uint64_t" name="u64">uint64_t</field>
<field type="int8_t" name="s8">int8_t</field>
<field type="int16_t" name="s16">int16_t</field>
<field type="int32_t" name="s32">int32_t</field>
<field type="int64_t" name="s64">int64_t</field>
<field type="float" name="f">float</field>
<field type="double" name="d">double</field>
<field type="uint8_t[3]" name="u8_array">uint8_t_array</field>
<field type="uint16_t[3]" name="u16_array">uint16_t_array</field>
<field type="uint32_t[3]" name="u32_array">uint32_t_array</field>
<field type="uint64_t[3]" name="u64_array">uint64_t_array</field>
<field type="int8_t[3]" name="s8_array">int8_t_array</field>
<field type="int16_t[3]" name="s16_array">int16_t_array</field>
<field type="int32_t[3]" name="s32_array">int32_t_array</field>
<field type="int64_t[3]" name="s64_array">int64_t_array</field>
<field type="float[3]" name="f_array">float_array</field>
<field type="double[3]" name="d_array">double_array</field>
</message>
</messages>
</mavlink>
/C-OSD/arducam-osd/libraries/GCS_MAVLink/message_definitions_v1.0/ualberta.xml
0,0 → 1,54
<?xml version='1.0'?>
<mavlink>
<include>common.xml</include>
<enums>
<enum name="UALBERTA_AUTOPILOT_MODE">
<description>Available autopilot modes for ualberta uav</description>
<entry name="MODE_MANUAL_DIRECT">Raw input pulse widts sent to output</entry>
<entry name="MODE_MANUAL_SCALED">Inputs are normalized using calibration, the converted back to raw pulse widths for output</entry>
<entry name="MODE_AUTO_PID_ATT"> dfsdfs</entry>
<entry name="MODE_AUTO_PID_VEL"> dfsfds</entry>
<entry name="MODE_AUTO_PID_POS"> dfsdfsdfs</entry>
</enum>
<enum name="UALBERTA_NAV_MODE">
<description>Navigation filter mode</description>
<entry name="NAV_AHRS_INIT" />
<entry name="NAV_AHRS">AHRS mode</entry>
<entry name="NAV_INS_GPS_INIT">INS/GPS initialization mode</entry>
<entry name="NAV_INS_GPS">INS/GPS mode</entry>
</enum>
<enum name="UALBERTA_PILOT_MODE">
<description>Mode currently commanded by pilot</description>
<entry name="PILOT_MANUAL"> sdf</entry>
<entry name="PILOT_AUTO"> dfs</entry>
<entry name="PILOT_ROTO"> Rotomotion mode </entry>
</enum>
</enums>
<messages>
<message id="220" name="NAV_FILTER_BIAS">
<description>Accelerometer and Gyro biases from the navigation filter</description>
<field type="uint64_t" name="usec">Timestamp (microseconds)</field>
<field type="float" name="accel_0">b_f[0]</field>
<field type="float" name="accel_1">b_f[1]</field>
<field type="float" name="accel_2">b_f[2]</field>
<field type="float" name="gyro_0">b_f[0]</field>
<field type="float" name="gyro_1">b_f[1]</field>
<field type="float" name="gyro_2">b_f[2]</field>
</message>
<message id="221" name="RADIO_CALIBRATION">
<description>Complete set of calibration parameters for the radio</description>
<field type="uint16_t[3]" name="aileron">Aileron setpoints: left, center, right</field>
<field type="uint16_t[3]" name="elevator">Elevator setpoints: nose down, center, nose up</field>
<field type="uint16_t[3]" name="rudder">Rudder setpoints: nose left, center, nose right</field>
<field type="uint16_t[2]" name="gyro">Tail gyro mode/gain setpoints: heading hold, rate mode</field>
<field type="uint16_t[5]" name="pitch">Pitch curve setpoints (every 25%)</field>
<field type="uint16_t[5]" name="throttle">Throttle curve setpoints (every 25%)</field>
</message>
<message id="222" name="UALBERTA_SYS_STATUS">
<description>System status specific to ualberta uav</description>
<field type="uint8_t" name="mode">System mode, see UALBERTA_AUTOPILOT_MODE ENUM</field>
<field type="uint8_t" name="nav_mode">Navigation mode, see UALBERTA_NAV_MODE ENUM</field>
<field type="uint8_t" name="pilot">Pilot mode, see UALBERTA_PILOT_MODE</field>
</message>
</messages>
</mavlink>
/C-OSD/arducam-osd/libraries/GCS_MAVLink/update
0,0 → 1,14
#!/bin/bash
if [[ $# != 1 ]]
then
echo "usage: $0 version"
exit
fi
 
MAVLINK_VERSION=$1
rm -rf VERSION mavlink* include lib share *.zip
wget http://github.com/downloads/mavlink/mavlink/mavlink-${MAVLINK_VERSION}.zip
unzip mavlink-${MAVLINK_VERSION}.zip
mv mavlink-${MAVLINK_VERSION}/* .
rm -rf mavlink* share lib
echo $MAVLINK_VERSION > VERSION