1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-20 06:45:16 +03:00

wit (rebase onto master) blind merge

This commit is contained in:
jflyper 2016-11-01 11:57:09 +09:00
commit ab7bb1342a
510 changed files with 68911 additions and 9793 deletions

3
.gitignore vendored
View file

@ -24,3 +24,6 @@ README.pdf
/build
# local changes only
make/local.mk
mcu.mak
mcu.mak.old

View file

@ -3,12 +3,14 @@ env:
# - PUBLISHMETA=True
# - PUBLISHDOCS=True
# - TARGET=AFROMINI
# - TARGET=BEEBRAIN
# - TARGET=AIORACERF3
# - TARGET=AIR32
# - TARGET=AIRHEROF3
# - TARGET=ALIENFLIGHTF1
- TARGET=ALIENFLIGHTF3
- TARGET=ALIENFLIGHTF4
- TARGET=ANYFCF7
- TARGET=BETAFLIGHTF3
- TARGET=BLUEJAYF4
- TARGET=CC3D
@ -19,7 +21,6 @@ env:
# - TARGET=COLIBRI_OPBL
# - TARGET=COLIBRI_RACE
# - TARGET=DOGE
# - TARGET=EUSTM32F103RC
# - TARGET=F4BY
# - TARGET=FURYF3
- TARGET=FURYF4
@ -30,11 +31,9 @@ env:
# - TARGET=MICROSCISKY
# - TARGET=MOTOLAB
- TARGET=NAZE
# - TARGET=OLIMEXINO
# - TARGET=OMNIBUS
# - TARGET=OMNIBUSF4
# - TARGET=PIKOBLX
# - TARGET=PORT103R
# - TARGET=RACEBASE
- TARGET=REVO
# - TARGET=REVONANO
@ -76,7 +75,7 @@ compiler: clang
install:
- make arm_sdk_install
before_script: tools/gcc-arm-none-eabi-5_4-2016q2/bin/arm-none-eabi-gcc --version
before_script: tools/gcc-arm-none-eabi-5_4-2016q3/bin/arm-none-eabi-gcc --version
script: ./.travis.sh
cache: apt

183
Makefile
View file

@ -37,9 +37,9 @@ SERIAL_DEVICE ?= $(firstword $(wildcard /dev/ttyUSB*) no-port-found)
# Flash size (KB). Some low-end chips actually have more flash than advertised, use this to override.
FLASH_SIZE ?=
## Set verbosity level based on the V= parameter
## V=0 Low
## v=1 High
## V : Set verbosity level based on the V= parameter
## V=0 Low
## V=1 High
export AT := @
ifndef V
@ -67,7 +67,7 @@ INCLUDE_DIRS = $(SRC_DIR) \
$(ROOT)/src/main/target
LINKER_DIR = $(ROOT)/src/main/target/link
## Build tools, so we all share the same versions
# Build tools, so we all share the same versions
# import macros common to all supported build systems
include $(ROOT)/make/system-id.mk
# developer preferences, edit these at will, they'll be gitignored
@ -92,6 +92,7 @@ HSE_VALUE = 8000000
# used for turning on features like VCP and SDCARD
FEATURES =
SAMPLE_TARGETS = ALIENFLIGHTF3 ALIENFLIGHTF4 ANYFCF7 BETAFLIGHTF3 BLUEJAYF4 CC3D FURYF4 NAZE REVO SIRINFPV SPARKY SPRACINGF3 SPRACINGF3EVO STM32F3DISCOVERY
ALT_TARGETS = $(sort $(filter-out target, $(basename $(notdir $(wildcard $(ROOT)/src/main/target/*/*.mk)))))
OPBL_TARGETS = $(filter %_OPBL, $(ALT_TARGETS))
@ -116,23 +117,27 @@ endif
-include $(ROOT)/src/main/target/$(BASE_TARGET)/target.mk
F4_TARGETS = $(F405_TARGETS) $(F411_TARGETS)
F7_TARGETS = $(F7X5XE_TARGETS) $(F7X5XG_TARGETS) $(F7X5XI_TARGETS)
ifeq ($(filter $(TARGET),$(VALID_TARGETS)),)
$(error Target '$(TARGET)' is not valid, must be one of $(VALID_TARGETS). Have you prepared a valid target.mk?)
endif
ifeq ($(filter $(TARGET),$(F1_TARGETS) $(F3_TARGETS) $(F4_TARGETS)),)
$(error Target '$(TARGET)' has not specified a valid STM group, must be one of F1, F3, F405, or F411. Have you prepared a valid target.mk?)
ifeq ($(filter $(TARGET),$(F1_TARGETS) $(F3_TARGETS) $(F4_TARGETS) $(F7_TARGETS)),)
$(error Target '$(TARGET)' has not specified a valid STM group, must be one of F1, F3, F405, F411 or F7x5. Have you prepared a valid target.mk?)
endif
128K_TARGETS = $(F1_TARGETS)
256K_TARGETS = $(F3_TARGETS)
512K_TARGETS = $(F411_TARGETS)
1024K_TARGETS = $(F405_TARGETS)
512K_TARGETS = $(F411_TARGETS) $(F7X5XE_TARGETS)
1024K_TARGETS = $(F405_TARGETS) $(F7X5XG_TARGETS)
2048K_TARGETS = $(F7X5XI_TARGETS)
# Configure default flash sizes for the targets (largest size specified gets hit first) if flash not specified already.
ifeq ($(FLASH_SIZE),)
ifeq ($(TARGET),$(filter $(TARGET),$(1024K_TARGETS)))
ifeq ($(TARGET),$(filter $(TARGET),$(2048K_TARGETS)))
FLASH_SIZE = 2048
else ifeq ($(TARGET),$(filter $(TARGET),$(1024K_TARGETS)))
FLASH_SIZE = 1024
else ifeq ($(TARGET),$(filter $(TARGET),$(512K_TARGETS)))
FLASH_SIZE = 512
@ -153,6 +158,10 @@ else
STM32F30x_COMMON_SRC = startup_stm32f30x_md_gcc.S
endif
ifeq ($(DEBUG_HARDFAULTS),F7)
CFLAGS += -DDEBUG_HARDFAULTS
endif
REVISION = $(shell git log -1 --format="%h")
FC_VER_MAJOR := $(shell grep " FC_VERSION_MAJOR" src/main/build/version.h | awk '{print $$3}' )
@ -307,6 +316,69 @@ DEVICE_FLAGS += -DHSE_VALUE=$(HSE_VALUE)
# End F4 targets
#
# Start F7 targets
else ifeq ($(TARGET),$(filter $(TARGET), $(F7_TARGETS)))
#STDPERIPH
STDPERIPH_DIR = $(ROOT)/lib/main/STM32F7xx_HAL_Driver
STDPERIPH_SRC = $(notdir $(wildcard $(STDPERIPH_DIR)/Src/*.c))
EXCLUDES = stm32f7xx_hal_timebase_rtc_wakeup_template.c \
stm32f7xx_hal_timebase_rtc_alarm_template.c \
stm32f7xx_hal_timebase_tim_template.c
STDPERIPH_SRC := $(filter-out ${EXCLUDES}, $(STDPERIPH_SRC))
#USB
USBCORE_DIR = $(ROOT)/lib/main/Middlewares/ST/STM32_USB_Device_Library/Core
USBCORE_SRC = $(notdir $(wildcard $(USBCORE_DIR)/Src/*.c))
EXCLUDES = usbd_conf_template.c
USBCORE_SRC := $(filter-out ${EXCLUDES}, $(USBCORE_SRC))
USBCDC_DIR = $(ROOT)/lib/main/Middlewares/ST/STM32_USB_Device_Library/Class/CDC
USBCDC_SRC = $(notdir $(wildcard $(USBCDC_DIR)/Src/*.c))
EXCLUDES = usbd_cdc_if_template.c
USBCDC_SRC := $(filter-out ${EXCLUDES}, $(USBCDC_SRC))
VPATH := $(VPATH):$(USBCDC_DIR)/Src:$(USBCORE_DIR)/Src
DEVICE_STDPERIPH_SRC := $(STDPERIPH_SRC) \
$(USBCORE_SRC) \
$(USBCDC_SRC)
#CMSIS
VPATH := $(VPATH):$(CMSIS_DIR)/CM7/Include:$(CMSIS_DIR)/CM7/Device/ST/STM32F7xx
VPATH := $(VPATH):$(STDPERIPH_DIR)/Src
CMSIS_SRC = $(notdir $(wildcard $(CMSIS_DIR)/CM7/Include/*.c \
$(CMSIS_DIR)/CM7/Device/ST/STM32F7xx/*.c))
INCLUDE_DIRS := $(INCLUDE_DIRS) \
$(STDPERIPH_DIR)/Inc \
$(USBCORE_DIR)/Inc \
$(USBCDC_DIR)/Inc \
$(CMSIS_DIR)/CM7/Include \
$(CMSIS_DIR)/CM7/Device/ST/STM32F7xx/Include \
$(ROOT)/src/main/vcp_hal
ifneq ($(filter SDCARD,$(FEATURES)),)
INCLUDE_DIRS := $(INCLUDE_DIRS) \
$(FATFS_DIR)
VPATH := $(VPATH):$(FATFS_DIR)
endif
#Flags
ARCH_FLAGS = -mthumb -mcpu=cortex-m7 -mfloat-abi=hard -mfpu=fpv5-sp-d16 -fsingle-precision-constant -Wdouble-promotion
ifeq ($(TARGET),$(filter $(TARGET),$(F7X5XG_TARGETS)))
DEVICE_FLAGS = -DSTM32F745xx -DUSE_HAL_DRIVER -D__FPU_PRESENT
LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f745.ld
else
$(error Unknown MCU for F7 target)
endif
DEVICE_FLAGS += -DHSE_VALUE=$(HSE_VALUE)
TARGET_FLAGS = -D$(TARGET)
# End F7 targets
#
# Start F1 targets
else
@ -385,6 +457,9 @@ else
.DEFAULT_GOAL := hex
endif
INCLUDE_DIRS := $(INCLUDE_DIRS) \
$(ROOT)/lib/main/MAVLink
INCLUDE_DIRS := $(INCLUDE_DIRS) \
$(TARGET_DIR)
@ -396,17 +471,15 @@ COMMON_SRC = \
build/version.c \
$(TARGET_DIR_SRC) \
main.c \
fc/mw.c \
common/encoding.c \
common/filter.c \
common/maths.c \
common/printf.c \
common/streambuf.c \
common/typeconversion.c \
config/config.c \
config/config_eeprom.c \
config/feature.c \
fc/runtime_config.c \
config/parameter_group.c \
drivers/adc.c \
drivers/buf_writer.c \
drivers/bus_i2c_soft.c \
@ -419,7 +492,6 @@ COMMON_SRC = \
drivers/rx_nrf24l01.c \
drivers/rx_spi.c \
drivers/rx_xn297.c \
drivers/pwm_mapping.c \
drivers/pwm_output.c \
drivers/pwm_rx.c \
drivers/rcc.c \
@ -428,24 +500,27 @@ COMMON_SRC = \
drivers/sound_beeper.c \
drivers/system.c \
drivers/timer.c \
fc/config.c \
fc/fc_tasks.c \
fc/fc_msp.c \
fc/mw.c \
fc/rc_controls.c \
fc/rc_curves.c \
fc/runtime_config.c \
flight/altitudehold.c \
flight/failsafe.c \
flight/imu.c \
flight/mixer.c \
flight/pid.c \
flight/pid_legacy.c \
flight/pid_betaflight.c \
flight/servos.c \
io/beeper.c \
fc/rc_controls.c \
fc/rc_curves.c \
io/serial.c \
io/serial_4way.c \
io/serial_4way_avrootloader.c \
io/serial_4way_stk500v2.c \
io/serial_cli.c \
io/serial_msp.c \
io/statusindicator.c \
msp/msp_server_fc.c \
msp/msp_serial.c \
rx/ibus.c \
rx/jetiexbus.c \
rx/msp.c \
@ -463,7 +538,6 @@ COMMON_SRC = \
rx/sumh.c \
rx/xbus.c \
scheduler/scheduler.c \
scheduler/scheduler_tasks.c \
sensors/acceleration.c \
sensors/battery.c \
sensors/boardalignment.c \
@ -478,6 +552,10 @@ HIGHEND_SRC = \
blackbox/blackbox_io.c \
common/colorconversion.c \
drivers/display_ug2864hsweg01.c \
drivers/light_ws2811strip.c \
drivers/serial_escserial.c \
drivers/serial_softserial.c \
drivers/sonar_hcsr04.c \
flight/gtune.c \
flight/navigation.c \
flight/gps_conversion.c \
@ -490,7 +568,8 @@ HIGHEND_SRC = \
telemetry/frsky.c \
telemetry/hott.c \
telemetry/smartport.c \
telemetry/ltm.c
telemetry/ltm.c \
telemetry/mavlink.c
ifeq ($(TARGET),$(filter $(TARGET),$(F4_TARGETS)))
VCP_SRC = \
@ -500,6 +579,12 @@ VCP_SRC = \
vcpf4/usbd_usr.c \
vcpf4/usbd_cdc_vcp.c \
drivers/serial_usb_vcp.c
else ifeq ($(TARGET),$(filter $(TARGET),$(F7_TARGETS)))
VCP_SRC = \
vcp_hal/usbd_desc.c \
vcp_hal/usbd_conf.c \
vcp_hal/usbd_cdc_interface.c \
drivers/serial_usb_vcp_hal.c
else
VCP_SRC = \
vcp/hw_config.c \
@ -520,7 +605,7 @@ STM32F10x_COMMON_SRC = \
drivers/dma.c \
drivers/gpio_stm32f10x.c \
drivers/inverter.c \
drivers/serial_softserial.c \
drivers/light_ws2811strip_stm32f10x.c \
drivers/serial_uart_stm32f10x.c \
drivers/system_stm32f10x.c \
drivers/timer_stm32f10x.c
@ -533,6 +618,7 @@ STM32F30x_COMMON_SRC = \
drivers/dma.c \
drivers/gpio_stm32f30x.c \
drivers/light_ws2811strip_stm32f30x.c \
drivers/pwm_output_stm32f3xx.c \
drivers/serial_uart_stm32f30x.c \
drivers/system_stm32f30x.c \
drivers/timer_stm32f30x.c
@ -542,19 +628,45 @@ STM32F4xx_COMMON_SRC = \
target/system_stm32f4xx.c \
drivers/accgyro_mpu.c \
drivers/adc_stm32f4xx.c \
drivers/adc_stm32f4xx.c \
drivers/bus_i2c_stm32f10x.c \
drivers/dma_stm32f4xx.c \
drivers/gpio_stm32f4xx.c \
drivers/inverter.c \
drivers/serial_softserial.c \
drivers/light_ws2811strip_stm32f4xx.c \
drivers/pwm_output_stm32f4xx.c \
drivers/serial_uart_stm32f4xx.c \
drivers/system_stm32f4xx.c \
drivers/timer_stm32f4xx.c \
drivers/dma_stm32f4xx.c
drivers/timer_stm32f4xx.c
STM32F7xx_COMMON_SRC = \
startup_stm32f745xx.s \
target/system_stm32f7xx.c \
drivers/accgyro_mpu.c \
drivers/adc_stm32f7xx.c \
drivers/bus_i2c_hal.c \
drivers/dma_stm32f7xx.c \
drivers/gpio_stm32f7xx.c \
drivers/inverter.c \
drivers/bus_spi_hal.c \
drivers/pwm_output_stm32f7xx.c \
drivers/timer_hal.c \
drivers/timer_stm32f7xx.c \
drivers/pwm_output_hal.c \
drivers/system_stm32f7xx.c \
drivers/serial_uart_stm32f7xx.c \
drivers/serial_uart_hal.c
F7EXCLUDES = drivers/bus_spi.c \
drivers/bus_i2c.c \
drivers/timer.c \
drivers/pwm_output.c \
drivers/serial_uart.c
# check if target.mk supplied
ifeq ($(TARGET),$(filter $(TARGET),$(F4_TARGETS)))
TARGET_SRC := $(STM32F4xx_COMMON_SRC) $(TARGET_SRC)
else ifeq ($(TARGET),$(filter $(TARGET),$(F7_TARGETS)))
TARGET_SRC := $(STM32F7xx_COMMON_SRC) $(TARGET_SRC)
else ifeq ($(TARGET),$(filter $(TARGET),$(F3_TARGETS)))
TARGET_SRC := $(STM32F30x_COMMON_SRC) $(TARGET_SRC)
else ifeq ($(TARGET),$(filter $(TARGET),$(F1_TARGETS)))
@ -567,13 +679,17 @@ TARGET_SRC += \
io/flashfs.c
endif
ifeq ($(TARGET),$(filter $(TARGET),$(F4_TARGETS) $(F3_TARGETS)))
ifeq ($(TARGET),$(filter $(TARGET),$(F7_TARGETS) $(F4_TARGETS) $(F3_TARGETS)))
TARGET_SRC += $(HIGHEND_SRC)
else ifneq ($(filter HIGHEND,$(FEATURES)),)
TARGET_SRC += $(HIGHEND_SRC)
endif
TARGET_SRC += $(COMMON_SRC)
#excludes
ifeq ($(TARGET),$(filter $(TARGET),$(F7_TARGETS)))
TARGET_SRC := $(filter-out ${F7EXCLUDES}, $(TARGET_SRC))
endif
ifneq ($(filter SDCARD,$(FEATURES)),)
TARGET_SRC += \
@ -718,6 +834,8 @@ $(OBJECT_DIR)/$(TARGET)/%.o: %.S
$(V1) echo %% $(notdir $<)
$(V1) $(CC) -c -o $@ $(ASFLAGS) $<
## sample : Build all sample (travis) targets
sample: $(SAMPLE_TARGETS)
## all : Build all valid targets
all: $(VALID_TARGETS)
@ -793,7 +911,7 @@ cppcheck: $(CSOURCES)
cppcheck-result.xml: $(CSOURCES)
$(V0) $(CPPCHECK) --xml-version=2 2> cppcheck-result.xml
## mkdirs
# mkdirs
$(DL_DIR):
mkdir -p $@
@ -804,7 +922,7 @@ $(BUILD_DIR):
mkdir -p $@
## help : print this help message and exit
help: Makefile
help: Makefile make/tools.mk
$(V0) @echo ""
$(V0) @echo "Makefile for the $(FORKNAME) firmware"
$(V0) @echo ""
@ -815,7 +933,7 @@ help: Makefile
$(V0) @echo ""
$(V0) @echo "Valid TARGET values are: $(VALID_TARGETS)"
$(V0) @echo ""
$(V0) @sed -n 's/^## //p' $<
$(V0) @sed -n 's/^## //p' $?
## targets : print a list of all valid target platforms (for consumption by scripts)
targets:
@ -824,8 +942,9 @@ targets:
$(V0) @echo "Base target: $(BASE_TARGET)"
## test : run the cleanflight test suite
test:
$(V0) cd src/test && $(MAKE) test || true
## junittest : run the cleanflight test suite, producing Junit XML result files.
test junittest:
$(V0) cd src/test && $(MAKE) $@ || true
# rebuild everything when makefile changes
$(TARGET_OBJS) : Makefile

View file

@ -11,6 +11,7 @@ targets=("PUBLISHMETA=True" \
"TARGET=OMNIBUS" \
"TARGET=NAZE" \
"TARGET=AFROMINI" \
"TARGET=BEEBRAIN" \
"TARGET=RMDO" \
"TARGET=SPARKY" \
"TARGET=MOTOLAB" \

96
lib/main/MAVLink/checksum.h Executable file
View file

@ -0,0 +1,96 @@
#ifdef __cplusplus
extern "C" {
#endif
#ifndef _CHECKSUM_H_
#define _CHECKSUM_H_
// Visual Studio versions before 2010 don't have stdint.h, so we just error out.
#if (defined _MSC_VER) && (_MSC_VER < 1600)
#error "The C-MAVLink implementation requires Visual Studio 2010 or greater"
#endif
#include <stdint.h>
/**
*
* CALCULATE THE CHECKSUM
*
*/
#define X25_INIT_CRC 0xffff
#define X25_VALIDATE_CRC 0xf0b8
#ifndef HAVE_CRC_ACCUMULATE
/**
* @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);
}
#endif
/**
* @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, uint16_t length)
{
const uint8_t *p = (const uint8_t *)pBuffer;
while (length--) {
crc_accumulate(*p++, crcAccum);
}
}
#endif /* _CHECKSUM_H_ */
#ifdef __cplusplus
}
#endif

777
lib/main/MAVLink/common/common.h Executable file

File diff suppressed because one or more lines are too long

View file

@ -0,0 +1,27 @@
/** @file
* @brief MAVLink comm protocol built from common.xml
* @see http://mavlink.org
*/
#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

View file

@ -0,0 +1,249 @@
// MESSAGE ACTUATOR_CONTROL_TARGET PACKING
#define MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET 140
typedef struct __mavlink_actuator_control_target_t
{
uint64_t time_usec; ///< Timestamp (micros since boot or Unix epoch)
float controls[8]; ///< Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs.
uint8_t group_mlx; ///< Actuator group. The "_mlx" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances.
} mavlink_actuator_control_target_t;
#define MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN 41
#define MAVLINK_MSG_ID_140_LEN 41
#define MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_CRC 181
#define MAVLINK_MSG_ID_140_CRC 181
#define MAVLINK_MSG_ACTUATOR_CONTROL_TARGET_FIELD_CONTROLS_LEN 8
#define MAVLINK_MESSAGE_INFO_ACTUATOR_CONTROL_TARGET { \
"ACTUATOR_CONTROL_TARGET", \
3, \
{ { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_actuator_control_target_t, time_usec) }, \
{ "controls", NULL, MAVLINK_TYPE_FLOAT, 8, 8, offsetof(mavlink_actuator_control_target_t, controls) }, \
{ "group_mlx", NULL, MAVLINK_TYPE_UINT8_T, 0, 40, offsetof(mavlink_actuator_control_target_t, group_mlx) }, \
} \
}
/**
* @brief Pack a actuator_control_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 time_usec Timestamp (micros since boot or Unix epoch)
* @param group_mlx Actuator group. The "_mlx" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances.
* @param controls Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_actuator_control_target_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint64_t time_usec, uint8_t group_mlx, const float *controls)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN];
_mav_put_uint64_t(buf, 0, time_usec);
_mav_put_uint8_t(buf, 40, group_mlx);
_mav_put_float_array(buf, 8, controls, 8);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN);
#else
mavlink_actuator_control_target_t packet;
packet.time_usec = time_usec;
packet.group_mlx = group_mlx;
mav_array_memcpy(packet.controls, controls, sizeof(float)*8);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_CRC);
#else
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN);
#endif
}
/**
* @brief Pack a actuator_control_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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param time_usec Timestamp (micros since boot or Unix epoch)
* @param group_mlx Actuator group. The "_mlx" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances.
* @param controls Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_actuator_control_target_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint64_t time_usec,uint8_t group_mlx,const float *controls)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN];
_mav_put_uint64_t(buf, 0, time_usec);
_mav_put_uint8_t(buf, 40, group_mlx);
_mav_put_float_array(buf, 8, controls, 8);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN);
#else
mavlink_actuator_control_target_t packet;
packet.time_usec = time_usec;
packet.group_mlx = group_mlx;
mav_array_memcpy(packet.controls, controls, sizeof(float)*8);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_CRC);
#else
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN);
#endif
}
/**
* @brief Encode a actuator_control_target struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param actuator_control_target C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_actuator_control_target_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_actuator_control_target_t* actuator_control_target)
{
return mavlink_msg_actuator_control_target_pack(system_id, component_id, msg, actuator_control_target->time_usec, actuator_control_target->group_mlx, actuator_control_target->controls);
}
/**
* @brief Encode a actuator_control_target struct 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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param actuator_control_target C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_actuator_control_target_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_actuator_control_target_t* actuator_control_target)
{
return mavlink_msg_actuator_control_target_pack_chan(system_id, component_id, chan, msg, actuator_control_target->time_usec, actuator_control_target->group_mlx, actuator_control_target->controls);
}
/**
* @brief Send a actuator_control_target message
* @param chan MAVLink channel to send the message
*
* @param time_usec Timestamp (micros since boot or Unix epoch)
* @param group_mlx Actuator group. The "_mlx" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances.
* @param controls Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs.
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_actuator_control_target_send(mavlink_channel_t chan, uint64_t time_usec, uint8_t group_mlx, const float *controls)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN];
_mav_put_uint64_t(buf, 0, time_usec);
_mav_put_uint8_t(buf, 40, group_mlx);
_mav_put_float_array(buf, 8, controls, 8);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET, buf, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET, buf, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN);
#endif
#else
mavlink_actuator_control_target_t packet;
packet.time_usec = time_usec;
packet.group_mlx = group_mlx;
mav_array_memcpy(packet.controls, controls, sizeof(float)*8);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET, (const char *)&packet, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET, (const char *)&packet, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN);
#endif
#endif
}
#if MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This varient of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_actuator_control_target_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, uint8_t group_mlx, const float *controls)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
_mav_put_uint64_t(buf, 0, time_usec);
_mav_put_uint8_t(buf, 40, group_mlx);
_mav_put_float_array(buf, 8, controls, 8);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET, buf, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET, buf, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN);
#endif
#else
mavlink_actuator_control_target_t *packet = (mavlink_actuator_control_target_t *)msgbuf;
packet->time_usec = time_usec;
packet->group_mlx = group_mlx;
mav_array_memcpy(packet->controls, controls, sizeof(float)*8);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET, (const char *)packet, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET, (const char *)packet, MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN);
#endif
#endif
}
#endif
#endif
// MESSAGE ACTUATOR_CONTROL_TARGET UNPACKING
/**
* @brief Get field time_usec from actuator_control_target message
*
* @return Timestamp (micros since boot or Unix epoch)
*/
static inline uint64_t mavlink_msg_actuator_control_target_get_time_usec(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint64_t(msg, 0);
}
/**
* @brief Get field group_mlx from actuator_control_target message
*
* @return Actuator group. The "_mlx" indicates this is a multi-instance message and a MAVLink parser should use this field to difference between instances.
*/
static inline uint8_t mavlink_msg_actuator_control_target_get_group_mlx(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 40);
}
/**
* @brief Get field controls from actuator_control_target message
*
* @return Actuator controls. Normed to -1..+1 where 0 is neutral position. Throttle for single rotation direction motors is 0..1, negative range for reverse direction. Standard mapping for attitude controls (group 0): (index 0-7): roll, pitch, yaw, throttle, flaps, spoilers, airbrakes, landing gear. Load a pass-through mixer to repurpose them as generic outputs.
*/
static inline uint16_t mavlink_msg_actuator_control_target_get_controls(const mavlink_message_t* msg, float *controls)
{
return _MAV_RETURN_float_array(msg, controls, 8, 8);
}
/**
* @brief Decode a actuator_control_target message into a struct
*
* @param msg The message to decode
* @param actuator_control_target C-struct to decode the message contents into
*/
static inline void mavlink_msg_actuator_control_target_decode(const mavlink_message_t* msg, mavlink_actuator_control_target_t* actuator_control_target)
{
#if MAVLINK_NEED_BYTE_SWAP
actuator_control_target->time_usec = mavlink_msg_actuator_control_target_get_time_usec(msg);
mavlink_msg_actuator_control_target_get_controls(msg, actuator_control_target->controls);
actuator_control_target->group_mlx = mavlink_msg_actuator_control_target_get_group_mlx(msg);
#else
memcpy(actuator_control_target, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_ACTUATOR_CONTROL_TARGET_LEN);
#endif
}

View file

@ -0,0 +1,297 @@
// MESSAGE ATT_POS_MOCAP PACKING
#define MAVLINK_MSG_ID_ATT_POS_MOCAP 138
typedef struct __mavlink_att_pos_mocap_t
{
uint64_t time_usec; ///< Timestamp (micros since boot or Unix epoch)
float q[4]; ///< Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0)
float x; ///< X position in meters (NED)
float y; ///< Y position in meters (NED)
float z; ///< Z position in meters (NED)
} mavlink_att_pos_mocap_t;
#define MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN 36
#define MAVLINK_MSG_ID_138_LEN 36
#define MAVLINK_MSG_ID_ATT_POS_MOCAP_CRC 109
#define MAVLINK_MSG_ID_138_CRC 109
#define MAVLINK_MSG_ATT_POS_MOCAP_FIELD_Q_LEN 4
#define MAVLINK_MESSAGE_INFO_ATT_POS_MOCAP { \
"ATT_POS_MOCAP", \
5, \
{ { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_att_pos_mocap_t, time_usec) }, \
{ "q", NULL, MAVLINK_TYPE_FLOAT, 4, 8, offsetof(mavlink_att_pos_mocap_t, q) }, \
{ "x", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_att_pos_mocap_t, x) }, \
{ "y", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_att_pos_mocap_t, y) }, \
{ "z", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_att_pos_mocap_t, z) }, \
} \
}
/**
* @brief Pack a att_pos_mocap message
* @param system_id ID of this 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 (micros since boot or Unix epoch)
* @param q Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0)
* @param x X position in meters (NED)
* @param y Y position in meters (NED)
* @param z Z position in meters (NED)
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_att_pos_mocap_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint64_t time_usec, const float *q, float x, float y, float z)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN];
_mav_put_uint64_t(buf, 0, time_usec);
_mav_put_float(buf, 24, x);
_mav_put_float(buf, 28, y);
_mav_put_float(buf, 32, z);
_mav_put_float_array(buf, 8, q, 4);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN);
#else
mavlink_att_pos_mocap_t packet;
packet.time_usec = time_usec;
packet.x = x;
packet.y = y;
packet.z = z;
mav_array_memcpy(packet.q, q, sizeof(float)*4);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_ATT_POS_MOCAP;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN, MAVLINK_MSG_ID_ATT_POS_MOCAP_CRC);
#else
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN);
#endif
}
/**
* @brief Pack a att_pos_mocap 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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param time_usec Timestamp (micros since boot or Unix epoch)
* @param q Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0)
* @param x X position in meters (NED)
* @param y Y position in meters (NED)
* @param z Z position in meters (NED)
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_att_pos_mocap_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint64_t time_usec,const float *q,float x,float y,float z)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN];
_mav_put_uint64_t(buf, 0, time_usec);
_mav_put_float(buf, 24, x);
_mav_put_float(buf, 28, y);
_mav_put_float(buf, 32, z);
_mav_put_float_array(buf, 8, q, 4);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN);
#else
mavlink_att_pos_mocap_t packet;
packet.time_usec = time_usec;
packet.x = x;
packet.y = y;
packet.z = z;
mav_array_memcpy(packet.q, q, sizeof(float)*4);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_ATT_POS_MOCAP;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN, MAVLINK_MSG_ID_ATT_POS_MOCAP_CRC);
#else
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN);
#endif
}
/**
* @brief Encode a att_pos_mocap struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param att_pos_mocap C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_att_pos_mocap_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_att_pos_mocap_t* att_pos_mocap)
{
return mavlink_msg_att_pos_mocap_pack(system_id, component_id, msg, att_pos_mocap->time_usec, att_pos_mocap->q, att_pos_mocap->x, att_pos_mocap->y, att_pos_mocap->z);
}
/**
* @brief Encode a att_pos_mocap struct 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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param att_pos_mocap C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_att_pos_mocap_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_att_pos_mocap_t* att_pos_mocap)
{
return mavlink_msg_att_pos_mocap_pack_chan(system_id, component_id, chan, msg, att_pos_mocap->time_usec, att_pos_mocap->q, att_pos_mocap->x, att_pos_mocap->y, att_pos_mocap->z);
}
/**
* @brief Send a att_pos_mocap message
* @param chan MAVLink channel to send the message
*
* @param time_usec Timestamp (micros since boot or Unix epoch)
* @param q Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0)
* @param x X position in meters (NED)
* @param y Y position in meters (NED)
* @param z Z position in meters (NED)
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_att_pos_mocap_send(mavlink_channel_t chan, uint64_t time_usec, const float *q, float x, float y, float z)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN];
_mav_put_uint64_t(buf, 0, time_usec);
_mav_put_float(buf, 24, x);
_mav_put_float(buf, 28, y);
_mav_put_float(buf, 32, z);
_mav_put_float_array(buf, 8, q, 4);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATT_POS_MOCAP, buf, MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN, MAVLINK_MSG_ID_ATT_POS_MOCAP_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATT_POS_MOCAP, buf, MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN);
#endif
#else
mavlink_att_pos_mocap_t packet;
packet.time_usec = time_usec;
packet.x = x;
packet.y = y;
packet.z = z;
mav_array_memcpy(packet.q, q, sizeof(float)*4);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATT_POS_MOCAP, (const char *)&packet, MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN, MAVLINK_MSG_ID_ATT_POS_MOCAP_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATT_POS_MOCAP, (const char *)&packet, MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN);
#endif
#endif
}
#if MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This varient of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_att_pos_mocap_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, const float *q, float x, float y, float z)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
_mav_put_uint64_t(buf, 0, time_usec);
_mav_put_float(buf, 24, x);
_mav_put_float(buf, 28, y);
_mav_put_float(buf, 32, z);
_mav_put_float_array(buf, 8, q, 4);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATT_POS_MOCAP, buf, MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN, MAVLINK_MSG_ID_ATT_POS_MOCAP_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATT_POS_MOCAP, buf, MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN);
#endif
#else
mavlink_att_pos_mocap_t *packet = (mavlink_att_pos_mocap_t *)msgbuf;
packet->time_usec = time_usec;
packet->x = x;
packet->y = y;
packet->z = z;
mav_array_memcpy(packet->q, q, sizeof(float)*4);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATT_POS_MOCAP, (const char *)packet, MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN, MAVLINK_MSG_ID_ATT_POS_MOCAP_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATT_POS_MOCAP, (const char *)packet, MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN);
#endif
#endif
}
#endif
#endif
// MESSAGE ATT_POS_MOCAP UNPACKING
/**
* @brief Get field time_usec from att_pos_mocap message
*
* @return Timestamp (micros since boot or Unix epoch)
*/
static inline uint64_t mavlink_msg_att_pos_mocap_get_time_usec(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint64_t(msg, 0);
}
/**
* @brief Get field q from att_pos_mocap message
*
* @return Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0)
*/
static inline uint16_t mavlink_msg_att_pos_mocap_get_q(const mavlink_message_t* msg, float *q)
{
return _MAV_RETURN_float_array(msg, q, 4, 8);
}
/**
* @brief Get field x from att_pos_mocap message
*
* @return X position in meters (NED)
*/
static inline float mavlink_msg_att_pos_mocap_get_x(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 24);
}
/**
* @brief Get field y from att_pos_mocap message
*
* @return Y position in meters (NED)
*/
static inline float mavlink_msg_att_pos_mocap_get_y(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 28);
}
/**
* @brief Get field z from att_pos_mocap message
*
* @return Z position in meters (NED)
*/
static inline float mavlink_msg_att_pos_mocap_get_z(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 32);
}
/**
* @brief Decode a att_pos_mocap message into a struct
*
* @param msg The message to decode
* @param att_pos_mocap C-struct to decode the message contents into
*/
static inline void mavlink_msg_att_pos_mocap_decode(const mavlink_message_t* msg, mavlink_att_pos_mocap_t* att_pos_mocap)
{
#if MAVLINK_NEED_BYTE_SWAP
att_pos_mocap->time_usec = mavlink_msg_att_pos_mocap_get_time_usec(msg);
mavlink_msg_att_pos_mocap_get_q(msg, att_pos_mocap->q);
att_pos_mocap->x = mavlink_msg_att_pos_mocap_get_x(msg);
att_pos_mocap->y = mavlink_msg_att_pos_mocap_get_y(msg);
att_pos_mocap->z = mavlink_msg_att_pos_mocap_get_z(msg);
#else
memcpy(att_pos_mocap, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN);
#endif
}

View file

@ -0,0 +1,353 @@
// 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, -pi..+pi)
float pitch; ///< Pitch angle (rad, -pi..+pi)
float yaw; ///< Yaw angle (rad, -pi..+pi)
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_MSG_ID_ATTITUDE_CRC 39
#define MAVLINK_MSG_ID_30_CRC 39
#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, -pi..+pi)
* @param pitch Pitch angle (rad, -pi..+pi)
* @param yaw Yaw angle (rad, -pi..+pi)
* @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[MAVLINK_MSG_ID_ATTITUDE_LEN];
_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, MAVLINK_MSG_ID_ATTITUDE_LEN);
#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, MAVLINK_MSG_ID_ATTITUDE_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_ATTITUDE;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ATTITUDE_LEN, MAVLINK_MSG_ID_ATTITUDE_CRC);
#else
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ATTITUDE_LEN);
#endif
}
/**
* @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 will be 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, -pi..+pi)
* @param pitch Pitch angle (rad, -pi..+pi)
* @param yaw Yaw angle (rad, -pi..+pi)
* @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[MAVLINK_MSG_ID_ATTITUDE_LEN];
_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, MAVLINK_MSG_ID_ATTITUDE_LEN);
#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, MAVLINK_MSG_ID_ATTITUDE_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_ATTITUDE;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ATTITUDE_LEN, MAVLINK_MSG_ID_ATTITUDE_CRC);
#else
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ATTITUDE_LEN);
#endif
}
/**
* @brief Encode a attitude struct
*
* @param system_id ID of this 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 Encode a attitude struct 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 will be sent over
* @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_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_attitude_t* attitude)
{
return mavlink_msg_attitude_pack_chan(system_id, component_id, chan, 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, -pi..+pi)
* @param pitch Pitch angle (rad, -pi..+pi)
* @param yaw Yaw angle (rad, -pi..+pi)
* @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[MAVLINK_MSG_ID_ATTITUDE_LEN];
_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);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE, buf, MAVLINK_MSG_ID_ATTITUDE_LEN, MAVLINK_MSG_ID_ATTITUDE_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE, buf, MAVLINK_MSG_ID_ATTITUDE_LEN);
#endif
#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;
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE, (const char *)&packet, MAVLINK_MSG_ID_ATTITUDE_LEN, MAVLINK_MSG_ID_ATTITUDE_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE, (const char *)&packet, MAVLINK_MSG_ID_ATTITUDE_LEN);
#endif
#endif
}
#if MAVLINK_MSG_ID_ATTITUDE_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This varient of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_attitude_send_buf(mavlink_message_t *msgbuf, 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 = (char *)msgbuf;
_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);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE, buf, MAVLINK_MSG_ID_ATTITUDE_LEN, MAVLINK_MSG_ID_ATTITUDE_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE, buf, MAVLINK_MSG_ID_ATTITUDE_LEN);
#endif
#else
mavlink_attitude_t *packet = (mavlink_attitude_t *)msgbuf;
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;
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE, (const char *)packet, MAVLINK_MSG_ID_ATTITUDE_LEN, MAVLINK_MSG_ID_ATTITUDE_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE, (const char *)packet, MAVLINK_MSG_ID_ATTITUDE_LEN);
#endif
#endif
}
#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, -pi..+pi)
*/
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, -pi..+pi)
*/
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, -pi..+pi)
*/
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), MAVLINK_MSG_ID_ATTITUDE_LEN);
#endif
}

View file

@ -0,0 +1,377 @@
// 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, w (1 in null-rotation)
float q2; ///< Quaternion component 2, x (0 in null-rotation)
float q3; ///< Quaternion component 3, y (0 in null-rotation)
float q4; ///< Quaternion component 4, z (0 in null-rotation)
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_MSG_ID_ATTITUDE_QUATERNION_CRC 246
#define MAVLINK_MSG_ID_31_CRC 246
#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, w (1 in null-rotation)
* @param q2 Quaternion component 2, x (0 in null-rotation)
* @param q3 Quaternion component 3, y (0 in null-rotation)
* @param q4 Quaternion component 4, z (0 in null-rotation)
* @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[MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN];
_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, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN);
#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, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_ATTITUDE_QUATERNION;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_CRC);
#else
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN);
#endif
}
/**
* @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 will be 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, w (1 in null-rotation)
* @param q2 Quaternion component 2, x (0 in null-rotation)
* @param q3 Quaternion component 3, y (0 in null-rotation)
* @param q4 Quaternion component 4, z (0 in null-rotation)
* @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[MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN];
_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, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN);
#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, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_ATTITUDE_QUATERNION;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_CRC);
#else
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN);
#endif
}
/**
* @brief Encode a attitude_quaternion struct
*
* @param system_id ID of this 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 Encode a attitude_quaternion struct 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 will be sent over
* @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_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_attitude_quaternion_t* attitude_quaternion)
{
return mavlink_msg_attitude_quaternion_pack_chan(system_id, component_id, chan, 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, w (1 in null-rotation)
* @param q2 Quaternion component 2, x (0 in null-rotation)
* @param q3 Quaternion component 3, y (0 in null-rotation)
* @param q4 Quaternion component 4, z (0 in null-rotation)
* @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[MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN];
_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);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION, buf, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION, buf, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN);
#endif
#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;
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION, (const char *)&packet, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION, (const char *)&packet, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN);
#endif
#endif
}
#if MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This varient of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_attitude_quaternion_send_buf(mavlink_message_t *msgbuf, 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 = (char *)msgbuf;
_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);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION, buf, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION, buf, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN);
#endif
#else
mavlink_attitude_quaternion_t *packet = (mavlink_attitude_quaternion_t *)msgbuf;
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;
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION, (const char *)packet, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION, (const char *)packet, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN);
#endif
#endif
}
#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, w (1 in null-rotation)
*/
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, x (0 in null-rotation)
*/
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, y (0 in null-rotation)
*/
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, z (0 in null-rotation)
*/
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), MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN);
#endif
}

View file

@ -0,0 +1,322 @@
// MESSAGE ATTITUDE_QUATERNION_COV PACKING
#define MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV 61
typedef struct __mavlink_attitude_quaternion_cov_t
{
uint32_t time_boot_ms; ///< Timestamp (milliseconds since system boot)
float q[4]; ///< Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation)
float rollspeed; ///< Roll angular speed (rad/s)
float pitchspeed; ///< Pitch angular speed (rad/s)
float yawspeed; ///< Yaw angular speed (rad/s)
float covariance[9]; ///< Attitude covariance
} mavlink_attitude_quaternion_cov_t;
#define MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN 68
#define MAVLINK_MSG_ID_61_LEN 68
#define MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_CRC 153
#define MAVLINK_MSG_ID_61_CRC 153
#define MAVLINK_MSG_ATTITUDE_QUATERNION_COV_FIELD_Q_LEN 4
#define MAVLINK_MSG_ATTITUDE_QUATERNION_COV_FIELD_COVARIANCE_LEN 9
#define MAVLINK_MESSAGE_INFO_ATTITUDE_QUATERNION_COV { \
"ATTITUDE_QUATERNION_COV", \
6, \
{ { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_attitude_quaternion_cov_t, time_boot_ms) }, \
{ "q", NULL, MAVLINK_TYPE_FLOAT, 4, 4, offsetof(mavlink_attitude_quaternion_cov_t, q) }, \
{ "rollspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_attitude_quaternion_cov_t, rollspeed) }, \
{ "pitchspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_attitude_quaternion_cov_t, pitchspeed) }, \
{ "yawspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_attitude_quaternion_cov_t, yawspeed) }, \
{ "covariance", NULL, MAVLINK_TYPE_FLOAT, 9, 32, offsetof(mavlink_attitude_quaternion_cov_t, covariance) }, \
} \
}
/**
* @brief Pack a attitude_quaternion_cov message
* @param system_id ID of this 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 q Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation)
* @param rollspeed Roll angular speed (rad/s)
* @param pitchspeed Pitch angular speed (rad/s)
* @param yawspeed Yaw angular speed (rad/s)
* @param covariance Attitude covariance
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_attitude_quaternion_cov_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint32_t time_boot_ms, const float *q, float rollspeed, float pitchspeed, float yawspeed, const float *covariance)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN];
_mav_put_uint32_t(buf, 0, time_boot_ms);
_mav_put_float(buf, 20, rollspeed);
_mav_put_float(buf, 24, pitchspeed);
_mav_put_float(buf, 28, yawspeed);
_mav_put_float_array(buf, 4, q, 4);
_mav_put_float_array(buf, 32, covariance, 9);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN);
#else
mavlink_attitude_quaternion_cov_t packet;
packet.time_boot_ms = time_boot_ms;
packet.rollspeed = rollspeed;
packet.pitchspeed = pitchspeed;
packet.yawspeed = yawspeed;
mav_array_memcpy(packet.q, q, sizeof(float)*4);
mav_array_memcpy(packet.covariance, covariance, sizeof(float)*9);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_CRC);
#else
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN);
#endif
}
/**
* @brief Pack a attitude_quaternion_cov 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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param time_boot_ms Timestamp (milliseconds since system boot)
* @param q Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation)
* @param rollspeed Roll angular speed (rad/s)
* @param pitchspeed Pitch angular speed (rad/s)
* @param yawspeed Yaw angular speed (rad/s)
* @param covariance Attitude covariance
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_attitude_quaternion_cov_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint32_t time_boot_ms,const float *q,float rollspeed,float pitchspeed,float yawspeed,const float *covariance)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN];
_mav_put_uint32_t(buf, 0, time_boot_ms);
_mav_put_float(buf, 20, rollspeed);
_mav_put_float(buf, 24, pitchspeed);
_mav_put_float(buf, 28, yawspeed);
_mav_put_float_array(buf, 4, q, 4);
_mav_put_float_array(buf, 32, covariance, 9);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN);
#else
mavlink_attitude_quaternion_cov_t packet;
packet.time_boot_ms = time_boot_ms;
packet.rollspeed = rollspeed;
packet.pitchspeed = pitchspeed;
packet.yawspeed = yawspeed;
mav_array_memcpy(packet.q, q, sizeof(float)*4);
mav_array_memcpy(packet.covariance, covariance, sizeof(float)*9);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_CRC);
#else
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN);
#endif
}
/**
* @brief Encode a attitude_quaternion_cov struct
*
* @param system_id ID of this 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_cov C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_attitude_quaternion_cov_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_attitude_quaternion_cov_t* attitude_quaternion_cov)
{
return mavlink_msg_attitude_quaternion_cov_pack(system_id, component_id, msg, attitude_quaternion_cov->time_boot_ms, attitude_quaternion_cov->q, attitude_quaternion_cov->rollspeed, attitude_quaternion_cov->pitchspeed, attitude_quaternion_cov->yawspeed, attitude_quaternion_cov->covariance);
}
/**
* @brief Encode a attitude_quaternion_cov struct 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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param attitude_quaternion_cov C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_attitude_quaternion_cov_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_attitude_quaternion_cov_t* attitude_quaternion_cov)
{
return mavlink_msg_attitude_quaternion_cov_pack_chan(system_id, component_id, chan, msg, attitude_quaternion_cov->time_boot_ms, attitude_quaternion_cov->q, attitude_quaternion_cov->rollspeed, attitude_quaternion_cov->pitchspeed, attitude_quaternion_cov->yawspeed, attitude_quaternion_cov->covariance);
}
/**
* @brief Send a attitude_quaternion_cov message
* @param chan MAVLink channel to send the message
*
* @param time_boot_ms Timestamp (milliseconds since system boot)
* @param q Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation)
* @param rollspeed Roll angular speed (rad/s)
* @param pitchspeed Pitch angular speed (rad/s)
* @param yawspeed Yaw angular speed (rad/s)
* @param covariance Attitude covariance
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_attitude_quaternion_cov_send(mavlink_channel_t chan, uint32_t time_boot_ms, const float *q, float rollspeed, float pitchspeed, float yawspeed, const float *covariance)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN];
_mav_put_uint32_t(buf, 0, time_boot_ms);
_mav_put_float(buf, 20, rollspeed);
_mav_put_float(buf, 24, pitchspeed);
_mav_put_float(buf, 28, yawspeed);
_mav_put_float_array(buf, 4, q, 4);
_mav_put_float_array(buf, 32, covariance, 9);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV, buf, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV, buf, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN);
#endif
#else
mavlink_attitude_quaternion_cov_t packet;
packet.time_boot_ms = time_boot_ms;
packet.rollspeed = rollspeed;
packet.pitchspeed = pitchspeed;
packet.yawspeed = yawspeed;
mav_array_memcpy(packet.q, q, sizeof(float)*4);
mav_array_memcpy(packet.covariance, covariance, sizeof(float)*9);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV, (const char *)&packet, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV, (const char *)&packet, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN);
#endif
#endif
}
#if MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This varient of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_attitude_quaternion_cov_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, const float *q, float rollspeed, float pitchspeed, float yawspeed, const float *covariance)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
_mav_put_uint32_t(buf, 0, time_boot_ms);
_mav_put_float(buf, 20, rollspeed);
_mav_put_float(buf, 24, pitchspeed);
_mav_put_float(buf, 28, yawspeed);
_mav_put_float_array(buf, 4, q, 4);
_mav_put_float_array(buf, 32, covariance, 9);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV, buf, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV, buf, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN);
#endif
#else
mavlink_attitude_quaternion_cov_t *packet = (mavlink_attitude_quaternion_cov_t *)msgbuf;
packet->time_boot_ms = time_boot_ms;
packet->rollspeed = rollspeed;
packet->pitchspeed = pitchspeed;
packet->yawspeed = yawspeed;
mav_array_memcpy(packet->q, q, sizeof(float)*4);
mav_array_memcpy(packet->covariance, covariance, sizeof(float)*9);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV, (const char *)packet, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV, (const char *)packet, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN);
#endif
#endif
}
#endif
#endif
// MESSAGE ATTITUDE_QUATERNION_COV UNPACKING
/**
* @brief Get field time_boot_ms from attitude_quaternion_cov message
*
* @return Timestamp (milliseconds since system boot)
*/
static inline uint32_t mavlink_msg_attitude_quaternion_cov_get_time_boot_ms(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint32_t(msg, 0);
}
/**
* @brief Get field q from attitude_quaternion_cov message
*
* @return Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation)
*/
static inline uint16_t mavlink_msg_attitude_quaternion_cov_get_q(const mavlink_message_t* msg, float *q)
{
return _MAV_RETURN_float_array(msg, q, 4, 4);
}
/**
* @brief Get field rollspeed from attitude_quaternion_cov message
*
* @return Roll angular speed (rad/s)
*/
static inline float mavlink_msg_attitude_quaternion_cov_get_rollspeed(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 20);
}
/**
* @brief Get field pitchspeed from attitude_quaternion_cov message
*
* @return Pitch angular speed (rad/s)
*/
static inline float mavlink_msg_attitude_quaternion_cov_get_pitchspeed(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 24);
}
/**
* @brief Get field yawspeed from attitude_quaternion_cov message
*
* @return Yaw angular speed (rad/s)
*/
static inline float mavlink_msg_attitude_quaternion_cov_get_yawspeed(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 28);
}
/**
* @brief Get field covariance from attitude_quaternion_cov message
*
* @return Attitude covariance
*/
static inline uint16_t mavlink_msg_attitude_quaternion_cov_get_covariance(const mavlink_message_t* msg, float *covariance)
{
return _MAV_RETURN_float_array(msg, covariance, 9, 32);
}
/**
* @brief Decode a attitude_quaternion_cov message into a struct
*
* @param msg The message to decode
* @param attitude_quaternion_cov C-struct to decode the message contents into
*/
static inline void mavlink_msg_attitude_quaternion_cov_decode(const mavlink_message_t* msg, mavlink_attitude_quaternion_cov_t* attitude_quaternion_cov)
{
#if MAVLINK_NEED_BYTE_SWAP
attitude_quaternion_cov->time_boot_ms = mavlink_msg_attitude_quaternion_cov_get_time_boot_ms(msg);
mavlink_msg_attitude_quaternion_cov_get_q(msg, attitude_quaternion_cov->q);
attitude_quaternion_cov->rollspeed = mavlink_msg_attitude_quaternion_cov_get_rollspeed(msg);
attitude_quaternion_cov->pitchspeed = mavlink_msg_attitude_quaternion_cov_get_pitchspeed(msg);
attitude_quaternion_cov->yawspeed = mavlink_msg_attitude_quaternion_cov_get_yawspeed(msg);
mavlink_msg_attitude_quaternion_cov_get_covariance(msg, attitude_quaternion_cov->covariance);
#else
memcpy(attitude_quaternion_cov, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_ATTITUDE_QUATERNION_COV_LEN);
#endif
}

View file

@ -0,0 +1,345 @@
// MESSAGE ATTITUDE_TARGET PACKING
#define MAVLINK_MSG_ID_ATTITUDE_TARGET 83
typedef struct __mavlink_attitude_target_t
{
uint32_t time_boot_ms; ///< Timestamp in milliseconds since system boot
float q[4]; ///< Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0)
float body_roll_rate; ///< Body roll rate in radians per second
float body_pitch_rate; ///< Body roll rate in radians per second
float body_yaw_rate; ///< Body roll rate in radians per second
float thrust; ///< Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust)
uint8_t type_mask; ///< Mappings: If any of these bits are set, the corresponding input should be ignored: bit 1: body roll rate, bit 2: body pitch rate, bit 3: body yaw rate. bit 4-bit 7: reserved, bit 8: attitude
} mavlink_attitude_target_t;
#define MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN 37
#define MAVLINK_MSG_ID_83_LEN 37
#define MAVLINK_MSG_ID_ATTITUDE_TARGET_CRC 22
#define MAVLINK_MSG_ID_83_CRC 22
#define MAVLINK_MSG_ATTITUDE_TARGET_FIELD_Q_LEN 4
#define MAVLINK_MESSAGE_INFO_ATTITUDE_TARGET { \
"ATTITUDE_TARGET", \
7, \
{ { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_attitude_target_t, time_boot_ms) }, \
{ "q", NULL, MAVLINK_TYPE_FLOAT, 4, 4, offsetof(mavlink_attitude_target_t, q) }, \
{ "body_roll_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_attitude_target_t, body_roll_rate) }, \
{ "body_pitch_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_attitude_target_t, body_pitch_rate) }, \
{ "body_yaw_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_attitude_target_t, body_yaw_rate) }, \
{ "thrust", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_attitude_target_t, thrust) }, \
{ "type_mask", NULL, MAVLINK_TYPE_UINT8_T, 0, 36, offsetof(mavlink_attitude_target_t, type_mask) }, \
} \
}
/**
* @brief Pack a attitude_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 time_boot_ms Timestamp in milliseconds since system boot
* @param type_mask Mappings: If any of these bits are set, the corresponding input should be ignored: bit 1: body roll rate, bit 2: body pitch rate, bit 3: body yaw rate. bit 4-bit 7: reserved, bit 8: attitude
* @param q Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0)
* @param body_roll_rate Body roll rate in radians per second
* @param body_pitch_rate Body roll rate in radians per second
* @param body_yaw_rate Body roll rate in radians per second
* @param thrust Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust)
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_attitude_target_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint32_t time_boot_ms, uint8_t type_mask, const float *q, float body_roll_rate, float body_pitch_rate, float body_yaw_rate, float thrust)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN];
_mav_put_uint32_t(buf, 0, time_boot_ms);
_mav_put_float(buf, 20, body_roll_rate);
_mav_put_float(buf, 24, body_pitch_rate);
_mav_put_float(buf, 28, body_yaw_rate);
_mav_put_float(buf, 32, thrust);
_mav_put_uint8_t(buf, 36, type_mask);
_mav_put_float_array(buf, 4, q, 4);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN);
#else
mavlink_attitude_target_t packet;
packet.time_boot_ms = time_boot_ms;
packet.body_roll_rate = body_roll_rate;
packet.body_pitch_rate = body_pitch_rate;
packet.body_yaw_rate = body_yaw_rate;
packet.thrust = thrust;
packet.type_mask = type_mask;
mav_array_memcpy(packet.q, q, sizeof(float)*4);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_ATTITUDE_TARGET;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN, MAVLINK_MSG_ID_ATTITUDE_TARGET_CRC);
#else
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN);
#endif
}
/**
* @brief Pack a attitude_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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param time_boot_ms Timestamp in milliseconds since system boot
* @param type_mask Mappings: If any of these bits are set, the corresponding input should be ignored: bit 1: body roll rate, bit 2: body pitch rate, bit 3: body yaw rate. bit 4-bit 7: reserved, bit 8: attitude
* @param q Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0)
* @param body_roll_rate Body roll rate in radians per second
* @param body_pitch_rate Body roll rate in radians per second
* @param body_yaw_rate Body roll rate in radians per second
* @param thrust Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust)
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_attitude_target_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint32_t time_boot_ms,uint8_t type_mask,const float *q,float body_roll_rate,float body_pitch_rate,float body_yaw_rate,float thrust)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN];
_mav_put_uint32_t(buf, 0, time_boot_ms);
_mav_put_float(buf, 20, body_roll_rate);
_mav_put_float(buf, 24, body_pitch_rate);
_mav_put_float(buf, 28, body_yaw_rate);
_mav_put_float(buf, 32, thrust);
_mav_put_uint8_t(buf, 36, type_mask);
_mav_put_float_array(buf, 4, q, 4);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN);
#else
mavlink_attitude_target_t packet;
packet.time_boot_ms = time_boot_ms;
packet.body_roll_rate = body_roll_rate;
packet.body_pitch_rate = body_pitch_rate;
packet.body_yaw_rate = body_yaw_rate;
packet.thrust = thrust;
packet.type_mask = type_mask;
mav_array_memcpy(packet.q, q, sizeof(float)*4);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_ATTITUDE_TARGET;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN, MAVLINK_MSG_ID_ATTITUDE_TARGET_CRC);
#else
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN);
#endif
}
/**
* @brief Encode a attitude_target struct
*
* @param system_id ID of this 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_target C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_attitude_target_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_attitude_target_t* attitude_target)
{
return mavlink_msg_attitude_target_pack(system_id, component_id, msg, attitude_target->time_boot_ms, attitude_target->type_mask, attitude_target->q, attitude_target->body_roll_rate, attitude_target->body_pitch_rate, attitude_target->body_yaw_rate, attitude_target->thrust);
}
/**
* @brief Encode a attitude_target struct 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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param attitude_target C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_attitude_target_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_attitude_target_t* attitude_target)
{
return mavlink_msg_attitude_target_pack_chan(system_id, component_id, chan, msg, attitude_target->time_boot_ms, attitude_target->type_mask, attitude_target->q, attitude_target->body_roll_rate, attitude_target->body_pitch_rate, attitude_target->body_yaw_rate, attitude_target->thrust);
}
/**
* @brief Send a attitude_target message
* @param chan MAVLink channel to send the message
*
* @param time_boot_ms Timestamp in milliseconds since system boot
* @param type_mask Mappings: If any of these bits are set, the corresponding input should be ignored: bit 1: body roll rate, bit 2: body pitch rate, bit 3: body yaw rate. bit 4-bit 7: reserved, bit 8: attitude
* @param q Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0)
* @param body_roll_rate Body roll rate in radians per second
* @param body_pitch_rate Body roll rate in radians per second
* @param body_yaw_rate Body roll rate in radians per second
* @param thrust Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust)
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_attitude_target_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t type_mask, const float *q, float body_roll_rate, float body_pitch_rate, float body_yaw_rate, float thrust)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN];
_mav_put_uint32_t(buf, 0, time_boot_ms);
_mav_put_float(buf, 20, body_roll_rate);
_mav_put_float(buf, 24, body_pitch_rate);
_mav_put_float(buf, 28, body_yaw_rate);
_mav_put_float(buf, 32, thrust);
_mav_put_uint8_t(buf, 36, type_mask);
_mav_put_float_array(buf, 4, q, 4);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_TARGET, buf, MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN, MAVLINK_MSG_ID_ATTITUDE_TARGET_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_TARGET, buf, MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN);
#endif
#else
mavlink_attitude_target_t packet;
packet.time_boot_ms = time_boot_ms;
packet.body_roll_rate = body_roll_rate;
packet.body_pitch_rate = body_pitch_rate;
packet.body_yaw_rate = body_yaw_rate;
packet.thrust = thrust;
packet.type_mask = type_mask;
mav_array_memcpy(packet.q, q, sizeof(float)*4);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_TARGET, (const char *)&packet, MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN, MAVLINK_MSG_ID_ATTITUDE_TARGET_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_TARGET, (const char *)&packet, MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN);
#endif
#endif
}
#if MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This varient of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_attitude_target_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t type_mask, const float *q, float body_roll_rate, float body_pitch_rate, float body_yaw_rate, float thrust)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
_mav_put_uint32_t(buf, 0, time_boot_ms);
_mav_put_float(buf, 20, body_roll_rate);
_mav_put_float(buf, 24, body_pitch_rate);
_mav_put_float(buf, 28, body_yaw_rate);
_mav_put_float(buf, 32, thrust);
_mav_put_uint8_t(buf, 36, type_mask);
_mav_put_float_array(buf, 4, q, 4);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_TARGET, buf, MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN, MAVLINK_MSG_ID_ATTITUDE_TARGET_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_TARGET, buf, MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN);
#endif
#else
mavlink_attitude_target_t *packet = (mavlink_attitude_target_t *)msgbuf;
packet->time_boot_ms = time_boot_ms;
packet->body_roll_rate = body_roll_rate;
packet->body_pitch_rate = body_pitch_rate;
packet->body_yaw_rate = body_yaw_rate;
packet->thrust = thrust;
packet->type_mask = type_mask;
mav_array_memcpy(packet->q, q, sizeof(float)*4);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_TARGET, (const char *)packet, MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN, MAVLINK_MSG_ID_ATTITUDE_TARGET_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_TARGET, (const char *)packet, MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN);
#endif
#endif
}
#endif
#endif
// MESSAGE ATTITUDE_TARGET UNPACKING
/**
* @brief Get field time_boot_ms from attitude_target message
*
* @return Timestamp in milliseconds since system boot
*/
static inline uint32_t mavlink_msg_attitude_target_get_time_boot_ms(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint32_t(msg, 0);
}
/**
* @brief Get field type_mask from attitude_target message
*
* @return Mappings: If any of these bits are set, the corresponding input should be ignored: bit 1: body roll rate, bit 2: body pitch rate, bit 3: body yaw rate. bit 4-bit 7: reserved, bit 8: attitude
*/
static inline uint8_t mavlink_msg_attitude_target_get_type_mask(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 36);
}
/**
* @brief Get field q from attitude_target message
*
* @return Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0)
*/
static inline uint16_t mavlink_msg_attitude_target_get_q(const mavlink_message_t* msg, float *q)
{
return _MAV_RETURN_float_array(msg, q, 4, 4);
}
/**
* @brief Get field body_roll_rate from attitude_target message
*
* @return Body roll rate in radians per second
*/
static inline float mavlink_msg_attitude_target_get_body_roll_rate(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 20);
}
/**
* @brief Get field body_pitch_rate from attitude_target message
*
* @return Body roll rate in radians per second
*/
static inline float mavlink_msg_attitude_target_get_body_pitch_rate(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 24);
}
/**
* @brief Get field body_yaw_rate from attitude_target message
*
* @return Body roll rate in radians per second
*/
static inline float mavlink_msg_attitude_target_get_body_yaw_rate(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 28);
}
/**
* @brief Get field thrust from attitude_target message
*
* @return Collective thrust, normalized to 0 .. 1 (-1 .. 1 for vehicles capable of reverse trust)
*/
static inline float mavlink_msg_attitude_target_get_thrust(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 32);
}
/**
* @brief Decode a attitude_target message into a struct
*
* @param msg The message to decode
* @param attitude_target C-struct to decode the message contents into
*/
static inline void mavlink_msg_attitude_target_decode(const mavlink_message_t* msg, mavlink_attitude_target_t* attitude_target)
{
#if MAVLINK_NEED_BYTE_SWAP
attitude_target->time_boot_ms = mavlink_msg_attitude_target_get_time_boot_ms(msg);
mavlink_msg_attitude_target_get_q(msg, attitude_target->q);
attitude_target->body_roll_rate = mavlink_msg_attitude_target_get_body_roll_rate(msg);
attitude_target->body_pitch_rate = mavlink_msg_attitude_target_get_body_pitch_rate(msg);
attitude_target->body_yaw_rate = mavlink_msg_attitude_target_get_body_yaw_rate(msg);
attitude_target->thrust = mavlink_msg_attitude_target_get_thrust(msg);
attitude_target->type_mask = mavlink_msg_attitude_target_get_type_mask(msg);
#else
memcpy(attitude_target, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN);
#endif
}

View file

@ -0,0 +1,209 @@
// 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_ID_AUTH_KEY_CRC 119
#define MAVLINK_MSG_ID_7_CRC 119
#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[MAVLINK_MSG_ID_AUTH_KEY_LEN];
_mav_put_char_array(buf, 0, key, 32);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_AUTH_KEY_LEN);
#else
mavlink_auth_key_t packet;
mav_array_memcpy(packet.key, key, sizeof(char)*32);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_AUTH_KEY_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_AUTH_KEY;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_AUTH_KEY_LEN, MAVLINK_MSG_ID_AUTH_KEY_CRC);
#else
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_AUTH_KEY_LEN);
#endif
}
/**
* @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 will be 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[MAVLINK_MSG_ID_AUTH_KEY_LEN];
_mav_put_char_array(buf, 0, key, 32);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_AUTH_KEY_LEN);
#else
mavlink_auth_key_t packet;
mav_array_memcpy(packet.key, key, sizeof(char)*32);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_AUTH_KEY_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_AUTH_KEY;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_AUTH_KEY_LEN, MAVLINK_MSG_ID_AUTH_KEY_CRC);
#else
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_AUTH_KEY_LEN);
#endif
}
/**
* @brief Encode a auth_key struct
*
* @param system_id ID of this 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 Encode a auth_key struct 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 will be sent over
* @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_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_auth_key_t* auth_key)
{
return mavlink_msg_auth_key_pack_chan(system_id, component_id, chan, 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[MAVLINK_MSG_ID_AUTH_KEY_LEN];
_mav_put_char_array(buf, 0, key, 32);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTH_KEY, buf, MAVLINK_MSG_ID_AUTH_KEY_LEN, MAVLINK_MSG_ID_AUTH_KEY_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTH_KEY, buf, MAVLINK_MSG_ID_AUTH_KEY_LEN);
#endif
#else
mavlink_auth_key_t packet;
mav_array_memcpy(packet.key, key, sizeof(char)*32);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTH_KEY, (const char *)&packet, MAVLINK_MSG_ID_AUTH_KEY_LEN, MAVLINK_MSG_ID_AUTH_KEY_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTH_KEY, (const char *)&packet, MAVLINK_MSG_ID_AUTH_KEY_LEN);
#endif
#endif
}
#if MAVLINK_MSG_ID_AUTH_KEY_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This varient of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_auth_key_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, const char *key)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
_mav_put_char_array(buf, 0, key, 32);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTH_KEY, buf, MAVLINK_MSG_ID_AUTH_KEY_LEN, MAVLINK_MSG_ID_AUTH_KEY_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTH_KEY, buf, MAVLINK_MSG_ID_AUTH_KEY_LEN);
#endif
#else
mavlink_auth_key_t *packet = (mavlink_auth_key_t *)msgbuf;
mav_array_memcpy(packet->key, key, sizeof(char)*32);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTH_KEY, (const char *)packet, MAVLINK_MSG_ID_AUTH_KEY_LEN, MAVLINK_MSG_ID_AUTH_KEY_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTH_KEY, (const char *)packet, MAVLINK_MSG_ID_AUTH_KEY_LEN);
#endif
#endif
}
#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), MAVLINK_MSG_ID_AUTH_KEY_LEN);
#endif
}

View file

@ -0,0 +1,443 @@
// MESSAGE AUTOPILOT_VERSION PACKING
#define MAVLINK_MSG_ID_AUTOPILOT_VERSION 148
typedef struct __mavlink_autopilot_version_t
{
uint64_t capabilities; ///< bitmask of capabilities (see MAV_PROTOCOL_CAPABILITY enum)
uint64_t uid; ///< UID if provided by hardware
uint32_t flight_sw_version; ///< Firmware version number
uint32_t middleware_sw_version; ///< Middleware version number
uint32_t os_sw_version; ///< Operating system version number
uint32_t board_version; ///< HW / board version (last 8 bytes should be silicon ID, if any)
uint16_t vendor_id; ///< ID of the board vendor
uint16_t product_id; ///< ID of the product
uint8_t flight_custom_version[8]; ///< Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases.
uint8_t middleware_custom_version[8]; ///< Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases.
uint8_t os_custom_version[8]; ///< Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases.
} mavlink_autopilot_version_t;
#define MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN 60
#define MAVLINK_MSG_ID_148_LEN 60
#define MAVLINK_MSG_ID_AUTOPILOT_VERSION_CRC 178
#define MAVLINK_MSG_ID_148_CRC 178
#define MAVLINK_MSG_AUTOPILOT_VERSION_FIELD_FLIGHT_CUSTOM_VERSION_LEN 8
#define MAVLINK_MSG_AUTOPILOT_VERSION_FIELD_MIDDLEWARE_CUSTOM_VERSION_LEN 8
#define MAVLINK_MSG_AUTOPILOT_VERSION_FIELD_OS_CUSTOM_VERSION_LEN 8
#define MAVLINK_MESSAGE_INFO_AUTOPILOT_VERSION { \
"AUTOPILOT_VERSION", \
11, \
{ { "capabilities", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_autopilot_version_t, capabilities) }, \
{ "uid", NULL, MAVLINK_TYPE_UINT64_T, 0, 8, offsetof(mavlink_autopilot_version_t, uid) }, \
{ "flight_sw_version", NULL, MAVLINK_TYPE_UINT32_T, 0, 16, offsetof(mavlink_autopilot_version_t, flight_sw_version) }, \
{ "middleware_sw_version", NULL, MAVLINK_TYPE_UINT32_T, 0, 20, offsetof(mavlink_autopilot_version_t, middleware_sw_version) }, \
{ "os_sw_version", NULL, MAVLINK_TYPE_UINT32_T, 0, 24, offsetof(mavlink_autopilot_version_t, os_sw_version) }, \
{ "board_version", NULL, MAVLINK_TYPE_UINT32_T, 0, 28, offsetof(mavlink_autopilot_version_t, board_version) }, \
{ "vendor_id", NULL, MAVLINK_TYPE_UINT16_T, 0, 32, offsetof(mavlink_autopilot_version_t, vendor_id) }, \
{ "product_id", NULL, MAVLINK_TYPE_UINT16_T, 0, 34, offsetof(mavlink_autopilot_version_t, product_id) }, \
{ "flight_custom_version", NULL, MAVLINK_TYPE_UINT8_T, 8, 36, offsetof(mavlink_autopilot_version_t, flight_custom_version) }, \
{ "middleware_custom_version", NULL, MAVLINK_TYPE_UINT8_T, 8, 44, offsetof(mavlink_autopilot_version_t, middleware_custom_version) }, \
{ "os_custom_version", NULL, MAVLINK_TYPE_UINT8_T, 8, 52, offsetof(mavlink_autopilot_version_t, os_custom_version) }, \
} \
}
/**
* @brief Pack a autopilot_version message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param capabilities bitmask of capabilities (see MAV_PROTOCOL_CAPABILITY enum)
* @param flight_sw_version Firmware version number
* @param middleware_sw_version Middleware version number
* @param os_sw_version Operating system version number
* @param board_version HW / board version (last 8 bytes should be silicon ID, if any)
* @param flight_custom_version Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases.
* @param middleware_custom_version Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases.
* @param os_custom_version Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases.
* @param vendor_id ID of the board vendor
* @param product_id ID of the product
* @param uid UID if provided by hardware
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_autopilot_version_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint64_t capabilities, uint32_t flight_sw_version, uint32_t middleware_sw_version, uint32_t os_sw_version, uint32_t board_version, const uint8_t *flight_custom_version, const uint8_t *middleware_custom_version, const uint8_t *os_custom_version, uint16_t vendor_id, uint16_t product_id, uint64_t uid)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN];
_mav_put_uint64_t(buf, 0, capabilities);
_mav_put_uint64_t(buf, 8, uid);
_mav_put_uint32_t(buf, 16, flight_sw_version);
_mav_put_uint32_t(buf, 20, middleware_sw_version);
_mav_put_uint32_t(buf, 24, os_sw_version);
_mav_put_uint32_t(buf, 28, board_version);
_mav_put_uint16_t(buf, 32, vendor_id);
_mav_put_uint16_t(buf, 34, product_id);
_mav_put_uint8_t_array(buf, 36, flight_custom_version, 8);
_mav_put_uint8_t_array(buf, 44, middleware_custom_version, 8);
_mav_put_uint8_t_array(buf, 52, os_custom_version, 8);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN);
#else
mavlink_autopilot_version_t packet;
packet.capabilities = capabilities;
packet.uid = uid;
packet.flight_sw_version = flight_sw_version;
packet.middleware_sw_version = middleware_sw_version;
packet.os_sw_version = os_sw_version;
packet.board_version = board_version;
packet.vendor_id = vendor_id;
packet.product_id = product_id;
mav_array_memcpy(packet.flight_custom_version, flight_custom_version, sizeof(uint8_t)*8);
mav_array_memcpy(packet.middleware_custom_version, middleware_custom_version, sizeof(uint8_t)*8);
mav_array_memcpy(packet.os_custom_version, os_custom_version, sizeof(uint8_t)*8);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_AUTOPILOT_VERSION;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN, MAVLINK_MSG_ID_AUTOPILOT_VERSION_CRC);
#else
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN);
#endif
}
/**
* @brief Pack a autopilot_version 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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param capabilities bitmask of capabilities (see MAV_PROTOCOL_CAPABILITY enum)
* @param flight_sw_version Firmware version number
* @param middleware_sw_version Middleware version number
* @param os_sw_version Operating system version number
* @param board_version HW / board version (last 8 bytes should be silicon ID, if any)
* @param flight_custom_version Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases.
* @param middleware_custom_version Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases.
* @param os_custom_version Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases.
* @param vendor_id ID of the board vendor
* @param product_id ID of the product
* @param uid UID if provided by hardware
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_autopilot_version_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint64_t capabilities,uint32_t flight_sw_version,uint32_t middleware_sw_version,uint32_t os_sw_version,uint32_t board_version,const uint8_t *flight_custom_version,const uint8_t *middleware_custom_version,const uint8_t *os_custom_version,uint16_t vendor_id,uint16_t product_id,uint64_t uid)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN];
_mav_put_uint64_t(buf, 0, capabilities);
_mav_put_uint64_t(buf, 8, uid);
_mav_put_uint32_t(buf, 16, flight_sw_version);
_mav_put_uint32_t(buf, 20, middleware_sw_version);
_mav_put_uint32_t(buf, 24, os_sw_version);
_mav_put_uint32_t(buf, 28, board_version);
_mav_put_uint16_t(buf, 32, vendor_id);
_mav_put_uint16_t(buf, 34, product_id);
_mav_put_uint8_t_array(buf, 36, flight_custom_version, 8);
_mav_put_uint8_t_array(buf, 44, middleware_custom_version, 8);
_mav_put_uint8_t_array(buf, 52, os_custom_version, 8);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN);
#else
mavlink_autopilot_version_t packet;
packet.capabilities = capabilities;
packet.uid = uid;
packet.flight_sw_version = flight_sw_version;
packet.middleware_sw_version = middleware_sw_version;
packet.os_sw_version = os_sw_version;
packet.board_version = board_version;
packet.vendor_id = vendor_id;
packet.product_id = product_id;
mav_array_memcpy(packet.flight_custom_version, flight_custom_version, sizeof(uint8_t)*8);
mav_array_memcpy(packet.middleware_custom_version, middleware_custom_version, sizeof(uint8_t)*8);
mav_array_memcpy(packet.os_custom_version, os_custom_version, sizeof(uint8_t)*8);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_AUTOPILOT_VERSION;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN, MAVLINK_MSG_ID_AUTOPILOT_VERSION_CRC);
#else
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN);
#endif
}
/**
* @brief Encode a autopilot_version struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param autopilot_version C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_autopilot_version_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_autopilot_version_t* autopilot_version)
{
return mavlink_msg_autopilot_version_pack(system_id, component_id, msg, autopilot_version->capabilities, autopilot_version->flight_sw_version, autopilot_version->middleware_sw_version, autopilot_version->os_sw_version, autopilot_version->board_version, autopilot_version->flight_custom_version, autopilot_version->middleware_custom_version, autopilot_version->os_custom_version, autopilot_version->vendor_id, autopilot_version->product_id, autopilot_version->uid);
}
/**
* @brief Encode a autopilot_version struct 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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param autopilot_version C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_autopilot_version_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_autopilot_version_t* autopilot_version)
{
return mavlink_msg_autopilot_version_pack_chan(system_id, component_id, chan, msg, autopilot_version->capabilities, autopilot_version->flight_sw_version, autopilot_version->middleware_sw_version, autopilot_version->os_sw_version, autopilot_version->board_version, autopilot_version->flight_custom_version, autopilot_version->middleware_custom_version, autopilot_version->os_custom_version, autopilot_version->vendor_id, autopilot_version->product_id, autopilot_version->uid);
}
/**
* @brief Send a autopilot_version message
* @param chan MAVLink channel to send the message
*
* @param capabilities bitmask of capabilities (see MAV_PROTOCOL_CAPABILITY enum)
* @param flight_sw_version Firmware version number
* @param middleware_sw_version Middleware version number
* @param os_sw_version Operating system version number
* @param board_version HW / board version (last 8 bytes should be silicon ID, if any)
* @param flight_custom_version Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases.
* @param middleware_custom_version Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases.
* @param os_custom_version Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases.
* @param vendor_id ID of the board vendor
* @param product_id ID of the product
* @param uid UID if provided by hardware
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_autopilot_version_send(mavlink_channel_t chan, uint64_t capabilities, uint32_t flight_sw_version, uint32_t middleware_sw_version, uint32_t os_sw_version, uint32_t board_version, const uint8_t *flight_custom_version, const uint8_t *middleware_custom_version, const uint8_t *os_custom_version, uint16_t vendor_id, uint16_t product_id, uint64_t uid)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN];
_mav_put_uint64_t(buf, 0, capabilities);
_mav_put_uint64_t(buf, 8, uid);
_mav_put_uint32_t(buf, 16, flight_sw_version);
_mav_put_uint32_t(buf, 20, middleware_sw_version);
_mav_put_uint32_t(buf, 24, os_sw_version);
_mav_put_uint32_t(buf, 28, board_version);
_mav_put_uint16_t(buf, 32, vendor_id);
_mav_put_uint16_t(buf, 34, product_id);
_mav_put_uint8_t_array(buf, 36, flight_custom_version, 8);
_mav_put_uint8_t_array(buf, 44, middleware_custom_version, 8);
_mav_put_uint8_t_array(buf, 52, os_custom_version, 8);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTOPILOT_VERSION, buf, MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN, MAVLINK_MSG_ID_AUTOPILOT_VERSION_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTOPILOT_VERSION, buf, MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN);
#endif
#else
mavlink_autopilot_version_t packet;
packet.capabilities = capabilities;
packet.uid = uid;
packet.flight_sw_version = flight_sw_version;
packet.middleware_sw_version = middleware_sw_version;
packet.os_sw_version = os_sw_version;
packet.board_version = board_version;
packet.vendor_id = vendor_id;
packet.product_id = product_id;
mav_array_memcpy(packet.flight_custom_version, flight_custom_version, sizeof(uint8_t)*8);
mav_array_memcpy(packet.middleware_custom_version, middleware_custom_version, sizeof(uint8_t)*8);
mav_array_memcpy(packet.os_custom_version, os_custom_version, sizeof(uint8_t)*8);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTOPILOT_VERSION, (const char *)&packet, MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN, MAVLINK_MSG_ID_AUTOPILOT_VERSION_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTOPILOT_VERSION, (const char *)&packet, MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN);
#endif
#endif
}
#if MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This varient of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_autopilot_version_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t capabilities, uint32_t flight_sw_version, uint32_t middleware_sw_version, uint32_t os_sw_version, uint32_t board_version, const uint8_t *flight_custom_version, const uint8_t *middleware_custom_version, const uint8_t *os_custom_version, uint16_t vendor_id, uint16_t product_id, uint64_t uid)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
_mav_put_uint64_t(buf, 0, capabilities);
_mav_put_uint64_t(buf, 8, uid);
_mav_put_uint32_t(buf, 16, flight_sw_version);
_mav_put_uint32_t(buf, 20, middleware_sw_version);
_mav_put_uint32_t(buf, 24, os_sw_version);
_mav_put_uint32_t(buf, 28, board_version);
_mav_put_uint16_t(buf, 32, vendor_id);
_mav_put_uint16_t(buf, 34, product_id);
_mav_put_uint8_t_array(buf, 36, flight_custom_version, 8);
_mav_put_uint8_t_array(buf, 44, middleware_custom_version, 8);
_mav_put_uint8_t_array(buf, 52, os_custom_version, 8);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTOPILOT_VERSION, buf, MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN, MAVLINK_MSG_ID_AUTOPILOT_VERSION_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTOPILOT_VERSION, buf, MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN);
#endif
#else
mavlink_autopilot_version_t *packet = (mavlink_autopilot_version_t *)msgbuf;
packet->capabilities = capabilities;
packet->uid = uid;
packet->flight_sw_version = flight_sw_version;
packet->middleware_sw_version = middleware_sw_version;
packet->os_sw_version = os_sw_version;
packet->board_version = board_version;
packet->vendor_id = vendor_id;
packet->product_id = product_id;
mav_array_memcpy(packet->flight_custom_version, flight_custom_version, sizeof(uint8_t)*8);
mav_array_memcpy(packet->middleware_custom_version, middleware_custom_version, sizeof(uint8_t)*8);
mav_array_memcpy(packet->os_custom_version, os_custom_version, sizeof(uint8_t)*8);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTOPILOT_VERSION, (const char *)packet, MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN, MAVLINK_MSG_ID_AUTOPILOT_VERSION_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTOPILOT_VERSION, (const char *)packet, MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN);
#endif
#endif
}
#endif
#endif
// MESSAGE AUTOPILOT_VERSION UNPACKING
/**
* @brief Get field capabilities from autopilot_version message
*
* @return bitmask of capabilities (see MAV_PROTOCOL_CAPABILITY enum)
*/
static inline uint64_t mavlink_msg_autopilot_version_get_capabilities(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint64_t(msg, 0);
}
/**
* @brief Get field flight_sw_version from autopilot_version message
*
* @return Firmware version number
*/
static inline uint32_t mavlink_msg_autopilot_version_get_flight_sw_version(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint32_t(msg, 16);
}
/**
* @brief Get field middleware_sw_version from autopilot_version message
*
* @return Middleware version number
*/
static inline uint32_t mavlink_msg_autopilot_version_get_middleware_sw_version(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint32_t(msg, 20);
}
/**
* @brief Get field os_sw_version from autopilot_version message
*
* @return Operating system version number
*/
static inline uint32_t mavlink_msg_autopilot_version_get_os_sw_version(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint32_t(msg, 24);
}
/**
* @brief Get field board_version from autopilot_version message
*
* @return HW / board version (last 8 bytes should be silicon ID, if any)
*/
static inline uint32_t mavlink_msg_autopilot_version_get_board_version(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint32_t(msg, 28);
}
/**
* @brief Get field flight_custom_version from autopilot_version message
*
* @return Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases.
*/
static inline uint16_t mavlink_msg_autopilot_version_get_flight_custom_version(const mavlink_message_t* msg, uint8_t *flight_custom_version)
{
return _MAV_RETURN_uint8_t_array(msg, flight_custom_version, 8, 36);
}
/**
* @brief Get field middleware_custom_version from autopilot_version message
*
* @return Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases.
*/
static inline uint16_t mavlink_msg_autopilot_version_get_middleware_custom_version(const mavlink_message_t* msg, uint8_t *middleware_custom_version)
{
return _MAV_RETURN_uint8_t_array(msg, middleware_custom_version, 8, 44);
}
/**
* @brief Get field os_custom_version from autopilot_version message
*
* @return Custom version field, commonly the first 8 bytes of the git hash. This is not an unique identifier, but should allow to identify the commit using the main version number even for very large code bases.
*/
static inline uint16_t mavlink_msg_autopilot_version_get_os_custom_version(const mavlink_message_t* msg, uint8_t *os_custom_version)
{
return _MAV_RETURN_uint8_t_array(msg, os_custom_version, 8, 52);
}
/**
* @brief Get field vendor_id from autopilot_version message
*
* @return ID of the board vendor
*/
static inline uint16_t mavlink_msg_autopilot_version_get_vendor_id(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 32);
}
/**
* @brief Get field product_id from autopilot_version message
*
* @return ID of the product
*/
static inline uint16_t mavlink_msg_autopilot_version_get_product_id(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 34);
}
/**
* @brief Get field uid from autopilot_version message
*
* @return UID if provided by hardware
*/
static inline uint64_t mavlink_msg_autopilot_version_get_uid(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint64_t(msg, 8);
}
/**
* @brief Decode a autopilot_version message into a struct
*
* @param msg The message to decode
* @param autopilot_version C-struct to decode the message contents into
*/
static inline void mavlink_msg_autopilot_version_decode(const mavlink_message_t* msg, mavlink_autopilot_version_t* autopilot_version)
{
#if MAVLINK_NEED_BYTE_SWAP
autopilot_version->capabilities = mavlink_msg_autopilot_version_get_capabilities(msg);
autopilot_version->uid = mavlink_msg_autopilot_version_get_uid(msg);
autopilot_version->flight_sw_version = mavlink_msg_autopilot_version_get_flight_sw_version(msg);
autopilot_version->middleware_sw_version = mavlink_msg_autopilot_version_get_middleware_sw_version(msg);
autopilot_version->os_sw_version = mavlink_msg_autopilot_version_get_os_sw_version(msg);
autopilot_version->board_version = mavlink_msg_autopilot_version_get_board_version(msg);
autopilot_version->vendor_id = mavlink_msg_autopilot_version_get_vendor_id(msg);
autopilot_version->product_id = mavlink_msg_autopilot_version_get_product_id(msg);
mavlink_msg_autopilot_version_get_flight_custom_version(msg, autopilot_version->flight_custom_version);
mavlink_msg_autopilot_version_get_middleware_custom_version(msg, autopilot_version->middleware_custom_version);
mavlink_msg_autopilot_version_get_os_custom_version(msg, autopilot_version->os_custom_version);
#else
memcpy(autopilot_version, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN);
#endif
}

View file

@ -0,0 +1,393 @@
// MESSAGE BATTERY_STATUS PACKING
#define MAVLINK_MSG_ID_BATTERY_STATUS 147
typedef struct __mavlink_battery_status_t
{
int32_t current_consumed; ///< Consumed charge, in milliampere hours (1 = 1 mAh), -1: autopilot does not provide mAh consumption estimate
int32_t energy_consumed; ///< Consumed energy, in 100*Joules (intergrated U*I*dt) (1 = 100 Joule), -1: autopilot does not provide energy consumption estimate
int16_t temperature; ///< Temperature of the battery in centi-degrees celsius. INT16_MAX for unknown temperature.
uint16_t voltages[10]; ///< Battery voltage of cells, in millivolts (1 = 1 millivolt)
int16_t current_battery; ///< Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current
uint8_t id; ///< Battery ID
uint8_t battery_function; ///< Function of the battery
uint8_t type; ///< Type (chemistry) of the battery
int8_t battery_remaining; ///< Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot does not estimate the remaining battery
} mavlink_battery_status_t;
#define MAVLINK_MSG_ID_BATTERY_STATUS_LEN 36
#define MAVLINK_MSG_ID_147_LEN 36
#define MAVLINK_MSG_ID_BATTERY_STATUS_CRC 154
#define MAVLINK_MSG_ID_147_CRC 154
#define MAVLINK_MSG_BATTERY_STATUS_FIELD_VOLTAGES_LEN 10
#define MAVLINK_MESSAGE_INFO_BATTERY_STATUS { \
"BATTERY_STATUS", \
9, \
{ { "current_consumed", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_battery_status_t, current_consumed) }, \
{ "energy_consumed", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_battery_status_t, energy_consumed) }, \
{ "temperature", NULL, MAVLINK_TYPE_INT16_T, 0, 8, offsetof(mavlink_battery_status_t, temperature) }, \
{ "voltages", NULL, MAVLINK_TYPE_UINT16_T, 10, 10, offsetof(mavlink_battery_status_t, voltages) }, \
{ "current_battery", NULL, MAVLINK_TYPE_INT16_T, 0, 30, offsetof(mavlink_battery_status_t, current_battery) }, \
{ "id", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_battery_status_t, id) }, \
{ "battery_function", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_battery_status_t, battery_function) }, \
{ "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_battery_status_t, type) }, \
{ "battery_remaining", NULL, MAVLINK_TYPE_INT8_T, 0, 35, offsetof(mavlink_battery_status_t, battery_remaining) }, \
} \
}
/**
* @brief Pack a battery_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 id Battery ID
* @param battery_function Function of the battery
* @param type Type (chemistry) of the battery
* @param temperature Temperature of the battery in centi-degrees celsius. INT16_MAX for unknown temperature.
* @param voltages Battery voltage of cells, in millivolts (1 = 1 millivolt)
* @param current_battery Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current
* @param current_consumed Consumed charge, in milliampere hours (1 = 1 mAh), -1: autopilot does not provide mAh consumption estimate
* @param energy_consumed Consumed energy, in 100*Joules (intergrated U*I*dt) (1 = 100 Joule), -1: autopilot does not provide energy consumption estimate
* @param battery_remaining Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot does not estimate the remaining battery
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_battery_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t id, uint8_t battery_function, uint8_t type, int16_t temperature, const uint16_t *voltages, int16_t current_battery, int32_t current_consumed, int32_t energy_consumed, int8_t battery_remaining)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_BATTERY_STATUS_LEN];
_mav_put_int32_t(buf, 0, current_consumed);
_mav_put_int32_t(buf, 4, energy_consumed);
_mav_put_int16_t(buf, 8, temperature);
_mav_put_int16_t(buf, 30, current_battery);
_mav_put_uint8_t(buf, 32, id);
_mav_put_uint8_t(buf, 33, battery_function);
_mav_put_uint8_t(buf, 34, type);
_mav_put_int8_t(buf, 35, battery_remaining);
_mav_put_uint16_t_array(buf, 10, voltages, 10);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_BATTERY_STATUS_LEN);
#else
mavlink_battery_status_t packet;
packet.current_consumed = current_consumed;
packet.energy_consumed = energy_consumed;
packet.temperature = temperature;
packet.current_battery = current_battery;
packet.id = id;
packet.battery_function = battery_function;
packet.type = type;
packet.battery_remaining = battery_remaining;
mav_array_memcpy(packet.voltages, voltages, sizeof(uint16_t)*10);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_BATTERY_STATUS_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_BATTERY_STATUS;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_BATTERY_STATUS_LEN, MAVLINK_MSG_ID_BATTERY_STATUS_CRC);
#else
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_BATTERY_STATUS_LEN);
#endif
}
/**
* @brief Pack a battery_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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param id Battery ID
* @param battery_function Function of the battery
* @param type Type (chemistry) of the battery
* @param temperature Temperature of the battery in centi-degrees celsius. INT16_MAX for unknown temperature.
* @param voltages Battery voltage of cells, in millivolts (1 = 1 millivolt)
* @param current_battery Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current
* @param current_consumed Consumed charge, in milliampere hours (1 = 1 mAh), -1: autopilot does not provide mAh consumption estimate
* @param energy_consumed Consumed energy, in 100*Joules (intergrated U*I*dt) (1 = 100 Joule), -1: autopilot does not provide energy consumption estimate
* @param battery_remaining Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot does not estimate the remaining battery
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_battery_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint8_t id,uint8_t battery_function,uint8_t type,int16_t temperature,const uint16_t *voltages,int16_t current_battery,int32_t current_consumed,int32_t energy_consumed,int8_t battery_remaining)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_BATTERY_STATUS_LEN];
_mav_put_int32_t(buf, 0, current_consumed);
_mav_put_int32_t(buf, 4, energy_consumed);
_mav_put_int16_t(buf, 8, temperature);
_mav_put_int16_t(buf, 30, current_battery);
_mav_put_uint8_t(buf, 32, id);
_mav_put_uint8_t(buf, 33, battery_function);
_mav_put_uint8_t(buf, 34, type);
_mav_put_int8_t(buf, 35, battery_remaining);
_mav_put_uint16_t_array(buf, 10, voltages, 10);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_BATTERY_STATUS_LEN);
#else
mavlink_battery_status_t packet;
packet.current_consumed = current_consumed;
packet.energy_consumed = energy_consumed;
packet.temperature = temperature;
packet.current_battery = current_battery;
packet.id = id;
packet.battery_function = battery_function;
packet.type = type;
packet.battery_remaining = battery_remaining;
mav_array_memcpy(packet.voltages, voltages, sizeof(uint16_t)*10);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_BATTERY_STATUS_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_BATTERY_STATUS;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_BATTERY_STATUS_LEN, MAVLINK_MSG_ID_BATTERY_STATUS_CRC);
#else
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_BATTERY_STATUS_LEN);
#endif
}
/**
* @brief Encode a battery_status struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param battery_status C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_battery_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_battery_status_t* battery_status)
{
return mavlink_msg_battery_status_pack(system_id, component_id, msg, battery_status->id, battery_status->battery_function, battery_status->type, battery_status->temperature, battery_status->voltages, battery_status->current_battery, battery_status->current_consumed, battery_status->energy_consumed, battery_status->battery_remaining);
}
/**
* @brief Encode a battery_status struct 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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param battery_status C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_battery_status_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_battery_status_t* battery_status)
{
return mavlink_msg_battery_status_pack_chan(system_id, component_id, chan, msg, battery_status->id, battery_status->battery_function, battery_status->type, battery_status->temperature, battery_status->voltages, battery_status->current_battery, battery_status->current_consumed, battery_status->energy_consumed, battery_status->battery_remaining);
}
/**
* @brief Send a battery_status message
* @param chan MAVLink channel to send the message
*
* @param id Battery ID
* @param battery_function Function of the battery
* @param type Type (chemistry) of the battery
* @param temperature Temperature of the battery in centi-degrees celsius. INT16_MAX for unknown temperature.
* @param voltages Battery voltage of cells, in millivolts (1 = 1 millivolt)
* @param current_battery Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current
* @param current_consumed Consumed charge, in milliampere hours (1 = 1 mAh), -1: autopilot does not provide mAh consumption estimate
* @param energy_consumed Consumed energy, in 100*Joules (intergrated U*I*dt) (1 = 100 Joule), -1: autopilot does not provide energy consumption estimate
* @param battery_remaining Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot does not estimate the remaining battery
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_battery_status_send(mavlink_channel_t chan, uint8_t id, uint8_t battery_function, uint8_t type, int16_t temperature, const uint16_t *voltages, int16_t current_battery, int32_t current_consumed, int32_t energy_consumed, int8_t battery_remaining)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_BATTERY_STATUS_LEN];
_mav_put_int32_t(buf, 0, current_consumed);
_mav_put_int32_t(buf, 4, energy_consumed);
_mav_put_int16_t(buf, 8, temperature);
_mav_put_int16_t(buf, 30, current_battery);
_mav_put_uint8_t(buf, 32, id);
_mav_put_uint8_t(buf, 33, battery_function);
_mav_put_uint8_t(buf, 34, type);
_mav_put_int8_t(buf, 35, battery_remaining);
_mav_put_uint16_t_array(buf, 10, voltages, 10);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_BATTERY_STATUS, buf, MAVLINK_MSG_ID_BATTERY_STATUS_LEN, MAVLINK_MSG_ID_BATTERY_STATUS_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_BATTERY_STATUS, buf, MAVLINK_MSG_ID_BATTERY_STATUS_LEN);
#endif
#else
mavlink_battery_status_t packet;
packet.current_consumed = current_consumed;
packet.energy_consumed = energy_consumed;
packet.temperature = temperature;
packet.current_battery = current_battery;
packet.id = id;
packet.battery_function = battery_function;
packet.type = type;
packet.battery_remaining = battery_remaining;
mav_array_memcpy(packet.voltages, voltages, sizeof(uint16_t)*10);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_BATTERY_STATUS, (const char *)&packet, MAVLINK_MSG_ID_BATTERY_STATUS_LEN, MAVLINK_MSG_ID_BATTERY_STATUS_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_BATTERY_STATUS, (const char *)&packet, MAVLINK_MSG_ID_BATTERY_STATUS_LEN);
#endif
#endif
}
#if MAVLINK_MSG_ID_BATTERY_STATUS_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This varient of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_battery_status_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t id, uint8_t battery_function, uint8_t type, int16_t temperature, const uint16_t *voltages, int16_t current_battery, int32_t current_consumed, int32_t energy_consumed, int8_t battery_remaining)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
_mav_put_int32_t(buf, 0, current_consumed);
_mav_put_int32_t(buf, 4, energy_consumed);
_mav_put_int16_t(buf, 8, temperature);
_mav_put_int16_t(buf, 30, current_battery);
_mav_put_uint8_t(buf, 32, id);
_mav_put_uint8_t(buf, 33, battery_function);
_mav_put_uint8_t(buf, 34, type);
_mav_put_int8_t(buf, 35, battery_remaining);
_mav_put_uint16_t_array(buf, 10, voltages, 10);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_BATTERY_STATUS, buf, MAVLINK_MSG_ID_BATTERY_STATUS_LEN, MAVLINK_MSG_ID_BATTERY_STATUS_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_BATTERY_STATUS, buf, MAVLINK_MSG_ID_BATTERY_STATUS_LEN);
#endif
#else
mavlink_battery_status_t *packet = (mavlink_battery_status_t *)msgbuf;
packet->current_consumed = current_consumed;
packet->energy_consumed = energy_consumed;
packet->temperature = temperature;
packet->current_battery = current_battery;
packet->id = id;
packet->battery_function = battery_function;
packet->type = type;
packet->battery_remaining = battery_remaining;
mav_array_memcpy(packet->voltages, voltages, sizeof(uint16_t)*10);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_BATTERY_STATUS, (const char *)packet, MAVLINK_MSG_ID_BATTERY_STATUS_LEN, MAVLINK_MSG_ID_BATTERY_STATUS_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_BATTERY_STATUS, (const char *)packet, MAVLINK_MSG_ID_BATTERY_STATUS_LEN);
#endif
#endif
}
#endif
#endif
// MESSAGE BATTERY_STATUS UNPACKING
/**
* @brief Get field id from battery_status message
*
* @return Battery ID
*/
static inline uint8_t mavlink_msg_battery_status_get_id(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 32);
}
/**
* @brief Get field battery_function from battery_status message
*
* @return Function of the battery
*/
static inline uint8_t mavlink_msg_battery_status_get_battery_function(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 33);
}
/**
* @brief Get field type from battery_status message
*
* @return Type (chemistry) of the battery
*/
static inline uint8_t mavlink_msg_battery_status_get_type(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 34);
}
/**
* @brief Get field temperature from battery_status message
*
* @return Temperature of the battery in centi-degrees celsius. INT16_MAX for unknown temperature.
*/
static inline int16_t mavlink_msg_battery_status_get_temperature(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 8);
}
/**
* @brief Get field voltages from battery_status message
*
* @return Battery voltage of cells, in millivolts (1 = 1 millivolt)
*/
static inline uint16_t mavlink_msg_battery_status_get_voltages(const mavlink_message_t* msg, uint16_t *voltages)
{
return _MAV_RETURN_uint16_t_array(msg, voltages, 10, 10);
}
/**
* @brief Get field current_battery from battery_status message
*
* @return Battery current, in 10*milliamperes (1 = 10 milliampere), -1: autopilot does not measure the current
*/
static inline int16_t mavlink_msg_battery_status_get_current_battery(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 30);
}
/**
* @brief Get field current_consumed from battery_status message
*
* @return Consumed charge, in milliampere hours (1 = 1 mAh), -1: autopilot does not provide mAh consumption estimate
*/
static inline int32_t mavlink_msg_battery_status_get_current_consumed(const mavlink_message_t* msg)
{
return _MAV_RETURN_int32_t(msg, 0);
}
/**
* @brief Get field energy_consumed from battery_status message
*
* @return Consumed energy, in 100*Joules (intergrated U*I*dt) (1 = 100 Joule), -1: autopilot does not provide energy consumption estimate
*/
static inline int32_t mavlink_msg_battery_status_get_energy_consumed(const mavlink_message_t* msg)
{
return _MAV_RETURN_int32_t(msg, 4);
}
/**
* @brief Get field battery_remaining from battery_status message
*
* @return Remaining battery energy: (0%: 0, 100%: 100), -1: autopilot does not estimate the remaining battery
*/
static inline int8_t mavlink_msg_battery_status_get_battery_remaining(const mavlink_message_t* msg)
{
return _MAV_RETURN_int8_t(msg, 35);
}
/**
* @brief Decode a battery_status message into a struct
*
* @param msg The message to decode
* @param battery_status C-struct to decode the message contents into
*/
static inline void mavlink_msg_battery_status_decode(const mavlink_message_t* msg, mavlink_battery_status_t* battery_status)
{
#if MAVLINK_NEED_BYTE_SWAP
battery_status->current_consumed = mavlink_msg_battery_status_get_current_consumed(msg);
battery_status->energy_consumed = mavlink_msg_battery_status_get_energy_consumed(msg);
battery_status->temperature = mavlink_msg_battery_status_get_temperature(msg);
mavlink_msg_battery_status_get_voltages(msg, battery_status->voltages);
battery_status->current_battery = mavlink_msg_battery_status_get_current_battery(msg);
battery_status->id = mavlink_msg_battery_status_get_id(msg);
battery_status->battery_function = mavlink_msg_battery_status_get_battery_function(msg);
battery_status->type = mavlink_msg_battery_status_get_type(msg);
battery_status->battery_remaining = mavlink_msg_battery_status_get_battery_remaining(msg);
#else
memcpy(battery_status, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_BATTERY_STATUS_LEN);
#endif
}

View file

@ -0,0 +1,233 @@
// MESSAGE CAMERA_TRIGGER PACKING
#define MAVLINK_MSG_ID_CAMERA_TRIGGER 112
typedef struct __mavlink_camera_trigger_t
{
uint64_t time_usec; ///< Timestamp for the image frame in microseconds
uint32_t seq; ///< Image frame sequence
} mavlink_camera_trigger_t;
#define MAVLINK_MSG_ID_CAMERA_TRIGGER_LEN 12
#define MAVLINK_MSG_ID_112_LEN 12
#define MAVLINK_MSG_ID_CAMERA_TRIGGER_CRC 174
#define MAVLINK_MSG_ID_112_CRC 174
#define MAVLINK_MESSAGE_INFO_CAMERA_TRIGGER { \
"CAMERA_TRIGGER", \
2, \
{ { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_camera_trigger_t, time_usec) }, \
{ "seq", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_camera_trigger_t, seq) }, \
} \
}
/**
* @brief Pack a camera_trigger message
* @param system_id ID of this 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 for the image frame in microseconds
* @param seq Image frame sequence
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_camera_trigger_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint64_t time_usec, uint32_t seq)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_CAMERA_TRIGGER_LEN];
_mav_put_uint64_t(buf, 0, time_usec);
_mav_put_uint32_t(buf, 8, seq);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CAMERA_TRIGGER_LEN);
#else
mavlink_camera_trigger_t packet;
packet.time_usec = time_usec;
packet.seq = seq;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CAMERA_TRIGGER_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_CAMERA_TRIGGER;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_CAMERA_TRIGGER_LEN, MAVLINK_MSG_ID_CAMERA_TRIGGER_CRC);
#else
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_CAMERA_TRIGGER_LEN);
#endif
}
/**
* @brief Pack a camera_trigger 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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param time_usec Timestamp for the image frame in microseconds
* @param seq Image frame sequence
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_camera_trigger_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint64_t time_usec,uint32_t seq)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_CAMERA_TRIGGER_LEN];
_mav_put_uint64_t(buf, 0, time_usec);
_mav_put_uint32_t(buf, 8, seq);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CAMERA_TRIGGER_LEN);
#else
mavlink_camera_trigger_t packet;
packet.time_usec = time_usec;
packet.seq = seq;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CAMERA_TRIGGER_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_CAMERA_TRIGGER;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_CAMERA_TRIGGER_LEN, MAVLINK_MSG_ID_CAMERA_TRIGGER_CRC);
#else
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_CAMERA_TRIGGER_LEN);
#endif
}
/**
* @brief Encode a camera_trigger struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param camera_trigger C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_camera_trigger_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_camera_trigger_t* camera_trigger)
{
return mavlink_msg_camera_trigger_pack(system_id, component_id, msg, camera_trigger->time_usec, camera_trigger->seq);
}
/**
* @brief Encode a camera_trigger struct 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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param camera_trigger C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_camera_trigger_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_camera_trigger_t* camera_trigger)
{
return mavlink_msg_camera_trigger_pack_chan(system_id, component_id, chan, msg, camera_trigger->time_usec, camera_trigger->seq);
}
/**
* @brief Send a camera_trigger message
* @param chan MAVLink channel to send the message
*
* @param time_usec Timestamp for the image frame in microseconds
* @param seq Image frame sequence
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_camera_trigger_send(mavlink_channel_t chan, uint64_t time_usec, uint32_t seq)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_CAMERA_TRIGGER_LEN];
_mav_put_uint64_t(buf, 0, time_usec);
_mav_put_uint32_t(buf, 8, seq);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_TRIGGER, buf, MAVLINK_MSG_ID_CAMERA_TRIGGER_LEN, MAVLINK_MSG_ID_CAMERA_TRIGGER_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_TRIGGER, buf, MAVLINK_MSG_ID_CAMERA_TRIGGER_LEN);
#endif
#else
mavlink_camera_trigger_t packet;
packet.time_usec = time_usec;
packet.seq = seq;
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_TRIGGER, (const char *)&packet, MAVLINK_MSG_ID_CAMERA_TRIGGER_LEN, MAVLINK_MSG_ID_CAMERA_TRIGGER_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_TRIGGER, (const char *)&packet, MAVLINK_MSG_ID_CAMERA_TRIGGER_LEN);
#endif
#endif
}
#if MAVLINK_MSG_ID_CAMERA_TRIGGER_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This varient of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_camera_trigger_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, uint32_t seq)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
_mav_put_uint64_t(buf, 0, time_usec);
_mav_put_uint32_t(buf, 8, seq);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_TRIGGER, buf, MAVLINK_MSG_ID_CAMERA_TRIGGER_LEN, MAVLINK_MSG_ID_CAMERA_TRIGGER_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_TRIGGER, buf, MAVLINK_MSG_ID_CAMERA_TRIGGER_LEN);
#endif
#else
mavlink_camera_trigger_t *packet = (mavlink_camera_trigger_t *)msgbuf;
packet->time_usec = time_usec;
packet->seq = seq;
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_TRIGGER, (const char *)packet, MAVLINK_MSG_ID_CAMERA_TRIGGER_LEN, MAVLINK_MSG_ID_CAMERA_TRIGGER_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_TRIGGER, (const char *)packet, MAVLINK_MSG_ID_CAMERA_TRIGGER_LEN);
#endif
#endif
}
#endif
#endif
// MESSAGE CAMERA_TRIGGER UNPACKING
/**
* @brief Get field time_usec from camera_trigger message
*
* @return Timestamp for the image frame in microseconds
*/
static inline uint64_t mavlink_msg_camera_trigger_get_time_usec(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint64_t(msg, 0);
}
/**
* @brief Get field seq from camera_trigger message
*
* @return Image frame sequence
*/
static inline uint32_t mavlink_msg_camera_trigger_get_seq(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint32_t(msg, 8);
}
/**
* @brief Decode a camera_trigger message into a struct
*
* @param msg The message to decode
* @param camera_trigger C-struct to decode the message contents into
*/
static inline void mavlink_msg_camera_trigger_decode(const mavlink_message_t* msg, mavlink_camera_trigger_t* camera_trigger)
{
#if MAVLINK_NEED_BYTE_SWAP
camera_trigger->time_usec = mavlink_msg_camera_trigger_get_time_usec(msg);
camera_trigger->seq = mavlink_msg_camera_trigger_get_seq(msg);
#else
memcpy(camera_trigger, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_CAMERA_TRIGGER_LEN);
#endif
}

View file

@ -0,0 +1,273 @@
// 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_ID_CHANGE_OPERATOR_CONTROL_CRC 217
#define MAVLINK_MSG_ID_5_CRC 217
#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[MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN];
_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, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN);
#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, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_CRC);
#else
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN);
#endif
}
/**
* @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 will be 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[MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN];
_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, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN);
#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, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_CRC);
#else
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN);
#endif
}
/**
* @brief Encode a change_operator_control struct
*
* @param system_id ID of this 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 Encode a change_operator_control struct 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 will be sent over
* @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_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_change_operator_control_t* change_operator_control)
{
return mavlink_msg_change_operator_control_pack_chan(system_id, component_id, chan, 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[MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN];
_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);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL, buf, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL, buf, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN);
#endif
#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);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL, (const char *)&packet, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL, (const char *)&packet, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN);
#endif
#endif
}
#if MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This varient of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_change_operator_control_send_buf(mavlink_message_t *msgbuf, 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 = (char *)msgbuf;
_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);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL, buf, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL, buf, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN);
#endif
#else
mavlink_change_operator_control_t *packet = (mavlink_change_operator_control_t *)msgbuf;
packet->target_system = target_system;
packet->control_request = control_request;
packet->version = version;
mav_array_memcpy(packet->passkey, passkey, sizeof(char)*25);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL, (const char *)packet, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL, (const char *)packet, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN);
#endif
#endif
}
#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), MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_LEN);
#endif
}

View file

@ -0,0 +1,257 @@
// 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_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_CRC 104
#define MAVLINK_MSG_ID_6_CRC 104
#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[MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN];
_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, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN);
#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, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_CRC);
#else
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN);
#endif
}
/**
* @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 will be 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[MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN];
_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, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN);
#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, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_CRC);
#else
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN);
#endif
}
/**
* @brief Encode a change_operator_control_ack struct
*
* @param system_id ID of this 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 Encode a change_operator_control_ack struct 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 will be sent over
* @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_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_change_operator_control_ack_t* change_operator_control_ack)
{
return mavlink_msg_change_operator_control_ack_pack_chan(system_id, component_id, chan, 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[MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN];
_mav_put_uint8_t(buf, 0, gcs_system_id);
_mav_put_uint8_t(buf, 1, control_request);
_mav_put_uint8_t(buf, 2, ack);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK, buf, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK, buf, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN);
#endif
#else
mavlink_change_operator_control_ack_t packet;
packet.gcs_system_id = gcs_system_id;
packet.control_request = control_request;
packet.ack = ack;
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK, (const char *)&packet, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK, (const char *)&packet, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN);
#endif
#endif
}
#if MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This varient of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_change_operator_control_ack_send_buf(mavlink_message_t *msgbuf, 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 = (char *)msgbuf;
_mav_put_uint8_t(buf, 0, gcs_system_id);
_mav_put_uint8_t(buf, 1, control_request);
_mav_put_uint8_t(buf, 2, ack);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK, buf, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK, buf, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN);
#endif
#else
mavlink_change_operator_control_ack_t *packet = (mavlink_change_operator_control_ack_t *)msgbuf;
packet->gcs_system_id = gcs_system_id;
packet->control_request = control_request;
packet->ack = ack;
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK, (const char *)packet, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK, (const char *)packet, MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN);
#endif
#endif
}
#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), MAVLINK_MSG_ID_CHANGE_OPERATOR_CONTROL_ACK_LEN);
#endif
}

View file

@ -0,0 +1,233 @@
// 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_MSG_ID_COMMAND_ACK_CRC 143
#define MAVLINK_MSG_ID_77_CRC 143
#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[MAVLINK_MSG_ID_COMMAND_ACK_LEN];
_mav_put_uint16_t(buf, 0, command);
_mav_put_uint8_t(buf, 2, result);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_COMMAND_ACK_LEN);
#else
mavlink_command_ack_t packet;
packet.command = command;
packet.result = result;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_COMMAND_ACK_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_COMMAND_ACK;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_COMMAND_ACK_LEN, MAVLINK_MSG_ID_COMMAND_ACK_CRC);
#else
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_COMMAND_ACK_LEN);
#endif
}
/**
* @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 will be 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[MAVLINK_MSG_ID_COMMAND_ACK_LEN];
_mav_put_uint16_t(buf, 0, command);
_mav_put_uint8_t(buf, 2, result);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_COMMAND_ACK_LEN);
#else
mavlink_command_ack_t packet;
packet.command = command;
packet.result = result;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_COMMAND_ACK_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_COMMAND_ACK;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_COMMAND_ACK_LEN, MAVLINK_MSG_ID_COMMAND_ACK_CRC);
#else
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_COMMAND_ACK_LEN);
#endif
}
/**
* @brief Encode a command_ack struct
*
* @param system_id ID of this 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 Encode a command_ack struct 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 will be sent over
* @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_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_command_ack_t* command_ack)
{
return mavlink_msg_command_ack_pack_chan(system_id, component_id, chan, 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[MAVLINK_MSG_ID_COMMAND_ACK_LEN];
_mav_put_uint16_t(buf, 0, command);
_mav_put_uint8_t(buf, 2, result);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_ACK, buf, MAVLINK_MSG_ID_COMMAND_ACK_LEN, MAVLINK_MSG_ID_COMMAND_ACK_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_ACK, buf, MAVLINK_MSG_ID_COMMAND_ACK_LEN);
#endif
#else
mavlink_command_ack_t packet;
packet.command = command;
packet.result = result;
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_ACK, (const char *)&packet, MAVLINK_MSG_ID_COMMAND_ACK_LEN, MAVLINK_MSG_ID_COMMAND_ACK_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_ACK, (const char *)&packet, MAVLINK_MSG_ID_COMMAND_ACK_LEN);
#endif
#endif
}
#if MAVLINK_MSG_ID_COMMAND_ACK_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This varient of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_command_ack_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint16_t command, uint8_t result)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
_mav_put_uint16_t(buf, 0, command);
_mav_put_uint8_t(buf, 2, result);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_ACK, buf, MAVLINK_MSG_ID_COMMAND_ACK_LEN, MAVLINK_MSG_ID_COMMAND_ACK_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_ACK, buf, MAVLINK_MSG_ID_COMMAND_ACK_LEN);
#endif
#else
mavlink_command_ack_t *packet = (mavlink_command_ack_t *)msgbuf;
packet->command = command;
packet->result = result;
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_ACK, (const char *)packet, MAVLINK_MSG_ID_COMMAND_ACK_LEN, MAVLINK_MSG_ID_COMMAND_ACK_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_ACK, (const char *)packet, MAVLINK_MSG_ID_COMMAND_ACK_LEN);
#endif
#endif
}
#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), MAVLINK_MSG_ID_COMMAND_ACK_LEN);
#endif
}

View file

@ -0,0 +1,497 @@
// MESSAGE COMMAND_INT PACKING
#define MAVLINK_MSG_ID_COMMAND_INT 75
typedef struct __mavlink_command_int_t
{
float param1; ///< PARAM1, see MAV_CMD enum
float param2; ///< PARAM2, see MAV_CMD enum
float param3; ///< PARAM3, see MAV_CMD enum
float param4; ///< PARAM4, see MAV_CMD enum
int32_t x; ///< PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7
int32_t y; ///< PARAM6 / local: y position in meters * 1e4, global: longitude in degrees * 10^7
float z; ///< PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame.
uint16_t command; ///< The scheduled action for the mission item. 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 COMMAND. see MAV_FRAME in mavlink_types.h
uint8_t current; ///< false:0, true:1
uint8_t autocontinue; ///< autocontinue to next wp
} mavlink_command_int_t;
#define MAVLINK_MSG_ID_COMMAND_INT_LEN 35
#define MAVLINK_MSG_ID_75_LEN 35
#define MAVLINK_MSG_ID_COMMAND_INT_CRC 158
#define MAVLINK_MSG_ID_75_CRC 158
#define MAVLINK_MESSAGE_INFO_COMMAND_INT { \
"COMMAND_INT", \
13, \
{ { "param1", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_command_int_t, param1) }, \
{ "param2", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_command_int_t, param2) }, \
{ "param3", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_command_int_t, param3) }, \
{ "param4", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_command_int_t, param4) }, \
{ "x", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_command_int_t, x) }, \
{ "y", NULL, MAVLINK_TYPE_INT32_T, 0, 20, offsetof(mavlink_command_int_t, y) }, \
{ "z", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_command_int_t, z) }, \
{ "command", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_command_int_t, command) }, \
{ "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 30, offsetof(mavlink_command_int_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 31, offsetof(mavlink_command_int_t, target_component) }, \
{ "frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_command_int_t, frame) }, \
{ "current", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_command_int_t, current) }, \
{ "autocontinue", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_command_int_t, autocontinue) }, \
} \
}
/**
* @brief Pack a command_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 target_system System ID
* @param target_component Component ID
* @param frame The coordinate system of the COMMAND. see MAV_FRAME in mavlink_types.h
* @param command The scheduled action for the mission item. see MAV_CMD in common.xml MAVLink specs
* @param current false:0, true:1
* @param autocontinue autocontinue to next wp
* @param param1 PARAM1, see MAV_CMD enum
* @param param2 PARAM2, see MAV_CMD enum
* @param param3 PARAM3, see MAV_CMD enum
* @param param4 PARAM4, see MAV_CMD enum
* @param x PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7
* @param y PARAM6 / local: y position in meters * 1e4, global: longitude in degrees * 10^7
* @param z PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_command_int_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t target_system, uint8_t target_component, uint8_t frame, uint16_t command, uint8_t current, uint8_t autocontinue, float param1, float param2, float param3, float param4, int32_t x, int32_t y, float z)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_COMMAND_INT_LEN];
_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_int32_t(buf, 16, x);
_mav_put_int32_t(buf, 20, y);
_mav_put_float(buf, 24, z);
_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, frame);
_mav_put_uint8_t(buf, 33, current);
_mav_put_uint8_t(buf, 34, autocontinue);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_COMMAND_INT_LEN);
#else
mavlink_command_int_t packet;
packet.param1 = param1;
packet.param2 = param2;
packet.param3 = param3;
packet.param4 = param4;
packet.x = x;
packet.y = y;
packet.z = z;
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, MAVLINK_MSG_ID_COMMAND_INT_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_COMMAND_INT;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_COMMAND_INT_LEN, MAVLINK_MSG_ID_COMMAND_INT_CRC);
#else
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_COMMAND_INT_LEN);
#endif
}
/**
* @brief Pack a command_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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param target_system System ID
* @param target_component Component ID
* @param frame The coordinate system of the COMMAND. see MAV_FRAME in mavlink_types.h
* @param command The scheduled action for the mission item. see MAV_CMD in common.xml MAVLink specs
* @param current false:0, true:1
* @param autocontinue autocontinue to next wp
* @param param1 PARAM1, see MAV_CMD enum
* @param param2 PARAM2, see MAV_CMD enum
* @param param3 PARAM3, see MAV_CMD enum
* @param param4 PARAM4, see MAV_CMD enum
* @param x PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7
* @param y PARAM6 / local: y position in meters * 1e4, global: longitude in degrees * 10^7
* @param z PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_command_int_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,uint16_t command,uint8_t current,uint8_t autocontinue,float param1,float param2,float param3,float param4,int32_t x,int32_t y,float z)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_COMMAND_INT_LEN];
_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_int32_t(buf, 16, x);
_mav_put_int32_t(buf, 20, y);
_mav_put_float(buf, 24, z);
_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, frame);
_mav_put_uint8_t(buf, 33, current);
_mav_put_uint8_t(buf, 34, autocontinue);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_COMMAND_INT_LEN);
#else
mavlink_command_int_t packet;
packet.param1 = param1;
packet.param2 = param2;
packet.param3 = param3;
packet.param4 = param4;
packet.x = x;
packet.y = y;
packet.z = z;
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, MAVLINK_MSG_ID_COMMAND_INT_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_COMMAND_INT;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_COMMAND_INT_LEN, MAVLINK_MSG_ID_COMMAND_INT_CRC);
#else
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_COMMAND_INT_LEN);
#endif
}
/**
* @brief Encode a command_int struct
*
* @param system_id ID of this 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_int C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_command_int_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_command_int_t* command_int)
{
return mavlink_msg_command_int_pack(system_id, component_id, msg, command_int->target_system, command_int->target_component, command_int->frame, command_int->command, command_int->current, command_int->autocontinue, command_int->param1, command_int->param2, command_int->param3, command_int->param4, command_int->x, command_int->y, command_int->z);
}
/**
* @brief Encode a command_int struct 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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param command_int C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_command_int_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_command_int_t* command_int)
{
return mavlink_msg_command_int_pack_chan(system_id, component_id, chan, msg, command_int->target_system, command_int->target_component, command_int->frame, command_int->command, command_int->current, command_int->autocontinue, command_int->param1, command_int->param2, command_int->param3, command_int->param4, command_int->x, command_int->y, command_int->z);
}
/**
* @brief Send a command_int message
* @param chan MAVLink channel to send the message
*
* @param target_system System ID
* @param target_component Component ID
* @param frame The coordinate system of the COMMAND. see MAV_FRAME in mavlink_types.h
* @param command The scheduled action for the mission item. see MAV_CMD in common.xml MAVLink specs
* @param current false:0, true:1
* @param autocontinue autocontinue to next wp
* @param param1 PARAM1, see MAV_CMD enum
* @param param2 PARAM2, see MAV_CMD enum
* @param param3 PARAM3, see MAV_CMD enum
* @param param4 PARAM4, see MAV_CMD enum
* @param x PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7
* @param y PARAM6 / local: y position in meters * 1e4, global: longitude in degrees * 10^7
* @param z PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame.
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_command_int_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t frame, uint16_t command, uint8_t current, uint8_t autocontinue, float param1, float param2, float param3, float param4, int32_t x, int32_t y, float z)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_COMMAND_INT_LEN];
_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_int32_t(buf, 16, x);
_mav_put_int32_t(buf, 20, y);
_mav_put_float(buf, 24, z);
_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, frame);
_mav_put_uint8_t(buf, 33, current);
_mav_put_uint8_t(buf, 34, autocontinue);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_INT, buf, MAVLINK_MSG_ID_COMMAND_INT_LEN, MAVLINK_MSG_ID_COMMAND_INT_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_INT, buf, MAVLINK_MSG_ID_COMMAND_INT_LEN);
#endif
#else
mavlink_command_int_t packet;
packet.param1 = param1;
packet.param2 = param2;
packet.param3 = param3;
packet.param4 = param4;
packet.x = x;
packet.y = y;
packet.z = z;
packet.command = command;
packet.target_system = target_system;
packet.target_component = target_component;
packet.frame = frame;
packet.current = current;
packet.autocontinue = autocontinue;
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_INT, (const char *)&packet, MAVLINK_MSG_ID_COMMAND_INT_LEN, MAVLINK_MSG_ID_COMMAND_INT_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_INT, (const char *)&packet, MAVLINK_MSG_ID_COMMAND_INT_LEN);
#endif
#endif
}
#if MAVLINK_MSG_ID_COMMAND_INT_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This varient of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_command_int_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t frame, uint16_t command, uint8_t current, uint8_t autocontinue, float param1, float param2, float param3, float param4, int32_t x, int32_t y, float z)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
_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_int32_t(buf, 16, x);
_mav_put_int32_t(buf, 20, y);
_mav_put_float(buf, 24, z);
_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, frame);
_mav_put_uint8_t(buf, 33, current);
_mav_put_uint8_t(buf, 34, autocontinue);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_INT, buf, MAVLINK_MSG_ID_COMMAND_INT_LEN, MAVLINK_MSG_ID_COMMAND_INT_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_INT, buf, MAVLINK_MSG_ID_COMMAND_INT_LEN);
#endif
#else
mavlink_command_int_t *packet = (mavlink_command_int_t *)msgbuf;
packet->param1 = param1;
packet->param2 = param2;
packet->param3 = param3;
packet->param4 = param4;
packet->x = x;
packet->y = y;
packet->z = z;
packet->command = command;
packet->target_system = target_system;
packet->target_component = target_component;
packet->frame = frame;
packet->current = current;
packet->autocontinue = autocontinue;
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_INT, (const char *)packet, MAVLINK_MSG_ID_COMMAND_INT_LEN, MAVLINK_MSG_ID_COMMAND_INT_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_INT, (const char *)packet, MAVLINK_MSG_ID_COMMAND_INT_LEN);
#endif
#endif
}
#endif
#endif
// MESSAGE COMMAND_INT UNPACKING
/**
* @brief Get field target_system from command_int message
*
* @return System ID
*/
static inline uint8_t mavlink_msg_command_int_get_target_system(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 30);
}
/**
* @brief Get field target_component from command_int message
*
* @return Component ID
*/
static inline uint8_t mavlink_msg_command_int_get_target_component(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 31);
}
/**
* @brief Get field frame from command_int message
*
* @return The coordinate system of the COMMAND. see MAV_FRAME in mavlink_types.h
*/
static inline uint8_t mavlink_msg_command_int_get_frame(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 32);
}
/**
* @brief Get field command from command_int message
*
* @return The scheduled action for the mission item. see MAV_CMD in common.xml MAVLink specs
*/
static inline uint16_t mavlink_msg_command_int_get_command(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 28);
}
/**
* @brief Get field current from command_int message
*
* @return false:0, true:1
*/
static inline uint8_t mavlink_msg_command_int_get_current(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 33);
}
/**
* @brief Get field autocontinue from command_int message
*
* @return autocontinue to next wp
*/
static inline uint8_t mavlink_msg_command_int_get_autocontinue(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 34);
}
/**
* @brief Get field param1 from command_int message
*
* @return PARAM1, see MAV_CMD enum
*/
static inline float mavlink_msg_command_int_get_param1(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 0);
}
/**
* @brief Get field param2 from command_int message
*
* @return PARAM2, see MAV_CMD enum
*/
static inline float mavlink_msg_command_int_get_param2(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 4);
}
/**
* @brief Get field param3 from command_int message
*
* @return PARAM3, see MAV_CMD enum
*/
static inline float mavlink_msg_command_int_get_param3(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 8);
}
/**
* @brief Get field param4 from command_int message
*
* @return PARAM4, see MAV_CMD enum
*/
static inline float mavlink_msg_command_int_get_param4(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 12);
}
/**
* @brief Get field x from command_int message
*
* @return PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7
*/
static inline int32_t mavlink_msg_command_int_get_x(const mavlink_message_t* msg)
{
return _MAV_RETURN_int32_t(msg, 16);
}
/**
* @brief Get field y from command_int message
*
* @return PARAM6 / local: y position in meters * 1e4, global: longitude in degrees * 10^7
*/
static inline int32_t mavlink_msg_command_int_get_y(const mavlink_message_t* msg)
{
return _MAV_RETURN_int32_t(msg, 20);
}
/**
* @brief Get field z from command_int message
*
* @return PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame.
*/
static inline float mavlink_msg_command_int_get_z(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 24);
}
/**
* @brief Decode a command_int message into a struct
*
* @param msg The message to decode
* @param command_int C-struct to decode the message contents into
*/
static inline void mavlink_msg_command_int_decode(const mavlink_message_t* msg, mavlink_command_int_t* command_int)
{
#if MAVLINK_NEED_BYTE_SWAP
command_int->param1 = mavlink_msg_command_int_get_param1(msg);
command_int->param2 = mavlink_msg_command_int_get_param2(msg);
command_int->param3 = mavlink_msg_command_int_get_param3(msg);
command_int->param4 = mavlink_msg_command_int_get_param4(msg);
command_int->x = mavlink_msg_command_int_get_x(msg);
command_int->y = mavlink_msg_command_int_get_y(msg);
command_int->z = mavlink_msg_command_int_get_z(msg);
command_int->command = mavlink_msg_command_int_get_command(msg);
command_int->target_system = mavlink_msg_command_int_get_target_system(msg);
command_int->target_component = mavlink_msg_command_int_get_target_component(msg);
command_int->frame = mavlink_msg_command_int_get_frame(msg);
command_int->current = mavlink_msg_command_int_get_current(msg);
command_int->autocontinue = mavlink_msg_command_int_get_autocontinue(msg);
#else
memcpy(command_int, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_COMMAND_INT_LEN);
#endif
}

View file

@ -0,0 +1,449 @@
// 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_MSG_ID_COMMAND_LONG_CRC 152
#define MAVLINK_MSG_ID_76_CRC 152
#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[MAVLINK_MSG_ID_COMMAND_LONG_LEN];
_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, MAVLINK_MSG_ID_COMMAND_LONG_LEN);
#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, MAVLINK_MSG_ID_COMMAND_LONG_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_COMMAND_LONG;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_COMMAND_LONG_LEN, MAVLINK_MSG_ID_COMMAND_LONG_CRC);
#else
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_COMMAND_LONG_LEN);
#endif
}
/**
* @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 will be 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[MAVLINK_MSG_ID_COMMAND_LONG_LEN];
_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, MAVLINK_MSG_ID_COMMAND_LONG_LEN);
#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, MAVLINK_MSG_ID_COMMAND_LONG_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_COMMAND_LONG;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_COMMAND_LONG_LEN, MAVLINK_MSG_ID_COMMAND_LONG_CRC);
#else
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_COMMAND_LONG_LEN);
#endif
}
/**
* @brief Encode a command_long struct
*
* @param system_id ID of this 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 Encode a command_long struct 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 will be sent over
* @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_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_command_long_t* command_long)
{
return mavlink_msg_command_long_pack_chan(system_id, component_id, chan, 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[MAVLINK_MSG_ID_COMMAND_LONG_LEN];
_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);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_LONG, buf, MAVLINK_MSG_ID_COMMAND_LONG_LEN, MAVLINK_MSG_ID_COMMAND_LONG_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_LONG, buf, MAVLINK_MSG_ID_COMMAND_LONG_LEN);
#endif
#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;
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_LONG, (const char *)&packet, MAVLINK_MSG_ID_COMMAND_LONG_LEN, MAVLINK_MSG_ID_COMMAND_LONG_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_LONG, (const char *)&packet, MAVLINK_MSG_ID_COMMAND_LONG_LEN);
#endif
#endif
}
#if MAVLINK_MSG_ID_COMMAND_LONG_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This varient of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_command_long_send_buf(mavlink_message_t *msgbuf, 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 = (char *)msgbuf;
_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);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_LONG, buf, MAVLINK_MSG_ID_COMMAND_LONG_LEN, MAVLINK_MSG_ID_COMMAND_LONG_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_LONG, buf, MAVLINK_MSG_ID_COMMAND_LONG_LEN);
#endif
#else
mavlink_command_long_t *packet = (mavlink_command_long_t *)msgbuf;
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;
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_LONG, (const char *)packet, MAVLINK_MSG_ID_COMMAND_LONG_LEN, MAVLINK_MSG_ID_COMMAND_LONG_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_LONG, (const char *)packet, MAVLINK_MSG_ID_COMMAND_LONG_LEN);
#endif
#endif
}
#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), MAVLINK_MSG_ID_COMMAND_LONG_LEN);
#endif
}

View file

@ -0,0 +1,257 @@
// 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_MSG_ID_DATA_STREAM_CRC 21
#define MAVLINK_MSG_ID_67_CRC 21
#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[MAVLINK_MSG_ID_DATA_STREAM_LEN];
_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, MAVLINK_MSG_ID_DATA_STREAM_LEN);
#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, MAVLINK_MSG_ID_DATA_STREAM_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_DATA_STREAM;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_DATA_STREAM_LEN, MAVLINK_MSG_ID_DATA_STREAM_CRC);
#else
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_DATA_STREAM_LEN);
#endif
}
/**
* @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 will be 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[MAVLINK_MSG_ID_DATA_STREAM_LEN];
_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, MAVLINK_MSG_ID_DATA_STREAM_LEN);
#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, MAVLINK_MSG_ID_DATA_STREAM_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_DATA_STREAM;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_DATA_STREAM_LEN, MAVLINK_MSG_ID_DATA_STREAM_CRC);
#else
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_DATA_STREAM_LEN);
#endif
}
/**
* @brief Encode a data_stream struct
*
* @param system_id ID of this 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 Encode a data_stream struct 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 will be sent over
* @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_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_data_stream_t* data_stream)
{
return mavlink_msg_data_stream_pack_chan(system_id, component_id, chan, 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[MAVLINK_MSG_ID_DATA_STREAM_LEN];
_mav_put_uint16_t(buf, 0, message_rate);
_mav_put_uint8_t(buf, 2, stream_id);
_mav_put_uint8_t(buf, 3, on_off);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA_STREAM, buf, MAVLINK_MSG_ID_DATA_STREAM_LEN, MAVLINK_MSG_ID_DATA_STREAM_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA_STREAM, buf, MAVLINK_MSG_ID_DATA_STREAM_LEN);
#endif
#else
mavlink_data_stream_t packet;
packet.message_rate = message_rate;
packet.stream_id = stream_id;
packet.on_off = on_off;
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA_STREAM, (const char *)&packet, MAVLINK_MSG_ID_DATA_STREAM_LEN, MAVLINK_MSG_ID_DATA_STREAM_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA_STREAM, (const char *)&packet, MAVLINK_MSG_ID_DATA_STREAM_LEN);
#endif
#endif
}
#if MAVLINK_MSG_ID_DATA_STREAM_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This varient of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_data_stream_send_buf(mavlink_message_t *msgbuf, 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 = (char *)msgbuf;
_mav_put_uint16_t(buf, 0, message_rate);
_mav_put_uint8_t(buf, 2, stream_id);
_mav_put_uint8_t(buf, 3, on_off);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA_STREAM, buf, MAVLINK_MSG_ID_DATA_STREAM_LEN, MAVLINK_MSG_ID_DATA_STREAM_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA_STREAM, buf, MAVLINK_MSG_ID_DATA_STREAM_LEN);
#endif
#else
mavlink_data_stream_t *packet = (mavlink_data_stream_t *)msgbuf;
packet->message_rate = message_rate;
packet->stream_id = stream_id;
packet->on_off = on_off;
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA_STREAM, (const char *)packet, MAVLINK_MSG_ID_DATA_STREAM_LEN, MAVLINK_MSG_ID_DATA_STREAM_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA_STREAM, (const char *)packet, MAVLINK_MSG_ID_DATA_STREAM_LEN);
#endif
#endif
}
#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), MAVLINK_MSG_ID_DATA_STREAM_LEN);
#endif
}

View file

@ -0,0 +1,353 @@
// MESSAGE DATA_TRANSMISSION_HANDSHAKE PACKING
#define MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE 130
typedef struct __mavlink_data_transmission_handshake_t
{
uint32_t size; ///< total data size in bytes (set on ACK only)
uint16_t width; ///< Width of a matrix or image
uint16_t height; ///< Height of a matrix or image
uint16_t packets; ///< number of packets beeing sent (set on ACK only)
uint8_t type; ///< type of requested/acknowledged data (as defined in ENUM DATA_TYPES in mavlink/include/mavlink_types.h)
uint8_t payload; ///< payload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only)
uint8_t jpg_quality; ///< JPEG quality out of [1,100]
} mavlink_data_transmission_handshake_t;
#define MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN 13
#define MAVLINK_MSG_ID_130_LEN 13
#define MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_CRC 29
#define MAVLINK_MSG_ID_130_CRC 29
#define MAVLINK_MESSAGE_INFO_DATA_TRANSMISSION_HANDSHAKE { \
"DATA_TRANSMISSION_HANDSHAKE", \
7, \
{ { "size", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_data_transmission_handshake_t, size) }, \
{ "width", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_data_transmission_handshake_t, width) }, \
{ "height", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_data_transmission_handshake_t, height) }, \
{ "packets", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_data_transmission_handshake_t, packets) }, \
{ "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_data_transmission_handshake_t, type) }, \
{ "payload", NULL, MAVLINK_TYPE_UINT8_T, 0, 11, offsetof(mavlink_data_transmission_handshake_t, payload) }, \
{ "jpg_quality", NULL, MAVLINK_TYPE_UINT8_T, 0, 12, offsetof(mavlink_data_transmission_handshake_t, jpg_quality) }, \
} \
}
/**
* @brief Pack a data_transmission_handshake message
* @param system_id ID of this 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 requested/acknowledged data (as defined in ENUM DATA_TYPES in mavlink/include/mavlink_types.h)
* @param size total data size in bytes (set on ACK only)
* @param width Width of a matrix or image
* @param height Height of a matrix or image
* @param packets number of packets beeing sent (set on ACK only)
* @param payload payload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only)
* @param jpg_quality JPEG quality out of [1,100]
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_data_transmission_handshake_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t type, uint32_t size, uint16_t width, uint16_t height, uint16_t packets, uint8_t payload, uint8_t jpg_quality)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN];
_mav_put_uint32_t(buf, 0, size);
_mav_put_uint16_t(buf, 4, width);
_mav_put_uint16_t(buf, 6, height);
_mav_put_uint16_t(buf, 8, packets);
_mav_put_uint8_t(buf, 10, type);
_mav_put_uint8_t(buf, 11, payload);
_mav_put_uint8_t(buf, 12, jpg_quality);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN);
#else
mavlink_data_transmission_handshake_t packet;
packet.size = size;
packet.width = width;
packet.height = height;
packet.packets = packets;
packet.type = type;
packet.payload = payload;
packet.jpg_quality = jpg_quality;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_CRC);
#else
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN);
#endif
}
/**
* @brief Pack a data_transmission_handshake 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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param type type of requested/acknowledged data (as defined in ENUM DATA_TYPES in mavlink/include/mavlink_types.h)
* @param size total data size in bytes (set on ACK only)
* @param width Width of a matrix or image
* @param height Height of a matrix or image
* @param packets number of packets beeing sent (set on ACK only)
* @param payload payload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only)
* @param jpg_quality JPEG quality out of [1,100]
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_data_transmission_handshake_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint8_t type,uint32_t size,uint16_t width,uint16_t height,uint16_t packets,uint8_t payload,uint8_t jpg_quality)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN];
_mav_put_uint32_t(buf, 0, size);
_mav_put_uint16_t(buf, 4, width);
_mav_put_uint16_t(buf, 6, height);
_mav_put_uint16_t(buf, 8, packets);
_mav_put_uint8_t(buf, 10, type);
_mav_put_uint8_t(buf, 11, payload);
_mav_put_uint8_t(buf, 12, jpg_quality);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN);
#else
mavlink_data_transmission_handshake_t packet;
packet.size = size;
packet.width = width;
packet.height = height;
packet.packets = packets;
packet.type = type;
packet.payload = payload;
packet.jpg_quality = jpg_quality;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_CRC);
#else
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN);
#endif
}
/**
* @brief Encode a data_transmission_handshake struct
*
* @param system_id ID of this 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_transmission_handshake C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_data_transmission_handshake_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_data_transmission_handshake_t* data_transmission_handshake)
{
return mavlink_msg_data_transmission_handshake_pack(system_id, component_id, msg, data_transmission_handshake->type, data_transmission_handshake->size, data_transmission_handshake->width, data_transmission_handshake->height, data_transmission_handshake->packets, data_transmission_handshake->payload, data_transmission_handshake->jpg_quality);
}
/**
* @brief Encode a data_transmission_handshake struct 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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param data_transmission_handshake C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_data_transmission_handshake_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_data_transmission_handshake_t* data_transmission_handshake)
{
return mavlink_msg_data_transmission_handshake_pack_chan(system_id, component_id, chan, msg, data_transmission_handshake->type, data_transmission_handshake->size, data_transmission_handshake->width, data_transmission_handshake->height, data_transmission_handshake->packets, data_transmission_handshake->payload, data_transmission_handshake->jpg_quality);
}
/**
* @brief Send a data_transmission_handshake message
* @param chan MAVLink channel to send the message
*
* @param type type of requested/acknowledged data (as defined in ENUM DATA_TYPES in mavlink/include/mavlink_types.h)
* @param size total data size in bytes (set on ACK only)
* @param width Width of a matrix or image
* @param height Height of a matrix or image
* @param packets number of packets beeing sent (set on ACK only)
* @param payload payload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only)
* @param jpg_quality JPEG quality out of [1,100]
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_data_transmission_handshake_send(mavlink_channel_t chan, uint8_t type, uint32_t size, uint16_t width, uint16_t height, uint16_t packets, uint8_t payload, uint8_t jpg_quality)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN];
_mav_put_uint32_t(buf, 0, size);
_mav_put_uint16_t(buf, 4, width);
_mav_put_uint16_t(buf, 6, height);
_mav_put_uint16_t(buf, 8, packets);
_mav_put_uint8_t(buf, 10, type);
_mav_put_uint8_t(buf, 11, payload);
_mav_put_uint8_t(buf, 12, jpg_quality);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE, buf, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE, buf, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN);
#endif
#else
mavlink_data_transmission_handshake_t packet;
packet.size = size;
packet.width = width;
packet.height = height;
packet.packets = packets;
packet.type = type;
packet.payload = payload;
packet.jpg_quality = jpg_quality;
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE, (const char *)&packet, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE, (const char *)&packet, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN);
#endif
#endif
}
#if MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This varient of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_data_transmission_handshake_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t type, uint32_t size, uint16_t width, uint16_t height, uint16_t packets, uint8_t payload, uint8_t jpg_quality)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
_mav_put_uint32_t(buf, 0, size);
_mav_put_uint16_t(buf, 4, width);
_mav_put_uint16_t(buf, 6, height);
_mav_put_uint16_t(buf, 8, packets);
_mav_put_uint8_t(buf, 10, type);
_mav_put_uint8_t(buf, 11, payload);
_mav_put_uint8_t(buf, 12, jpg_quality);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE, buf, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE, buf, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN);
#endif
#else
mavlink_data_transmission_handshake_t *packet = (mavlink_data_transmission_handshake_t *)msgbuf;
packet->size = size;
packet->width = width;
packet->height = height;
packet->packets = packets;
packet->type = type;
packet->payload = payload;
packet->jpg_quality = jpg_quality;
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE, (const char *)packet, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE, (const char *)packet, MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN);
#endif
#endif
}
#endif
#endif
// MESSAGE DATA_TRANSMISSION_HANDSHAKE UNPACKING
/**
* @brief Get field type from data_transmission_handshake message
*
* @return type of requested/acknowledged data (as defined in ENUM DATA_TYPES in mavlink/include/mavlink_types.h)
*/
static inline uint8_t mavlink_msg_data_transmission_handshake_get_type(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 10);
}
/**
* @brief Get field size from data_transmission_handshake message
*
* @return total data size in bytes (set on ACK only)
*/
static inline uint32_t mavlink_msg_data_transmission_handshake_get_size(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint32_t(msg, 0);
}
/**
* @brief Get field width from data_transmission_handshake message
*
* @return Width of a matrix or image
*/
static inline uint16_t mavlink_msg_data_transmission_handshake_get_width(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 4);
}
/**
* @brief Get field height from data_transmission_handshake message
*
* @return Height of a matrix or image
*/
static inline uint16_t mavlink_msg_data_transmission_handshake_get_height(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 6);
}
/**
* @brief Get field packets from data_transmission_handshake message
*
* @return number of packets beeing sent (set on ACK only)
*/
static inline uint16_t mavlink_msg_data_transmission_handshake_get_packets(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 8);
}
/**
* @brief Get field payload from data_transmission_handshake message
*
* @return payload size per packet (normally 253 byte, see DATA field size in message ENCAPSULATED_DATA) (set on ACK only)
*/
static inline uint8_t mavlink_msg_data_transmission_handshake_get_payload(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 11);
}
/**
* @brief Get field jpg_quality from data_transmission_handshake message
*
* @return JPEG quality out of [1,100]
*/
static inline uint8_t mavlink_msg_data_transmission_handshake_get_jpg_quality(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 12);
}
/**
* @brief Decode a data_transmission_handshake message into a struct
*
* @param msg The message to decode
* @param data_transmission_handshake C-struct to decode the message contents into
*/
static inline void mavlink_msg_data_transmission_handshake_decode(const mavlink_message_t* msg, mavlink_data_transmission_handshake_t* data_transmission_handshake)
{
#if MAVLINK_NEED_BYTE_SWAP
data_transmission_handshake->size = mavlink_msg_data_transmission_handshake_get_size(msg);
data_transmission_handshake->width = mavlink_msg_data_transmission_handshake_get_width(msg);
data_transmission_handshake->height = mavlink_msg_data_transmission_handshake_get_height(msg);
data_transmission_handshake->packets = mavlink_msg_data_transmission_handshake_get_packets(msg);
data_transmission_handshake->type = mavlink_msg_data_transmission_handshake_get_type(msg);
data_transmission_handshake->payload = mavlink_msg_data_transmission_handshake_get_payload(msg);
data_transmission_handshake->jpg_quality = mavlink_msg_data_transmission_handshake_get_jpg_quality(msg);
#else
memcpy(data_transmission_handshake, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_DATA_TRANSMISSION_HANDSHAKE_LEN);
#endif
}

View file

@ -0,0 +1,257 @@
// 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_MSG_ID_DEBUG_CRC 46
#define MAVLINK_MSG_ID_254_CRC 46
#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[MAVLINK_MSG_ID_DEBUG_LEN];
_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, MAVLINK_MSG_ID_DEBUG_LEN);
#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, MAVLINK_MSG_ID_DEBUG_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_DEBUG;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_DEBUG_LEN, MAVLINK_MSG_ID_DEBUG_CRC);
#else
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_DEBUG_LEN);
#endif
}
/**
* @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 will be 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[MAVLINK_MSG_ID_DEBUG_LEN];
_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, MAVLINK_MSG_ID_DEBUG_LEN);
#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, MAVLINK_MSG_ID_DEBUG_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_DEBUG;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_DEBUG_LEN, MAVLINK_MSG_ID_DEBUG_CRC);
#else
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_DEBUG_LEN);
#endif
}
/**
* @brief Encode a debug struct
*
* @param system_id ID of this 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 Encode a debug struct 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 will be sent over
* @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_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_debug_t* debug)
{
return mavlink_msg_debug_pack_chan(system_id, component_id, chan, 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[MAVLINK_MSG_ID_DEBUG_LEN];
_mav_put_uint32_t(buf, 0, time_boot_ms);
_mav_put_float(buf, 4, value);
_mav_put_uint8_t(buf, 8, ind);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG, buf, MAVLINK_MSG_ID_DEBUG_LEN, MAVLINK_MSG_ID_DEBUG_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG, buf, MAVLINK_MSG_ID_DEBUG_LEN);
#endif
#else
mavlink_debug_t packet;
packet.time_boot_ms = time_boot_ms;
packet.value = value;
packet.ind = ind;
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG, (const char *)&packet, MAVLINK_MSG_ID_DEBUG_LEN, MAVLINK_MSG_ID_DEBUG_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG, (const char *)&packet, MAVLINK_MSG_ID_DEBUG_LEN);
#endif
#endif
}
#if MAVLINK_MSG_ID_DEBUG_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This varient of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_debug_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t ind, float value)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
_mav_put_uint32_t(buf, 0, time_boot_ms);
_mav_put_float(buf, 4, value);
_mav_put_uint8_t(buf, 8, ind);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG, buf, MAVLINK_MSG_ID_DEBUG_LEN, MAVLINK_MSG_ID_DEBUG_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG, buf, MAVLINK_MSG_ID_DEBUG_LEN);
#endif
#else
mavlink_debug_t *packet = (mavlink_debug_t *)msgbuf;
packet->time_boot_ms = time_boot_ms;
packet->value = value;
packet->ind = ind;
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG, (const char *)packet, MAVLINK_MSG_ID_DEBUG_LEN, MAVLINK_MSG_ID_DEBUG_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG, (const char *)packet, MAVLINK_MSG_ID_DEBUG_LEN);
#endif
#endif
}
#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), MAVLINK_MSG_ID_DEBUG_LEN);
#endif
}

View file

@ -0,0 +1,297 @@
// 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_ID_DEBUG_VECT_CRC 49
#define MAVLINK_MSG_ID_250_CRC 49
#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[MAVLINK_MSG_ID_DEBUG_VECT_LEN];
_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, MAVLINK_MSG_ID_DEBUG_VECT_LEN);
#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, MAVLINK_MSG_ID_DEBUG_VECT_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_DEBUG_VECT;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_DEBUG_VECT_LEN, MAVLINK_MSG_ID_DEBUG_VECT_CRC);
#else
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_DEBUG_VECT_LEN);
#endif
}
/**
* @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 will be 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[MAVLINK_MSG_ID_DEBUG_VECT_LEN];
_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, MAVLINK_MSG_ID_DEBUG_VECT_LEN);
#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, MAVLINK_MSG_ID_DEBUG_VECT_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_DEBUG_VECT;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_DEBUG_VECT_LEN, MAVLINK_MSG_ID_DEBUG_VECT_CRC);
#else
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_DEBUG_VECT_LEN);
#endif
}
/**
* @brief Encode a debug_vect struct
*
* @param system_id ID of this 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 Encode a debug_vect struct 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 will be sent over
* @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_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_debug_vect_t* debug_vect)
{
return mavlink_msg_debug_vect_pack_chan(system_id, component_id, chan, 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[MAVLINK_MSG_ID_DEBUG_VECT_LEN];
_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);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG_VECT, buf, MAVLINK_MSG_ID_DEBUG_VECT_LEN, MAVLINK_MSG_ID_DEBUG_VECT_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG_VECT, buf, MAVLINK_MSG_ID_DEBUG_VECT_LEN);
#endif
#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);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG_VECT, (const char *)&packet, MAVLINK_MSG_ID_DEBUG_VECT_LEN, MAVLINK_MSG_ID_DEBUG_VECT_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG_VECT, (const char *)&packet, MAVLINK_MSG_ID_DEBUG_VECT_LEN);
#endif
#endif
}
#if MAVLINK_MSG_ID_DEBUG_VECT_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This varient of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_debug_vect_send_buf(mavlink_message_t *msgbuf, 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 = (char *)msgbuf;
_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);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG_VECT, buf, MAVLINK_MSG_ID_DEBUG_VECT_LEN, MAVLINK_MSG_ID_DEBUG_VECT_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG_VECT, buf, MAVLINK_MSG_ID_DEBUG_VECT_LEN);
#endif
#else
mavlink_debug_vect_t *packet = (mavlink_debug_vect_t *)msgbuf;
packet->time_usec = time_usec;
packet->x = x;
packet->y = y;
packet->z = z;
mav_array_memcpy(packet->name, name, sizeof(char)*10);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG_VECT, (const char *)packet, MAVLINK_MSG_ID_DEBUG_VECT_LEN, MAVLINK_MSG_ID_DEBUG_VECT_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG_VECT, (const char *)packet, MAVLINK_MSG_ID_DEBUG_VECT_LEN);
#endif
#endif
}
#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), MAVLINK_MSG_ID_DEBUG_VECT_LEN);
#endif
}

View file

@ -0,0 +1,377 @@
// MESSAGE DISTANCE_SENSOR PACKING
#define MAVLINK_MSG_ID_DISTANCE_SENSOR 132
typedef struct __mavlink_distance_sensor_t
{
uint32_t time_boot_ms; ///< Time since system boot
uint16_t min_distance; ///< Minimum distance the sensor can measure in centimeters
uint16_t max_distance; ///< Maximum distance the sensor can measure in centimeters
uint16_t current_distance; ///< Current distance reading
uint8_t type; ///< Type from MAV_DISTANCE_SENSOR enum.
uint8_t id; ///< Onboard ID of the sensor
uint8_t orientation; ///< Direction the sensor faces from FIXME enum.
uint8_t covariance; ///< Measurement covariance in centimeters, 0 for unknown / invalid readings
} mavlink_distance_sensor_t;
#define MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN 14
#define MAVLINK_MSG_ID_132_LEN 14
#define MAVLINK_MSG_ID_DISTANCE_SENSOR_CRC 85
#define MAVLINK_MSG_ID_132_CRC 85
#define MAVLINK_MESSAGE_INFO_DISTANCE_SENSOR { \
"DISTANCE_SENSOR", \
8, \
{ { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_distance_sensor_t, time_boot_ms) }, \
{ "min_distance", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_distance_sensor_t, min_distance) }, \
{ "max_distance", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_distance_sensor_t, max_distance) }, \
{ "current_distance", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_distance_sensor_t, current_distance) }, \
{ "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_distance_sensor_t, type) }, \
{ "id", NULL, MAVLINK_TYPE_UINT8_T, 0, 11, offsetof(mavlink_distance_sensor_t, id) }, \
{ "orientation", NULL, MAVLINK_TYPE_UINT8_T, 0, 12, offsetof(mavlink_distance_sensor_t, orientation) }, \
{ "covariance", NULL, MAVLINK_TYPE_UINT8_T, 0, 13, offsetof(mavlink_distance_sensor_t, covariance) }, \
} \
}
/**
* @brief Pack a distance_sensor message
* @param system_id ID of this 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 Time since system boot
* @param min_distance Minimum distance the sensor can measure in centimeters
* @param max_distance Maximum distance the sensor can measure in centimeters
* @param current_distance Current distance reading
* @param type Type from MAV_DISTANCE_SENSOR enum.
* @param id Onboard ID of the sensor
* @param orientation Direction the sensor faces from FIXME enum.
* @param covariance Measurement covariance in centimeters, 0 for unknown / invalid readings
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_distance_sensor_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint32_t time_boot_ms, uint16_t min_distance, uint16_t max_distance, uint16_t current_distance, uint8_t type, uint8_t id, uint8_t orientation, uint8_t covariance)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN];
_mav_put_uint32_t(buf, 0, time_boot_ms);
_mav_put_uint16_t(buf, 4, min_distance);
_mav_put_uint16_t(buf, 6, max_distance);
_mav_put_uint16_t(buf, 8, current_distance);
_mav_put_uint8_t(buf, 10, type);
_mav_put_uint8_t(buf, 11, id);
_mav_put_uint8_t(buf, 12, orientation);
_mav_put_uint8_t(buf, 13, covariance);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN);
#else
mavlink_distance_sensor_t packet;
packet.time_boot_ms = time_boot_ms;
packet.min_distance = min_distance;
packet.max_distance = max_distance;
packet.current_distance = current_distance;
packet.type = type;
packet.id = id;
packet.orientation = orientation;
packet.covariance = covariance;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_DISTANCE_SENSOR;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN, MAVLINK_MSG_ID_DISTANCE_SENSOR_CRC);
#else
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN);
#endif
}
/**
* @brief Pack a distance_sensor 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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param time_boot_ms Time since system boot
* @param min_distance Minimum distance the sensor can measure in centimeters
* @param max_distance Maximum distance the sensor can measure in centimeters
* @param current_distance Current distance reading
* @param type Type from MAV_DISTANCE_SENSOR enum.
* @param id Onboard ID of the sensor
* @param orientation Direction the sensor faces from FIXME enum.
* @param covariance Measurement covariance in centimeters, 0 for unknown / invalid readings
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_distance_sensor_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint32_t time_boot_ms,uint16_t min_distance,uint16_t max_distance,uint16_t current_distance,uint8_t type,uint8_t id,uint8_t orientation,uint8_t covariance)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN];
_mav_put_uint32_t(buf, 0, time_boot_ms);
_mav_put_uint16_t(buf, 4, min_distance);
_mav_put_uint16_t(buf, 6, max_distance);
_mav_put_uint16_t(buf, 8, current_distance);
_mav_put_uint8_t(buf, 10, type);
_mav_put_uint8_t(buf, 11, id);
_mav_put_uint8_t(buf, 12, orientation);
_mav_put_uint8_t(buf, 13, covariance);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN);
#else
mavlink_distance_sensor_t packet;
packet.time_boot_ms = time_boot_ms;
packet.min_distance = min_distance;
packet.max_distance = max_distance;
packet.current_distance = current_distance;
packet.type = type;
packet.id = id;
packet.orientation = orientation;
packet.covariance = covariance;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_DISTANCE_SENSOR;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN, MAVLINK_MSG_ID_DISTANCE_SENSOR_CRC);
#else
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN);
#endif
}
/**
* @brief Encode a distance_sensor struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param distance_sensor C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_distance_sensor_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_distance_sensor_t* distance_sensor)
{
return mavlink_msg_distance_sensor_pack(system_id, component_id, msg, distance_sensor->time_boot_ms, distance_sensor->min_distance, distance_sensor->max_distance, distance_sensor->current_distance, distance_sensor->type, distance_sensor->id, distance_sensor->orientation, distance_sensor->covariance);
}
/**
* @brief Encode a distance_sensor struct 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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param distance_sensor C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_distance_sensor_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_distance_sensor_t* distance_sensor)
{
return mavlink_msg_distance_sensor_pack_chan(system_id, component_id, chan, msg, distance_sensor->time_boot_ms, distance_sensor->min_distance, distance_sensor->max_distance, distance_sensor->current_distance, distance_sensor->type, distance_sensor->id, distance_sensor->orientation, distance_sensor->covariance);
}
/**
* @brief Send a distance_sensor message
* @param chan MAVLink channel to send the message
*
* @param time_boot_ms Time since system boot
* @param min_distance Minimum distance the sensor can measure in centimeters
* @param max_distance Maximum distance the sensor can measure in centimeters
* @param current_distance Current distance reading
* @param type Type from MAV_DISTANCE_SENSOR enum.
* @param id Onboard ID of the sensor
* @param orientation Direction the sensor faces from FIXME enum.
* @param covariance Measurement covariance in centimeters, 0 for unknown / invalid readings
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_distance_sensor_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint16_t min_distance, uint16_t max_distance, uint16_t current_distance, uint8_t type, uint8_t id, uint8_t orientation, uint8_t covariance)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN];
_mav_put_uint32_t(buf, 0, time_boot_ms);
_mav_put_uint16_t(buf, 4, min_distance);
_mav_put_uint16_t(buf, 6, max_distance);
_mav_put_uint16_t(buf, 8, current_distance);
_mav_put_uint8_t(buf, 10, type);
_mav_put_uint8_t(buf, 11, id);
_mav_put_uint8_t(buf, 12, orientation);
_mav_put_uint8_t(buf, 13, covariance);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DISTANCE_SENSOR, buf, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN, MAVLINK_MSG_ID_DISTANCE_SENSOR_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DISTANCE_SENSOR, buf, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN);
#endif
#else
mavlink_distance_sensor_t packet;
packet.time_boot_ms = time_boot_ms;
packet.min_distance = min_distance;
packet.max_distance = max_distance;
packet.current_distance = current_distance;
packet.type = type;
packet.id = id;
packet.orientation = orientation;
packet.covariance = covariance;
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DISTANCE_SENSOR, (const char *)&packet, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN, MAVLINK_MSG_ID_DISTANCE_SENSOR_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DISTANCE_SENSOR, (const char *)&packet, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN);
#endif
#endif
}
#if MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This varient of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_distance_sensor_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, uint16_t min_distance, uint16_t max_distance, uint16_t current_distance, uint8_t type, uint8_t id, uint8_t orientation, uint8_t covariance)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
_mav_put_uint32_t(buf, 0, time_boot_ms);
_mav_put_uint16_t(buf, 4, min_distance);
_mav_put_uint16_t(buf, 6, max_distance);
_mav_put_uint16_t(buf, 8, current_distance);
_mav_put_uint8_t(buf, 10, type);
_mav_put_uint8_t(buf, 11, id);
_mav_put_uint8_t(buf, 12, orientation);
_mav_put_uint8_t(buf, 13, covariance);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DISTANCE_SENSOR, buf, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN, MAVLINK_MSG_ID_DISTANCE_SENSOR_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DISTANCE_SENSOR, buf, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN);
#endif
#else
mavlink_distance_sensor_t *packet = (mavlink_distance_sensor_t *)msgbuf;
packet->time_boot_ms = time_boot_ms;
packet->min_distance = min_distance;
packet->max_distance = max_distance;
packet->current_distance = current_distance;
packet->type = type;
packet->id = id;
packet->orientation = orientation;
packet->covariance = covariance;
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DISTANCE_SENSOR, (const char *)packet, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN, MAVLINK_MSG_ID_DISTANCE_SENSOR_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DISTANCE_SENSOR, (const char *)packet, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN);
#endif
#endif
}
#endif
#endif
// MESSAGE DISTANCE_SENSOR UNPACKING
/**
* @brief Get field time_boot_ms from distance_sensor message
*
* @return Time since system boot
*/
static inline uint32_t mavlink_msg_distance_sensor_get_time_boot_ms(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint32_t(msg, 0);
}
/**
* @brief Get field min_distance from distance_sensor message
*
* @return Minimum distance the sensor can measure in centimeters
*/
static inline uint16_t mavlink_msg_distance_sensor_get_min_distance(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 4);
}
/**
* @brief Get field max_distance from distance_sensor message
*
* @return Maximum distance the sensor can measure in centimeters
*/
static inline uint16_t mavlink_msg_distance_sensor_get_max_distance(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 6);
}
/**
* @brief Get field current_distance from distance_sensor message
*
* @return Current distance reading
*/
static inline uint16_t mavlink_msg_distance_sensor_get_current_distance(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 8);
}
/**
* @brief Get field type from distance_sensor message
*
* @return Type from MAV_DISTANCE_SENSOR enum.
*/
static inline uint8_t mavlink_msg_distance_sensor_get_type(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 10);
}
/**
* @brief Get field id from distance_sensor message
*
* @return Onboard ID of the sensor
*/
static inline uint8_t mavlink_msg_distance_sensor_get_id(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 11);
}
/**
* @brief Get field orientation from distance_sensor message
*
* @return Direction the sensor faces from FIXME enum.
*/
static inline uint8_t mavlink_msg_distance_sensor_get_orientation(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 12);
}
/**
* @brief Get field covariance from distance_sensor message
*
* @return Measurement covariance in centimeters, 0 for unknown / invalid readings
*/
static inline uint8_t mavlink_msg_distance_sensor_get_covariance(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 13);
}
/**
* @brief Decode a distance_sensor message into a struct
*
* @param msg The message to decode
* @param distance_sensor C-struct to decode the message contents into
*/
static inline void mavlink_msg_distance_sensor_decode(const mavlink_message_t* msg, mavlink_distance_sensor_t* distance_sensor)
{
#if MAVLINK_NEED_BYTE_SWAP
distance_sensor->time_boot_ms = mavlink_msg_distance_sensor_get_time_boot_ms(msg);
distance_sensor->min_distance = mavlink_msg_distance_sensor_get_min_distance(msg);
distance_sensor->max_distance = mavlink_msg_distance_sensor_get_max_distance(msg);
distance_sensor->current_distance = mavlink_msg_distance_sensor_get_current_distance(msg);
distance_sensor->type = mavlink_msg_distance_sensor_get_type(msg);
distance_sensor->id = mavlink_msg_distance_sensor_get_id(msg);
distance_sensor->orientation = mavlink_msg_distance_sensor_get_orientation(msg);
distance_sensor->covariance = mavlink_msg_distance_sensor_get_covariance(msg);
#else
memcpy(distance_sensor, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN);
#endif
}

View file

@ -0,0 +1,225 @@
// MESSAGE ENCAPSULATED_DATA PACKING
#define MAVLINK_MSG_ID_ENCAPSULATED_DATA 131
typedef struct __mavlink_encapsulated_data_t
{
uint16_t seqnr; ///< sequence number (starting with 0 on every transmission)
uint8_t data[253]; ///< image data bytes
} mavlink_encapsulated_data_t;
#define MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN 255
#define MAVLINK_MSG_ID_131_LEN 255
#define MAVLINK_MSG_ID_ENCAPSULATED_DATA_CRC 223
#define MAVLINK_MSG_ID_131_CRC 223
#define MAVLINK_MSG_ENCAPSULATED_DATA_FIELD_DATA_LEN 253
#define MAVLINK_MESSAGE_INFO_ENCAPSULATED_DATA { \
"ENCAPSULATED_DATA", \
2, \
{ { "seqnr", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_encapsulated_data_t, seqnr) }, \
{ "data", NULL, MAVLINK_TYPE_UINT8_T, 253, 2, offsetof(mavlink_encapsulated_data_t, data) }, \
} \
}
/**
* @brief Pack a encapsulated_data message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param seqnr sequence number (starting with 0 on every transmission)
* @param data image data bytes
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_encapsulated_data_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint16_t seqnr, const uint8_t *data)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN];
_mav_put_uint16_t(buf, 0, seqnr);
_mav_put_uint8_t_array(buf, 2, data, 253);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN);
#else
mavlink_encapsulated_data_t packet;
packet.seqnr = seqnr;
mav_array_memcpy(packet.data, data, sizeof(uint8_t)*253);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_ENCAPSULATED_DATA;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN, MAVLINK_MSG_ID_ENCAPSULATED_DATA_CRC);
#else
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN);
#endif
}
/**
* @brief Pack a encapsulated_data 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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param seqnr sequence number (starting with 0 on every transmission)
* @param data image data bytes
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_encapsulated_data_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint16_t seqnr,const uint8_t *data)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN];
_mav_put_uint16_t(buf, 0, seqnr);
_mav_put_uint8_t_array(buf, 2, data, 253);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN);
#else
mavlink_encapsulated_data_t packet;
packet.seqnr = seqnr;
mav_array_memcpy(packet.data, data, sizeof(uint8_t)*253);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_ENCAPSULATED_DATA;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN, MAVLINK_MSG_ID_ENCAPSULATED_DATA_CRC);
#else
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN);
#endif
}
/**
* @brief Encode a encapsulated_data struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param encapsulated_data C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_encapsulated_data_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_encapsulated_data_t* encapsulated_data)
{
return mavlink_msg_encapsulated_data_pack(system_id, component_id, msg, encapsulated_data->seqnr, encapsulated_data->data);
}
/**
* @brief Encode a encapsulated_data struct 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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param encapsulated_data C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_encapsulated_data_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_encapsulated_data_t* encapsulated_data)
{
return mavlink_msg_encapsulated_data_pack_chan(system_id, component_id, chan, msg, encapsulated_data->seqnr, encapsulated_data->data);
}
/**
* @brief Send a encapsulated_data message
* @param chan MAVLink channel to send the message
*
* @param seqnr sequence number (starting with 0 on every transmission)
* @param data image data bytes
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_encapsulated_data_send(mavlink_channel_t chan, uint16_t seqnr, const uint8_t *data)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN];
_mav_put_uint16_t(buf, 0, seqnr);
_mav_put_uint8_t_array(buf, 2, data, 253);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ENCAPSULATED_DATA, buf, MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN, MAVLINK_MSG_ID_ENCAPSULATED_DATA_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ENCAPSULATED_DATA, buf, MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN);
#endif
#else
mavlink_encapsulated_data_t packet;
packet.seqnr = seqnr;
mav_array_memcpy(packet.data, data, sizeof(uint8_t)*253);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ENCAPSULATED_DATA, (const char *)&packet, MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN, MAVLINK_MSG_ID_ENCAPSULATED_DATA_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ENCAPSULATED_DATA, (const char *)&packet, MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN);
#endif
#endif
}
#if MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This varient of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_encapsulated_data_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint16_t seqnr, const uint8_t *data)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
_mav_put_uint16_t(buf, 0, seqnr);
_mav_put_uint8_t_array(buf, 2, data, 253);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ENCAPSULATED_DATA, buf, MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN, MAVLINK_MSG_ID_ENCAPSULATED_DATA_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ENCAPSULATED_DATA, buf, MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN);
#endif
#else
mavlink_encapsulated_data_t *packet = (mavlink_encapsulated_data_t *)msgbuf;
packet->seqnr = seqnr;
mav_array_memcpy(packet->data, data, sizeof(uint8_t)*253);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ENCAPSULATED_DATA, (const char *)packet, MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN, MAVLINK_MSG_ID_ENCAPSULATED_DATA_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ENCAPSULATED_DATA, (const char *)packet, MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN);
#endif
#endif
}
#endif
#endif
// MESSAGE ENCAPSULATED_DATA UNPACKING
/**
* @brief Get field seqnr from encapsulated_data message
*
* @return sequence number (starting with 0 on every transmission)
*/
static inline uint16_t mavlink_msg_encapsulated_data_get_seqnr(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 0);
}
/**
* @brief Get field data from encapsulated_data message
*
* @return image data bytes
*/
static inline uint16_t mavlink_msg_encapsulated_data_get_data(const mavlink_message_t* msg, uint8_t *data)
{
return _MAV_RETURN_uint8_t_array(msg, data, 253, 2);
}
/**
* @brief Decode a encapsulated_data message into a struct
*
* @param msg The message to decode
* @param encapsulated_data C-struct to decode the message contents into
*/
static inline void mavlink_msg_encapsulated_data_decode(const mavlink_message_t* msg, mavlink_encapsulated_data_t* encapsulated_data)
{
#if MAVLINK_NEED_BYTE_SWAP
encapsulated_data->seqnr = mavlink_msg_encapsulated_data_get_seqnr(msg);
mavlink_msg_encapsulated_data_get_data(msg, encapsulated_data->data);
#else
memcpy(encapsulated_data, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_ENCAPSULATED_DATA_LEN);
#endif
}

View file

@ -0,0 +1,273 @@
// MESSAGE FILE_TRANSFER_PROTOCOL PACKING
#define MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL 110
typedef struct __mavlink_file_transfer_protocol_t
{
uint8_t target_network; ///< Network ID (0 for broadcast)
uint8_t target_system; ///< System ID (0 for broadcast)
uint8_t target_component; ///< Component ID (0 for broadcast)
uint8_t payload[251]; ///< Variable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The entire content of this block is opaque unless you understand any the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the mavlink specification.
} mavlink_file_transfer_protocol_t;
#define MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN 254
#define MAVLINK_MSG_ID_110_LEN 254
#define MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_CRC 84
#define MAVLINK_MSG_ID_110_CRC 84
#define MAVLINK_MSG_FILE_TRANSFER_PROTOCOL_FIELD_PAYLOAD_LEN 251
#define MAVLINK_MESSAGE_INFO_FILE_TRANSFER_PROTOCOL { \
"FILE_TRANSFER_PROTOCOL", \
4, \
{ { "target_network", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_file_transfer_protocol_t, target_network) }, \
{ "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_file_transfer_protocol_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_file_transfer_protocol_t, target_component) }, \
{ "payload", NULL, MAVLINK_TYPE_UINT8_T, 251, 3, offsetof(mavlink_file_transfer_protocol_t, payload) }, \
} \
}
/**
* @brief Pack a file_transfer_protocol message
* @param system_id ID of this 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_network Network ID (0 for broadcast)
* @param target_system System ID (0 for broadcast)
* @param target_component Component ID (0 for broadcast)
* @param payload Variable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The entire content of this block is opaque unless you understand any the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the mavlink specification.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_file_transfer_protocol_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t target_network, uint8_t target_system, uint8_t target_component, const uint8_t *payload)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN];
_mav_put_uint8_t(buf, 0, target_network);
_mav_put_uint8_t(buf, 1, target_system);
_mav_put_uint8_t(buf, 2, target_component);
_mav_put_uint8_t_array(buf, 3, payload, 251);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN);
#else
mavlink_file_transfer_protocol_t packet;
packet.target_network = target_network;
packet.target_system = target_system;
packet.target_component = target_component;
mav_array_memcpy(packet.payload, payload, sizeof(uint8_t)*251);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_CRC);
#else
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN);
#endif
}
/**
* @brief Pack a file_transfer_protocol 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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param target_network Network ID (0 for broadcast)
* @param target_system System ID (0 for broadcast)
* @param target_component Component ID (0 for broadcast)
* @param payload Variable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The entire content of this block is opaque unless you understand any the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the mavlink specification.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_file_transfer_protocol_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint8_t target_network,uint8_t target_system,uint8_t target_component,const uint8_t *payload)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN];
_mav_put_uint8_t(buf, 0, target_network);
_mav_put_uint8_t(buf, 1, target_system);
_mav_put_uint8_t(buf, 2, target_component);
_mav_put_uint8_t_array(buf, 3, payload, 251);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN);
#else
mavlink_file_transfer_protocol_t packet;
packet.target_network = target_network;
packet.target_system = target_system;
packet.target_component = target_component;
mav_array_memcpy(packet.payload, payload, sizeof(uint8_t)*251);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_CRC);
#else
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN);
#endif
}
/**
* @brief Encode a file_transfer_protocol struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param file_transfer_protocol C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_file_transfer_protocol_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_file_transfer_protocol_t* file_transfer_protocol)
{
return mavlink_msg_file_transfer_protocol_pack(system_id, component_id, msg, file_transfer_protocol->target_network, file_transfer_protocol->target_system, file_transfer_protocol->target_component, file_transfer_protocol->payload);
}
/**
* @brief Encode a file_transfer_protocol struct 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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param file_transfer_protocol C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_file_transfer_protocol_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_file_transfer_protocol_t* file_transfer_protocol)
{
return mavlink_msg_file_transfer_protocol_pack_chan(system_id, component_id, chan, msg, file_transfer_protocol->target_network, file_transfer_protocol->target_system, file_transfer_protocol->target_component, file_transfer_protocol->payload);
}
/**
* @brief Send a file_transfer_protocol message
* @param chan MAVLink channel to send the message
*
* @param target_network Network ID (0 for broadcast)
* @param target_system System ID (0 for broadcast)
* @param target_component Component ID (0 for broadcast)
* @param payload Variable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The entire content of this block is opaque unless you understand any the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the mavlink specification.
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_file_transfer_protocol_send(mavlink_channel_t chan, uint8_t target_network, uint8_t target_system, uint8_t target_component, const uint8_t *payload)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN];
_mav_put_uint8_t(buf, 0, target_network);
_mav_put_uint8_t(buf, 1, target_system);
_mav_put_uint8_t(buf, 2, target_component);
_mav_put_uint8_t_array(buf, 3, payload, 251);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL, buf, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL, buf, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN);
#endif
#else
mavlink_file_transfer_protocol_t packet;
packet.target_network = target_network;
packet.target_system = target_system;
packet.target_component = target_component;
mav_array_memcpy(packet.payload, payload, sizeof(uint8_t)*251);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL, (const char *)&packet, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL, (const char *)&packet, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN);
#endif
#endif
}
#if MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This varient of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_file_transfer_protocol_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_network, uint8_t target_system, uint8_t target_component, const uint8_t *payload)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
_mav_put_uint8_t(buf, 0, target_network);
_mav_put_uint8_t(buf, 1, target_system);
_mav_put_uint8_t(buf, 2, target_component);
_mav_put_uint8_t_array(buf, 3, payload, 251);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL, buf, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL, buf, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN);
#endif
#else
mavlink_file_transfer_protocol_t *packet = (mavlink_file_transfer_protocol_t *)msgbuf;
packet->target_network = target_network;
packet->target_system = target_system;
packet->target_component = target_component;
mav_array_memcpy(packet->payload, payload, sizeof(uint8_t)*251);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL, (const char *)packet, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL, (const char *)packet, MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN);
#endif
#endif
}
#endif
#endif
// MESSAGE FILE_TRANSFER_PROTOCOL UNPACKING
/**
* @brief Get field target_network from file_transfer_protocol message
*
* @return Network ID (0 for broadcast)
*/
static inline uint8_t mavlink_msg_file_transfer_protocol_get_target_network(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 0);
}
/**
* @brief Get field target_system from file_transfer_protocol message
*
* @return System ID (0 for broadcast)
*/
static inline uint8_t mavlink_msg_file_transfer_protocol_get_target_system(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 1);
}
/**
* @brief Get field target_component from file_transfer_protocol message
*
* @return Component ID (0 for broadcast)
*/
static inline uint8_t mavlink_msg_file_transfer_protocol_get_target_component(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 2);
}
/**
* @brief Get field payload from file_transfer_protocol message
*
* @return Variable length payload. The length is defined by the remaining message length when subtracting the header and other fields. The entire content of this block is opaque unless you understand any the encoding message_type. The particular encoding used can be extension specific and might not always be documented as part of the mavlink specification.
*/
static inline uint16_t mavlink_msg_file_transfer_protocol_get_payload(const mavlink_message_t* msg, uint8_t *payload)
{
return _MAV_RETURN_uint8_t_array(msg, payload, 251, 3);
}
/**
* @brief Decode a file_transfer_protocol message into a struct
*
* @param msg The message to decode
* @param file_transfer_protocol C-struct to decode the message contents into
*/
static inline void mavlink_msg_file_transfer_protocol_decode(const mavlink_message_t* msg, mavlink_file_transfer_protocol_t* file_transfer_protocol)
{
#if MAVLINK_NEED_BYTE_SWAP
file_transfer_protocol->target_network = mavlink_msg_file_transfer_protocol_get_target_network(msg);
file_transfer_protocol->target_system = mavlink_msg_file_transfer_protocol_get_target_system(msg);
file_transfer_protocol->target_component = mavlink_msg_file_transfer_protocol_get_target_component(msg);
mavlink_msg_file_transfer_protocol_get_payload(msg, file_transfer_protocol->payload);
#else
memcpy(file_transfer_protocol, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL_LEN);
#endif
}

View file

@ -0,0 +1,401 @@
// 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), AMSL (not WGS84 - note that virtually all GPS modules provide the AMSL as well)
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: UINT16_MAX
} mavlink_global_position_int_t;
#define MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN 28
#define MAVLINK_MSG_ID_33_LEN 28
#define MAVLINK_MSG_ID_GLOBAL_POSITION_INT_CRC 104
#define MAVLINK_MSG_ID_33_CRC 104
#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), AMSL (not WGS84 - note that virtually all GPS modules provide the AMSL as well)
* @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: UINT16_MAX
* @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[MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN];
_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, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN);
#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, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_GLOBAL_POSITION_INT;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_CRC);
#else
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN);
#endif
}
/**
* @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 will be 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), AMSL (not WGS84 - note that virtually all GPS modules provide the AMSL as well)
* @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: UINT16_MAX
* @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[MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN];
_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, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN);
#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, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_GLOBAL_POSITION_INT;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_CRC);
#else
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN);
#endif
}
/**
* @brief Encode a global_position_int struct
*
* @param system_id ID of this 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 Encode a global_position_int struct 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 will be sent over
* @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_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_global_position_int_t* global_position_int)
{
return mavlink_msg_global_position_int_pack_chan(system_id, component_id, chan, 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), AMSL (not WGS84 - note that virtually all GPS modules provide the AMSL as well)
* @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: UINT16_MAX
*/
#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[MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN];
_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);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT, buf, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT, buf, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN);
#endif
#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;
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT, (const char *)&packet, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT, (const char *)&packet, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN);
#endif
#endif
}
#if MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This varient of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_global_position_int_send_buf(mavlink_message_t *msgbuf, 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 = (char *)msgbuf;
_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);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT, buf, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT, buf, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN);
#endif
#else
mavlink_global_position_int_t *packet = (mavlink_global_position_int_t *)msgbuf;
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;
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT, (const char *)packet, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT, (const char *)packet, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN);
#endif
#endif
}
#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), AMSL (not WGS84 - note that virtually all GPS modules provide the AMSL as well)
*/
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: UINT16_MAX
*/
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), MAVLINK_MSG_ID_GLOBAL_POSITION_INT_LEN);
#endif
}

View file

@ -0,0 +1,441 @@
// MESSAGE GLOBAL_POSITION_INT_COV PACKING
#define MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV 63
typedef struct __mavlink_global_position_int_cov_t
{
uint64_t time_utc; ///< Timestamp (microseconds since UNIX epoch) in UTC. 0 for unknown. Commonly filled by the precision time source of a GPS receiver.
uint32_t time_boot_ms; ///< Timestamp (milliseconds since system boot)
int32_t lat; ///< Latitude, expressed as degrees * 1E7
int32_t lon; ///< Longitude, expressed as degrees * 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)
float vx; ///< Ground X Speed (Latitude), expressed as m/s
float vy; ///< Ground Y Speed (Longitude), expressed as m/s
float vz; ///< Ground Z Speed (Altitude), expressed as m/s
float covariance[36]; ///< Covariance matrix (first six entries are the first ROW, next six entries are the second row, etc.)
uint8_t estimator_type; ///< Class id of the estimator this estimate originated from.
} mavlink_global_position_int_cov_t;
#define MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN 185
#define MAVLINK_MSG_ID_63_LEN 185
#define MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_CRC 51
#define MAVLINK_MSG_ID_63_CRC 51
#define MAVLINK_MSG_GLOBAL_POSITION_INT_COV_FIELD_COVARIANCE_LEN 36
#define MAVLINK_MESSAGE_INFO_GLOBAL_POSITION_INT_COV { \
"GLOBAL_POSITION_INT_COV", \
11, \
{ { "time_utc", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_global_position_int_cov_t, time_utc) }, \
{ "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_global_position_int_cov_t, time_boot_ms) }, \
{ "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_global_position_int_cov_t, lat) }, \
{ "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_global_position_int_cov_t, lon) }, \
{ "alt", NULL, MAVLINK_TYPE_INT32_T, 0, 20, offsetof(mavlink_global_position_int_cov_t, alt) }, \
{ "relative_alt", NULL, MAVLINK_TYPE_INT32_T, 0, 24, offsetof(mavlink_global_position_int_cov_t, relative_alt) }, \
{ "vx", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_global_position_int_cov_t, vx) }, \
{ "vy", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_global_position_int_cov_t, vy) }, \
{ "vz", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_global_position_int_cov_t, vz) }, \
{ "covariance", NULL, MAVLINK_TYPE_FLOAT, 36, 40, offsetof(mavlink_global_position_int_cov_t, covariance) }, \
{ "estimator_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 184, offsetof(mavlink_global_position_int_cov_t, estimator_type) }, \
} \
}
/**
* @brief Pack a global_position_int_cov message
* @param system_id ID of this 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 time_utc Timestamp (microseconds since UNIX epoch) in UTC. 0 for unknown. Commonly filled by the precision time source of a GPS receiver.
* @param estimator_type Class id of the estimator this estimate originated from.
* @param lat Latitude, expressed as degrees * 1E7
* @param lon Longitude, expressed as degrees * 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
* @param vy Ground Y Speed (Longitude), expressed as m/s
* @param vz Ground Z Speed (Altitude), expressed as m/s
* @param covariance Covariance matrix (first six entries are the first ROW, next six entries are the second row, etc.)
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_global_position_int_cov_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint32_t time_boot_ms, uint64_t time_utc, uint8_t estimator_type, int32_t lat, int32_t lon, int32_t alt, int32_t relative_alt, float vx, float vy, float vz, const float *covariance)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN];
_mav_put_uint64_t(buf, 0, time_utc);
_mav_put_uint32_t(buf, 8, time_boot_ms);
_mav_put_int32_t(buf, 12, lat);
_mav_put_int32_t(buf, 16, lon);
_mav_put_int32_t(buf, 20, alt);
_mav_put_int32_t(buf, 24, relative_alt);
_mav_put_float(buf, 28, vx);
_mav_put_float(buf, 32, vy);
_mav_put_float(buf, 36, vz);
_mav_put_uint8_t(buf, 184, estimator_type);
_mav_put_float_array(buf, 40, covariance, 36);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN);
#else
mavlink_global_position_int_cov_t packet;
packet.time_utc = time_utc;
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.estimator_type = estimator_type;
mav_array_memcpy(packet.covariance, covariance, sizeof(float)*36);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_CRC);
#else
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN);
#endif
}
/**
* @brief Pack a global_position_int_cov 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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param time_boot_ms Timestamp (milliseconds since system boot)
* @param time_utc Timestamp (microseconds since UNIX epoch) in UTC. 0 for unknown. Commonly filled by the precision time source of a GPS receiver.
* @param estimator_type Class id of the estimator this estimate originated from.
* @param lat Latitude, expressed as degrees * 1E7
* @param lon Longitude, expressed as degrees * 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
* @param vy Ground Y Speed (Longitude), expressed as m/s
* @param vz Ground Z Speed (Altitude), expressed as m/s
* @param covariance Covariance matrix (first six entries are the first ROW, next six entries are the second row, etc.)
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_global_position_int_cov_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint32_t time_boot_ms,uint64_t time_utc,uint8_t estimator_type,int32_t lat,int32_t lon,int32_t alt,int32_t relative_alt,float vx,float vy,float vz,const float *covariance)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN];
_mav_put_uint64_t(buf, 0, time_utc);
_mav_put_uint32_t(buf, 8, time_boot_ms);
_mav_put_int32_t(buf, 12, lat);
_mav_put_int32_t(buf, 16, lon);
_mav_put_int32_t(buf, 20, alt);
_mav_put_int32_t(buf, 24, relative_alt);
_mav_put_float(buf, 28, vx);
_mav_put_float(buf, 32, vy);
_mav_put_float(buf, 36, vz);
_mav_put_uint8_t(buf, 184, estimator_type);
_mav_put_float_array(buf, 40, covariance, 36);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN);
#else
mavlink_global_position_int_cov_t packet;
packet.time_utc = time_utc;
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.estimator_type = estimator_type;
mav_array_memcpy(packet.covariance, covariance, sizeof(float)*36);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_CRC);
#else
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN);
#endif
}
/**
* @brief Encode a global_position_int_cov struct
*
* @param system_id ID of this 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_cov C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_global_position_int_cov_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_global_position_int_cov_t* global_position_int_cov)
{
return mavlink_msg_global_position_int_cov_pack(system_id, component_id, msg, global_position_int_cov->time_boot_ms, global_position_int_cov->time_utc, global_position_int_cov->estimator_type, global_position_int_cov->lat, global_position_int_cov->lon, global_position_int_cov->alt, global_position_int_cov->relative_alt, global_position_int_cov->vx, global_position_int_cov->vy, global_position_int_cov->vz, global_position_int_cov->covariance);
}
/**
* @brief Encode a global_position_int_cov struct 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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param global_position_int_cov C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_global_position_int_cov_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_global_position_int_cov_t* global_position_int_cov)
{
return mavlink_msg_global_position_int_cov_pack_chan(system_id, component_id, chan, msg, global_position_int_cov->time_boot_ms, global_position_int_cov->time_utc, global_position_int_cov->estimator_type, global_position_int_cov->lat, global_position_int_cov->lon, global_position_int_cov->alt, global_position_int_cov->relative_alt, global_position_int_cov->vx, global_position_int_cov->vy, global_position_int_cov->vz, global_position_int_cov->covariance);
}
/**
* @brief Send a global_position_int_cov message
* @param chan MAVLink channel to send the message
*
* @param time_boot_ms Timestamp (milliseconds since system boot)
* @param time_utc Timestamp (microseconds since UNIX epoch) in UTC. 0 for unknown. Commonly filled by the precision time source of a GPS receiver.
* @param estimator_type Class id of the estimator this estimate originated from.
* @param lat Latitude, expressed as degrees * 1E7
* @param lon Longitude, expressed as degrees * 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
* @param vy Ground Y Speed (Longitude), expressed as m/s
* @param vz Ground Z Speed (Altitude), expressed as m/s
* @param covariance Covariance matrix (first six entries are the first ROW, next six entries are the second row, etc.)
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_global_position_int_cov_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint64_t time_utc, uint8_t estimator_type, int32_t lat, int32_t lon, int32_t alt, int32_t relative_alt, float vx, float vy, float vz, const float *covariance)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN];
_mav_put_uint64_t(buf, 0, time_utc);
_mav_put_uint32_t(buf, 8, time_boot_ms);
_mav_put_int32_t(buf, 12, lat);
_mav_put_int32_t(buf, 16, lon);
_mav_put_int32_t(buf, 20, alt);
_mav_put_int32_t(buf, 24, relative_alt);
_mav_put_float(buf, 28, vx);
_mav_put_float(buf, 32, vy);
_mav_put_float(buf, 36, vz);
_mav_put_uint8_t(buf, 184, estimator_type);
_mav_put_float_array(buf, 40, covariance, 36);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV, buf, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV, buf, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN);
#endif
#else
mavlink_global_position_int_cov_t packet;
packet.time_utc = time_utc;
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.estimator_type = estimator_type;
mav_array_memcpy(packet.covariance, covariance, sizeof(float)*36);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV, (const char *)&packet, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV, (const char *)&packet, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN);
#endif
#endif
}
#if MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This varient of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_global_position_int_cov_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, uint64_t time_utc, uint8_t estimator_type, int32_t lat, int32_t lon, int32_t alt, int32_t relative_alt, float vx, float vy, float vz, const float *covariance)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
_mav_put_uint64_t(buf, 0, time_utc);
_mav_put_uint32_t(buf, 8, time_boot_ms);
_mav_put_int32_t(buf, 12, lat);
_mav_put_int32_t(buf, 16, lon);
_mav_put_int32_t(buf, 20, alt);
_mav_put_int32_t(buf, 24, relative_alt);
_mav_put_float(buf, 28, vx);
_mav_put_float(buf, 32, vy);
_mav_put_float(buf, 36, vz);
_mav_put_uint8_t(buf, 184, estimator_type);
_mav_put_float_array(buf, 40, covariance, 36);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV, buf, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV, buf, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN);
#endif
#else
mavlink_global_position_int_cov_t *packet = (mavlink_global_position_int_cov_t *)msgbuf;
packet->time_utc = time_utc;
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->estimator_type = estimator_type;
mav_array_memcpy(packet->covariance, covariance, sizeof(float)*36);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV, (const char *)packet, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV, (const char *)packet, MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN);
#endif
#endif
}
#endif
#endif
// MESSAGE GLOBAL_POSITION_INT_COV UNPACKING
/**
* @brief Get field time_boot_ms from global_position_int_cov message
*
* @return Timestamp (milliseconds since system boot)
*/
static inline uint32_t mavlink_msg_global_position_int_cov_get_time_boot_ms(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint32_t(msg, 8);
}
/**
* @brief Get field time_utc from global_position_int_cov message
*
* @return Timestamp (microseconds since UNIX epoch) in UTC. 0 for unknown. Commonly filled by the precision time source of a GPS receiver.
*/
static inline uint64_t mavlink_msg_global_position_int_cov_get_time_utc(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint64_t(msg, 0);
}
/**
* @brief Get field estimator_type from global_position_int_cov message
*
* @return Class id of the estimator this estimate originated from.
*/
static inline uint8_t mavlink_msg_global_position_int_cov_get_estimator_type(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 184);
}
/**
* @brief Get field lat from global_position_int_cov message
*
* @return Latitude, expressed as degrees * 1E7
*/
static inline int32_t mavlink_msg_global_position_int_cov_get_lat(const mavlink_message_t* msg)
{
return _MAV_RETURN_int32_t(msg, 12);
}
/**
* @brief Get field lon from global_position_int_cov message
*
* @return Longitude, expressed as degrees * 1E7
*/
static inline int32_t mavlink_msg_global_position_int_cov_get_lon(const mavlink_message_t* msg)
{
return _MAV_RETURN_int32_t(msg, 16);
}
/**
* @brief Get field alt from global_position_int_cov message
*
* @return Altitude in meters, expressed as * 1000 (millimeters), above MSL
*/
static inline int32_t mavlink_msg_global_position_int_cov_get_alt(const mavlink_message_t* msg)
{
return _MAV_RETURN_int32_t(msg, 20);
}
/**
* @brief Get field relative_alt from global_position_int_cov message
*
* @return Altitude above ground in meters, expressed as * 1000 (millimeters)
*/
static inline int32_t mavlink_msg_global_position_int_cov_get_relative_alt(const mavlink_message_t* msg)
{
return _MAV_RETURN_int32_t(msg, 24);
}
/**
* @brief Get field vx from global_position_int_cov message
*
* @return Ground X Speed (Latitude), expressed as m/s
*/
static inline float mavlink_msg_global_position_int_cov_get_vx(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 28);
}
/**
* @brief Get field vy from global_position_int_cov message
*
* @return Ground Y Speed (Longitude), expressed as m/s
*/
static inline float mavlink_msg_global_position_int_cov_get_vy(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 32);
}
/**
* @brief Get field vz from global_position_int_cov message
*
* @return Ground Z Speed (Altitude), expressed as m/s
*/
static inline float mavlink_msg_global_position_int_cov_get_vz(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 36);
}
/**
* @brief Get field covariance from global_position_int_cov message
*
* @return Covariance matrix (first six entries are the first ROW, next six entries are the second row, etc.)
*/
static inline uint16_t mavlink_msg_global_position_int_cov_get_covariance(const mavlink_message_t* msg, float *covariance)
{
return _MAV_RETURN_float_array(msg, covariance, 36, 40);
}
/**
* @brief Decode a global_position_int_cov message into a struct
*
* @param msg The message to decode
* @param global_position_int_cov C-struct to decode the message contents into
*/
static inline void mavlink_msg_global_position_int_cov_decode(const mavlink_message_t* msg, mavlink_global_position_int_cov_t* global_position_int_cov)
{
#if MAVLINK_NEED_BYTE_SWAP
global_position_int_cov->time_utc = mavlink_msg_global_position_int_cov_get_time_utc(msg);
global_position_int_cov->time_boot_ms = mavlink_msg_global_position_int_cov_get_time_boot_ms(msg);
global_position_int_cov->lat = mavlink_msg_global_position_int_cov_get_lat(msg);
global_position_int_cov->lon = mavlink_msg_global_position_int_cov_get_lon(msg);
global_position_int_cov->alt = mavlink_msg_global_position_int_cov_get_alt(msg);
global_position_int_cov->relative_alt = mavlink_msg_global_position_int_cov_get_relative_alt(msg);
global_position_int_cov->vx = mavlink_msg_global_position_int_cov_get_vx(msg);
global_position_int_cov->vy = mavlink_msg_global_position_int_cov_get_vy(msg);
global_position_int_cov->vz = mavlink_msg_global_position_int_cov_get_vz(msg);
mavlink_msg_global_position_int_cov_get_covariance(msg, global_position_int_cov->covariance);
global_position_int_cov->estimator_type = mavlink_msg_global_position_int_cov_get_estimator_type(msg);
#else
memcpy(global_position_int_cov, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_GLOBAL_POSITION_INT_COV_LEN);
#endif
}

View file

@ -0,0 +1,353 @@
// 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 (microseconds, synced to UNIX time or since system boot)
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_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_CRC 102
#define MAVLINK_MSG_ID_101_CRC 102
#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 (microseconds, synced to UNIX time or since system boot)
* @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[MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN];
_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, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN);
#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, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_CRC);
#else
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN);
#endif
}
/**
* @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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param usec Timestamp (microseconds, synced to UNIX time or since system boot)
* @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[MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN];
_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, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN);
#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, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_CRC);
#else
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN);
#endif
}
/**
* @brief Encode a global_vision_position_estimate struct
*
* @param system_id ID of this 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 Encode a global_vision_position_estimate struct 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 will be sent over
* @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_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_global_vision_position_estimate_t* global_vision_position_estimate)
{
return mavlink_msg_global_vision_position_estimate_pack_chan(system_id, component_id, chan, 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 (microseconds, synced to UNIX time or since system boot)
* @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[MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN];
_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);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE, buf, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE, buf, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN);
#endif
#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;
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE, (const char *)&packet, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE, (const char *)&packet, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN);
#endif
#endif
}
#if MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This varient of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_global_vision_position_estimate_send_buf(mavlink_message_t *msgbuf, 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 = (char *)msgbuf;
_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);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE, buf, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE, buf, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN);
#endif
#else
mavlink_global_vision_position_estimate_t *packet = (mavlink_global_vision_position_estimate_t *)msgbuf;
packet->usec = usec;
packet->x = x;
packet->y = y;
packet->z = z;
packet->roll = roll;
packet->pitch = pitch;
packet->yaw = yaw;
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE, (const char *)packet, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE, (const char *)packet, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN);
#endif
#endif
}
#endif
#endif
// MESSAGE GLOBAL_VISION_POSITION_ESTIMATE UNPACKING
/**
* @brief Get field usec from global_vision_position_estimate message
*
* @return Timestamp (microseconds, synced to UNIX time or since system boot)
*/
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), MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN);
#endif
}

View file

@ -0,0 +1,473 @@
// MESSAGE GPS2_RAW PACKING
#define MAVLINK_MSG_ID_GPS2_RAW 124
typedef struct __mavlink_gps2_raw_t
{
uint64_t time_usec; ///< Timestamp (microseconds since UNIX epoch or microseconds since system boot)
int32_t lat; ///< Latitude (WGS84), in degrees * 1E7
int32_t lon; ///< Longitude (WGS84), in degrees * 1E7
int32_t alt; ///< Altitude (AMSL, not WGS84), in meters * 1000 (positive for up)
uint32_t dgps_age; ///< Age of DGPS info
uint16_t eph; ///< GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: UINT16_MAX
uint16_t epv; ///< GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: UINT16_MAX
uint16_t vel; ///< GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX
uint16_t cog; ///< Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX
uint8_t fix_type; ///< 0-1: no fix, 2: 2D fix, 3: 3D fix, 4: DGPS fix, 5: RTK 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
uint8_t dgps_numch; ///< Number of DGPS satellites
} mavlink_gps2_raw_t;
#define MAVLINK_MSG_ID_GPS2_RAW_LEN 35
#define MAVLINK_MSG_ID_124_LEN 35
#define MAVLINK_MSG_ID_GPS2_RAW_CRC 87
#define MAVLINK_MSG_ID_124_CRC 87
#define MAVLINK_MESSAGE_INFO_GPS2_RAW { \
"GPS2_RAW", \
12, \
{ { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_gps2_raw_t, time_usec) }, \
{ "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_gps2_raw_t, lat) }, \
{ "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_gps2_raw_t, lon) }, \
{ "alt", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_gps2_raw_t, alt) }, \
{ "dgps_age", NULL, MAVLINK_TYPE_UINT32_T, 0, 20, offsetof(mavlink_gps2_raw_t, dgps_age) }, \
{ "eph", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_gps2_raw_t, eph) }, \
{ "epv", NULL, MAVLINK_TYPE_UINT16_T, 0, 26, offsetof(mavlink_gps2_raw_t, epv) }, \
{ "vel", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_gps2_raw_t, vel) }, \
{ "cog", NULL, MAVLINK_TYPE_UINT16_T, 0, 30, offsetof(mavlink_gps2_raw_t, cog) }, \
{ "fix_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_gps2_raw_t, fix_type) }, \
{ "satellites_visible", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_gps2_raw_t, satellites_visible) }, \
{ "dgps_numch", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_gps2_raw_t, dgps_numch) }, \
} \
}
/**
* @brief Pack a gps2_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 fix_type 0-1: no fix, 2: 2D fix, 3: 3D fix, 4: DGPS fix, 5: RTK 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 (WGS84), in degrees * 1E7
* @param lon Longitude (WGS84), in degrees * 1E7
* @param alt Altitude (AMSL, not WGS84), in meters * 1000 (positive for up)
* @param eph GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: UINT16_MAX
* @param epv GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: UINT16_MAX
* @param vel GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX
* @param cog Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX
* @param satellites_visible Number of satellites visible. If unknown, set to 255
* @param dgps_numch Number of DGPS satellites
* @param dgps_age Age of DGPS info
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_gps2_raw_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, uint8_t dgps_numch, uint32_t dgps_age)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_GPS2_RAW_LEN];
_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_uint32_t(buf, 20, dgps_age);
_mav_put_uint16_t(buf, 24, eph);
_mav_put_uint16_t(buf, 26, epv);
_mav_put_uint16_t(buf, 28, vel);
_mav_put_uint16_t(buf, 30, cog);
_mav_put_uint8_t(buf, 32, fix_type);
_mav_put_uint8_t(buf, 33, satellites_visible);
_mav_put_uint8_t(buf, 34, dgps_numch);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GPS2_RAW_LEN);
#else
mavlink_gps2_raw_t packet;
packet.time_usec = time_usec;
packet.lat = lat;
packet.lon = lon;
packet.alt = alt;
packet.dgps_age = dgps_age;
packet.eph = eph;
packet.epv = epv;
packet.vel = vel;
packet.cog = cog;
packet.fix_type = fix_type;
packet.satellites_visible = satellites_visible;
packet.dgps_numch = dgps_numch;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GPS2_RAW_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_GPS2_RAW;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GPS2_RAW_LEN, MAVLINK_MSG_ID_GPS2_RAW_CRC);
#else
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GPS2_RAW_LEN);
#endif
}
/**
* @brief Pack a gps2_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 will be 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, 4: DGPS fix, 5: RTK 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 (WGS84), in degrees * 1E7
* @param lon Longitude (WGS84), in degrees * 1E7
* @param alt Altitude (AMSL, not WGS84), in meters * 1000 (positive for up)
* @param eph GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: UINT16_MAX
* @param epv GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: UINT16_MAX
* @param vel GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX
* @param cog Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX
* @param satellites_visible Number of satellites visible. If unknown, set to 255
* @param dgps_numch Number of DGPS satellites
* @param dgps_age Age of DGPS info
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_gps2_raw_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,uint8_t dgps_numch,uint32_t dgps_age)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_GPS2_RAW_LEN];
_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_uint32_t(buf, 20, dgps_age);
_mav_put_uint16_t(buf, 24, eph);
_mav_put_uint16_t(buf, 26, epv);
_mav_put_uint16_t(buf, 28, vel);
_mav_put_uint16_t(buf, 30, cog);
_mav_put_uint8_t(buf, 32, fix_type);
_mav_put_uint8_t(buf, 33, satellites_visible);
_mav_put_uint8_t(buf, 34, dgps_numch);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GPS2_RAW_LEN);
#else
mavlink_gps2_raw_t packet;
packet.time_usec = time_usec;
packet.lat = lat;
packet.lon = lon;
packet.alt = alt;
packet.dgps_age = dgps_age;
packet.eph = eph;
packet.epv = epv;
packet.vel = vel;
packet.cog = cog;
packet.fix_type = fix_type;
packet.satellites_visible = satellites_visible;
packet.dgps_numch = dgps_numch;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GPS2_RAW_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_GPS2_RAW;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GPS2_RAW_LEN, MAVLINK_MSG_ID_GPS2_RAW_CRC);
#else
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GPS2_RAW_LEN);
#endif
}
/**
* @brief Encode a gps2_raw struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param gps2_raw C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_gps2_raw_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gps2_raw_t* gps2_raw)
{
return mavlink_msg_gps2_raw_pack(system_id, component_id, msg, gps2_raw->time_usec, gps2_raw->fix_type, gps2_raw->lat, gps2_raw->lon, gps2_raw->alt, gps2_raw->eph, gps2_raw->epv, gps2_raw->vel, gps2_raw->cog, gps2_raw->satellites_visible, gps2_raw->dgps_numch, gps2_raw->dgps_age);
}
/**
* @brief Encode a gps2_raw struct 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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param gps2_raw C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_gps2_raw_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_gps2_raw_t* gps2_raw)
{
return mavlink_msg_gps2_raw_pack_chan(system_id, component_id, chan, msg, gps2_raw->time_usec, gps2_raw->fix_type, gps2_raw->lat, gps2_raw->lon, gps2_raw->alt, gps2_raw->eph, gps2_raw->epv, gps2_raw->vel, gps2_raw->cog, gps2_raw->satellites_visible, gps2_raw->dgps_numch, gps2_raw->dgps_age);
}
/**
* @brief Send a gps2_raw 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, 4: DGPS fix, 5: RTK 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 (WGS84), in degrees * 1E7
* @param lon Longitude (WGS84), in degrees * 1E7
* @param alt Altitude (AMSL, not WGS84), in meters * 1000 (positive for up)
* @param eph GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: UINT16_MAX
* @param epv GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: UINT16_MAX
* @param vel GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX
* @param cog Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX
* @param satellites_visible Number of satellites visible. If unknown, set to 255
* @param dgps_numch Number of DGPS satellites
* @param dgps_age Age of DGPS info
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_gps2_raw_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, uint8_t dgps_numch, uint32_t dgps_age)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_GPS2_RAW_LEN];
_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_uint32_t(buf, 20, dgps_age);
_mav_put_uint16_t(buf, 24, eph);
_mav_put_uint16_t(buf, 26, epv);
_mav_put_uint16_t(buf, 28, vel);
_mav_put_uint16_t(buf, 30, cog);
_mav_put_uint8_t(buf, 32, fix_type);
_mav_put_uint8_t(buf, 33, satellites_visible);
_mav_put_uint8_t(buf, 34, dgps_numch);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RAW, buf, MAVLINK_MSG_ID_GPS2_RAW_LEN, MAVLINK_MSG_ID_GPS2_RAW_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RAW, buf, MAVLINK_MSG_ID_GPS2_RAW_LEN);
#endif
#else
mavlink_gps2_raw_t packet;
packet.time_usec = time_usec;
packet.lat = lat;
packet.lon = lon;
packet.alt = alt;
packet.dgps_age = dgps_age;
packet.eph = eph;
packet.epv = epv;
packet.vel = vel;
packet.cog = cog;
packet.fix_type = fix_type;
packet.satellites_visible = satellites_visible;
packet.dgps_numch = dgps_numch;
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RAW, (const char *)&packet, MAVLINK_MSG_ID_GPS2_RAW_LEN, MAVLINK_MSG_ID_GPS2_RAW_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RAW, (const char *)&packet, MAVLINK_MSG_ID_GPS2_RAW_LEN);
#endif
#endif
}
#if MAVLINK_MSG_ID_GPS2_RAW_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This varient of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_gps2_raw_send_buf(mavlink_message_t *msgbuf, 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, uint8_t dgps_numch, uint32_t dgps_age)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
_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_uint32_t(buf, 20, dgps_age);
_mav_put_uint16_t(buf, 24, eph);
_mav_put_uint16_t(buf, 26, epv);
_mav_put_uint16_t(buf, 28, vel);
_mav_put_uint16_t(buf, 30, cog);
_mav_put_uint8_t(buf, 32, fix_type);
_mav_put_uint8_t(buf, 33, satellites_visible);
_mav_put_uint8_t(buf, 34, dgps_numch);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RAW, buf, MAVLINK_MSG_ID_GPS2_RAW_LEN, MAVLINK_MSG_ID_GPS2_RAW_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RAW, buf, MAVLINK_MSG_ID_GPS2_RAW_LEN);
#endif
#else
mavlink_gps2_raw_t *packet = (mavlink_gps2_raw_t *)msgbuf;
packet->time_usec = time_usec;
packet->lat = lat;
packet->lon = lon;
packet->alt = alt;
packet->dgps_age = dgps_age;
packet->eph = eph;
packet->epv = epv;
packet->vel = vel;
packet->cog = cog;
packet->fix_type = fix_type;
packet->satellites_visible = satellites_visible;
packet->dgps_numch = dgps_numch;
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RAW, (const char *)packet, MAVLINK_MSG_ID_GPS2_RAW_LEN, MAVLINK_MSG_ID_GPS2_RAW_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RAW, (const char *)packet, MAVLINK_MSG_ID_GPS2_RAW_LEN);
#endif
#endif
}
#endif
#endif
// MESSAGE GPS2_RAW UNPACKING
/**
* @brief Get field time_usec from gps2_raw message
*
* @return Timestamp (microseconds since UNIX epoch or microseconds since system boot)
*/
static inline uint64_t mavlink_msg_gps2_raw_get_time_usec(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint64_t(msg, 0);
}
/**
* @brief Get field fix_type from gps2_raw message
*
* @return 0-1: no fix, 2: 2D fix, 3: 3D fix, 4: DGPS fix, 5: RTK 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_gps2_raw_get_fix_type(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 32);
}
/**
* @brief Get field lat from gps2_raw message
*
* @return Latitude (WGS84), in degrees * 1E7
*/
static inline int32_t mavlink_msg_gps2_raw_get_lat(const mavlink_message_t* msg)
{
return _MAV_RETURN_int32_t(msg, 8);
}
/**
* @brief Get field lon from gps2_raw message
*
* @return Longitude (WGS84), in degrees * 1E7
*/
static inline int32_t mavlink_msg_gps2_raw_get_lon(const mavlink_message_t* msg)
{
return _MAV_RETURN_int32_t(msg, 12);
}
/**
* @brief Get field alt from gps2_raw message
*
* @return Altitude (AMSL, not WGS84), in meters * 1000 (positive for up)
*/
static inline int32_t mavlink_msg_gps2_raw_get_alt(const mavlink_message_t* msg)
{
return _MAV_RETURN_int32_t(msg, 16);
}
/**
* @brief Get field eph from gps2_raw message
*
* @return GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: UINT16_MAX
*/
static inline uint16_t mavlink_msg_gps2_raw_get_eph(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 24);
}
/**
* @brief Get field epv from gps2_raw message
*
* @return GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: UINT16_MAX
*/
static inline uint16_t mavlink_msg_gps2_raw_get_epv(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 26);
}
/**
* @brief Get field vel from gps2_raw message
*
* @return GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX
*/
static inline uint16_t mavlink_msg_gps2_raw_get_vel(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 28);
}
/**
* @brief Get field cog from gps2_raw message
*
* @return Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX
*/
static inline uint16_t mavlink_msg_gps2_raw_get_cog(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 30);
}
/**
* @brief Get field satellites_visible from gps2_raw message
*
* @return Number of satellites visible. If unknown, set to 255
*/
static inline uint8_t mavlink_msg_gps2_raw_get_satellites_visible(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 33);
}
/**
* @brief Get field dgps_numch from gps2_raw message
*
* @return Number of DGPS satellites
*/
static inline uint8_t mavlink_msg_gps2_raw_get_dgps_numch(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 34);
}
/**
* @brief Get field dgps_age from gps2_raw message
*
* @return Age of DGPS info
*/
static inline uint32_t mavlink_msg_gps2_raw_get_dgps_age(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint32_t(msg, 20);
}
/**
* @brief Decode a gps2_raw message into a struct
*
* @param msg The message to decode
* @param gps2_raw C-struct to decode the message contents into
*/
static inline void mavlink_msg_gps2_raw_decode(const mavlink_message_t* msg, mavlink_gps2_raw_t* gps2_raw)
{
#if MAVLINK_NEED_BYTE_SWAP
gps2_raw->time_usec = mavlink_msg_gps2_raw_get_time_usec(msg);
gps2_raw->lat = mavlink_msg_gps2_raw_get_lat(msg);
gps2_raw->lon = mavlink_msg_gps2_raw_get_lon(msg);
gps2_raw->alt = mavlink_msg_gps2_raw_get_alt(msg);
gps2_raw->dgps_age = mavlink_msg_gps2_raw_get_dgps_age(msg);
gps2_raw->eph = mavlink_msg_gps2_raw_get_eph(msg);
gps2_raw->epv = mavlink_msg_gps2_raw_get_epv(msg);
gps2_raw->vel = mavlink_msg_gps2_raw_get_vel(msg);
gps2_raw->cog = mavlink_msg_gps2_raw_get_cog(msg);
gps2_raw->fix_type = mavlink_msg_gps2_raw_get_fix_type(msg);
gps2_raw->satellites_visible = mavlink_msg_gps2_raw_get_satellites_visible(msg);
gps2_raw->dgps_numch = mavlink_msg_gps2_raw_get_dgps_numch(msg);
#else
memcpy(gps2_raw, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_GPS2_RAW_LEN);
#endif
}

View file

@ -0,0 +1,497 @@
// MESSAGE GPS2_RTK PACKING
#define MAVLINK_MSG_ID_GPS2_RTK 128
typedef struct __mavlink_gps2_rtk_t
{
uint32_t time_last_baseline_ms; ///< Time since boot of last baseline message received in ms.
uint32_t tow; ///< GPS Time of Week of last baseline
int32_t baseline_a_mm; ///< Current baseline in ECEF x or NED north component in mm.
int32_t baseline_b_mm; ///< Current baseline in ECEF y or NED east component in mm.
int32_t baseline_c_mm; ///< Current baseline in ECEF z or NED down component in mm.
uint32_t accuracy; ///< Current estimate of baseline accuracy.
int32_t iar_num_hypotheses; ///< Current number of integer ambiguity hypotheses.
uint16_t wn; ///< GPS Week Number of last baseline
uint8_t rtk_receiver_id; ///< Identification of connected RTK receiver.
uint8_t rtk_health; ///< GPS-specific health report for RTK data.
uint8_t rtk_rate; ///< Rate of baseline messages being received by GPS, in HZ
uint8_t nsats; ///< Current number of sats used for RTK calculation.
uint8_t baseline_coords_type; ///< Coordinate system of baseline. 0 == ECEF, 1 == NED
} mavlink_gps2_rtk_t;
#define MAVLINK_MSG_ID_GPS2_RTK_LEN 35
#define MAVLINK_MSG_ID_128_LEN 35
#define MAVLINK_MSG_ID_GPS2_RTK_CRC 226
#define MAVLINK_MSG_ID_128_CRC 226
#define MAVLINK_MESSAGE_INFO_GPS2_RTK { \
"GPS2_RTK", \
13, \
{ { "time_last_baseline_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_gps2_rtk_t, time_last_baseline_ms) }, \
{ "tow", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_gps2_rtk_t, tow) }, \
{ "baseline_a_mm", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_gps2_rtk_t, baseline_a_mm) }, \
{ "baseline_b_mm", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_gps2_rtk_t, baseline_b_mm) }, \
{ "baseline_c_mm", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_gps2_rtk_t, baseline_c_mm) }, \
{ "accuracy", NULL, MAVLINK_TYPE_UINT32_T, 0, 20, offsetof(mavlink_gps2_rtk_t, accuracy) }, \
{ "iar_num_hypotheses", NULL, MAVLINK_TYPE_INT32_T, 0, 24, offsetof(mavlink_gps2_rtk_t, iar_num_hypotheses) }, \
{ "wn", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_gps2_rtk_t, wn) }, \
{ "rtk_receiver_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 30, offsetof(mavlink_gps2_rtk_t, rtk_receiver_id) }, \
{ "rtk_health", NULL, MAVLINK_TYPE_UINT8_T, 0, 31, offsetof(mavlink_gps2_rtk_t, rtk_health) }, \
{ "rtk_rate", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_gps2_rtk_t, rtk_rate) }, \
{ "nsats", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_gps2_rtk_t, nsats) }, \
{ "baseline_coords_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_gps2_rtk_t, baseline_coords_type) }, \
} \
}
/**
* @brief Pack a gps2_rtk message
* @param system_id ID of this 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_last_baseline_ms Time since boot of last baseline message received in ms.
* @param rtk_receiver_id Identification of connected RTK receiver.
* @param wn GPS Week Number of last baseline
* @param tow GPS Time of Week of last baseline
* @param rtk_health GPS-specific health report for RTK data.
* @param rtk_rate Rate of baseline messages being received by GPS, in HZ
* @param nsats Current number of sats used for RTK calculation.
* @param baseline_coords_type Coordinate system of baseline. 0 == ECEF, 1 == NED
* @param baseline_a_mm Current baseline in ECEF x or NED north component in mm.
* @param baseline_b_mm Current baseline in ECEF y or NED east component in mm.
* @param baseline_c_mm Current baseline in ECEF z or NED down component in mm.
* @param accuracy Current estimate of baseline accuracy.
* @param iar_num_hypotheses Current number of integer ambiguity hypotheses.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_gps2_rtk_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint32_t time_last_baseline_ms, uint8_t rtk_receiver_id, uint16_t wn, uint32_t tow, uint8_t rtk_health, uint8_t rtk_rate, uint8_t nsats, uint8_t baseline_coords_type, int32_t baseline_a_mm, int32_t baseline_b_mm, int32_t baseline_c_mm, uint32_t accuracy, int32_t iar_num_hypotheses)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_GPS2_RTK_LEN];
_mav_put_uint32_t(buf, 0, time_last_baseline_ms);
_mav_put_uint32_t(buf, 4, tow);
_mav_put_int32_t(buf, 8, baseline_a_mm);
_mav_put_int32_t(buf, 12, baseline_b_mm);
_mav_put_int32_t(buf, 16, baseline_c_mm);
_mav_put_uint32_t(buf, 20, accuracy);
_mav_put_int32_t(buf, 24, iar_num_hypotheses);
_mav_put_uint16_t(buf, 28, wn);
_mav_put_uint8_t(buf, 30, rtk_receiver_id);
_mav_put_uint8_t(buf, 31, rtk_health);
_mav_put_uint8_t(buf, 32, rtk_rate);
_mav_put_uint8_t(buf, 33, nsats);
_mav_put_uint8_t(buf, 34, baseline_coords_type);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GPS2_RTK_LEN);
#else
mavlink_gps2_rtk_t packet;
packet.time_last_baseline_ms = time_last_baseline_ms;
packet.tow = tow;
packet.baseline_a_mm = baseline_a_mm;
packet.baseline_b_mm = baseline_b_mm;
packet.baseline_c_mm = baseline_c_mm;
packet.accuracy = accuracy;
packet.iar_num_hypotheses = iar_num_hypotheses;
packet.wn = wn;
packet.rtk_receiver_id = rtk_receiver_id;
packet.rtk_health = rtk_health;
packet.rtk_rate = rtk_rate;
packet.nsats = nsats;
packet.baseline_coords_type = baseline_coords_type;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GPS2_RTK_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_GPS2_RTK;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GPS2_RTK_LEN, MAVLINK_MSG_ID_GPS2_RTK_CRC);
#else
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GPS2_RTK_LEN);
#endif
}
/**
* @brief Pack a gps2_rtk 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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param time_last_baseline_ms Time since boot of last baseline message received in ms.
* @param rtk_receiver_id Identification of connected RTK receiver.
* @param wn GPS Week Number of last baseline
* @param tow GPS Time of Week of last baseline
* @param rtk_health GPS-specific health report for RTK data.
* @param rtk_rate Rate of baseline messages being received by GPS, in HZ
* @param nsats Current number of sats used for RTK calculation.
* @param baseline_coords_type Coordinate system of baseline. 0 == ECEF, 1 == NED
* @param baseline_a_mm Current baseline in ECEF x or NED north component in mm.
* @param baseline_b_mm Current baseline in ECEF y or NED east component in mm.
* @param baseline_c_mm Current baseline in ECEF z or NED down component in mm.
* @param accuracy Current estimate of baseline accuracy.
* @param iar_num_hypotheses Current number of integer ambiguity hypotheses.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_gps2_rtk_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint32_t time_last_baseline_ms,uint8_t rtk_receiver_id,uint16_t wn,uint32_t tow,uint8_t rtk_health,uint8_t rtk_rate,uint8_t nsats,uint8_t baseline_coords_type,int32_t baseline_a_mm,int32_t baseline_b_mm,int32_t baseline_c_mm,uint32_t accuracy,int32_t iar_num_hypotheses)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_GPS2_RTK_LEN];
_mav_put_uint32_t(buf, 0, time_last_baseline_ms);
_mav_put_uint32_t(buf, 4, tow);
_mav_put_int32_t(buf, 8, baseline_a_mm);
_mav_put_int32_t(buf, 12, baseline_b_mm);
_mav_put_int32_t(buf, 16, baseline_c_mm);
_mav_put_uint32_t(buf, 20, accuracy);
_mav_put_int32_t(buf, 24, iar_num_hypotheses);
_mav_put_uint16_t(buf, 28, wn);
_mav_put_uint8_t(buf, 30, rtk_receiver_id);
_mav_put_uint8_t(buf, 31, rtk_health);
_mav_put_uint8_t(buf, 32, rtk_rate);
_mav_put_uint8_t(buf, 33, nsats);
_mav_put_uint8_t(buf, 34, baseline_coords_type);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GPS2_RTK_LEN);
#else
mavlink_gps2_rtk_t packet;
packet.time_last_baseline_ms = time_last_baseline_ms;
packet.tow = tow;
packet.baseline_a_mm = baseline_a_mm;
packet.baseline_b_mm = baseline_b_mm;
packet.baseline_c_mm = baseline_c_mm;
packet.accuracy = accuracy;
packet.iar_num_hypotheses = iar_num_hypotheses;
packet.wn = wn;
packet.rtk_receiver_id = rtk_receiver_id;
packet.rtk_health = rtk_health;
packet.rtk_rate = rtk_rate;
packet.nsats = nsats;
packet.baseline_coords_type = baseline_coords_type;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GPS2_RTK_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_GPS2_RTK;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GPS2_RTK_LEN, MAVLINK_MSG_ID_GPS2_RTK_CRC);
#else
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GPS2_RTK_LEN);
#endif
}
/**
* @brief Encode a gps2_rtk struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param gps2_rtk C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_gps2_rtk_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gps2_rtk_t* gps2_rtk)
{
return mavlink_msg_gps2_rtk_pack(system_id, component_id, msg, gps2_rtk->time_last_baseline_ms, gps2_rtk->rtk_receiver_id, gps2_rtk->wn, gps2_rtk->tow, gps2_rtk->rtk_health, gps2_rtk->rtk_rate, gps2_rtk->nsats, gps2_rtk->baseline_coords_type, gps2_rtk->baseline_a_mm, gps2_rtk->baseline_b_mm, gps2_rtk->baseline_c_mm, gps2_rtk->accuracy, gps2_rtk->iar_num_hypotheses);
}
/**
* @brief Encode a gps2_rtk struct 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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param gps2_rtk C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_gps2_rtk_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_gps2_rtk_t* gps2_rtk)
{
return mavlink_msg_gps2_rtk_pack_chan(system_id, component_id, chan, msg, gps2_rtk->time_last_baseline_ms, gps2_rtk->rtk_receiver_id, gps2_rtk->wn, gps2_rtk->tow, gps2_rtk->rtk_health, gps2_rtk->rtk_rate, gps2_rtk->nsats, gps2_rtk->baseline_coords_type, gps2_rtk->baseline_a_mm, gps2_rtk->baseline_b_mm, gps2_rtk->baseline_c_mm, gps2_rtk->accuracy, gps2_rtk->iar_num_hypotheses);
}
/**
* @brief Send a gps2_rtk message
* @param chan MAVLink channel to send the message
*
* @param time_last_baseline_ms Time since boot of last baseline message received in ms.
* @param rtk_receiver_id Identification of connected RTK receiver.
* @param wn GPS Week Number of last baseline
* @param tow GPS Time of Week of last baseline
* @param rtk_health GPS-specific health report for RTK data.
* @param rtk_rate Rate of baseline messages being received by GPS, in HZ
* @param nsats Current number of sats used for RTK calculation.
* @param baseline_coords_type Coordinate system of baseline. 0 == ECEF, 1 == NED
* @param baseline_a_mm Current baseline in ECEF x or NED north component in mm.
* @param baseline_b_mm Current baseline in ECEF y or NED east component in mm.
* @param baseline_c_mm Current baseline in ECEF z or NED down component in mm.
* @param accuracy Current estimate of baseline accuracy.
* @param iar_num_hypotheses Current number of integer ambiguity hypotheses.
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_gps2_rtk_send(mavlink_channel_t chan, uint32_t time_last_baseline_ms, uint8_t rtk_receiver_id, uint16_t wn, uint32_t tow, uint8_t rtk_health, uint8_t rtk_rate, uint8_t nsats, uint8_t baseline_coords_type, int32_t baseline_a_mm, int32_t baseline_b_mm, int32_t baseline_c_mm, uint32_t accuracy, int32_t iar_num_hypotheses)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_GPS2_RTK_LEN];
_mav_put_uint32_t(buf, 0, time_last_baseline_ms);
_mav_put_uint32_t(buf, 4, tow);
_mav_put_int32_t(buf, 8, baseline_a_mm);
_mav_put_int32_t(buf, 12, baseline_b_mm);
_mav_put_int32_t(buf, 16, baseline_c_mm);
_mav_put_uint32_t(buf, 20, accuracy);
_mav_put_int32_t(buf, 24, iar_num_hypotheses);
_mav_put_uint16_t(buf, 28, wn);
_mav_put_uint8_t(buf, 30, rtk_receiver_id);
_mav_put_uint8_t(buf, 31, rtk_health);
_mav_put_uint8_t(buf, 32, rtk_rate);
_mav_put_uint8_t(buf, 33, nsats);
_mav_put_uint8_t(buf, 34, baseline_coords_type);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RTK, buf, MAVLINK_MSG_ID_GPS2_RTK_LEN, MAVLINK_MSG_ID_GPS2_RTK_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RTK, buf, MAVLINK_MSG_ID_GPS2_RTK_LEN);
#endif
#else
mavlink_gps2_rtk_t packet;
packet.time_last_baseline_ms = time_last_baseline_ms;
packet.tow = tow;
packet.baseline_a_mm = baseline_a_mm;
packet.baseline_b_mm = baseline_b_mm;
packet.baseline_c_mm = baseline_c_mm;
packet.accuracy = accuracy;
packet.iar_num_hypotheses = iar_num_hypotheses;
packet.wn = wn;
packet.rtk_receiver_id = rtk_receiver_id;
packet.rtk_health = rtk_health;
packet.rtk_rate = rtk_rate;
packet.nsats = nsats;
packet.baseline_coords_type = baseline_coords_type;
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RTK, (const char *)&packet, MAVLINK_MSG_ID_GPS2_RTK_LEN, MAVLINK_MSG_ID_GPS2_RTK_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RTK, (const char *)&packet, MAVLINK_MSG_ID_GPS2_RTK_LEN);
#endif
#endif
}
#if MAVLINK_MSG_ID_GPS2_RTK_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This varient of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_gps2_rtk_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_last_baseline_ms, uint8_t rtk_receiver_id, uint16_t wn, uint32_t tow, uint8_t rtk_health, uint8_t rtk_rate, uint8_t nsats, uint8_t baseline_coords_type, int32_t baseline_a_mm, int32_t baseline_b_mm, int32_t baseline_c_mm, uint32_t accuracy, int32_t iar_num_hypotheses)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
_mav_put_uint32_t(buf, 0, time_last_baseline_ms);
_mav_put_uint32_t(buf, 4, tow);
_mav_put_int32_t(buf, 8, baseline_a_mm);
_mav_put_int32_t(buf, 12, baseline_b_mm);
_mav_put_int32_t(buf, 16, baseline_c_mm);
_mav_put_uint32_t(buf, 20, accuracy);
_mav_put_int32_t(buf, 24, iar_num_hypotheses);
_mav_put_uint16_t(buf, 28, wn);
_mav_put_uint8_t(buf, 30, rtk_receiver_id);
_mav_put_uint8_t(buf, 31, rtk_health);
_mav_put_uint8_t(buf, 32, rtk_rate);
_mav_put_uint8_t(buf, 33, nsats);
_mav_put_uint8_t(buf, 34, baseline_coords_type);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RTK, buf, MAVLINK_MSG_ID_GPS2_RTK_LEN, MAVLINK_MSG_ID_GPS2_RTK_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RTK, buf, MAVLINK_MSG_ID_GPS2_RTK_LEN);
#endif
#else
mavlink_gps2_rtk_t *packet = (mavlink_gps2_rtk_t *)msgbuf;
packet->time_last_baseline_ms = time_last_baseline_ms;
packet->tow = tow;
packet->baseline_a_mm = baseline_a_mm;
packet->baseline_b_mm = baseline_b_mm;
packet->baseline_c_mm = baseline_c_mm;
packet->accuracy = accuracy;
packet->iar_num_hypotheses = iar_num_hypotheses;
packet->wn = wn;
packet->rtk_receiver_id = rtk_receiver_id;
packet->rtk_health = rtk_health;
packet->rtk_rate = rtk_rate;
packet->nsats = nsats;
packet->baseline_coords_type = baseline_coords_type;
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RTK, (const char *)packet, MAVLINK_MSG_ID_GPS2_RTK_LEN, MAVLINK_MSG_ID_GPS2_RTK_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RTK, (const char *)packet, MAVLINK_MSG_ID_GPS2_RTK_LEN);
#endif
#endif
}
#endif
#endif
// MESSAGE GPS2_RTK UNPACKING
/**
* @brief Get field time_last_baseline_ms from gps2_rtk message
*
* @return Time since boot of last baseline message received in ms.
*/
static inline uint32_t mavlink_msg_gps2_rtk_get_time_last_baseline_ms(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint32_t(msg, 0);
}
/**
* @brief Get field rtk_receiver_id from gps2_rtk message
*
* @return Identification of connected RTK receiver.
*/
static inline uint8_t mavlink_msg_gps2_rtk_get_rtk_receiver_id(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 30);
}
/**
* @brief Get field wn from gps2_rtk message
*
* @return GPS Week Number of last baseline
*/
static inline uint16_t mavlink_msg_gps2_rtk_get_wn(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 28);
}
/**
* @brief Get field tow from gps2_rtk message
*
* @return GPS Time of Week of last baseline
*/
static inline uint32_t mavlink_msg_gps2_rtk_get_tow(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint32_t(msg, 4);
}
/**
* @brief Get field rtk_health from gps2_rtk message
*
* @return GPS-specific health report for RTK data.
*/
static inline uint8_t mavlink_msg_gps2_rtk_get_rtk_health(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 31);
}
/**
* @brief Get field rtk_rate from gps2_rtk message
*
* @return Rate of baseline messages being received by GPS, in HZ
*/
static inline uint8_t mavlink_msg_gps2_rtk_get_rtk_rate(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 32);
}
/**
* @brief Get field nsats from gps2_rtk message
*
* @return Current number of sats used for RTK calculation.
*/
static inline uint8_t mavlink_msg_gps2_rtk_get_nsats(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 33);
}
/**
* @brief Get field baseline_coords_type from gps2_rtk message
*
* @return Coordinate system of baseline. 0 == ECEF, 1 == NED
*/
static inline uint8_t mavlink_msg_gps2_rtk_get_baseline_coords_type(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 34);
}
/**
* @brief Get field baseline_a_mm from gps2_rtk message
*
* @return Current baseline in ECEF x or NED north component in mm.
*/
static inline int32_t mavlink_msg_gps2_rtk_get_baseline_a_mm(const mavlink_message_t* msg)
{
return _MAV_RETURN_int32_t(msg, 8);
}
/**
* @brief Get field baseline_b_mm from gps2_rtk message
*
* @return Current baseline in ECEF y or NED east component in mm.
*/
static inline int32_t mavlink_msg_gps2_rtk_get_baseline_b_mm(const mavlink_message_t* msg)
{
return _MAV_RETURN_int32_t(msg, 12);
}
/**
* @brief Get field baseline_c_mm from gps2_rtk message
*
* @return Current baseline in ECEF z or NED down component in mm.
*/
static inline int32_t mavlink_msg_gps2_rtk_get_baseline_c_mm(const mavlink_message_t* msg)
{
return _MAV_RETURN_int32_t(msg, 16);
}
/**
* @brief Get field accuracy from gps2_rtk message
*
* @return Current estimate of baseline accuracy.
*/
static inline uint32_t mavlink_msg_gps2_rtk_get_accuracy(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint32_t(msg, 20);
}
/**
* @brief Get field iar_num_hypotheses from gps2_rtk message
*
* @return Current number of integer ambiguity hypotheses.
*/
static inline int32_t mavlink_msg_gps2_rtk_get_iar_num_hypotheses(const mavlink_message_t* msg)
{
return _MAV_RETURN_int32_t(msg, 24);
}
/**
* @brief Decode a gps2_rtk message into a struct
*
* @param msg The message to decode
* @param gps2_rtk C-struct to decode the message contents into
*/
static inline void mavlink_msg_gps2_rtk_decode(const mavlink_message_t* msg, mavlink_gps2_rtk_t* gps2_rtk)
{
#if MAVLINK_NEED_BYTE_SWAP
gps2_rtk->time_last_baseline_ms = mavlink_msg_gps2_rtk_get_time_last_baseline_ms(msg);
gps2_rtk->tow = mavlink_msg_gps2_rtk_get_tow(msg);
gps2_rtk->baseline_a_mm = mavlink_msg_gps2_rtk_get_baseline_a_mm(msg);
gps2_rtk->baseline_b_mm = mavlink_msg_gps2_rtk_get_baseline_b_mm(msg);
gps2_rtk->baseline_c_mm = mavlink_msg_gps2_rtk_get_baseline_c_mm(msg);
gps2_rtk->accuracy = mavlink_msg_gps2_rtk_get_accuracy(msg);
gps2_rtk->iar_num_hypotheses = mavlink_msg_gps2_rtk_get_iar_num_hypotheses(msg);
gps2_rtk->wn = mavlink_msg_gps2_rtk_get_wn(msg);
gps2_rtk->rtk_receiver_id = mavlink_msg_gps2_rtk_get_rtk_receiver_id(msg);
gps2_rtk->rtk_health = mavlink_msg_gps2_rtk_get_rtk_health(msg);
gps2_rtk->rtk_rate = mavlink_msg_gps2_rtk_get_rtk_rate(msg);
gps2_rtk->nsats = mavlink_msg_gps2_rtk_get_nsats(msg);
gps2_rtk->baseline_coords_type = mavlink_msg_gps2_rtk_get_baseline_coords_type(msg);
#else
memcpy(gps2_rtk, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_GPS2_RTK_LEN);
#endif
}

View file

@ -0,0 +1,257 @@
// 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), in degrees * 1E7
int32_t longitude; ///< Longitude (WGS84), in degrees * 1E7
int32_t altitude; ///< Altitude (AMSL), in meters * 1000 (positive for up)
} mavlink_gps_global_origin_t;
#define MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN 12
#define MAVLINK_MSG_ID_49_LEN 12
#define MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_CRC 39
#define MAVLINK_MSG_ID_49_CRC 39
#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), in degrees * 1E7
* @param longitude Longitude (WGS84), in degrees * 1E7
* @param altitude Altitude (AMSL), in meters * 1000 (positive for up)
* @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[MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN];
_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, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN);
#else
mavlink_gps_global_origin_t packet;
packet.latitude = latitude;
packet.longitude = longitude;
packet.altitude = altitude;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_CRC);
#else
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN);
#endif
}
/**
* @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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param latitude Latitude (WGS84), in degrees * 1E7
* @param longitude Longitude (WGS84), in degrees * 1E7
* @param altitude Altitude (AMSL), in meters * 1000 (positive for up)
* @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[MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN];
_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, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN);
#else
mavlink_gps_global_origin_t packet;
packet.latitude = latitude;
packet.longitude = longitude;
packet.altitude = altitude;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_CRC);
#else
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN);
#endif
}
/**
* @brief Encode a gps_global_origin struct
*
* @param system_id ID of this 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 Encode a gps_global_origin struct 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 will be sent over
* @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_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_gps_global_origin_t* gps_global_origin)
{
return mavlink_msg_gps_global_origin_pack_chan(system_id, component_id, chan, 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), in degrees * 1E7
* @param longitude Longitude (WGS84), in degrees * 1E7
* @param altitude Altitude (AMSL), in meters * 1000 (positive for up)
*/
#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[MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN];
_mav_put_int32_t(buf, 0, latitude);
_mav_put_int32_t(buf, 4, longitude);
_mav_put_int32_t(buf, 8, altitude);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN, buf, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN, buf, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN);
#endif
#else
mavlink_gps_global_origin_t packet;
packet.latitude = latitude;
packet.longitude = longitude;
packet.altitude = altitude;
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN, (const char *)&packet, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN, (const char *)&packet, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN);
#endif
#endif
}
#if MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This varient of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_gps_global_origin_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, int32_t latitude, int32_t longitude, int32_t altitude)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
_mav_put_int32_t(buf, 0, latitude);
_mav_put_int32_t(buf, 4, longitude);
_mav_put_int32_t(buf, 8, altitude);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN, buf, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN, buf, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN);
#endif
#else
mavlink_gps_global_origin_t *packet = (mavlink_gps_global_origin_t *)msgbuf;
packet->latitude = latitude;
packet->longitude = longitude;
packet->altitude = altitude;
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN, (const char *)packet, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN, (const char *)packet, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN);
#endif
#endif
}
#endif
#endif
// MESSAGE GPS_GLOBAL_ORIGIN UNPACKING
/**
* @brief Get field latitude from gps_global_origin message
*
* @return Latitude (WGS84), in degrees * 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), in degrees * 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 (AMSL), in meters * 1000 (positive for up)
*/
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), MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN);
#endif
}

View file

@ -0,0 +1,273 @@
// MESSAGE GPS_INJECT_DATA PACKING
#define MAVLINK_MSG_ID_GPS_INJECT_DATA 123
typedef struct __mavlink_gps_inject_data_t
{
uint8_t target_system; ///< System ID
uint8_t target_component; ///< Component ID
uint8_t len; ///< data length
uint8_t data[110]; ///< raw data (110 is enough for 12 satellites of RTCMv2)
} mavlink_gps_inject_data_t;
#define MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN 113
#define MAVLINK_MSG_ID_123_LEN 113
#define MAVLINK_MSG_ID_GPS_INJECT_DATA_CRC 250
#define MAVLINK_MSG_ID_123_CRC 250
#define MAVLINK_MSG_GPS_INJECT_DATA_FIELD_DATA_LEN 110
#define MAVLINK_MESSAGE_INFO_GPS_INJECT_DATA { \
"GPS_INJECT_DATA", \
4, \
{ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_gps_inject_data_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_gps_inject_data_t, target_component) }, \
{ "len", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_gps_inject_data_t, len) }, \
{ "data", NULL, MAVLINK_TYPE_UINT8_T, 110, 3, offsetof(mavlink_gps_inject_data_t, data) }, \
} \
}
/**
* @brief Pack a gps_inject_data message
* @param system_id ID of this 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 len data length
* @param data raw data (110 is enough for 12 satellites of RTCMv2)
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_gps_inject_data_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t target_system, uint8_t target_component, uint8_t len, const uint8_t *data)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
_mav_put_uint8_t(buf, 2, len);
_mav_put_uint8_t_array(buf, 3, data, 110);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN);
#else
mavlink_gps_inject_data_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
packet.len = len;
mav_array_memcpy(packet.data, data, sizeof(uint8_t)*110);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_GPS_INJECT_DATA;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN, MAVLINK_MSG_ID_GPS_INJECT_DATA_CRC);
#else
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN);
#endif
}
/**
* @brief Pack a gps_inject_data 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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param target_system System ID
* @param target_component Component ID
* @param len data length
* @param data raw data (110 is enough for 12 satellites of RTCMv2)
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_gps_inject_data_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint8_t target_system,uint8_t target_component,uint8_t len,const uint8_t *data)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
_mav_put_uint8_t(buf, 2, len);
_mav_put_uint8_t_array(buf, 3, data, 110);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN);
#else
mavlink_gps_inject_data_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
packet.len = len;
mav_array_memcpy(packet.data, data, sizeof(uint8_t)*110);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_GPS_INJECT_DATA;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN, MAVLINK_MSG_ID_GPS_INJECT_DATA_CRC);
#else
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN);
#endif
}
/**
* @brief Encode a gps_inject_data struct
*
* @param system_id ID of this 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_inject_data C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_gps_inject_data_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gps_inject_data_t* gps_inject_data)
{
return mavlink_msg_gps_inject_data_pack(system_id, component_id, msg, gps_inject_data->target_system, gps_inject_data->target_component, gps_inject_data->len, gps_inject_data->data);
}
/**
* @brief Encode a gps_inject_data struct 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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param gps_inject_data C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_gps_inject_data_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_gps_inject_data_t* gps_inject_data)
{
return mavlink_msg_gps_inject_data_pack_chan(system_id, component_id, chan, msg, gps_inject_data->target_system, gps_inject_data->target_component, gps_inject_data->len, gps_inject_data->data);
}
/**
* @brief Send a gps_inject_data message
* @param chan MAVLink channel to send the message
*
* @param target_system System ID
* @param target_component Component ID
* @param len data length
* @param data raw data (110 is enough for 12 satellites of RTCMv2)
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_gps_inject_data_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t len, const uint8_t *data)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
_mav_put_uint8_t(buf, 2, len);
_mav_put_uint8_t_array(buf, 3, data, 110);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_INJECT_DATA, buf, MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN, MAVLINK_MSG_ID_GPS_INJECT_DATA_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_INJECT_DATA, buf, MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN);
#endif
#else
mavlink_gps_inject_data_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
packet.len = len;
mav_array_memcpy(packet.data, data, sizeof(uint8_t)*110);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_INJECT_DATA, (const char *)&packet, MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN, MAVLINK_MSG_ID_GPS_INJECT_DATA_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_INJECT_DATA, (const char *)&packet, MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN);
#endif
#endif
}
#if MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This varient of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_gps_inject_data_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t len, const uint8_t *data)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
_mav_put_uint8_t(buf, 2, len);
_mav_put_uint8_t_array(buf, 3, data, 110);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_INJECT_DATA, buf, MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN, MAVLINK_MSG_ID_GPS_INJECT_DATA_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_INJECT_DATA, buf, MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN);
#endif
#else
mavlink_gps_inject_data_t *packet = (mavlink_gps_inject_data_t *)msgbuf;
packet->target_system = target_system;
packet->target_component = target_component;
packet->len = len;
mav_array_memcpy(packet->data, data, sizeof(uint8_t)*110);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_INJECT_DATA, (const char *)packet, MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN, MAVLINK_MSG_ID_GPS_INJECT_DATA_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_INJECT_DATA, (const char *)packet, MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN);
#endif
#endif
}
#endif
#endif
// MESSAGE GPS_INJECT_DATA UNPACKING
/**
* @brief Get field target_system from gps_inject_data message
*
* @return System ID
*/
static inline uint8_t mavlink_msg_gps_inject_data_get_target_system(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 0);
}
/**
* @brief Get field target_component from gps_inject_data message
*
* @return Component ID
*/
static inline uint8_t mavlink_msg_gps_inject_data_get_target_component(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 1);
}
/**
* @brief Get field len from gps_inject_data message
*
* @return data length
*/
static inline uint8_t mavlink_msg_gps_inject_data_get_len(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 2);
}
/**
* @brief Get field data from gps_inject_data message
*
* @return raw data (110 is enough for 12 satellites of RTCMv2)
*/
static inline uint16_t mavlink_msg_gps_inject_data_get_data(const mavlink_message_t* msg, uint8_t *data)
{
return _MAV_RETURN_uint8_t_array(msg, data, 110, 3);
}
/**
* @brief Decode a gps_inject_data message into a struct
*
* @param msg The message to decode
* @param gps_inject_data C-struct to decode the message contents into
*/
static inline void mavlink_msg_gps_inject_data_decode(const mavlink_message_t* msg, mavlink_gps_inject_data_t* gps_inject_data)
{
#if MAVLINK_NEED_BYTE_SWAP
gps_inject_data->target_system = mavlink_msg_gps_inject_data_get_target_system(msg);
gps_inject_data->target_component = mavlink_msg_gps_inject_data_get_target_component(msg);
gps_inject_data->len = mavlink_msg_gps_inject_data_get_len(msg);
mavlink_msg_gps_inject_data_get_data(msg, gps_inject_data->data);
#else
memcpy(gps_inject_data, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_GPS_INJECT_DATA_LEN);
#endif
}

View file

@ -0,0 +1,425 @@
// 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 (WGS84), in degrees * 1E7
int32_t lon; ///< Longitude (WGS84), in degrees * 1E7
int32_t alt; ///< Altitude (AMSL, NOT WGS84), in meters * 1000 (positive for up). Note that virtually all GPS modules provide the AMSL altitude in addition to the WGS84 altitude.
uint16_t eph; ///< GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: UINT16_MAX
uint16_t epv; ///< GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: UINT16_MAX
uint16_t vel; ///< GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX
uint16_t cog; ///< Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX
uint8_t fix_type; ///< 0-1: no fix, 2: 2D fix, 3: 3D fix, 4: DGPS, 5: RTK. 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_MSG_ID_GPS_RAW_INT_CRC 24
#define MAVLINK_MSG_ID_24_CRC 24
#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, 4: DGPS, 5: RTK. 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 (WGS84), in degrees * 1E7
* @param lon Longitude (WGS84), in degrees * 1E7
* @param alt Altitude (AMSL, NOT WGS84), in meters * 1000 (positive for up). Note that virtually all GPS modules provide the AMSL altitude in addition to the WGS84 altitude.
* @param eph GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: UINT16_MAX
* @param epv GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: UINT16_MAX
* @param vel GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX
* @param cog Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX
* @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[MAVLINK_MSG_ID_GPS_RAW_INT_LEN];
_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, MAVLINK_MSG_ID_GPS_RAW_INT_LEN);
#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, MAVLINK_MSG_ID_GPS_RAW_INT_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_GPS_RAW_INT;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GPS_RAW_INT_LEN, MAVLINK_MSG_ID_GPS_RAW_INT_CRC);
#else
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GPS_RAW_INT_LEN);
#endif
}
/**
* @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 will be 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, 4: DGPS, 5: RTK. 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 (WGS84), in degrees * 1E7
* @param lon Longitude (WGS84), in degrees * 1E7
* @param alt Altitude (AMSL, NOT WGS84), in meters * 1000 (positive for up). Note that virtually all GPS modules provide the AMSL altitude in addition to the WGS84 altitude.
* @param eph GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: UINT16_MAX
* @param epv GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: UINT16_MAX
* @param vel GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX
* @param cog Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX
* @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[MAVLINK_MSG_ID_GPS_RAW_INT_LEN];
_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, MAVLINK_MSG_ID_GPS_RAW_INT_LEN);
#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, MAVLINK_MSG_ID_GPS_RAW_INT_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_GPS_RAW_INT;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GPS_RAW_INT_LEN, MAVLINK_MSG_ID_GPS_RAW_INT_CRC);
#else
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GPS_RAW_INT_LEN);
#endif
}
/**
* @brief Encode a gps_raw_int struct
*
* @param system_id ID of this 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 Encode a gps_raw_int struct 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 will be sent over
* @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_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_gps_raw_int_t* gps_raw_int)
{
return mavlink_msg_gps_raw_int_pack_chan(system_id, component_id, chan, 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, 4: DGPS, 5: RTK. 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 (WGS84), in degrees * 1E7
* @param lon Longitude (WGS84), in degrees * 1E7
* @param alt Altitude (AMSL, NOT WGS84), in meters * 1000 (positive for up). Note that virtually all GPS modules provide the AMSL altitude in addition to the WGS84 altitude.
* @param eph GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: UINT16_MAX
* @param epv GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: UINT16_MAX
* @param vel GPS ground speed (m/s * 100). If unknown, set to: UINT16_MAX
* @param cog Course over ground (NOT heading, but direction of movement) in degrees * 100, 0.0..359.99 degrees. If unknown, set to: UINT16_MAX
* @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[MAVLINK_MSG_ID_GPS_RAW_INT_LEN];
_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);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RAW_INT, buf, MAVLINK_MSG_ID_GPS_RAW_INT_LEN, MAVLINK_MSG_ID_GPS_RAW_INT_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RAW_INT, buf, MAVLINK_MSG_ID_GPS_RAW_INT_LEN);
#endif
#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;
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RAW_INT, (const char *)&packet, MAVLINK_MSG_ID_GPS_RAW_INT_LEN, MAVLINK_MSG_ID_GPS_RAW_INT_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RAW_INT, (const char *)&packet, MAVLINK_MSG_ID_GPS_RAW_INT_LEN);
#endif
#endif
}
#if MAVLINK_MSG_ID_GPS_RAW_INT_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This varient of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_gps_raw_int_send_buf(mavlink_message_t *msgbuf, 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 = (char *)msgbuf;
_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);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RAW_INT, buf, MAVLINK_MSG_ID_GPS_RAW_INT_LEN, MAVLINK_MSG_ID_GPS_RAW_INT_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RAW_INT, buf, MAVLINK_MSG_ID_GPS_RAW_INT_LEN);
#endif
#else
mavlink_gps_raw_int_t *packet = (mavlink_gps_raw_int_t *)msgbuf;
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;
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RAW_INT, (const char *)packet, MAVLINK_MSG_ID_GPS_RAW_INT_LEN, MAVLINK_MSG_ID_GPS_RAW_INT_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RAW_INT, (const char *)packet, MAVLINK_MSG_ID_GPS_RAW_INT_LEN);
#endif
#endif
}
#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, 4: DGPS, 5: RTK. 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 (WGS84), in degrees * 1E7
*/
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 (WGS84), in degrees * 1E7
*/
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 (AMSL, NOT WGS84), in meters * 1000 (positive for up). Note that virtually all GPS modules provide the AMSL altitude in addition to the WGS84 altitude.
*/
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: UINT16_MAX
*/
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 vertical dilution of position in cm (m*100). If unknown, set to: UINT16_MAX
*/
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: UINT16_MAX
*/
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: UINT16_MAX
*/
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), MAVLINK_MSG_ID_GPS_RAW_INT_LEN);
#endif
}

View file

@ -0,0 +1,497 @@
// MESSAGE GPS_RTK PACKING
#define MAVLINK_MSG_ID_GPS_RTK 127
typedef struct __mavlink_gps_rtk_t
{
uint32_t time_last_baseline_ms; ///< Time since boot of last baseline message received in ms.
uint32_t tow; ///< GPS Time of Week of last baseline
int32_t baseline_a_mm; ///< Current baseline in ECEF x or NED north component in mm.
int32_t baseline_b_mm; ///< Current baseline in ECEF y or NED east component in mm.
int32_t baseline_c_mm; ///< Current baseline in ECEF z or NED down component in mm.
uint32_t accuracy; ///< Current estimate of baseline accuracy.
int32_t iar_num_hypotheses; ///< Current number of integer ambiguity hypotheses.
uint16_t wn; ///< GPS Week Number of last baseline
uint8_t rtk_receiver_id; ///< Identification of connected RTK receiver.
uint8_t rtk_health; ///< GPS-specific health report for RTK data.
uint8_t rtk_rate; ///< Rate of baseline messages being received by GPS, in HZ
uint8_t nsats; ///< Current number of sats used for RTK calculation.
uint8_t baseline_coords_type; ///< Coordinate system of baseline. 0 == ECEF, 1 == NED
} mavlink_gps_rtk_t;
#define MAVLINK_MSG_ID_GPS_RTK_LEN 35
#define MAVLINK_MSG_ID_127_LEN 35
#define MAVLINK_MSG_ID_GPS_RTK_CRC 25
#define MAVLINK_MSG_ID_127_CRC 25
#define MAVLINK_MESSAGE_INFO_GPS_RTK { \
"GPS_RTK", \
13, \
{ { "time_last_baseline_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_gps_rtk_t, time_last_baseline_ms) }, \
{ "tow", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_gps_rtk_t, tow) }, \
{ "baseline_a_mm", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_gps_rtk_t, baseline_a_mm) }, \
{ "baseline_b_mm", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_gps_rtk_t, baseline_b_mm) }, \
{ "baseline_c_mm", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_gps_rtk_t, baseline_c_mm) }, \
{ "accuracy", NULL, MAVLINK_TYPE_UINT32_T, 0, 20, offsetof(mavlink_gps_rtk_t, accuracy) }, \
{ "iar_num_hypotheses", NULL, MAVLINK_TYPE_INT32_T, 0, 24, offsetof(mavlink_gps_rtk_t, iar_num_hypotheses) }, \
{ "wn", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_gps_rtk_t, wn) }, \
{ "rtk_receiver_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 30, offsetof(mavlink_gps_rtk_t, rtk_receiver_id) }, \
{ "rtk_health", NULL, MAVLINK_TYPE_UINT8_T, 0, 31, offsetof(mavlink_gps_rtk_t, rtk_health) }, \
{ "rtk_rate", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_gps_rtk_t, rtk_rate) }, \
{ "nsats", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_gps_rtk_t, nsats) }, \
{ "baseline_coords_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_gps_rtk_t, baseline_coords_type) }, \
} \
}
/**
* @brief Pack a gps_rtk message
* @param system_id ID of this 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_last_baseline_ms Time since boot of last baseline message received in ms.
* @param rtk_receiver_id Identification of connected RTK receiver.
* @param wn GPS Week Number of last baseline
* @param tow GPS Time of Week of last baseline
* @param rtk_health GPS-specific health report for RTK data.
* @param rtk_rate Rate of baseline messages being received by GPS, in HZ
* @param nsats Current number of sats used for RTK calculation.
* @param baseline_coords_type Coordinate system of baseline. 0 == ECEF, 1 == NED
* @param baseline_a_mm Current baseline in ECEF x or NED north component in mm.
* @param baseline_b_mm Current baseline in ECEF y or NED east component in mm.
* @param baseline_c_mm Current baseline in ECEF z or NED down component in mm.
* @param accuracy Current estimate of baseline accuracy.
* @param iar_num_hypotheses Current number of integer ambiguity hypotheses.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_gps_rtk_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint32_t time_last_baseline_ms, uint8_t rtk_receiver_id, uint16_t wn, uint32_t tow, uint8_t rtk_health, uint8_t rtk_rate, uint8_t nsats, uint8_t baseline_coords_type, int32_t baseline_a_mm, int32_t baseline_b_mm, int32_t baseline_c_mm, uint32_t accuracy, int32_t iar_num_hypotheses)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_GPS_RTK_LEN];
_mav_put_uint32_t(buf, 0, time_last_baseline_ms);
_mav_put_uint32_t(buf, 4, tow);
_mav_put_int32_t(buf, 8, baseline_a_mm);
_mav_put_int32_t(buf, 12, baseline_b_mm);
_mav_put_int32_t(buf, 16, baseline_c_mm);
_mav_put_uint32_t(buf, 20, accuracy);
_mav_put_int32_t(buf, 24, iar_num_hypotheses);
_mav_put_uint16_t(buf, 28, wn);
_mav_put_uint8_t(buf, 30, rtk_receiver_id);
_mav_put_uint8_t(buf, 31, rtk_health);
_mav_put_uint8_t(buf, 32, rtk_rate);
_mav_put_uint8_t(buf, 33, nsats);
_mav_put_uint8_t(buf, 34, baseline_coords_type);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GPS_RTK_LEN);
#else
mavlink_gps_rtk_t packet;
packet.time_last_baseline_ms = time_last_baseline_ms;
packet.tow = tow;
packet.baseline_a_mm = baseline_a_mm;
packet.baseline_b_mm = baseline_b_mm;
packet.baseline_c_mm = baseline_c_mm;
packet.accuracy = accuracy;
packet.iar_num_hypotheses = iar_num_hypotheses;
packet.wn = wn;
packet.rtk_receiver_id = rtk_receiver_id;
packet.rtk_health = rtk_health;
packet.rtk_rate = rtk_rate;
packet.nsats = nsats;
packet.baseline_coords_type = baseline_coords_type;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GPS_RTK_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_GPS_RTK;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GPS_RTK_LEN, MAVLINK_MSG_ID_GPS_RTK_CRC);
#else
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GPS_RTK_LEN);
#endif
}
/**
* @brief Pack a gps_rtk 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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param time_last_baseline_ms Time since boot of last baseline message received in ms.
* @param rtk_receiver_id Identification of connected RTK receiver.
* @param wn GPS Week Number of last baseline
* @param tow GPS Time of Week of last baseline
* @param rtk_health GPS-specific health report for RTK data.
* @param rtk_rate Rate of baseline messages being received by GPS, in HZ
* @param nsats Current number of sats used for RTK calculation.
* @param baseline_coords_type Coordinate system of baseline. 0 == ECEF, 1 == NED
* @param baseline_a_mm Current baseline in ECEF x or NED north component in mm.
* @param baseline_b_mm Current baseline in ECEF y or NED east component in mm.
* @param baseline_c_mm Current baseline in ECEF z or NED down component in mm.
* @param accuracy Current estimate of baseline accuracy.
* @param iar_num_hypotheses Current number of integer ambiguity hypotheses.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_gps_rtk_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint32_t time_last_baseline_ms,uint8_t rtk_receiver_id,uint16_t wn,uint32_t tow,uint8_t rtk_health,uint8_t rtk_rate,uint8_t nsats,uint8_t baseline_coords_type,int32_t baseline_a_mm,int32_t baseline_b_mm,int32_t baseline_c_mm,uint32_t accuracy,int32_t iar_num_hypotheses)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_GPS_RTK_LEN];
_mav_put_uint32_t(buf, 0, time_last_baseline_ms);
_mav_put_uint32_t(buf, 4, tow);
_mav_put_int32_t(buf, 8, baseline_a_mm);
_mav_put_int32_t(buf, 12, baseline_b_mm);
_mav_put_int32_t(buf, 16, baseline_c_mm);
_mav_put_uint32_t(buf, 20, accuracy);
_mav_put_int32_t(buf, 24, iar_num_hypotheses);
_mav_put_uint16_t(buf, 28, wn);
_mav_put_uint8_t(buf, 30, rtk_receiver_id);
_mav_put_uint8_t(buf, 31, rtk_health);
_mav_put_uint8_t(buf, 32, rtk_rate);
_mav_put_uint8_t(buf, 33, nsats);
_mav_put_uint8_t(buf, 34, baseline_coords_type);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GPS_RTK_LEN);
#else
mavlink_gps_rtk_t packet;
packet.time_last_baseline_ms = time_last_baseline_ms;
packet.tow = tow;
packet.baseline_a_mm = baseline_a_mm;
packet.baseline_b_mm = baseline_b_mm;
packet.baseline_c_mm = baseline_c_mm;
packet.accuracy = accuracy;
packet.iar_num_hypotheses = iar_num_hypotheses;
packet.wn = wn;
packet.rtk_receiver_id = rtk_receiver_id;
packet.rtk_health = rtk_health;
packet.rtk_rate = rtk_rate;
packet.nsats = nsats;
packet.baseline_coords_type = baseline_coords_type;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GPS_RTK_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_GPS_RTK;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GPS_RTK_LEN, MAVLINK_MSG_ID_GPS_RTK_CRC);
#else
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GPS_RTK_LEN);
#endif
}
/**
* @brief Encode a gps_rtk struct
*
* @param system_id ID of this 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_rtk C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_gps_rtk_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gps_rtk_t* gps_rtk)
{
return mavlink_msg_gps_rtk_pack(system_id, component_id, msg, gps_rtk->time_last_baseline_ms, gps_rtk->rtk_receiver_id, gps_rtk->wn, gps_rtk->tow, gps_rtk->rtk_health, gps_rtk->rtk_rate, gps_rtk->nsats, gps_rtk->baseline_coords_type, gps_rtk->baseline_a_mm, gps_rtk->baseline_b_mm, gps_rtk->baseline_c_mm, gps_rtk->accuracy, gps_rtk->iar_num_hypotheses);
}
/**
* @brief Encode a gps_rtk struct 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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param gps_rtk C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_gps_rtk_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_gps_rtk_t* gps_rtk)
{
return mavlink_msg_gps_rtk_pack_chan(system_id, component_id, chan, msg, gps_rtk->time_last_baseline_ms, gps_rtk->rtk_receiver_id, gps_rtk->wn, gps_rtk->tow, gps_rtk->rtk_health, gps_rtk->rtk_rate, gps_rtk->nsats, gps_rtk->baseline_coords_type, gps_rtk->baseline_a_mm, gps_rtk->baseline_b_mm, gps_rtk->baseline_c_mm, gps_rtk->accuracy, gps_rtk->iar_num_hypotheses);
}
/**
* @brief Send a gps_rtk message
* @param chan MAVLink channel to send the message
*
* @param time_last_baseline_ms Time since boot of last baseline message received in ms.
* @param rtk_receiver_id Identification of connected RTK receiver.
* @param wn GPS Week Number of last baseline
* @param tow GPS Time of Week of last baseline
* @param rtk_health GPS-specific health report for RTK data.
* @param rtk_rate Rate of baseline messages being received by GPS, in HZ
* @param nsats Current number of sats used for RTK calculation.
* @param baseline_coords_type Coordinate system of baseline. 0 == ECEF, 1 == NED
* @param baseline_a_mm Current baseline in ECEF x or NED north component in mm.
* @param baseline_b_mm Current baseline in ECEF y or NED east component in mm.
* @param baseline_c_mm Current baseline in ECEF z or NED down component in mm.
* @param accuracy Current estimate of baseline accuracy.
* @param iar_num_hypotheses Current number of integer ambiguity hypotheses.
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_gps_rtk_send(mavlink_channel_t chan, uint32_t time_last_baseline_ms, uint8_t rtk_receiver_id, uint16_t wn, uint32_t tow, uint8_t rtk_health, uint8_t rtk_rate, uint8_t nsats, uint8_t baseline_coords_type, int32_t baseline_a_mm, int32_t baseline_b_mm, int32_t baseline_c_mm, uint32_t accuracy, int32_t iar_num_hypotheses)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_GPS_RTK_LEN];
_mav_put_uint32_t(buf, 0, time_last_baseline_ms);
_mav_put_uint32_t(buf, 4, tow);
_mav_put_int32_t(buf, 8, baseline_a_mm);
_mav_put_int32_t(buf, 12, baseline_b_mm);
_mav_put_int32_t(buf, 16, baseline_c_mm);
_mav_put_uint32_t(buf, 20, accuracy);
_mav_put_int32_t(buf, 24, iar_num_hypotheses);
_mav_put_uint16_t(buf, 28, wn);
_mav_put_uint8_t(buf, 30, rtk_receiver_id);
_mav_put_uint8_t(buf, 31, rtk_health);
_mav_put_uint8_t(buf, 32, rtk_rate);
_mav_put_uint8_t(buf, 33, nsats);
_mav_put_uint8_t(buf, 34, baseline_coords_type);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RTK, buf, MAVLINK_MSG_ID_GPS_RTK_LEN, MAVLINK_MSG_ID_GPS_RTK_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RTK, buf, MAVLINK_MSG_ID_GPS_RTK_LEN);
#endif
#else
mavlink_gps_rtk_t packet;
packet.time_last_baseline_ms = time_last_baseline_ms;
packet.tow = tow;
packet.baseline_a_mm = baseline_a_mm;
packet.baseline_b_mm = baseline_b_mm;
packet.baseline_c_mm = baseline_c_mm;
packet.accuracy = accuracy;
packet.iar_num_hypotheses = iar_num_hypotheses;
packet.wn = wn;
packet.rtk_receiver_id = rtk_receiver_id;
packet.rtk_health = rtk_health;
packet.rtk_rate = rtk_rate;
packet.nsats = nsats;
packet.baseline_coords_type = baseline_coords_type;
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RTK, (const char *)&packet, MAVLINK_MSG_ID_GPS_RTK_LEN, MAVLINK_MSG_ID_GPS_RTK_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RTK, (const char *)&packet, MAVLINK_MSG_ID_GPS_RTK_LEN);
#endif
#endif
}
#if MAVLINK_MSG_ID_GPS_RTK_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This varient of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_gps_rtk_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_last_baseline_ms, uint8_t rtk_receiver_id, uint16_t wn, uint32_t tow, uint8_t rtk_health, uint8_t rtk_rate, uint8_t nsats, uint8_t baseline_coords_type, int32_t baseline_a_mm, int32_t baseline_b_mm, int32_t baseline_c_mm, uint32_t accuracy, int32_t iar_num_hypotheses)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
_mav_put_uint32_t(buf, 0, time_last_baseline_ms);
_mav_put_uint32_t(buf, 4, tow);
_mav_put_int32_t(buf, 8, baseline_a_mm);
_mav_put_int32_t(buf, 12, baseline_b_mm);
_mav_put_int32_t(buf, 16, baseline_c_mm);
_mav_put_uint32_t(buf, 20, accuracy);
_mav_put_int32_t(buf, 24, iar_num_hypotheses);
_mav_put_uint16_t(buf, 28, wn);
_mav_put_uint8_t(buf, 30, rtk_receiver_id);
_mav_put_uint8_t(buf, 31, rtk_health);
_mav_put_uint8_t(buf, 32, rtk_rate);
_mav_put_uint8_t(buf, 33, nsats);
_mav_put_uint8_t(buf, 34, baseline_coords_type);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RTK, buf, MAVLINK_MSG_ID_GPS_RTK_LEN, MAVLINK_MSG_ID_GPS_RTK_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RTK, buf, MAVLINK_MSG_ID_GPS_RTK_LEN);
#endif
#else
mavlink_gps_rtk_t *packet = (mavlink_gps_rtk_t *)msgbuf;
packet->time_last_baseline_ms = time_last_baseline_ms;
packet->tow = tow;
packet->baseline_a_mm = baseline_a_mm;
packet->baseline_b_mm = baseline_b_mm;
packet->baseline_c_mm = baseline_c_mm;
packet->accuracy = accuracy;
packet->iar_num_hypotheses = iar_num_hypotheses;
packet->wn = wn;
packet->rtk_receiver_id = rtk_receiver_id;
packet->rtk_health = rtk_health;
packet->rtk_rate = rtk_rate;
packet->nsats = nsats;
packet->baseline_coords_type = baseline_coords_type;
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RTK, (const char *)packet, MAVLINK_MSG_ID_GPS_RTK_LEN, MAVLINK_MSG_ID_GPS_RTK_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RTK, (const char *)packet, MAVLINK_MSG_ID_GPS_RTK_LEN);
#endif
#endif
}
#endif
#endif
// MESSAGE GPS_RTK UNPACKING
/**
* @brief Get field time_last_baseline_ms from gps_rtk message
*
* @return Time since boot of last baseline message received in ms.
*/
static inline uint32_t mavlink_msg_gps_rtk_get_time_last_baseline_ms(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint32_t(msg, 0);
}
/**
* @brief Get field rtk_receiver_id from gps_rtk message
*
* @return Identification of connected RTK receiver.
*/
static inline uint8_t mavlink_msg_gps_rtk_get_rtk_receiver_id(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 30);
}
/**
* @brief Get field wn from gps_rtk message
*
* @return GPS Week Number of last baseline
*/
static inline uint16_t mavlink_msg_gps_rtk_get_wn(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 28);
}
/**
* @brief Get field tow from gps_rtk message
*
* @return GPS Time of Week of last baseline
*/
static inline uint32_t mavlink_msg_gps_rtk_get_tow(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint32_t(msg, 4);
}
/**
* @brief Get field rtk_health from gps_rtk message
*
* @return GPS-specific health report for RTK data.
*/
static inline uint8_t mavlink_msg_gps_rtk_get_rtk_health(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 31);
}
/**
* @brief Get field rtk_rate from gps_rtk message
*
* @return Rate of baseline messages being received by GPS, in HZ
*/
static inline uint8_t mavlink_msg_gps_rtk_get_rtk_rate(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 32);
}
/**
* @brief Get field nsats from gps_rtk message
*
* @return Current number of sats used for RTK calculation.
*/
static inline uint8_t mavlink_msg_gps_rtk_get_nsats(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 33);
}
/**
* @brief Get field baseline_coords_type from gps_rtk message
*
* @return Coordinate system of baseline. 0 == ECEF, 1 == NED
*/
static inline uint8_t mavlink_msg_gps_rtk_get_baseline_coords_type(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 34);
}
/**
* @brief Get field baseline_a_mm from gps_rtk message
*
* @return Current baseline in ECEF x or NED north component in mm.
*/
static inline int32_t mavlink_msg_gps_rtk_get_baseline_a_mm(const mavlink_message_t* msg)
{
return _MAV_RETURN_int32_t(msg, 8);
}
/**
* @brief Get field baseline_b_mm from gps_rtk message
*
* @return Current baseline in ECEF y or NED east component in mm.
*/
static inline int32_t mavlink_msg_gps_rtk_get_baseline_b_mm(const mavlink_message_t* msg)
{
return _MAV_RETURN_int32_t(msg, 12);
}
/**
* @brief Get field baseline_c_mm from gps_rtk message
*
* @return Current baseline in ECEF z or NED down component in mm.
*/
static inline int32_t mavlink_msg_gps_rtk_get_baseline_c_mm(const mavlink_message_t* msg)
{
return _MAV_RETURN_int32_t(msg, 16);
}
/**
* @brief Get field accuracy from gps_rtk message
*
* @return Current estimate of baseline accuracy.
*/
static inline uint32_t mavlink_msg_gps_rtk_get_accuracy(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint32_t(msg, 20);
}
/**
* @brief Get field iar_num_hypotheses from gps_rtk message
*
* @return Current number of integer ambiguity hypotheses.
*/
static inline int32_t mavlink_msg_gps_rtk_get_iar_num_hypotheses(const mavlink_message_t* msg)
{
return _MAV_RETURN_int32_t(msg, 24);
}
/**
* @brief Decode a gps_rtk message into a struct
*
* @param msg The message to decode
* @param gps_rtk C-struct to decode the message contents into
*/
static inline void mavlink_msg_gps_rtk_decode(const mavlink_message_t* msg, mavlink_gps_rtk_t* gps_rtk)
{
#if MAVLINK_NEED_BYTE_SWAP
gps_rtk->time_last_baseline_ms = mavlink_msg_gps_rtk_get_time_last_baseline_ms(msg);
gps_rtk->tow = mavlink_msg_gps_rtk_get_tow(msg);
gps_rtk->baseline_a_mm = mavlink_msg_gps_rtk_get_baseline_a_mm(msg);
gps_rtk->baseline_b_mm = mavlink_msg_gps_rtk_get_baseline_b_mm(msg);
gps_rtk->baseline_c_mm = mavlink_msg_gps_rtk_get_baseline_c_mm(msg);
gps_rtk->accuracy = mavlink_msg_gps_rtk_get_accuracy(msg);
gps_rtk->iar_num_hypotheses = mavlink_msg_gps_rtk_get_iar_num_hypotheses(msg);
gps_rtk->wn = mavlink_msg_gps_rtk_get_wn(msg);
gps_rtk->rtk_receiver_id = mavlink_msg_gps_rtk_get_rtk_receiver_id(msg);
gps_rtk->rtk_health = mavlink_msg_gps_rtk_get_rtk_health(msg);
gps_rtk->rtk_rate = mavlink_msg_gps_rtk_get_rtk_rate(msg);
gps_rtk->nsats = mavlink_msg_gps_rtk_get_nsats(msg);
gps_rtk->baseline_coords_type = mavlink_msg_gps_rtk_get_baseline_coords_type(msg);
#else
memcpy(gps_rtk, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_GPS_RTK_LEN);
#endif
}

View file

@ -0,0 +1,325 @@
// 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_ID_GPS_STATUS_CRC 23
#define MAVLINK_MSG_ID_25_CRC 23
#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[MAVLINK_MSG_ID_GPS_STATUS_LEN];
_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, MAVLINK_MSG_ID_GPS_STATUS_LEN);
#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, MAVLINK_MSG_ID_GPS_STATUS_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_GPS_STATUS;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GPS_STATUS_LEN, MAVLINK_MSG_ID_GPS_STATUS_CRC);
#else
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GPS_STATUS_LEN);
#endif
}
/**
* @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 will be 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[MAVLINK_MSG_ID_GPS_STATUS_LEN];
_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, MAVLINK_MSG_ID_GPS_STATUS_LEN);
#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, MAVLINK_MSG_ID_GPS_STATUS_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_GPS_STATUS;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GPS_STATUS_LEN, MAVLINK_MSG_ID_GPS_STATUS_CRC);
#else
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GPS_STATUS_LEN);
#endif
}
/**
* @brief Encode a gps_status struct
*
* @param system_id ID of this 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 Encode a gps_status struct 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 will be sent over
* @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_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_gps_status_t* gps_status)
{
return mavlink_msg_gps_status_pack_chan(system_id, component_id, chan, 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[MAVLINK_MSG_ID_GPS_STATUS_LEN];
_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);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_STATUS, buf, MAVLINK_MSG_ID_GPS_STATUS_LEN, MAVLINK_MSG_ID_GPS_STATUS_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_STATUS, buf, MAVLINK_MSG_ID_GPS_STATUS_LEN);
#endif
#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);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_STATUS, (const char *)&packet, MAVLINK_MSG_ID_GPS_STATUS_LEN, MAVLINK_MSG_ID_GPS_STATUS_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_STATUS, (const char *)&packet, MAVLINK_MSG_ID_GPS_STATUS_LEN);
#endif
#endif
}
#if MAVLINK_MSG_ID_GPS_STATUS_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This varient of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_gps_status_send_buf(mavlink_message_t *msgbuf, 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 = (char *)msgbuf;
_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);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_STATUS, buf, MAVLINK_MSG_ID_GPS_STATUS_LEN, MAVLINK_MSG_ID_GPS_STATUS_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_STATUS, buf, MAVLINK_MSG_ID_GPS_STATUS_LEN);
#endif
#else
mavlink_gps_status_t *packet = (mavlink_gps_status_t *)msgbuf;
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);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_STATUS, (const char *)packet, MAVLINK_MSG_ID_GPS_STATUS_LEN, MAVLINK_MSG_ID_GPS_STATUS_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_STATUS, (const char *)packet, MAVLINK_MSG_ID_GPS_STATUS_LEN);
#endif
#endif
}
#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), MAVLINK_MSG_ID_GPS_STATUS_LEN);
#endif
}

View file

@ -0,0 +1,326 @@
// 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_FLAG 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_MSG_ID_HEARTBEAT_CRC 50
#define MAVLINK_MSG_ID_0_CRC 50
#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_FLAG 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[MAVLINK_MSG_ID_HEARTBEAT_LEN];
_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, MAVLINK_MSG_ID_HEARTBEAT_LEN);
#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, MAVLINK_MSG_ID_HEARTBEAT_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_HEARTBEAT;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HEARTBEAT_LEN, MAVLINK_MSG_ID_HEARTBEAT_CRC);
#else
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HEARTBEAT_LEN);
#endif
}
/**
* @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 will be 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_FLAG 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[MAVLINK_MSG_ID_HEARTBEAT_LEN];
_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, MAVLINK_MSG_ID_HEARTBEAT_LEN);
#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, MAVLINK_MSG_ID_HEARTBEAT_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_HEARTBEAT;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HEARTBEAT_LEN, MAVLINK_MSG_ID_HEARTBEAT_CRC);
#else
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HEARTBEAT_LEN);
#endif
}
/**
* @brief Encode a heartbeat struct
*
* @param system_id ID of this 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 Encode a heartbeat struct 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 will be sent over
* @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_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_heartbeat_t* heartbeat)
{
return mavlink_msg_heartbeat_pack_chan(system_id, component_id, chan, 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_FLAG 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[MAVLINK_MSG_ID_HEARTBEAT_LEN];
_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);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HEARTBEAT, buf, MAVLINK_MSG_ID_HEARTBEAT_LEN, MAVLINK_MSG_ID_HEARTBEAT_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HEARTBEAT, buf, MAVLINK_MSG_ID_HEARTBEAT_LEN);
#endif
#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;
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HEARTBEAT, (const char *)&packet, MAVLINK_MSG_ID_HEARTBEAT_LEN, MAVLINK_MSG_ID_HEARTBEAT_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HEARTBEAT, (const char *)&packet, MAVLINK_MSG_ID_HEARTBEAT_LEN);
#endif
#endif
}
#if MAVLINK_MSG_ID_HEARTBEAT_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This varient of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_heartbeat_send_buf(mavlink_message_t *msgbuf, 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 = (char *)msgbuf;
_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);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HEARTBEAT, buf, MAVLINK_MSG_ID_HEARTBEAT_LEN, MAVLINK_MSG_ID_HEARTBEAT_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HEARTBEAT, buf, MAVLINK_MSG_ID_HEARTBEAT_LEN);
#endif
#else
mavlink_heartbeat_t *packet = (mavlink_heartbeat_t *)msgbuf;
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;
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HEARTBEAT, (const char *)packet, MAVLINK_MSG_ID_HEARTBEAT_LEN, MAVLINK_MSG_ID_HEARTBEAT_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HEARTBEAT, (const char *)packet, MAVLINK_MSG_ID_HEARTBEAT_LEN);
#endif
#endif
}
#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_FLAG 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), MAVLINK_MSG_ID_HEARTBEAT_LEN);
#endif
}

View file

@ -0,0 +1,545 @@
// MESSAGE HIGHRES_IMU PACKING
#define MAVLINK_MSG_ID_HIGHRES_IMU 105
typedef struct __mavlink_highres_imu_t
{
uint64_t time_usec; ///< Timestamp (microseconds, synced to UNIX time or since system boot)
float xacc; ///< X acceleration (m/s^2)
float yacc; ///< Y acceleration (m/s^2)
float zacc; ///< Z acceleration (m/s^2)
float xgyro; ///< Angular speed around X axis (rad / sec)
float ygyro; ///< Angular speed around Y axis (rad / sec)
float zgyro; ///< Angular speed around Z axis (rad / sec)
float xmag; ///< X Magnetic field (Gauss)
float ymag; ///< Y Magnetic field (Gauss)
float zmag; ///< Z Magnetic field (Gauss)
float abs_pressure; ///< Absolute pressure in millibar
float diff_pressure; ///< Differential pressure in millibar
float pressure_alt; ///< Altitude calculated from pressure
float temperature; ///< Temperature in degrees celsius
uint16_t fields_updated; ///< Bitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature
} mavlink_highres_imu_t;
#define MAVLINK_MSG_ID_HIGHRES_IMU_LEN 62
#define MAVLINK_MSG_ID_105_LEN 62
#define MAVLINK_MSG_ID_HIGHRES_IMU_CRC 93
#define MAVLINK_MSG_ID_105_CRC 93
#define MAVLINK_MESSAGE_INFO_HIGHRES_IMU { \
"HIGHRES_IMU", \
15, \
{ { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_highres_imu_t, time_usec) }, \
{ "xacc", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_highres_imu_t, xacc) }, \
{ "yacc", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_highres_imu_t, yacc) }, \
{ "zacc", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_highres_imu_t, zacc) }, \
{ "xgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_highres_imu_t, xgyro) }, \
{ "ygyro", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_highres_imu_t, ygyro) }, \
{ "zgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_highres_imu_t, zgyro) }, \
{ "xmag", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_highres_imu_t, xmag) }, \
{ "ymag", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_highres_imu_t, ymag) }, \
{ "zmag", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_highres_imu_t, zmag) }, \
{ "abs_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_highres_imu_t, abs_pressure) }, \
{ "diff_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_highres_imu_t, diff_pressure) }, \
{ "pressure_alt", NULL, MAVLINK_TYPE_FLOAT, 0, 52, offsetof(mavlink_highres_imu_t, pressure_alt) }, \
{ "temperature", NULL, MAVLINK_TYPE_FLOAT, 0, 56, offsetof(mavlink_highres_imu_t, temperature) }, \
{ "fields_updated", NULL, MAVLINK_TYPE_UINT16_T, 0, 60, offsetof(mavlink_highres_imu_t, fields_updated) }, \
} \
}
/**
* @brief Pack a highres_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, synced to UNIX time or since system boot)
* @param xacc X acceleration (m/s^2)
* @param yacc Y acceleration (m/s^2)
* @param zacc Z acceleration (m/s^2)
* @param xgyro Angular speed around X axis (rad / sec)
* @param ygyro Angular speed around Y axis (rad / sec)
* @param zgyro Angular speed around Z axis (rad / sec)
* @param xmag X Magnetic field (Gauss)
* @param ymag Y Magnetic field (Gauss)
* @param zmag Z Magnetic field (Gauss)
* @param abs_pressure Absolute pressure in millibar
* @param diff_pressure Differential pressure in millibar
* @param pressure_alt Altitude calculated from pressure
* @param temperature Temperature in degrees celsius
* @param fields_updated Bitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_highres_imu_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint64_t time_usec, float xacc, float yacc, float zacc, float xgyro, float ygyro, float zgyro, float xmag, float ymag, float zmag, float abs_pressure, float diff_pressure, float pressure_alt, float temperature, uint16_t fields_updated)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_HIGHRES_IMU_LEN];
_mav_put_uint64_t(buf, 0, time_usec);
_mav_put_float(buf, 8, xacc);
_mav_put_float(buf, 12, yacc);
_mav_put_float(buf, 16, zacc);
_mav_put_float(buf, 20, xgyro);
_mav_put_float(buf, 24, ygyro);
_mav_put_float(buf, 28, zgyro);
_mav_put_float(buf, 32, xmag);
_mav_put_float(buf, 36, ymag);
_mav_put_float(buf, 40, zmag);
_mav_put_float(buf, 44, abs_pressure);
_mav_put_float(buf, 48, diff_pressure);
_mav_put_float(buf, 52, pressure_alt);
_mav_put_float(buf, 56, temperature);
_mav_put_uint16_t(buf, 60, fields_updated);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HIGHRES_IMU_LEN);
#else
mavlink_highres_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;
packet.abs_pressure = abs_pressure;
packet.diff_pressure = diff_pressure;
packet.pressure_alt = pressure_alt;
packet.temperature = temperature;
packet.fields_updated = fields_updated;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HIGHRES_IMU_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_HIGHRES_IMU;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HIGHRES_IMU_LEN, MAVLINK_MSG_ID_HIGHRES_IMU_CRC);
#else
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HIGHRES_IMU_LEN);
#endif
}
/**
* @brief Pack a highres_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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param time_usec Timestamp (microseconds, synced to UNIX time or since system boot)
* @param xacc X acceleration (m/s^2)
* @param yacc Y acceleration (m/s^2)
* @param zacc Z acceleration (m/s^2)
* @param xgyro Angular speed around X axis (rad / sec)
* @param ygyro Angular speed around Y axis (rad / sec)
* @param zgyro Angular speed around Z axis (rad / sec)
* @param xmag X Magnetic field (Gauss)
* @param ymag Y Magnetic field (Gauss)
* @param zmag Z Magnetic field (Gauss)
* @param abs_pressure Absolute pressure in millibar
* @param diff_pressure Differential pressure in millibar
* @param pressure_alt Altitude calculated from pressure
* @param temperature Temperature in degrees celsius
* @param fields_updated Bitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_highres_imu_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint64_t time_usec,float xacc,float yacc,float zacc,float xgyro,float ygyro,float zgyro,float xmag,float ymag,float zmag,float abs_pressure,float diff_pressure,float pressure_alt,float temperature,uint16_t fields_updated)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_HIGHRES_IMU_LEN];
_mav_put_uint64_t(buf, 0, time_usec);
_mav_put_float(buf, 8, xacc);
_mav_put_float(buf, 12, yacc);
_mav_put_float(buf, 16, zacc);
_mav_put_float(buf, 20, xgyro);
_mav_put_float(buf, 24, ygyro);
_mav_put_float(buf, 28, zgyro);
_mav_put_float(buf, 32, xmag);
_mav_put_float(buf, 36, ymag);
_mav_put_float(buf, 40, zmag);
_mav_put_float(buf, 44, abs_pressure);
_mav_put_float(buf, 48, diff_pressure);
_mav_put_float(buf, 52, pressure_alt);
_mav_put_float(buf, 56, temperature);
_mav_put_uint16_t(buf, 60, fields_updated);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HIGHRES_IMU_LEN);
#else
mavlink_highres_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;
packet.abs_pressure = abs_pressure;
packet.diff_pressure = diff_pressure;
packet.pressure_alt = pressure_alt;
packet.temperature = temperature;
packet.fields_updated = fields_updated;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HIGHRES_IMU_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_HIGHRES_IMU;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HIGHRES_IMU_LEN, MAVLINK_MSG_ID_HIGHRES_IMU_CRC);
#else
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HIGHRES_IMU_LEN);
#endif
}
/**
* @brief Encode a highres_imu struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param highres_imu C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_highres_imu_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_highres_imu_t* highres_imu)
{
return mavlink_msg_highres_imu_pack(system_id, component_id, msg, highres_imu->time_usec, highres_imu->xacc, highres_imu->yacc, highres_imu->zacc, highres_imu->xgyro, highres_imu->ygyro, highres_imu->zgyro, highres_imu->xmag, highres_imu->ymag, highres_imu->zmag, highres_imu->abs_pressure, highres_imu->diff_pressure, highres_imu->pressure_alt, highres_imu->temperature, highres_imu->fields_updated);
}
/**
* @brief Encode a highres_imu struct 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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param highres_imu C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_highres_imu_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_highres_imu_t* highres_imu)
{
return mavlink_msg_highres_imu_pack_chan(system_id, component_id, chan, msg, highres_imu->time_usec, highres_imu->xacc, highres_imu->yacc, highres_imu->zacc, highres_imu->xgyro, highres_imu->ygyro, highres_imu->zgyro, highres_imu->xmag, highres_imu->ymag, highres_imu->zmag, highres_imu->abs_pressure, highres_imu->diff_pressure, highres_imu->pressure_alt, highres_imu->temperature, highres_imu->fields_updated);
}
/**
* @brief Send a highres_imu message
* @param chan MAVLink channel to send the message
*
* @param time_usec Timestamp (microseconds, synced to UNIX time or since system boot)
* @param xacc X acceleration (m/s^2)
* @param yacc Y acceleration (m/s^2)
* @param zacc Z acceleration (m/s^2)
* @param xgyro Angular speed around X axis (rad / sec)
* @param ygyro Angular speed around Y axis (rad / sec)
* @param zgyro Angular speed around Z axis (rad / sec)
* @param xmag X Magnetic field (Gauss)
* @param ymag Y Magnetic field (Gauss)
* @param zmag Z Magnetic field (Gauss)
* @param abs_pressure Absolute pressure in millibar
* @param diff_pressure Differential pressure in millibar
* @param pressure_alt Altitude calculated from pressure
* @param temperature Temperature in degrees celsius
* @param fields_updated Bitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_highres_imu_send(mavlink_channel_t chan, uint64_t time_usec, float xacc, float yacc, float zacc, float xgyro, float ygyro, float zgyro, float xmag, float ymag, float zmag, float abs_pressure, float diff_pressure, float pressure_alt, float temperature, uint16_t fields_updated)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_HIGHRES_IMU_LEN];
_mav_put_uint64_t(buf, 0, time_usec);
_mav_put_float(buf, 8, xacc);
_mav_put_float(buf, 12, yacc);
_mav_put_float(buf, 16, zacc);
_mav_put_float(buf, 20, xgyro);
_mav_put_float(buf, 24, ygyro);
_mav_put_float(buf, 28, zgyro);
_mav_put_float(buf, 32, xmag);
_mav_put_float(buf, 36, ymag);
_mav_put_float(buf, 40, zmag);
_mav_put_float(buf, 44, abs_pressure);
_mav_put_float(buf, 48, diff_pressure);
_mav_put_float(buf, 52, pressure_alt);
_mav_put_float(buf, 56, temperature);
_mav_put_uint16_t(buf, 60, fields_updated);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIGHRES_IMU, buf, MAVLINK_MSG_ID_HIGHRES_IMU_LEN, MAVLINK_MSG_ID_HIGHRES_IMU_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIGHRES_IMU, buf, MAVLINK_MSG_ID_HIGHRES_IMU_LEN);
#endif
#else
mavlink_highres_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;
packet.abs_pressure = abs_pressure;
packet.diff_pressure = diff_pressure;
packet.pressure_alt = pressure_alt;
packet.temperature = temperature;
packet.fields_updated = fields_updated;
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIGHRES_IMU, (const char *)&packet, MAVLINK_MSG_ID_HIGHRES_IMU_LEN, MAVLINK_MSG_ID_HIGHRES_IMU_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIGHRES_IMU, (const char *)&packet, MAVLINK_MSG_ID_HIGHRES_IMU_LEN);
#endif
#endif
}
#if MAVLINK_MSG_ID_HIGHRES_IMU_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This varient of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_highres_imu_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, float xacc, float yacc, float zacc, float xgyro, float ygyro, float zgyro, float xmag, float ymag, float zmag, float abs_pressure, float diff_pressure, float pressure_alt, float temperature, uint16_t fields_updated)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
_mav_put_uint64_t(buf, 0, time_usec);
_mav_put_float(buf, 8, xacc);
_mav_put_float(buf, 12, yacc);
_mav_put_float(buf, 16, zacc);
_mav_put_float(buf, 20, xgyro);
_mav_put_float(buf, 24, ygyro);
_mav_put_float(buf, 28, zgyro);
_mav_put_float(buf, 32, xmag);
_mav_put_float(buf, 36, ymag);
_mav_put_float(buf, 40, zmag);
_mav_put_float(buf, 44, abs_pressure);
_mav_put_float(buf, 48, diff_pressure);
_mav_put_float(buf, 52, pressure_alt);
_mav_put_float(buf, 56, temperature);
_mav_put_uint16_t(buf, 60, fields_updated);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIGHRES_IMU, buf, MAVLINK_MSG_ID_HIGHRES_IMU_LEN, MAVLINK_MSG_ID_HIGHRES_IMU_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIGHRES_IMU, buf, MAVLINK_MSG_ID_HIGHRES_IMU_LEN);
#endif
#else
mavlink_highres_imu_t *packet = (mavlink_highres_imu_t *)msgbuf;
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;
packet->abs_pressure = abs_pressure;
packet->diff_pressure = diff_pressure;
packet->pressure_alt = pressure_alt;
packet->temperature = temperature;
packet->fields_updated = fields_updated;
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIGHRES_IMU, (const char *)packet, MAVLINK_MSG_ID_HIGHRES_IMU_LEN, MAVLINK_MSG_ID_HIGHRES_IMU_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIGHRES_IMU, (const char *)packet, MAVLINK_MSG_ID_HIGHRES_IMU_LEN);
#endif
#endif
}
#endif
#endif
// MESSAGE HIGHRES_IMU UNPACKING
/**
* @brief Get field time_usec from highres_imu message
*
* @return Timestamp (microseconds, synced to UNIX time or since system boot)
*/
static inline uint64_t mavlink_msg_highres_imu_get_time_usec(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint64_t(msg, 0);
}
/**
* @brief Get field xacc from highres_imu message
*
* @return X acceleration (m/s^2)
*/
static inline float mavlink_msg_highres_imu_get_xacc(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 8);
}
/**
* @brief Get field yacc from highres_imu message
*
* @return Y acceleration (m/s^2)
*/
static inline float mavlink_msg_highres_imu_get_yacc(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 12);
}
/**
* @brief Get field zacc from highres_imu message
*
* @return Z acceleration (m/s^2)
*/
static inline float mavlink_msg_highres_imu_get_zacc(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 16);
}
/**
* @brief Get field xgyro from highres_imu message
*
* @return Angular speed around X axis (rad / sec)
*/
static inline float mavlink_msg_highres_imu_get_xgyro(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 20);
}
/**
* @brief Get field ygyro from highres_imu message
*
* @return Angular speed around Y axis (rad / sec)
*/
static inline float mavlink_msg_highres_imu_get_ygyro(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 24);
}
/**
* @brief Get field zgyro from highres_imu message
*
* @return Angular speed around Z axis (rad / sec)
*/
static inline float mavlink_msg_highres_imu_get_zgyro(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 28);
}
/**
* @brief Get field xmag from highres_imu message
*
* @return X Magnetic field (Gauss)
*/
static inline float mavlink_msg_highres_imu_get_xmag(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 32);
}
/**
* @brief Get field ymag from highres_imu message
*
* @return Y Magnetic field (Gauss)
*/
static inline float mavlink_msg_highres_imu_get_ymag(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 36);
}
/**
* @brief Get field zmag from highres_imu message
*
* @return Z Magnetic field (Gauss)
*/
static inline float mavlink_msg_highres_imu_get_zmag(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 40);
}
/**
* @brief Get field abs_pressure from highres_imu message
*
* @return Absolute pressure in millibar
*/
static inline float mavlink_msg_highres_imu_get_abs_pressure(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 44);
}
/**
* @brief Get field diff_pressure from highres_imu message
*
* @return Differential pressure in millibar
*/
static inline float mavlink_msg_highres_imu_get_diff_pressure(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 48);
}
/**
* @brief Get field pressure_alt from highres_imu message
*
* @return Altitude calculated from pressure
*/
static inline float mavlink_msg_highres_imu_get_pressure_alt(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 52);
}
/**
* @brief Get field temperature from highres_imu message
*
* @return Temperature in degrees celsius
*/
static inline float mavlink_msg_highres_imu_get_temperature(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 56);
}
/**
* @brief Get field fields_updated from highres_imu message
*
* @return Bitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature
*/
static inline uint16_t mavlink_msg_highres_imu_get_fields_updated(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 60);
}
/**
* @brief Decode a highres_imu message into a struct
*
* @param msg The message to decode
* @param highres_imu C-struct to decode the message contents into
*/
static inline void mavlink_msg_highres_imu_decode(const mavlink_message_t* msg, mavlink_highres_imu_t* highres_imu)
{
#if MAVLINK_NEED_BYTE_SWAP
highres_imu->time_usec = mavlink_msg_highres_imu_get_time_usec(msg);
highres_imu->xacc = mavlink_msg_highres_imu_get_xacc(msg);
highres_imu->yacc = mavlink_msg_highres_imu_get_yacc(msg);
highres_imu->zacc = mavlink_msg_highres_imu_get_zacc(msg);
highres_imu->xgyro = mavlink_msg_highres_imu_get_xgyro(msg);
highres_imu->ygyro = mavlink_msg_highres_imu_get_ygyro(msg);
highres_imu->zgyro = mavlink_msg_highres_imu_get_zgyro(msg);
highres_imu->xmag = mavlink_msg_highres_imu_get_xmag(msg);
highres_imu->ymag = mavlink_msg_highres_imu_get_ymag(msg);
highres_imu->zmag = mavlink_msg_highres_imu_get_zmag(msg);
highres_imu->abs_pressure = mavlink_msg_highres_imu_get_abs_pressure(msg);
highres_imu->diff_pressure = mavlink_msg_highres_imu_get_diff_pressure(msg);
highres_imu->pressure_alt = mavlink_msg_highres_imu_get_pressure_alt(msg);
highres_imu->temperature = mavlink_msg_highres_imu_get_temperature(msg);
highres_imu->fields_updated = mavlink_msg_highres_imu_get_fields_updated(msg);
#else
memcpy(highres_imu, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_HIGHRES_IMU_LEN);
#endif
}

View file

@ -0,0 +1,449 @@
// 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_MSG_ID_HIL_CONTROLS_CRC 63
#define MAVLINK_MSG_ID_91_CRC 63
#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[MAVLINK_MSG_ID_HIL_CONTROLS_LEN];
_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, MAVLINK_MSG_ID_HIL_CONTROLS_LEN);
#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, MAVLINK_MSG_ID_HIL_CONTROLS_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_HIL_CONTROLS;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HIL_CONTROLS_LEN, MAVLINK_MSG_ID_HIL_CONTROLS_CRC);
#else
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HIL_CONTROLS_LEN);
#endif
}
/**
* @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 will be 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[MAVLINK_MSG_ID_HIL_CONTROLS_LEN];
_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, MAVLINK_MSG_ID_HIL_CONTROLS_LEN);
#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, MAVLINK_MSG_ID_HIL_CONTROLS_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_HIL_CONTROLS;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HIL_CONTROLS_LEN, MAVLINK_MSG_ID_HIL_CONTROLS_CRC);
#else
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HIL_CONTROLS_LEN);
#endif
}
/**
* @brief Encode a hil_controls struct
*
* @param system_id ID of this 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 Encode a hil_controls struct 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 will be sent over
* @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_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_hil_controls_t* hil_controls)
{
return mavlink_msg_hil_controls_pack_chan(system_id, component_id, chan, 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[MAVLINK_MSG_ID_HIL_CONTROLS_LEN];
_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);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_CONTROLS, buf, MAVLINK_MSG_ID_HIL_CONTROLS_LEN, MAVLINK_MSG_ID_HIL_CONTROLS_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_CONTROLS, buf, MAVLINK_MSG_ID_HIL_CONTROLS_LEN);
#endif
#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;
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_CONTROLS, (const char *)&packet, MAVLINK_MSG_ID_HIL_CONTROLS_LEN, MAVLINK_MSG_ID_HIL_CONTROLS_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_CONTROLS, (const char *)&packet, MAVLINK_MSG_ID_HIL_CONTROLS_LEN);
#endif
#endif
}
#if MAVLINK_MSG_ID_HIL_CONTROLS_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This varient of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_hil_controls_send_buf(mavlink_message_t *msgbuf, 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 = (char *)msgbuf;
_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);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_CONTROLS, buf, MAVLINK_MSG_ID_HIL_CONTROLS_LEN, MAVLINK_MSG_ID_HIL_CONTROLS_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_CONTROLS, buf, MAVLINK_MSG_ID_HIL_CONTROLS_LEN);
#endif
#else
mavlink_hil_controls_t *packet = (mavlink_hil_controls_t *)msgbuf;
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;
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_CONTROLS, (const char *)packet, MAVLINK_MSG_ID_HIL_CONTROLS_LEN, MAVLINK_MSG_ID_HIL_CONTROLS_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_CONTROLS, (const char *)packet, MAVLINK_MSG_ID_HIL_CONTROLS_LEN);
#endif
#endif
}
#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), MAVLINK_MSG_ID_HIL_CONTROLS_LEN);
#endif
}

View file

@ -0,0 +1,497 @@
// MESSAGE HIL_GPS PACKING
#define MAVLINK_MSG_ID_HIL_GPS 113
typedef struct __mavlink_hil_gps_t
{
uint64_t time_usec; ///< Timestamp (microseconds since UNIX epoch or microseconds since system boot)
int32_t lat; ///< Latitude (WGS84), in degrees * 1E7
int32_t lon; ///< Longitude (WGS84), in degrees * 1E7
int32_t alt; ///< Altitude (AMSL, not WGS84), in meters * 1000 (positive for up)
uint16_t eph; ///< GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535
uint16_t epv; ///< GPS VDOP vertical 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
int16_t vn; ///< GPS velocity in cm/s in NORTH direction in earth-fixed NED frame
int16_t ve; ///< GPS velocity in cm/s in EAST direction in earth-fixed NED frame
int16_t vd; ///< GPS velocity in cm/s in DOWN direction in earth-fixed NED frame
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_hil_gps_t;
#define MAVLINK_MSG_ID_HIL_GPS_LEN 36
#define MAVLINK_MSG_ID_113_LEN 36
#define MAVLINK_MSG_ID_HIL_GPS_CRC 124
#define MAVLINK_MSG_ID_113_CRC 124
#define MAVLINK_MESSAGE_INFO_HIL_GPS { \
"HIL_GPS", \
13, \
{ { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_hil_gps_t, time_usec) }, \
{ "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_hil_gps_t, lat) }, \
{ "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_hil_gps_t, lon) }, \
{ "alt", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_hil_gps_t, alt) }, \
{ "eph", NULL, MAVLINK_TYPE_UINT16_T, 0, 20, offsetof(mavlink_hil_gps_t, eph) }, \
{ "epv", NULL, MAVLINK_TYPE_UINT16_T, 0, 22, offsetof(mavlink_hil_gps_t, epv) }, \
{ "vel", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_hil_gps_t, vel) }, \
{ "vn", NULL, MAVLINK_TYPE_INT16_T, 0, 26, offsetof(mavlink_hil_gps_t, vn) }, \
{ "ve", NULL, MAVLINK_TYPE_INT16_T, 0, 28, offsetof(mavlink_hil_gps_t, ve) }, \
{ "vd", NULL, MAVLINK_TYPE_INT16_T, 0, 30, offsetof(mavlink_hil_gps_t, vd) }, \
{ "cog", NULL, MAVLINK_TYPE_UINT16_T, 0, 32, offsetof(mavlink_hil_gps_t, cog) }, \
{ "fix_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_hil_gps_t, fix_type) }, \
{ "satellites_visible", NULL, MAVLINK_TYPE_UINT8_T, 0, 35, offsetof(mavlink_hil_gps_t, satellites_visible) }, \
} \
}
/**
* @brief Pack a hil_gps message
* @param system_id ID of this 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 (WGS84), in degrees * 1E7
* @param lon Longitude (WGS84), in degrees * 1E7
* @param alt Altitude (AMSL, not WGS84), in meters * 1000 (positive for up)
* @param eph GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535
* @param epv GPS VDOP vertical 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 vn GPS velocity in cm/s in NORTH direction in earth-fixed NED frame
* @param ve GPS velocity in cm/s in EAST direction in earth-fixed NED frame
* @param vd GPS velocity in cm/s in DOWN direction in earth-fixed NED frame
* @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_hil_gps_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, int16_t vn, int16_t ve, int16_t vd, uint16_t cog, uint8_t satellites_visible)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_HIL_GPS_LEN];
_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_int16_t(buf, 26, vn);
_mav_put_int16_t(buf, 28, ve);
_mav_put_int16_t(buf, 30, vd);
_mav_put_uint16_t(buf, 32, cog);
_mav_put_uint8_t(buf, 34, fix_type);
_mav_put_uint8_t(buf, 35, satellites_visible);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HIL_GPS_LEN);
#else
mavlink_hil_gps_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.vn = vn;
packet.ve = ve;
packet.vd = vd;
packet.cog = cog;
packet.fix_type = fix_type;
packet.satellites_visible = satellites_visible;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HIL_GPS_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_HIL_GPS;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HIL_GPS_LEN, MAVLINK_MSG_ID_HIL_GPS_CRC);
#else
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HIL_GPS_LEN);
#endif
}
/**
* @brief Pack a hil_gps 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 will be 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 (WGS84), in degrees * 1E7
* @param lon Longitude (WGS84), in degrees * 1E7
* @param alt Altitude (AMSL, not WGS84), in meters * 1000 (positive for up)
* @param eph GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535
* @param epv GPS VDOP vertical 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 vn GPS velocity in cm/s in NORTH direction in earth-fixed NED frame
* @param ve GPS velocity in cm/s in EAST direction in earth-fixed NED frame
* @param vd GPS velocity in cm/s in DOWN direction in earth-fixed NED frame
* @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_hil_gps_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,int16_t vn,int16_t ve,int16_t vd,uint16_t cog,uint8_t satellites_visible)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_HIL_GPS_LEN];
_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_int16_t(buf, 26, vn);
_mav_put_int16_t(buf, 28, ve);
_mav_put_int16_t(buf, 30, vd);
_mav_put_uint16_t(buf, 32, cog);
_mav_put_uint8_t(buf, 34, fix_type);
_mav_put_uint8_t(buf, 35, satellites_visible);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HIL_GPS_LEN);
#else
mavlink_hil_gps_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.vn = vn;
packet.ve = ve;
packet.vd = vd;
packet.cog = cog;
packet.fix_type = fix_type;
packet.satellites_visible = satellites_visible;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HIL_GPS_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_HIL_GPS;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HIL_GPS_LEN, MAVLINK_MSG_ID_HIL_GPS_CRC);
#else
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HIL_GPS_LEN);
#endif
}
/**
* @brief Encode a hil_gps struct
*
* @param system_id ID of this 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_gps C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_hil_gps_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_hil_gps_t* hil_gps)
{
return mavlink_msg_hil_gps_pack(system_id, component_id, msg, hil_gps->time_usec, hil_gps->fix_type, hil_gps->lat, hil_gps->lon, hil_gps->alt, hil_gps->eph, hil_gps->epv, hil_gps->vel, hil_gps->vn, hil_gps->ve, hil_gps->vd, hil_gps->cog, hil_gps->satellites_visible);
}
/**
* @brief Encode a hil_gps struct 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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param hil_gps C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_hil_gps_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_hil_gps_t* hil_gps)
{
return mavlink_msg_hil_gps_pack_chan(system_id, component_id, chan, msg, hil_gps->time_usec, hil_gps->fix_type, hil_gps->lat, hil_gps->lon, hil_gps->alt, hil_gps->eph, hil_gps->epv, hil_gps->vel, hil_gps->vn, hil_gps->ve, hil_gps->vd, hil_gps->cog, hil_gps->satellites_visible);
}
/**
* @brief Send a hil_gps 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 (WGS84), in degrees * 1E7
* @param lon Longitude (WGS84), in degrees * 1E7
* @param alt Altitude (AMSL, not WGS84), in meters * 1000 (positive for up)
* @param eph GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535
* @param epv GPS VDOP vertical 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 vn GPS velocity in cm/s in NORTH direction in earth-fixed NED frame
* @param ve GPS velocity in cm/s in EAST direction in earth-fixed NED frame
* @param vd GPS velocity in cm/s in DOWN direction in earth-fixed NED frame
* @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_hil_gps_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, int16_t vn, int16_t ve, int16_t vd, uint16_t cog, uint8_t satellites_visible)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_HIL_GPS_LEN];
_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_int16_t(buf, 26, vn);
_mav_put_int16_t(buf, 28, ve);
_mav_put_int16_t(buf, 30, vd);
_mav_put_uint16_t(buf, 32, cog);
_mav_put_uint8_t(buf, 34, fix_type);
_mav_put_uint8_t(buf, 35, satellites_visible);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_GPS, buf, MAVLINK_MSG_ID_HIL_GPS_LEN, MAVLINK_MSG_ID_HIL_GPS_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_GPS, buf, MAVLINK_MSG_ID_HIL_GPS_LEN);
#endif
#else
mavlink_hil_gps_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.vn = vn;
packet.ve = ve;
packet.vd = vd;
packet.cog = cog;
packet.fix_type = fix_type;
packet.satellites_visible = satellites_visible;
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_GPS, (const char *)&packet, MAVLINK_MSG_ID_HIL_GPS_LEN, MAVLINK_MSG_ID_HIL_GPS_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_GPS, (const char *)&packet, MAVLINK_MSG_ID_HIL_GPS_LEN);
#endif
#endif
}
#if MAVLINK_MSG_ID_HIL_GPS_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This varient of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_hil_gps_send_buf(mavlink_message_t *msgbuf, 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, int16_t vn, int16_t ve, int16_t vd, uint16_t cog, uint8_t satellites_visible)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
_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_int16_t(buf, 26, vn);
_mav_put_int16_t(buf, 28, ve);
_mav_put_int16_t(buf, 30, vd);
_mav_put_uint16_t(buf, 32, cog);
_mav_put_uint8_t(buf, 34, fix_type);
_mav_put_uint8_t(buf, 35, satellites_visible);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_GPS, buf, MAVLINK_MSG_ID_HIL_GPS_LEN, MAVLINK_MSG_ID_HIL_GPS_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_GPS, buf, MAVLINK_MSG_ID_HIL_GPS_LEN);
#endif
#else
mavlink_hil_gps_t *packet = (mavlink_hil_gps_t *)msgbuf;
packet->time_usec = time_usec;
packet->lat = lat;
packet->lon = lon;
packet->alt = alt;
packet->eph = eph;
packet->epv = epv;
packet->vel = vel;
packet->vn = vn;
packet->ve = ve;
packet->vd = vd;
packet->cog = cog;
packet->fix_type = fix_type;
packet->satellites_visible = satellites_visible;
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_GPS, (const char *)packet, MAVLINK_MSG_ID_HIL_GPS_LEN, MAVLINK_MSG_ID_HIL_GPS_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_GPS, (const char *)packet, MAVLINK_MSG_ID_HIL_GPS_LEN);
#endif
#endif
}
#endif
#endif
// MESSAGE HIL_GPS UNPACKING
/**
* @brief Get field time_usec from hil_gps message
*
* @return Timestamp (microseconds since UNIX epoch or microseconds since system boot)
*/
static inline uint64_t mavlink_msg_hil_gps_get_time_usec(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint64_t(msg, 0);
}
/**
* @brief Get field fix_type from hil_gps 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_hil_gps_get_fix_type(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 34);
}
/**
* @brief Get field lat from hil_gps message
*
* @return Latitude (WGS84), in degrees * 1E7
*/
static inline int32_t mavlink_msg_hil_gps_get_lat(const mavlink_message_t* msg)
{
return _MAV_RETURN_int32_t(msg, 8);
}
/**
* @brief Get field lon from hil_gps message
*
* @return Longitude (WGS84), in degrees * 1E7
*/
static inline int32_t mavlink_msg_hil_gps_get_lon(const mavlink_message_t* msg)
{
return _MAV_RETURN_int32_t(msg, 12);
}
/**
* @brief Get field alt from hil_gps message
*
* @return Altitude (AMSL, not WGS84), in meters * 1000 (positive for up)
*/
static inline int32_t mavlink_msg_hil_gps_get_alt(const mavlink_message_t* msg)
{
return _MAV_RETURN_int32_t(msg, 16);
}
/**
* @brief Get field eph from hil_gps message
*
* @return GPS HDOP horizontal dilution of position in cm (m*100). If unknown, set to: 65535
*/
static inline uint16_t mavlink_msg_hil_gps_get_eph(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 20);
}
/**
* @brief Get field epv from hil_gps message
*
* @return GPS VDOP vertical dilution of position in cm (m*100). If unknown, set to: 65535
*/
static inline uint16_t mavlink_msg_hil_gps_get_epv(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 22);
}
/**
* @brief Get field vel from hil_gps message
*
* @return GPS ground speed (m/s * 100). If unknown, set to: 65535
*/
static inline uint16_t mavlink_msg_hil_gps_get_vel(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 24);
}
/**
* @brief Get field vn from hil_gps message
*
* @return GPS velocity in cm/s in NORTH direction in earth-fixed NED frame
*/
static inline int16_t mavlink_msg_hil_gps_get_vn(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 26);
}
/**
* @brief Get field ve from hil_gps message
*
* @return GPS velocity in cm/s in EAST direction in earth-fixed NED frame
*/
static inline int16_t mavlink_msg_hil_gps_get_ve(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 28);
}
/**
* @brief Get field vd from hil_gps message
*
* @return GPS velocity in cm/s in DOWN direction in earth-fixed NED frame
*/
static inline int16_t mavlink_msg_hil_gps_get_vd(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 30);
}
/**
* @brief Get field cog from hil_gps 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_hil_gps_get_cog(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 32);
}
/**
* @brief Get field satellites_visible from hil_gps message
*
* @return Number of satellites visible. If unknown, set to 255
*/
static inline uint8_t mavlink_msg_hil_gps_get_satellites_visible(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 35);
}
/**
* @brief Decode a hil_gps message into a struct
*
* @param msg The message to decode
* @param hil_gps C-struct to decode the message contents into
*/
static inline void mavlink_msg_hil_gps_decode(const mavlink_message_t* msg, mavlink_hil_gps_t* hil_gps)
{
#if MAVLINK_NEED_BYTE_SWAP
hil_gps->time_usec = mavlink_msg_hil_gps_get_time_usec(msg);
hil_gps->lat = mavlink_msg_hil_gps_get_lat(msg);
hil_gps->lon = mavlink_msg_hil_gps_get_lon(msg);
hil_gps->alt = mavlink_msg_hil_gps_get_alt(msg);
hil_gps->eph = mavlink_msg_hil_gps_get_eph(msg);
hil_gps->epv = mavlink_msg_hil_gps_get_epv(msg);
hil_gps->vel = mavlink_msg_hil_gps_get_vel(msg);
hil_gps->vn = mavlink_msg_hil_gps_get_vn(msg);
hil_gps->ve = mavlink_msg_hil_gps_get_ve(msg);
hil_gps->vd = mavlink_msg_hil_gps_get_vd(msg);
hil_gps->cog = mavlink_msg_hil_gps_get_cog(msg);
hil_gps->fix_type = mavlink_msg_hil_gps_get_fix_type(msg);
hil_gps->satellites_visible = mavlink_msg_hil_gps_get_satellites_visible(msg);
#else
memcpy(hil_gps, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_HIL_GPS_LEN);
#endif
}

View file

@ -0,0 +1,473 @@
// MESSAGE HIL_OPTICAL_FLOW PACKING
#define MAVLINK_MSG_ID_HIL_OPTICAL_FLOW 114
typedef struct __mavlink_hil_optical_flow_t
{
uint64_t time_usec; ///< Timestamp (microseconds, synced to UNIX time or since system boot)
uint32_t integration_time_us; ///< Integration time in microseconds. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the.
float integrated_x; ///< Flow in radians around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.)
float integrated_y; ///< Flow in radians around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.)
float integrated_xgyro; ///< RH rotation around X axis (rad)
float integrated_ygyro; ///< RH rotation around Y axis (rad)
float integrated_zgyro; ///< RH rotation around Z axis (rad)
uint32_t time_delta_distance_us; ///< Time in microseconds since the distance was sampled.
float distance; ///< Distance to the center of the flow field in meters. Positive value (including zero): distance known. Negative value: Unknown distance.
int16_t temperature; ///< Temperature * 100 in centi-degrees Celsius
uint8_t sensor_id; ///< Sensor ID
uint8_t quality; ///< Optical flow quality / confidence. 0: no valid flow, 255: maximum quality
} mavlink_hil_optical_flow_t;
#define MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN 44
#define MAVLINK_MSG_ID_114_LEN 44
#define MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_CRC 237
#define MAVLINK_MSG_ID_114_CRC 237
#define MAVLINK_MESSAGE_INFO_HIL_OPTICAL_FLOW { \
"HIL_OPTICAL_FLOW", \
12, \
{ { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_hil_optical_flow_t, time_usec) }, \
{ "integration_time_us", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_hil_optical_flow_t, integration_time_us) }, \
{ "integrated_x", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_hil_optical_flow_t, integrated_x) }, \
{ "integrated_y", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_hil_optical_flow_t, integrated_y) }, \
{ "integrated_xgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_hil_optical_flow_t, integrated_xgyro) }, \
{ "integrated_ygyro", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_hil_optical_flow_t, integrated_ygyro) }, \
{ "integrated_zgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_hil_optical_flow_t, integrated_zgyro) }, \
{ "time_delta_distance_us", NULL, MAVLINK_TYPE_UINT32_T, 0, 32, offsetof(mavlink_hil_optical_flow_t, time_delta_distance_us) }, \
{ "distance", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_hil_optical_flow_t, distance) }, \
{ "temperature", NULL, MAVLINK_TYPE_INT16_T, 0, 40, offsetof(mavlink_hil_optical_flow_t, temperature) }, \
{ "sensor_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 42, offsetof(mavlink_hil_optical_flow_t, sensor_id) }, \
{ "quality", NULL, MAVLINK_TYPE_UINT8_T, 0, 43, offsetof(mavlink_hil_optical_flow_t, quality) }, \
} \
}
/**
* @brief Pack a hil_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 (microseconds, synced to UNIX time or since system boot)
* @param sensor_id Sensor ID
* @param integration_time_us Integration time in microseconds. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the.
* @param integrated_x Flow in radians around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.)
* @param integrated_y Flow in radians around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.)
* @param integrated_xgyro RH rotation around X axis (rad)
* @param integrated_ygyro RH rotation around Y axis (rad)
* @param integrated_zgyro RH rotation around Z axis (rad)
* @param temperature Temperature * 100 in centi-degrees Celsius
* @param quality Optical flow quality / confidence. 0: no valid flow, 255: maximum quality
* @param time_delta_distance_us Time in microseconds since the distance was sampled.
* @param distance Distance to the center of the flow field in meters. Positive value (including zero): distance known. Negative value: Unknown distance.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_hil_optical_flow_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint64_t time_usec, uint8_t sensor_id, uint32_t integration_time_us, float integrated_x, float integrated_y, float integrated_xgyro, float integrated_ygyro, float integrated_zgyro, int16_t temperature, uint8_t quality, uint32_t time_delta_distance_us, float distance)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN];
_mav_put_uint64_t(buf, 0, time_usec);
_mav_put_uint32_t(buf, 8, integration_time_us);
_mav_put_float(buf, 12, integrated_x);
_mav_put_float(buf, 16, integrated_y);
_mav_put_float(buf, 20, integrated_xgyro);
_mav_put_float(buf, 24, integrated_ygyro);
_mav_put_float(buf, 28, integrated_zgyro);
_mav_put_uint32_t(buf, 32, time_delta_distance_us);
_mav_put_float(buf, 36, distance);
_mav_put_int16_t(buf, 40, temperature);
_mav_put_uint8_t(buf, 42, sensor_id);
_mav_put_uint8_t(buf, 43, quality);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN);
#else
mavlink_hil_optical_flow_t packet;
packet.time_usec = time_usec;
packet.integration_time_us = integration_time_us;
packet.integrated_x = integrated_x;
packet.integrated_y = integrated_y;
packet.integrated_xgyro = integrated_xgyro;
packet.integrated_ygyro = integrated_ygyro;
packet.integrated_zgyro = integrated_zgyro;
packet.time_delta_distance_us = time_delta_distance_us;
packet.distance = distance;
packet.temperature = temperature;
packet.sensor_id = sensor_id;
packet.quality = quality;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_HIL_OPTICAL_FLOW;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_CRC);
#else
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN);
#endif
}
/**
* @brief Pack a hil_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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param time_usec Timestamp (microseconds, synced to UNIX time or since system boot)
* @param sensor_id Sensor ID
* @param integration_time_us Integration time in microseconds. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the.
* @param integrated_x Flow in radians around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.)
* @param integrated_y Flow in radians around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.)
* @param integrated_xgyro RH rotation around X axis (rad)
* @param integrated_ygyro RH rotation around Y axis (rad)
* @param integrated_zgyro RH rotation around Z axis (rad)
* @param temperature Temperature * 100 in centi-degrees Celsius
* @param quality Optical flow quality / confidence. 0: no valid flow, 255: maximum quality
* @param time_delta_distance_us Time in microseconds since the distance was sampled.
* @param distance Distance to the center of the flow field in meters. Positive value (including zero): distance known. Negative value: Unknown distance.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_hil_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,uint32_t integration_time_us,float integrated_x,float integrated_y,float integrated_xgyro,float integrated_ygyro,float integrated_zgyro,int16_t temperature,uint8_t quality,uint32_t time_delta_distance_us,float distance)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN];
_mav_put_uint64_t(buf, 0, time_usec);
_mav_put_uint32_t(buf, 8, integration_time_us);
_mav_put_float(buf, 12, integrated_x);
_mav_put_float(buf, 16, integrated_y);
_mav_put_float(buf, 20, integrated_xgyro);
_mav_put_float(buf, 24, integrated_ygyro);
_mav_put_float(buf, 28, integrated_zgyro);
_mav_put_uint32_t(buf, 32, time_delta_distance_us);
_mav_put_float(buf, 36, distance);
_mav_put_int16_t(buf, 40, temperature);
_mav_put_uint8_t(buf, 42, sensor_id);
_mav_put_uint8_t(buf, 43, quality);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN);
#else
mavlink_hil_optical_flow_t packet;
packet.time_usec = time_usec;
packet.integration_time_us = integration_time_us;
packet.integrated_x = integrated_x;
packet.integrated_y = integrated_y;
packet.integrated_xgyro = integrated_xgyro;
packet.integrated_ygyro = integrated_ygyro;
packet.integrated_zgyro = integrated_zgyro;
packet.time_delta_distance_us = time_delta_distance_us;
packet.distance = distance;
packet.temperature = temperature;
packet.sensor_id = sensor_id;
packet.quality = quality;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_HIL_OPTICAL_FLOW;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_CRC);
#else
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN);
#endif
}
/**
* @brief Encode a hil_optical_flow struct
*
* @param system_id ID of this 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_optical_flow C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_hil_optical_flow_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_hil_optical_flow_t* hil_optical_flow)
{
return mavlink_msg_hil_optical_flow_pack(system_id, component_id, msg, hil_optical_flow->time_usec, hil_optical_flow->sensor_id, hil_optical_flow->integration_time_us, hil_optical_flow->integrated_x, hil_optical_flow->integrated_y, hil_optical_flow->integrated_xgyro, hil_optical_flow->integrated_ygyro, hil_optical_flow->integrated_zgyro, hil_optical_flow->temperature, hil_optical_flow->quality, hil_optical_flow->time_delta_distance_us, hil_optical_flow->distance);
}
/**
* @brief Encode a hil_optical_flow struct 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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param hil_optical_flow C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_hil_optical_flow_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_hil_optical_flow_t* hil_optical_flow)
{
return mavlink_msg_hil_optical_flow_pack_chan(system_id, component_id, chan, msg, hil_optical_flow->time_usec, hil_optical_flow->sensor_id, hil_optical_flow->integration_time_us, hil_optical_flow->integrated_x, hil_optical_flow->integrated_y, hil_optical_flow->integrated_xgyro, hil_optical_flow->integrated_ygyro, hil_optical_flow->integrated_zgyro, hil_optical_flow->temperature, hil_optical_flow->quality, hil_optical_flow->time_delta_distance_us, hil_optical_flow->distance);
}
/**
* @brief Send a hil_optical_flow message
* @param chan MAVLink channel to send the message
*
* @param time_usec Timestamp (microseconds, synced to UNIX time or since system boot)
* @param sensor_id Sensor ID
* @param integration_time_us Integration time in microseconds. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the.
* @param integrated_x Flow in radians around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.)
* @param integrated_y Flow in radians around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.)
* @param integrated_xgyro RH rotation around X axis (rad)
* @param integrated_ygyro RH rotation around Y axis (rad)
* @param integrated_zgyro RH rotation around Z axis (rad)
* @param temperature Temperature * 100 in centi-degrees Celsius
* @param quality Optical flow quality / confidence. 0: no valid flow, 255: maximum quality
* @param time_delta_distance_us Time in microseconds since the distance was sampled.
* @param distance Distance to the center of the flow field in meters. Positive value (including zero): distance known. Negative value: Unknown distance.
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_hil_optical_flow_send(mavlink_channel_t chan, uint64_t time_usec, uint8_t sensor_id, uint32_t integration_time_us, float integrated_x, float integrated_y, float integrated_xgyro, float integrated_ygyro, float integrated_zgyro, int16_t temperature, uint8_t quality, uint32_t time_delta_distance_us, float distance)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN];
_mav_put_uint64_t(buf, 0, time_usec);
_mav_put_uint32_t(buf, 8, integration_time_us);
_mav_put_float(buf, 12, integrated_x);
_mav_put_float(buf, 16, integrated_y);
_mav_put_float(buf, 20, integrated_xgyro);
_mav_put_float(buf, 24, integrated_ygyro);
_mav_put_float(buf, 28, integrated_zgyro);
_mav_put_uint32_t(buf, 32, time_delta_distance_us);
_mav_put_float(buf, 36, distance);
_mav_put_int16_t(buf, 40, temperature);
_mav_put_uint8_t(buf, 42, sensor_id);
_mav_put_uint8_t(buf, 43, quality);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW, buf, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW, buf, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN);
#endif
#else
mavlink_hil_optical_flow_t packet;
packet.time_usec = time_usec;
packet.integration_time_us = integration_time_us;
packet.integrated_x = integrated_x;
packet.integrated_y = integrated_y;
packet.integrated_xgyro = integrated_xgyro;
packet.integrated_ygyro = integrated_ygyro;
packet.integrated_zgyro = integrated_zgyro;
packet.time_delta_distance_us = time_delta_distance_us;
packet.distance = distance;
packet.temperature = temperature;
packet.sensor_id = sensor_id;
packet.quality = quality;
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW, (const char *)&packet, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW, (const char *)&packet, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN);
#endif
#endif
}
#if MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This varient of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_hil_optical_flow_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, uint8_t sensor_id, uint32_t integration_time_us, float integrated_x, float integrated_y, float integrated_xgyro, float integrated_ygyro, float integrated_zgyro, int16_t temperature, uint8_t quality, uint32_t time_delta_distance_us, float distance)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
_mav_put_uint64_t(buf, 0, time_usec);
_mav_put_uint32_t(buf, 8, integration_time_us);
_mav_put_float(buf, 12, integrated_x);
_mav_put_float(buf, 16, integrated_y);
_mav_put_float(buf, 20, integrated_xgyro);
_mav_put_float(buf, 24, integrated_ygyro);
_mav_put_float(buf, 28, integrated_zgyro);
_mav_put_uint32_t(buf, 32, time_delta_distance_us);
_mav_put_float(buf, 36, distance);
_mav_put_int16_t(buf, 40, temperature);
_mav_put_uint8_t(buf, 42, sensor_id);
_mav_put_uint8_t(buf, 43, quality);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW, buf, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW, buf, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN);
#endif
#else
mavlink_hil_optical_flow_t *packet = (mavlink_hil_optical_flow_t *)msgbuf;
packet->time_usec = time_usec;
packet->integration_time_us = integration_time_us;
packet->integrated_x = integrated_x;
packet->integrated_y = integrated_y;
packet->integrated_xgyro = integrated_xgyro;
packet->integrated_ygyro = integrated_ygyro;
packet->integrated_zgyro = integrated_zgyro;
packet->time_delta_distance_us = time_delta_distance_us;
packet->distance = distance;
packet->temperature = temperature;
packet->sensor_id = sensor_id;
packet->quality = quality;
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW, (const char *)packet, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW, (const char *)packet, MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN);
#endif
#endif
}
#endif
#endif
// MESSAGE HIL_OPTICAL_FLOW UNPACKING
/**
* @brief Get field time_usec from hil_optical_flow message
*
* @return Timestamp (microseconds, synced to UNIX time or since system boot)
*/
static inline uint64_t mavlink_msg_hil_optical_flow_get_time_usec(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint64_t(msg, 0);
}
/**
* @brief Get field sensor_id from hil_optical_flow message
*
* @return Sensor ID
*/
static inline uint8_t mavlink_msg_hil_optical_flow_get_sensor_id(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 42);
}
/**
* @brief Get field integration_time_us from hil_optical_flow message
*
* @return Integration time in microseconds. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the.
*/
static inline uint32_t mavlink_msg_hil_optical_flow_get_integration_time_us(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint32_t(msg, 8);
}
/**
* @brief Get field integrated_x from hil_optical_flow message
*
* @return Flow in radians around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.)
*/
static inline float mavlink_msg_hil_optical_flow_get_integrated_x(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 12);
}
/**
* @brief Get field integrated_y from hil_optical_flow message
*
* @return Flow in radians around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.)
*/
static inline float mavlink_msg_hil_optical_flow_get_integrated_y(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 16);
}
/**
* @brief Get field integrated_xgyro from hil_optical_flow message
*
* @return RH rotation around X axis (rad)
*/
static inline float mavlink_msg_hil_optical_flow_get_integrated_xgyro(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 20);
}
/**
* @brief Get field integrated_ygyro from hil_optical_flow message
*
* @return RH rotation around Y axis (rad)
*/
static inline float mavlink_msg_hil_optical_flow_get_integrated_ygyro(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 24);
}
/**
* @brief Get field integrated_zgyro from hil_optical_flow message
*
* @return RH rotation around Z axis (rad)
*/
static inline float mavlink_msg_hil_optical_flow_get_integrated_zgyro(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 28);
}
/**
* @brief Get field temperature from hil_optical_flow message
*
* @return Temperature * 100 in centi-degrees Celsius
*/
static inline int16_t mavlink_msg_hil_optical_flow_get_temperature(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 40);
}
/**
* @brief Get field quality from hil_optical_flow message
*
* @return Optical flow quality / confidence. 0: no valid flow, 255: maximum quality
*/
static inline uint8_t mavlink_msg_hil_optical_flow_get_quality(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 43);
}
/**
* @brief Get field time_delta_distance_us from hil_optical_flow message
*
* @return Time in microseconds since the distance was sampled.
*/
static inline uint32_t mavlink_msg_hil_optical_flow_get_time_delta_distance_us(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint32_t(msg, 32);
}
/**
* @brief Get field distance from hil_optical_flow message
*
* @return Distance to the center of the flow field in meters. Positive value (including zero): distance known. Negative value: Unknown distance.
*/
static inline float mavlink_msg_hil_optical_flow_get_distance(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 36);
}
/**
* @brief Decode a hil_optical_flow message into a struct
*
* @param msg The message to decode
* @param hil_optical_flow C-struct to decode the message contents into
*/
static inline void mavlink_msg_hil_optical_flow_decode(const mavlink_message_t* msg, mavlink_hil_optical_flow_t* hil_optical_flow)
{
#if MAVLINK_NEED_BYTE_SWAP
hil_optical_flow->time_usec = mavlink_msg_hil_optical_flow_get_time_usec(msg);
hil_optical_flow->integration_time_us = mavlink_msg_hil_optical_flow_get_integration_time_us(msg);
hil_optical_flow->integrated_x = mavlink_msg_hil_optical_flow_get_integrated_x(msg);
hil_optical_flow->integrated_y = mavlink_msg_hil_optical_flow_get_integrated_y(msg);
hil_optical_flow->integrated_xgyro = mavlink_msg_hil_optical_flow_get_integrated_xgyro(msg);
hil_optical_flow->integrated_ygyro = mavlink_msg_hil_optical_flow_get_integrated_ygyro(msg);
hil_optical_flow->integrated_zgyro = mavlink_msg_hil_optical_flow_get_integrated_zgyro(msg);
hil_optical_flow->time_delta_distance_us = mavlink_msg_hil_optical_flow_get_time_delta_distance_us(msg);
hil_optical_flow->distance = mavlink_msg_hil_optical_flow_get_distance(msg);
hil_optical_flow->temperature = mavlink_msg_hil_optical_flow_get_temperature(msg);
hil_optical_flow->sensor_id = mavlink_msg_hil_optical_flow_get_sensor_id(msg);
hil_optical_flow->quality = mavlink_msg_hil_optical_flow_get_quality(msg);
#else
memcpy(hil_optical_flow, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_HIL_OPTICAL_FLOW_LEN);
#endif
}

View file

@ -0,0 +1,521 @@
// 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_MSG_ID_HIL_RC_INPUTS_RAW_CRC 54
#define MAVLINK_MSG_ID_92_CRC 54
#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[MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_LEN];
_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, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_LEN);
#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, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_LEN, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_CRC);
#else
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_LEN);
#endif
}
/**
* @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 will be 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[MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_LEN];
_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, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_LEN);
#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, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_LEN, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_CRC);
#else
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_LEN);
#endif
}
/**
* @brief Encode a hil_rc_inputs_raw struct
*
* @param system_id ID of this 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 Encode a hil_rc_inputs_raw struct 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 will be sent over
* @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_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_hil_rc_inputs_raw_t* hil_rc_inputs_raw)
{
return mavlink_msg_hil_rc_inputs_raw_pack_chan(system_id, component_id, chan, 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[MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_LEN];
_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);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW, buf, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_LEN, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW, buf, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_LEN);
#endif
#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;
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW, (const char *)&packet, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_LEN, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW, (const char *)&packet, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_LEN);
#endif
#endif
}
#if MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This varient of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_hil_rc_inputs_raw_send_buf(mavlink_message_t *msgbuf, 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 = (char *)msgbuf;
_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);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW, buf, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_LEN, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW, buf, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_LEN);
#endif
#else
mavlink_hil_rc_inputs_raw_t *packet = (mavlink_hil_rc_inputs_raw_t *)msgbuf;
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;
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW, (const char *)packet, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_LEN, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW, (const char *)packet, MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_LEN);
#endif
#endif
}
#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), MAVLINK_MSG_ID_HIL_RC_INPUTS_RAW_LEN);
#endif
}

View file

@ -0,0 +1,545 @@
// MESSAGE HIL_SENSOR PACKING
#define MAVLINK_MSG_ID_HIL_SENSOR 107
typedef struct __mavlink_hil_sensor_t
{
uint64_t time_usec; ///< Timestamp (microseconds, synced to UNIX time or since system boot)
float xacc; ///< X acceleration (m/s^2)
float yacc; ///< Y acceleration (m/s^2)
float zacc; ///< Z acceleration (m/s^2)
float xgyro; ///< Angular speed around X axis in body frame (rad / sec)
float ygyro; ///< Angular speed around Y axis in body frame (rad / sec)
float zgyro; ///< Angular speed around Z axis in body frame (rad / sec)
float xmag; ///< X Magnetic field (Gauss)
float ymag; ///< Y Magnetic field (Gauss)
float zmag; ///< Z Magnetic field (Gauss)
float abs_pressure; ///< Absolute pressure in millibar
float diff_pressure; ///< Differential pressure (airspeed) in millibar
float pressure_alt; ///< Altitude calculated from pressure
float temperature; ///< Temperature in degrees celsius
uint32_t fields_updated; ///< Bitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature
} mavlink_hil_sensor_t;
#define MAVLINK_MSG_ID_HIL_SENSOR_LEN 64
#define MAVLINK_MSG_ID_107_LEN 64
#define MAVLINK_MSG_ID_HIL_SENSOR_CRC 108
#define MAVLINK_MSG_ID_107_CRC 108
#define MAVLINK_MESSAGE_INFO_HIL_SENSOR { \
"HIL_SENSOR", \
15, \
{ { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_hil_sensor_t, time_usec) }, \
{ "xacc", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_hil_sensor_t, xacc) }, \
{ "yacc", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_hil_sensor_t, yacc) }, \
{ "zacc", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_hil_sensor_t, zacc) }, \
{ "xgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_hil_sensor_t, xgyro) }, \
{ "ygyro", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_hil_sensor_t, ygyro) }, \
{ "zgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_hil_sensor_t, zgyro) }, \
{ "xmag", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_hil_sensor_t, xmag) }, \
{ "ymag", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_hil_sensor_t, ymag) }, \
{ "zmag", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_hil_sensor_t, zmag) }, \
{ "abs_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_hil_sensor_t, abs_pressure) }, \
{ "diff_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_hil_sensor_t, diff_pressure) }, \
{ "pressure_alt", NULL, MAVLINK_TYPE_FLOAT, 0, 52, offsetof(mavlink_hil_sensor_t, pressure_alt) }, \
{ "temperature", NULL, MAVLINK_TYPE_FLOAT, 0, 56, offsetof(mavlink_hil_sensor_t, temperature) }, \
{ "fields_updated", NULL, MAVLINK_TYPE_UINT32_T, 0, 60, offsetof(mavlink_hil_sensor_t, fields_updated) }, \
} \
}
/**
* @brief Pack a hil_sensor message
* @param system_id ID of this 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, synced to UNIX time or since system boot)
* @param xacc X acceleration (m/s^2)
* @param yacc Y acceleration (m/s^2)
* @param zacc Z acceleration (m/s^2)
* @param xgyro Angular speed around X axis in body frame (rad / sec)
* @param ygyro Angular speed around Y axis in body frame (rad / sec)
* @param zgyro Angular speed around Z axis in body frame (rad / sec)
* @param xmag X Magnetic field (Gauss)
* @param ymag Y Magnetic field (Gauss)
* @param zmag Z Magnetic field (Gauss)
* @param abs_pressure Absolute pressure in millibar
* @param diff_pressure Differential pressure (airspeed) in millibar
* @param pressure_alt Altitude calculated from pressure
* @param temperature Temperature in degrees celsius
* @param fields_updated Bitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_hil_sensor_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint64_t time_usec, float xacc, float yacc, float zacc, float xgyro, float ygyro, float zgyro, float xmag, float ymag, float zmag, float abs_pressure, float diff_pressure, float pressure_alt, float temperature, uint32_t fields_updated)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_HIL_SENSOR_LEN];
_mav_put_uint64_t(buf, 0, time_usec);
_mav_put_float(buf, 8, xacc);
_mav_put_float(buf, 12, yacc);
_mav_put_float(buf, 16, zacc);
_mav_put_float(buf, 20, xgyro);
_mav_put_float(buf, 24, ygyro);
_mav_put_float(buf, 28, zgyro);
_mav_put_float(buf, 32, xmag);
_mav_put_float(buf, 36, ymag);
_mav_put_float(buf, 40, zmag);
_mav_put_float(buf, 44, abs_pressure);
_mav_put_float(buf, 48, diff_pressure);
_mav_put_float(buf, 52, pressure_alt);
_mav_put_float(buf, 56, temperature);
_mav_put_uint32_t(buf, 60, fields_updated);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HIL_SENSOR_LEN);
#else
mavlink_hil_sensor_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;
packet.abs_pressure = abs_pressure;
packet.diff_pressure = diff_pressure;
packet.pressure_alt = pressure_alt;
packet.temperature = temperature;
packet.fields_updated = fields_updated;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HIL_SENSOR_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_HIL_SENSOR;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HIL_SENSOR_LEN, MAVLINK_MSG_ID_HIL_SENSOR_CRC);
#else
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HIL_SENSOR_LEN);
#endif
}
/**
* @brief Pack a hil_sensor 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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param time_usec Timestamp (microseconds, synced to UNIX time or since system boot)
* @param xacc X acceleration (m/s^2)
* @param yacc Y acceleration (m/s^2)
* @param zacc Z acceleration (m/s^2)
* @param xgyro Angular speed around X axis in body frame (rad / sec)
* @param ygyro Angular speed around Y axis in body frame (rad / sec)
* @param zgyro Angular speed around Z axis in body frame (rad / sec)
* @param xmag X Magnetic field (Gauss)
* @param ymag Y Magnetic field (Gauss)
* @param zmag Z Magnetic field (Gauss)
* @param abs_pressure Absolute pressure in millibar
* @param diff_pressure Differential pressure (airspeed) in millibar
* @param pressure_alt Altitude calculated from pressure
* @param temperature Temperature in degrees celsius
* @param fields_updated Bitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_hil_sensor_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint64_t time_usec,float xacc,float yacc,float zacc,float xgyro,float ygyro,float zgyro,float xmag,float ymag,float zmag,float abs_pressure,float diff_pressure,float pressure_alt,float temperature,uint32_t fields_updated)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_HIL_SENSOR_LEN];
_mav_put_uint64_t(buf, 0, time_usec);
_mav_put_float(buf, 8, xacc);
_mav_put_float(buf, 12, yacc);
_mav_put_float(buf, 16, zacc);
_mav_put_float(buf, 20, xgyro);
_mav_put_float(buf, 24, ygyro);
_mav_put_float(buf, 28, zgyro);
_mav_put_float(buf, 32, xmag);
_mav_put_float(buf, 36, ymag);
_mav_put_float(buf, 40, zmag);
_mav_put_float(buf, 44, abs_pressure);
_mav_put_float(buf, 48, diff_pressure);
_mav_put_float(buf, 52, pressure_alt);
_mav_put_float(buf, 56, temperature);
_mav_put_uint32_t(buf, 60, fields_updated);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HIL_SENSOR_LEN);
#else
mavlink_hil_sensor_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;
packet.abs_pressure = abs_pressure;
packet.diff_pressure = diff_pressure;
packet.pressure_alt = pressure_alt;
packet.temperature = temperature;
packet.fields_updated = fields_updated;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HIL_SENSOR_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_HIL_SENSOR;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HIL_SENSOR_LEN, MAVLINK_MSG_ID_HIL_SENSOR_CRC);
#else
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HIL_SENSOR_LEN);
#endif
}
/**
* @brief Encode a hil_sensor struct
*
* @param system_id ID of this 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_sensor C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_hil_sensor_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_hil_sensor_t* hil_sensor)
{
return mavlink_msg_hil_sensor_pack(system_id, component_id, msg, hil_sensor->time_usec, hil_sensor->xacc, hil_sensor->yacc, hil_sensor->zacc, hil_sensor->xgyro, hil_sensor->ygyro, hil_sensor->zgyro, hil_sensor->xmag, hil_sensor->ymag, hil_sensor->zmag, hil_sensor->abs_pressure, hil_sensor->diff_pressure, hil_sensor->pressure_alt, hil_sensor->temperature, hil_sensor->fields_updated);
}
/**
* @brief Encode a hil_sensor struct 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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param hil_sensor C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_hil_sensor_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_hil_sensor_t* hil_sensor)
{
return mavlink_msg_hil_sensor_pack_chan(system_id, component_id, chan, msg, hil_sensor->time_usec, hil_sensor->xacc, hil_sensor->yacc, hil_sensor->zacc, hil_sensor->xgyro, hil_sensor->ygyro, hil_sensor->zgyro, hil_sensor->xmag, hil_sensor->ymag, hil_sensor->zmag, hil_sensor->abs_pressure, hil_sensor->diff_pressure, hil_sensor->pressure_alt, hil_sensor->temperature, hil_sensor->fields_updated);
}
/**
* @brief Send a hil_sensor message
* @param chan MAVLink channel to send the message
*
* @param time_usec Timestamp (microseconds, synced to UNIX time or since system boot)
* @param xacc X acceleration (m/s^2)
* @param yacc Y acceleration (m/s^2)
* @param zacc Z acceleration (m/s^2)
* @param xgyro Angular speed around X axis in body frame (rad / sec)
* @param ygyro Angular speed around Y axis in body frame (rad / sec)
* @param zgyro Angular speed around Z axis in body frame (rad / sec)
* @param xmag X Magnetic field (Gauss)
* @param ymag Y Magnetic field (Gauss)
* @param zmag Z Magnetic field (Gauss)
* @param abs_pressure Absolute pressure in millibar
* @param diff_pressure Differential pressure (airspeed) in millibar
* @param pressure_alt Altitude calculated from pressure
* @param temperature Temperature in degrees celsius
* @param fields_updated Bitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_hil_sensor_send(mavlink_channel_t chan, uint64_t time_usec, float xacc, float yacc, float zacc, float xgyro, float ygyro, float zgyro, float xmag, float ymag, float zmag, float abs_pressure, float diff_pressure, float pressure_alt, float temperature, uint32_t fields_updated)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_HIL_SENSOR_LEN];
_mav_put_uint64_t(buf, 0, time_usec);
_mav_put_float(buf, 8, xacc);
_mav_put_float(buf, 12, yacc);
_mav_put_float(buf, 16, zacc);
_mav_put_float(buf, 20, xgyro);
_mav_put_float(buf, 24, ygyro);
_mav_put_float(buf, 28, zgyro);
_mav_put_float(buf, 32, xmag);
_mav_put_float(buf, 36, ymag);
_mav_put_float(buf, 40, zmag);
_mav_put_float(buf, 44, abs_pressure);
_mav_put_float(buf, 48, diff_pressure);
_mav_put_float(buf, 52, pressure_alt);
_mav_put_float(buf, 56, temperature);
_mav_put_uint32_t(buf, 60, fields_updated);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_SENSOR, buf, MAVLINK_MSG_ID_HIL_SENSOR_LEN, MAVLINK_MSG_ID_HIL_SENSOR_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_SENSOR, buf, MAVLINK_MSG_ID_HIL_SENSOR_LEN);
#endif
#else
mavlink_hil_sensor_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;
packet.abs_pressure = abs_pressure;
packet.diff_pressure = diff_pressure;
packet.pressure_alt = pressure_alt;
packet.temperature = temperature;
packet.fields_updated = fields_updated;
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_SENSOR, (const char *)&packet, MAVLINK_MSG_ID_HIL_SENSOR_LEN, MAVLINK_MSG_ID_HIL_SENSOR_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_SENSOR, (const char *)&packet, MAVLINK_MSG_ID_HIL_SENSOR_LEN);
#endif
#endif
}
#if MAVLINK_MSG_ID_HIL_SENSOR_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This varient of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_hil_sensor_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, float xacc, float yacc, float zacc, float xgyro, float ygyro, float zgyro, float xmag, float ymag, float zmag, float abs_pressure, float diff_pressure, float pressure_alt, float temperature, uint32_t fields_updated)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
_mav_put_uint64_t(buf, 0, time_usec);
_mav_put_float(buf, 8, xacc);
_mav_put_float(buf, 12, yacc);
_mav_put_float(buf, 16, zacc);
_mav_put_float(buf, 20, xgyro);
_mav_put_float(buf, 24, ygyro);
_mav_put_float(buf, 28, zgyro);
_mav_put_float(buf, 32, xmag);
_mav_put_float(buf, 36, ymag);
_mav_put_float(buf, 40, zmag);
_mav_put_float(buf, 44, abs_pressure);
_mav_put_float(buf, 48, diff_pressure);
_mav_put_float(buf, 52, pressure_alt);
_mav_put_float(buf, 56, temperature);
_mav_put_uint32_t(buf, 60, fields_updated);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_SENSOR, buf, MAVLINK_MSG_ID_HIL_SENSOR_LEN, MAVLINK_MSG_ID_HIL_SENSOR_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_SENSOR, buf, MAVLINK_MSG_ID_HIL_SENSOR_LEN);
#endif
#else
mavlink_hil_sensor_t *packet = (mavlink_hil_sensor_t *)msgbuf;
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;
packet->abs_pressure = abs_pressure;
packet->diff_pressure = diff_pressure;
packet->pressure_alt = pressure_alt;
packet->temperature = temperature;
packet->fields_updated = fields_updated;
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_SENSOR, (const char *)packet, MAVLINK_MSG_ID_HIL_SENSOR_LEN, MAVLINK_MSG_ID_HIL_SENSOR_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_SENSOR, (const char *)packet, MAVLINK_MSG_ID_HIL_SENSOR_LEN);
#endif
#endif
}
#endif
#endif
// MESSAGE HIL_SENSOR UNPACKING
/**
* @brief Get field time_usec from hil_sensor message
*
* @return Timestamp (microseconds, synced to UNIX time or since system boot)
*/
static inline uint64_t mavlink_msg_hil_sensor_get_time_usec(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint64_t(msg, 0);
}
/**
* @brief Get field xacc from hil_sensor message
*
* @return X acceleration (m/s^2)
*/
static inline float mavlink_msg_hil_sensor_get_xacc(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 8);
}
/**
* @brief Get field yacc from hil_sensor message
*
* @return Y acceleration (m/s^2)
*/
static inline float mavlink_msg_hil_sensor_get_yacc(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 12);
}
/**
* @brief Get field zacc from hil_sensor message
*
* @return Z acceleration (m/s^2)
*/
static inline float mavlink_msg_hil_sensor_get_zacc(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 16);
}
/**
* @brief Get field xgyro from hil_sensor message
*
* @return Angular speed around X axis in body frame (rad / sec)
*/
static inline float mavlink_msg_hil_sensor_get_xgyro(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 20);
}
/**
* @brief Get field ygyro from hil_sensor message
*
* @return Angular speed around Y axis in body frame (rad / sec)
*/
static inline float mavlink_msg_hil_sensor_get_ygyro(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 24);
}
/**
* @brief Get field zgyro from hil_sensor message
*
* @return Angular speed around Z axis in body frame (rad / sec)
*/
static inline float mavlink_msg_hil_sensor_get_zgyro(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 28);
}
/**
* @brief Get field xmag from hil_sensor message
*
* @return X Magnetic field (Gauss)
*/
static inline float mavlink_msg_hil_sensor_get_xmag(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 32);
}
/**
* @brief Get field ymag from hil_sensor message
*
* @return Y Magnetic field (Gauss)
*/
static inline float mavlink_msg_hil_sensor_get_ymag(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 36);
}
/**
* @brief Get field zmag from hil_sensor message
*
* @return Z Magnetic field (Gauss)
*/
static inline float mavlink_msg_hil_sensor_get_zmag(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 40);
}
/**
* @brief Get field abs_pressure from hil_sensor message
*
* @return Absolute pressure in millibar
*/
static inline float mavlink_msg_hil_sensor_get_abs_pressure(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 44);
}
/**
* @brief Get field diff_pressure from hil_sensor message
*
* @return Differential pressure (airspeed) in millibar
*/
static inline float mavlink_msg_hil_sensor_get_diff_pressure(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 48);
}
/**
* @brief Get field pressure_alt from hil_sensor message
*
* @return Altitude calculated from pressure
*/
static inline float mavlink_msg_hil_sensor_get_pressure_alt(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 52);
}
/**
* @brief Get field temperature from hil_sensor message
*
* @return Temperature in degrees celsius
*/
static inline float mavlink_msg_hil_sensor_get_temperature(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 56);
}
/**
* @brief Get field fields_updated from hil_sensor message
*
* @return Bitmask for fields that have updated since last message, bit 0 = xacc, bit 12: temperature
*/
static inline uint32_t mavlink_msg_hil_sensor_get_fields_updated(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint32_t(msg, 60);
}
/**
* @brief Decode a hil_sensor message into a struct
*
* @param msg The message to decode
* @param hil_sensor C-struct to decode the message contents into
*/
static inline void mavlink_msg_hil_sensor_decode(const mavlink_message_t* msg, mavlink_hil_sensor_t* hil_sensor)
{
#if MAVLINK_NEED_BYTE_SWAP
hil_sensor->time_usec = mavlink_msg_hil_sensor_get_time_usec(msg);
hil_sensor->xacc = mavlink_msg_hil_sensor_get_xacc(msg);
hil_sensor->yacc = mavlink_msg_hil_sensor_get_yacc(msg);
hil_sensor->zacc = mavlink_msg_hil_sensor_get_zacc(msg);
hil_sensor->xgyro = mavlink_msg_hil_sensor_get_xgyro(msg);
hil_sensor->ygyro = mavlink_msg_hil_sensor_get_ygyro(msg);
hil_sensor->zgyro = mavlink_msg_hil_sensor_get_zgyro(msg);
hil_sensor->xmag = mavlink_msg_hil_sensor_get_xmag(msg);
hil_sensor->ymag = mavlink_msg_hil_sensor_get_ymag(msg);
hil_sensor->zmag = mavlink_msg_hil_sensor_get_zmag(msg);
hil_sensor->abs_pressure = mavlink_msg_hil_sensor_get_abs_pressure(msg);
hil_sensor->diff_pressure = mavlink_msg_hil_sensor_get_diff_pressure(msg);
hil_sensor->pressure_alt = mavlink_msg_hil_sensor_get_pressure_alt(msg);
hil_sensor->temperature = mavlink_msg_hil_sensor_get_temperature(msg);
hil_sensor->fields_updated = mavlink_msg_hil_sensor_get_fields_updated(msg);
#else
memcpy(hil_sensor, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_HIL_SENSOR_LEN);
#endif
}

View file

@ -0,0 +1,569 @@
// 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; ///< Body frame roll / phi angular speed (rad/s)
float pitchspeed; ///< Body frame pitch / theta angular speed (rad/s)
float yawspeed; ///< Body frame yaw / psi 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_MSG_ID_HIL_STATE_CRC 183
#define MAVLINK_MSG_ID_90_CRC 183
#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 Body frame roll / phi angular speed (rad/s)
* @param pitchspeed Body frame pitch / theta angular speed (rad/s)
* @param yawspeed Body frame yaw / psi 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[MAVLINK_MSG_ID_HIL_STATE_LEN];
_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, MAVLINK_MSG_ID_HIL_STATE_LEN);
#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, MAVLINK_MSG_ID_HIL_STATE_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_HIL_STATE;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HIL_STATE_LEN, MAVLINK_MSG_ID_HIL_STATE_CRC);
#else
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HIL_STATE_LEN);
#endif
}
/**
* @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 will be 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 Body frame roll / phi angular speed (rad/s)
* @param pitchspeed Body frame pitch / theta angular speed (rad/s)
* @param yawspeed Body frame yaw / psi 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[MAVLINK_MSG_ID_HIL_STATE_LEN];
_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, MAVLINK_MSG_ID_HIL_STATE_LEN);
#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, MAVLINK_MSG_ID_HIL_STATE_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_HIL_STATE;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HIL_STATE_LEN, MAVLINK_MSG_ID_HIL_STATE_CRC);
#else
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HIL_STATE_LEN);
#endif
}
/**
* @brief Encode a hil_state struct
*
* @param system_id ID of this 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 Encode a hil_state struct 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 will be sent over
* @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_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_hil_state_t* hil_state)
{
return mavlink_msg_hil_state_pack_chan(system_id, component_id, chan, 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 Body frame roll / phi angular speed (rad/s)
* @param pitchspeed Body frame pitch / theta angular speed (rad/s)
* @param yawspeed Body frame yaw / psi 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[MAVLINK_MSG_ID_HIL_STATE_LEN];
_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);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_STATE, buf, MAVLINK_MSG_ID_HIL_STATE_LEN, MAVLINK_MSG_ID_HIL_STATE_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_STATE, buf, MAVLINK_MSG_ID_HIL_STATE_LEN);
#endif
#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;
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_STATE, (const char *)&packet, MAVLINK_MSG_ID_HIL_STATE_LEN, MAVLINK_MSG_ID_HIL_STATE_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_STATE, (const char *)&packet, MAVLINK_MSG_ID_HIL_STATE_LEN);
#endif
#endif
}
#if MAVLINK_MSG_ID_HIL_STATE_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This varient of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_hil_state_send_buf(mavlink_message_t *msgbuf, 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 = (char *)msgbuf;
_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);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_STATE, buf, MAVLINK_MSG_ID_HIL_STATE_LEN, MAVLINK_MSG_ID_HIL_STATE_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_STATE, buf, MAVLINK_MSG_ID_HIL_STATE_LEN);
#endif
#else
mavlink_hil_state_t *packet = (mavlink_hil_state_t *)msgbuf;
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;
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_STATE, (const char *)packet, MAVLINK_MSG_ID_HIL_STATE_LEN, MAVLINK_MSG_ID_HIL_STATE_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_STATE, (const char *)packet, MAVLINK_MSG_ID_HIL_STATE_LEN);
#endif
#endif
}
#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 Body frame roll / phi 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 Body frame pitch / theta 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 Body frame yaw / psi 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), MAVLINK_MSG_ID_HIL_STATE_LEN);
#endif
}

View file

@ -0,0 +1,561 @@
// MESSAGE HIL_STATE_QUATERNION PACKING
#define MAVLINK_MSG_ID_HIL_STATE_QUATERNION 115
typedef struct __mavlink_hil_state_quaternion_t
{
uint64_t time_usec; ///< Timestamp (microseconds since UNIX epoch or microseconds since system boot)
float attitude_quaternion[4]; ///< Vehicle attitude expressed as normalized quaternion in w, x, y, z order (with 1 0 0 0 being the null-rotation)
float rollspeed; ///< Body frame roll / phi angular speed (rad/s)
float pitchspeed; ///< Body frame pitch / theta angular speed (rad/s)
float yawspeed; ///< Body frame yaw / psi 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
uint16_t ind_airspeed; ///< Indicated airspeed, expressed as m/s * 100
uint16_t true_airspeed; ///< True airspeed, 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_quaternion_t;
#define MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN 64
#define MAVLINK_MSG_ID_115_LEN 64
#define MAVLINK_MSG_ID_HIL_STATE_QUATERNION_CRC 4
#define MAVLINK_MSG_ID_115_CRC 4
#define MAVLINK_MSG_HIL_STATE_QUATERNION_FIELD_ATTITUDE_QUATERNION_LEN 4
#define MAVLINK_MESSAGE_INFO_HIL_STATE_QUATERNION { \
"HIL_STATE_QUATERNION", \
16, \
{ { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_hil_state_quaternion_t, time_usec) }, \
{ "attitude_quaternion", NULL, MAVLINK_TYPE_FLOAT, 4, 8, offsetof(mavlink_hil_state_quaternion_t, attitude_quaternion) }, \
{ "rollspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_hil_state_quaternion_t, rollspeed) }, \
{ "pitchspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_hil_state_quaternion_t, pitchspeed) }, \
{ "yawspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_hil_state_quaternion_t, yawspeed) }, \
{ "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 36, offsetof(mavlink_hil_state_quaternion_t, lat) }, \
{ "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 40, offsetof(mavlink_hil_state_quaternion_t, lon) }, \
{ "alt", NULL, MAVLINK_TYPE_INT32_T, 0, 44, offsetof(mavlink_hil_state_quaternion_t, alt) }, \
{ "vx", NULL, MAVLINK_TYPE_INT16_T, 0, 48, offsetof(mavlink_hil_state_quaternion_t, vx) }, \
{ "vy", NULL, MAVLINK_TYPE_INT16_T, 0, 50, offsetof(mavlink_hil_state_quaternion_t, vy) }, \
{ "vz", NULL, MAVLINK_TYPE_INT16_T, 0, 52, offsetof(mavlink_hil_state_quaternion_t, vz) }, \
{ "ind_airspeed", NULL, MAVLINK_TYPE_UINT16_T, 0, 54, offsetof(mavlink_hil_state_quaternion_t, ind_airspeed) }, \
{ "true_airspeed", NULL, MAVLINK_TYPE_UINT16_T, 0, 56, offsetof(mavlink_hil_state_quaternion_t, true_airspeed) }, \
{ "xacc", NULL, MAVLINK_TYPE_INT16_T, 0, 58, offsetof(mavlink_hil_state_quaternion_t, xacc) }, \
{ "yacc", NULL, MAVLINK_TYPE_INT16_T, 0, 60, offsetof(mavlink_hil_state_quaternion_t, yacc) }, \
{ "zacc", NULL, MAVLINK_TYPE_INT16_T, 0, 62, offsetof(mavlink_hil_state_quaternion_t, zacc) }, \
} \
}
/**
* @brief Pack a hil_state_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_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
* @param attitude_quaternion Vehicle attitude expressed as normalized quaternion in w, x, y, z order (with 1 0 0 0 being the null-rotation)
* @param rollspeed Body frame roll / phi angular speed (rad/s)
* @param pitchspeed Body frame pitch / theta angular speed (rad/s)
* @param yawspeed Body frame yaw / psi 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 ind_airspeed Indicated airspeed, expressed as m/s * 100
* @param true_airspeed True airspeed, 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_quaternion_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint64_t time_usec, const float *attitude_quaternion, float rollspeed, float pitchspeed, float yawspeed, int32_t lat, int32_t lon, int32_t alt, int16_t vx, int16_t vy, int16_t vz, uint16_t ind_airspeed, uint16_t true_airspeed, int16_t xacc, int16_t yacc, int16_t zacc)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN];
_mav_put_uint64_t(buf, 0, time_usec);
_mav_put_float(buf, 24, rollspeed);
_mav_put_float(buf, 28, pitchspeed);
_mav_put_float(buf, 32, yawspeed);
_mav_put_int32_t(buf, 36, lat);
_mav_put_int32_t(buf, 40, lon);
_mav_put_int32_t(buf, 44, alt);
_mav_put_int16_t(buf, 48, vx);
_mav_put_int16_t(buf, 50, vy);
_mav_put_int16_t(buf, 52, vz);
_mav_put_uint16_t(buf, 54, ind_airspeed);
_mav_put_uint16_t(buf, 56, true_airspeed);
_mav_put_int16_t(buf, 58, xacc);
_mav_put_int16_t(buf, 60, yacc);
_mav_put_int16_t(buf, 62, zacc);
_mav_put_float_array(buf, 8, attitude_quaternion, 4);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN);
#else
mavlink_hil_state_quaternion_t packet;
packet.time_usec = time_usec;
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.ind_airspeed = ind_airspeed;
packet.true_airspeed = true_airspeed;
packet.xacc = xacc;
packet.yacc = yacc;
packet.zacc = zacc;
mav_array_memcpy(packet.attitude_quaternion, attitude_quaternion, sizeof(float)*4);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_HIL_STATE_QUATERNION;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_CRC);
#else
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN);
#endif
}
/**
* @brief Pack a hil_state_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 will be 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 attitude_quaternion Vehicle attitude expressed as normalized quaternion in w, x, y, z order (with 1 0 0 0 being the null-rotation)
* @param rollspeed Body frame roll / phi angular speed (rad/s)
* @param pitchspeed Body frame pitch / theta angular speed (rad/s)
* @param yawspeed Body frame yaw / psi 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 ind_airspeed Indicated airspeed, expressed as m/s * 100
* @param true_airspeed True airspeed, 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_quaternion_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint64_t time_usec,const float *attitude_quaternion,float rollspeed,float pitchspeed,float yawspeed,int32_t lat,int32_t lon,int32_t alt,int16_t vx,int16_t vy,int16_t vz,uint16_t ind_airspeed,uint16_t true_airspeed,int16_t xacc,int16_t yacc,int16_t zacc)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN];
_mav_put_uint64_t(buf, 0, time_usec);
_mav_put_float(buf, 24, rollspeed);
_mav_put_float(buf, 28, pitchspeed);
_mav_put_float(buf, 32, yawspeed);
_mav_put_int32_t(buf, 36, lat);
_mav_put_int32_t(buf, 40, lon);
_mav_put_int32_t(buf, 44, alt);
_mav_put_int16_t(buf, 48, vx);
_mav_put_int16_t(buf, 50, vy);
_mav_put_int16_t(buf, 52, vz);
_mav_put_uint16_t(buf, 54, ind_airspeed);
_mav_put_uint16_t(buf, 56, true_airspeed);
_mav_put_int16_t(buf, 58, xacc);
_mav_put_int16_t(buf, 60, yacc);
_mav_put_int16_t(buf, 62, zacc);
_mav_put_float_array(buf, 8, attitude_quaternion, 4);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN);
#else
mavlink_hil_state_quaternion_t packet;
packet.time_usec = time_usec;
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.ind_airspeed = ind_airspeed;
packet.true_airspeed = true_airspeed;
packet.xacc = xacc;
packet.yacc = yacc;
packet.zacc = zacc;
mav_array_memcpy(packet.attitude_quaternion, attitude_quaternion, sizeof(float)*4);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_HIL_STATE_QUATERNION;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_CRC);
#else
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN);
#endif
}
/**
* @brief Encode a hil_state_quaternion struct
*
* @param system_id ID of this 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_quaternion C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_hil_state_quaternion_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_hil_state_quaternion_t* hil_state_quaternion)
{
return mavlink_msg_hil_state_quaternion_pack(system_id, component_id, msg, hil_state_quaternion->time_usec, hil_state_quaternion->attitude_quaternion, hil_state_quaternion->rollspeed, hil_state_quaternion->pitchspeed, hil_state_quaternion->yawspeed, hil_state_quaternion->lat, hil_state_quaternion->lon, hil_state_quaternion->alt, hil_state_quaternion->vx, hil_state_quaternion->vy, hil_state_quaternion->vz, hil_state_quaternion->ind_airspeed, hil_state_quaternion->true_airspeed, hil_state_quaternion->xacc, hil_state_quaternion->yacc, hil_state_quaternion->zacc);
}
/**
* @brief Encode a hil_state_quaternion struct 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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param hil_state_quaternion C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_hil_state_quaternion_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_hil_state_quaternion_t* hil_state_quaternion)
{
return mavlink_msg_hil_state_quaternion_pack_chan(system_id, component_id, chan, msg, hil_state_quaternion->time_usec, hil_state_quaternion->attitude_quaternion, hil_state_quaternion->rollspeed, hil_state_quaternion->pitchspeed, hil_state_quaternion->yawspeed, hil_state_quaternion->lat, hil_state_quaternion->lon, hil_state_quaternion->alt, hil_state_quaternion->vx, hil_state_quaternion->vy, hil_state_quaternion->vz, hil_state_quaternion->ind_airspeed, hil_state_quaternion->true_airspeed, hil_state_quaternion->xacc, hil_state_quaternion->yacc, hil_state_quaternion->zacc);
}
/**
* @brief Send a hil_state_quaternion message
* @param chan MAVLink channel to send the message
*
* @param time_usec Timestamp (microseconds since UNIX epoch or microseconds since system boot)
* @param attitude_quaternion Vehicle attitude expressed as normalized quaternion in w, x, y, z order (with 1 0 0 0 being the null-rotation)
* @param rollspeed Body frame roll / phi angular speed (rad/s)
* @param pitchspeed Body frame pitch / theta angular speed (rad/s)
* @param yawspeed Body frame yaw / psi 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 ind_airspeed Indicated airspeed, expressed as m/s * 100
* @param true_airspeed True airspeed, 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_quaternion_send(mavlink_channel_t chan, uint64_t time_usec, const float *attitude_quaternion, float rollspeed, float pitchspeed, float yawspeed, int32_t lat, int32_t lon, int32_t alt, int16_t vx, int16_t vy, int16_t vz, uint16_t ind_airspeed, uint16_t true_airspeed, int16_t xacc, int16_t yacc, int16_t zacc)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN];
_mav_put_uint64_t(buf, 0, time_usec);
_mav_put_float(buf, 24, rollspeed);
_mav_put_float(buf, 28, pitchspeed);
_mav_put_float(buf, 32, yawspeed);
_mav_put_int32_t(buf, 36, lat);
_mav_put_int32_t(buf, 40, lon);
_mav_put_int32_t(buf, 44, alt);
_mav_put_int16_t(buf, 48, vx);
_mav_put_int16_t(buf, 50, vy);
_mav_put_int16_t(buf, 52, vz);
_mav_put_uint16_t(buf, 54, ind_airspeed);
_mav_put_uint16_t(buf, 56, true_airspeed);
_mav_put_int16_t(buf, 58, xacc);
_mav_put_int16_t(buf, 60, yacc);
_mav_put_int16_t(buf, 62, zacc);
_mav_put_float_array(buf, 8, attitude_quaternion, 4);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_STATE_QUATERNION, buf, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_STATE_QUATERNION, buf, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN);
#endif
#else
mavlink_hil_state_quaternion_t packet;
packet.time_usec = time_usec;
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.ind_airspeed = ind_airspeed;
packet.true_airspeed = true_airspeed;
packet.xacc = xacc;
packet.yacc = yacc;
packet.zacc = zacc;
mav_array_memcpy(packet.attitude_quaternion, attitude_quaternion, sizeof(float)*4);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_STATE_QUATERNION, (const char *)&packet, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_STATE_QUATERNION, (const char *)&packet, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN);
#endif
#endif
}
#if MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This varient of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_hil_state_quaternion_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, const float *attitude_quaternion, float rollspeed, float pitchspeed, float yawspeed, int32_t lat, int32_t lon, int32_t alt, int16_t vx, int16_t vy, int16_t vz, uint16_t ind_airspeed, uint16_t true_airspeed, int16_t xacc, int16_t yacc, int16_t zacc)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
_mav_put_uint64_t(buf, 0, time_usec);
_mav_put_float(buf, 24, rollspeed);
_mav_put_float(buf, 28, pitchspeed);
_mav_put_float(buf, 32, yawspeed);
_mav_put_int32_t(buf, 36, lat);
_mav_put_int32_t(buf, 40, lon);
_mav_put_int32_t(buf, 44, alt);
_mav_put_int16_t(buf, 48, vx);
_mav_put_int16_t(buf, 50, vy);
_mav_put_int16_t(buf, 52, vz);
_mav_put_uint16_t(buf, 54, ind_airspeed);
_mav_put_uint16_t(buf, 56, true_airspeed);
_mav_put_int16_t(buf, 58, xacc);
_mav_put_int16_t(buf, 60, yacc);
_mav_put_int16_t(buf, 62, zacc);
_mav_put_float_array(buf, 8, attitude_quaternion, 4);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_STATE_QUATERNION, buf, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_STATE_QUATERNION, buf, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN);
#endif
#else
mavlink_hil_state_quaternion_t *packet = (mavlink_hil_state_quaternion_t *)msgbuf;
packet->time_usec = time_usec;
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->ind_airspeed = ind_airspeed;
packet->true_airspeed = true_airspeed;
packet->xacc = xacc;
packet->yacc = yacc;
packet->zacc = zacc;
mav_array_memcpy(packet->attitude_quaternion, attitude_quaternion, sizeof(float)*4);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_STATE_QUATERNION, (const char *)packet, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_STATE_QUATERNION, (const char *)packet, MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN);
#endif
#endif
}
#endif
#endif
// MESSAGE HIL_STATE_QUATERNION UNPACKING
/**
* @brief Get field time_usec from hil_state_quaternion message
*
* @return Timestamp (microseconds since UNIX epoch or microseconds since system boot)
*/
static inline uint64_t mavlink_msg_hil_state_quaternion_get_time_usec(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint64_t(msg, 0);
}
/**
* @brief Get field attitude_quaternion from hil_state_quaternion message
*
* @return Vehicle attitude expressed as normalized quaternion in w, x, y, z order (with 1 0 0 0 being the null-rotation)
*/
static inline uint16_t mavlink_msg_hil_state_quaternion_get_attitude_quaternion(const mavlink_message_t* msg, float *attitude_quaternion)
{
return _MAV_RETURN_float_array(msg, attitude_quaternion, 4, 8);
}
/**
* @brief Get field rollspeed from hil_state_quaternion message
*
* @return Body frame roll / phi angular speed (rad/s)
*/
static inline float mavlink_msg_hil_state_quaternion_get_rollspeed(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 24);
}
/**
* @brief Get field pitchspeed from hil_state_quaternion message
*
* @return Body frame pitch / theta angular speed (rad/s)
*/
static inline float mavlink_msg_hil_state_quaternion_get_pitchspeed(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 28);
}
/**
* @brief Get field yawspeed from hil_state_quaternion message
*
* @return Body frame yaw / psi angular speed (rad/s)
*/
static inline float mavlink_msg_hil_state_quaternion_get_yawspeed(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 32);
}
/**
* @brief Get field lat from hil_state_quaternion message
*
* @return Latitude, expressed as * 1E7
*/
static inline int32_t mavlink_msg_hil_state_quaternion_get_lat(const mavlink_message_t* msg)
{
return _MAV_RETURN_int32_t(msg, 36);
}
/**
* @brief Get field lon from hil_state_quaternion message
*
* @return Longitude, expressed as * 1E7
*/
static inline int32_t mavlink_msg_hil_state_quaternion_get_lon(const mavlink_message_t* msg)
{
return _MAV_RETURN_int32_t(msg, 40);
}
/**
* @brief Get field alt from hil_state_quaternion message
*
* @return Altitude in meters, expressed as * 1000 (millimeters)
*/
static inline int32_t mavlink_msg_hil_state_quaternion_get_alt(const mavlink_message_t* msg)
{
return _MAV_RETURN_int32_t(msg, 44);
}
/**
* @brief Get field vx from hil_state_quaternion message
*
* @return Ground X Speed (Latitude), expressed as m/s * 100
*/
static inline int16_t mavlink_msg_hil_state_quaternion_get_vx(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 48);
}
/**
* @brief Get field vy from hil_state_quaternion message
*
* @return Ground Y Speed (Longitude), expressed as m/s * 100
*/
static inline int16_t mavlink_msg_hil_state_quaternion_get_vy(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 50);
}
/**
* @brief Get field vz from hil_state_quaternion message
*
* @return Ground Z Speed (Altitude), expressed as m/s * 100
*/
static inline int16_t mavlink_msg_hil_state_quaternion_get_vz(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 52);
}
/**
* @brief Get field ind_airspeed from hil_state_quaternion message
*
* @return Indicated airspeed, expressed as m/s * 100
*/
static inline uint16_t mavlink_msg_hil_state_quaternion_get_ind_airspeed(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 54);
}
/**
* @brief Get field true_airspeed from hil_state_quaternion message
*
* @return True airspeed, expressed as m/s * 100
*/
static inline uint16_t mavlink_msg_hil_state_quaternion_get_true_airspeed(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 56);
}
/**
* @brief Get field xacc from hil_state_quaternion message
*
* @return X acceleration (mg)
*/
static inline int16_t mavlink_msg_hil_state_quaternion_get_xacc(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 58);
}
/**
* @brief Get field yacc from hil_state_quaternion message
*
* @return Y acceleration (mg)
*/
static inline int16_t mavlink_msg_hil_state_quaternion_get_yacc(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 60);
}
/**
* @brief Get field zacc from hil_state_quaternion message
*
* @return Z acceleration (mg)
*/
static inline int16_t mavlink_msg_hil_state_quaternion_get_zacc(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 62);
}
/**
* @brief Decode a hil_state_quaternion message into a struct
*
* @param msg The message to decode
* @param hil_state_quaternion C-struct to decode the message contents into
*/
static inline void mavlink_msg_hil_state_quaternion_decode(const mavlink_message_t* msg, mavlink_hil_state_quaternion_t* hil_state_quaternion)
{
#if MAVLINK_NEED_BYTE_SWAP
hil_state_quaternion->time_usec = mavlink_msg_hil_state_quaternion_get_time_usec(msg);
mavlink_msg_hil_state_quaternion_get_attitude_quaternion(msg, hil_state_quaternion->attitude_quaternion);
hil_state_quaternion->rollspeed = mavlink_msg_hil_state_quaternion_get_rollspeed(msg);
hil_state_quaternion->pitchspeed = mavlink_msg_hil_state_quaternion_get_pitchspeed(msg);
hil_state_quaternion->yawspeed = mavlink_msg_hil_state_quaternion_get_yawspeed(msg);
hil_state_quaternion->lat = mavlink_msg_hil_state_quaternion_get_lat(msg);
hil_state_quaternion->lon = mavlink_msg_hil_state_quaternion_get_lon(msg);
hil_state_quaternion->alt = mavlink_msg_hil_state_quaternion_get_alt(msg);
hil_state_quaternion->vx = mavlink_msg_hil_state_quaternion_get_vx(msg);
hil_state_quaternion->vy = mavlink_msg_hil_state_quaternion_get_vy(msg);
hil_state_quaternion->vz = mavlink_msg_hil_state_quaternion_get_vz(msg);
hil_state_quaternion->ind_airspeed = mavlink_msg_hil_state_quaternion_get_ind_airspeed(msg);
hil_state_quaternion->true_airspeed = mavlink_msg_hil_state_quaternion_get_true_airspeed(msg);
hil_state_quaternion->xacc = mavlink_msg_hil_state_quaternion_get_xacc(msg);
hil_state_quaternion->yacc = mavlink_msg_hil_state_quaternion_get_yacc(msg);
hil_state_quaternion->zacc = mavlink_msg_hil_state_quaternion_get_zacc(msg);
#else
memcpy(hil_state_quaternion, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_HIL_STATE_QUATERNION_LEN);
#endif
}

View file

@ -0,0 +1,353 @@
// 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_MSG_ID_LOCAL_POSITION_NED_CRC 185
#define MAVLINK_MSG_ID_32_CRC 185
#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[MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN];
_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, MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN);
#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, MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_LOCAL_POSITION_NED;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_CRC);
#else
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN);
#endif
}
/**
* @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 will be 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[MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN];
_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, MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN);
#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, MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_LOCAL_POSITION_NED;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_CRC);
#else
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN);
#endif
}
/**
* @brief Encode a local_position_ned struct
*
* @param system_id ID of this 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 Encode a local_position_ned struct 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 will be sent over
* @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_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_local_position_ned_t* local_position_ned)
{
return mavlink_msg_local_position_ned_pack_chan(system_id, component_id, chan, 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[MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN];
_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);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED, buf, MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED, buf, MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN);
#endif
#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;
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED, (const char *)&packet, MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED, (const char *)&packet, MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN);
#endif
#endif
}
#if MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This varient of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_local_position_ned_send_buf(mavlink_message_t *msgbuf, 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 = (char *)msgbuf;
_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);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED, buf, MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED, buf, MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN);
#endif
#else
mavlink_local_position_ned_t *packet = (mavlink_local_position_ned_t *)msgbuf;
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;
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED, (const char *)packet, MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED, (const char *)packet, MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN);
#endif
#endif
}
#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), MAVLINK_MSG_ID_LOCAL_POSITION_NED_LEN);
#endif
}

View file

@ -0,0 +1,489 @@
// MESSAGE LOCAL_POSITION_NED_COV PACKING
#define MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV 64
typedef struct __mavlink_local_position_ned_cov_t
{
uint64_t time_utc; ///< Timestamp (microseconds since UNIX epoch) in UTC. 0 for unknown. Commonly filled by the precision time source of a GPS receiver.
uint32_t time_boot_ms; ///< Timestamp (milliseconds since system boot). 0 for system without monotonic timestamp
float x; ///< X Position
float y; ///< Y Position
float z; ///< Z Position
float vx; ///< X Speed (m/s)
float vy; ///< Y Speed (m/s)
float vz; ///< Z Speed (m/s)
float ax; ///< X Acceleration (m/s^2)
float ay; ///< Y Acceleration (m/s^2)
float az; ///< Z Acceleration (m/s^2)
float covariance[45]; ///< Covariance matrix upper right triangular (first nine entries are the first ROW, next eight entries are the second row, etc.)
uint8_t estimator_type; ///< Class id of the estimator this estimate originated from.
} mavlink_local_position_ned_cov_t;
#define MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN 229
#define MAVLINK_MSG_ID_64_LEN 229
#define MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_CRC 59
#define MAVLINK_MSG_ID_64_CRC 59
#define MAVLINK_MSG_LOCAL_POSITION_NED_COV_FIELD_COVARIANCE_LEN 45
#define MAVLINK_MESSAGE_INFO_LOCAL_POSITION_NED_COV { \
"LOCAL_POSITION_NED_COV", \
13, \
{ { "time_utc", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_local_position_ned_cov_t, time_utc) }, \
{ "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_local_position_ned_cov_t, time_boot_ms) }, \
{ "x", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_local_position_ned_cov_t, x) }, \
{ "y", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_local_position_ned_cov_t, y) }, \
{ "z", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_local_position_ned_cov_t, z) }, \
{ "vx", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_local_position_ned_cov_t, vx) }, \
{ "vy", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_local_position_ned_cov_t, vy) }, \
{ "vz", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_local_position_ned_cov_t, vz) }, \
{ "ax", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_local_position_ned_cov_t, ax) }, \
{ "ay", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_local_position_ned_cov_t, ay) }, \
{ "az", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_local_position_ned_cov_t, az) }, \
{ "covariance", NULL, MAVLINK_TYPE_FLOAT, 45, 48, offsetof(mavlink_local_position_ned_cov_t, covariance) }, \
{ "estimator_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 228, offsetof(mavlink_local_position_ned_cov_t, estimator_type) }, \
} \
}
/**
* @brief Pack a local_position_ned_cov message
* @param system_id ID of this 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). 0 for system without monotonic timestamp
* @param time_utc Timestamp (microseconds since UNIX epoch) in UTC. 0 for unknown. Commonly filled by the precision time source of a GPS receiver.
* @param estimator_type Class id of the estimator this estimate originated from.
* @param x X Position
* @param y Y Position
* @param z Z Position
* @param vx X Speed (m/s)
* @param vy Y Speed (m/s)
* @param vz Z Speed (m/s)
* @param ax X Acceleration (m/s^2)
* @param ay Y Acceleration (m/s^2)
* @param az Z Acceleration (m/s^2)
* @param covariance Covariance matrix upper right triangular (first nine entries are the first ROW, next eight entries are the second row, etc.)
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_local_position_ned_cov_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint32_t time_boot_ms, uint64_t time_utc, uint8_t estimator_type, float x, float y, float z, float vx, float vy, float vz, float ax, float ay, float az, const float *covariance)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN];
_mav_put_uint64_t(buf, 0, time_utc);
_mav_put_uint32_t(buf, 8, time_boot_ms);
_mav_put_float(buf, 12, x);
_mav_put_float(buf, 16, y);
_mav_put_float(buf, 20, z);
_mav_put_float(buf, 24, vx);
_mav_put_float(buf, 28, vy);
_mav_put_float(buf, 32, vz);
_mav_put_float(buf, 36, ax);
_mav_put_float(buf, 40, ay);
_mav_put_float(buf, 44, az);
_mav_put_uint8_t(buf, 228, estimator_type);
_mav_put_float_array(buf, 48, covariance, 45);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN);
#else
mavlink_local_position_ned_cov_t packet;
packet.time_utc = time_utc;
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;
packet.ax = ax;
packet.ay = ay;
packet.az = az;
packet.estimator_type = estimator_type;
mav_array_memcpy(packet.covariance, covariance, sizeof(float)*45);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_CRC);
#else
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN);
#endif
}
/**
* @brief Pack a local_position_ned_cov 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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param time_boot_ms Timestamp (milliseconds since system boot). 0 for system without monotonic timestamp
* @param time_utc Timestamp (microseconds since UNIX epoch) in UTC. 0 for unknown. Commonly filled by the precision time source of a GPS receiver.
* @param estimator_type Class id of the estimator this estimate originated from.
* @param x X Position
* @param y Y Position
* @param z Z Position
* @param vx X Speed (m/s)
* @param vy Y Speed (m/s)
* @param vz Z Speed (m/s)
* @param ax X Acceleration (m/s^2)
* @param ay Y Acceleration (m/s^2)
* @param az Z Acceleration (m/s^2)
* @param covariance Covariance matrix upper right triangular (first nine entries are the first ROW, next eight entries are the second row, etc.)
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_local_position_ned_cov_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint32_t time_boot_ms,uint64_t time_utc,uint8_t estimator_type,float x,float y,float z,float vx,float vy,float vz,float ax,float ay,float az,const float *covariance)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN];
_mav_put_uint64_t(buf, 0, time_utc);
_mav_put_uint32_t(buf, 8, time_boot_ms);
_mav_put_float(buf, 12, x);
_mav_put_float(buf, 16, y);
_mav_put_float(buf, 20, z);
_mav_put_float(buf, 24, vx);
_mav_put_float(buf, 28, vy);
_mav_put_float(buf, 32, vz);
_mav_put_float(buf, 36, ax);
_mav_put_float(buf, 40, ay);
_mav_put_float(buf, 44, az);
_mav_put_uint8_t(buf, 228, estimator_type);
_mav_put_float_array(buf, 48, covariance, 45);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN);
#else
mavlink_local_position_ned_cov_t packet;
packet.time_utc = time_utc;
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;
packet.ax = ax;
packet.ay = ay;
packet.az = az;
packet.estimator_type = estimator_type;
mav_array_memcpy(packet.covariance, covariance, sizeof(float)*45);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_CRC);
#else
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN);
#endif
}
/**
* @brief Encode a local_position_ned_cov struct
*
* @param system_id ID of this 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_cov C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_local_position_ned_cov_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_local_position_ned_cov_t* local_position_ned_cov)
{
return mavlink_msg_local_position_ned_cov_pack(system_id, component_id, msg, local_position_ned_cov->time_boot_ms, local_position_ned_cov->time_utc, local_position_ned_cov->estimator_type, local_position_ned_cov->x, local_position_ned_cov->y, local_position_ned_cov->z, local_position_ned_cov->vx, local_position_ned_cov->vy, local_position_ned_cov->vz, local_position_ned_cov->ax, local_position_ned_cov->ay, local_position_ned_cov->az, local_position_ned_cov->covariance);
}
/**
* @brief Encode a local_position_ned_cov struct 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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param local_position_ned_cov C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_local_position_ned_cov_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_local_position_ned_cov_t* local_position_ned_cov)
{
return mavlink_msg_local_position_ned_cov_pack_chan(system_id, component_id, chan, msg, local_position_ned_cov->time_boot_ms, local_position_ned_cov->time_utc, local_position_ned_cov->estimator_type, local_position_ned_cov->x, local_position_ned_cov->y, local_position_ned_cov->z, local_position_ned_cov->vx, local_position_ned_cov->vy, local_position_ned_cov->vz, local_position_ned_cov->ax, local_position_ned_cov->ay, local_position_ned_cov->az, local_position_ned_cov->covariance);
}
/**
* @brief Send a local_position_ned_cov message
* @param chan MAVLink channel to send the message
*
* @param time_boot_ms Timestamp (milliseconds since system boot). 0 for system without monotonic timestamp
* @param time_utc Timestamp (microseconds since UNIX epoch) in UTC. 0 for unknown. Commonly filled by the precision time source of a GPS receiver.
* @param estimator_type Class id of the estimator this estimate originated from.
* @param x X Position
* @param y Y Position
* @param z Z Position
* @param vx X Speed (m/s)
* @param vy Y Speed (m/s)
* @param vz Z Speed (m/s)
* @param ax X Acceleration (m/s^2)
* @param ay Y Acceleration (m/s^2)
* @param az Z Acceleration (m/s^2)
* @param covariance Covariance matrix upper right triangular (first nine entries are the first ROW, next eight entries are the second row, etc.)
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_local_position_ned_cov_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint64_t time_utc, uint8_t estimator_type, float x, float y, float z, float vx, float vy, float vz, float ax, float ay, float az, const float *covariance)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN];
_mav_put_uint64_t(buf, 0, time_utc);
_mav_put_uint32_t(buf, 8, time_boot_ms);
_mav_put_float(buf, 12, x);
_mav_put_float(buf, 16, y);
_mav_put_float(buf, 20, z);
_mav_put_float(buf, 24, vx);
_mav_put_float(buf, 28, vy);
_mav_put_float(buf, 32, vz);
_mav_put_float(buf, 36, ax);
_mav_put_float(buf, 40, ay);
_mav_put_float(buf, 44, az);
_mav_put_uint8_t(buf, 228, estimator_type);
_mav_put_float_array(buf, 48, covariance, 45);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV, buf, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV, buf, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN);
#endif
#else
mavlink_local_position_ned_cov_t packet;
packet.time_utc = time_utc;
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;
packet.ax = ax;
packet.ay = ay;
packet.az = az;
packet.estimator_type = estimator_type;
mav_array_memcpy(packet.covariance, covariance, sizeof(float)*45);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV, (const char *)&packet, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV, (const char *)&packet, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN);
#endif
#endif
}
#if MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This varient of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_local_position_ned_cov_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, uint64_t time_utc, uint8_t estimator_type, float x, float y, float z, float vx, float vy, float vz, float ax, float ay, float az, const float *covariance)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
_mav_put_uint64_t(buf, 0, time_utc);
_mav_put_uint32_t(buf, 8, time_boot_ms);
_mav_put_float(buf, 12, x);
_mav_put_float(buf, 16, y);
_mav_put_float(buf, 20, z);
_mav_put_float(buf, 24, vx);
_mav_put_float(buf, 28, vy);
_mav_put_float(buf, 32, vz);
_mav_put_float(buf, 36, ax);
_mav_put_float(buf, 40, ay);
_mav_put_float(buf, 44, az);
_mav_put_uint8_t(buf, 228, estimator_type);
_mav_put_float_array(buf, 48, covariance, 45);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV, buf, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV, buf, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN);
#endif
#else
mavlink_local_position_ned_cov_t *packet = (mavlink_local_position_ned_cov_t *)msgbuf;
packet->time_utc = time_utc;
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;
packet->ax = ax;
packet->ay = ay;
packet->az = az;
packet->estimator_type = estimator_type;
mav_array_memcpy(packet->covariance, covariance, sizeof(float)*45);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV, (const char *)packet, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV, (const char *)packet, MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN);
#endif
#endif
}
#endif
#endif
// MESSAGE LOCAL_POSITION_NED_COV UNPACKING
/**
* @brief Get field time_boot_ms from local_position_ned_cov message
*
* @return Timestamp (milliseconds since system boot). 0 for system without monotonic timestamp
*/
static inline uint32_t mavlink_msg_local_position_ned_cov_get_time_boot_ms(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint32_t(msg, 8);
}
/**
* @brief Get field time_utc from local_position_ned_cov message
*
* @return Timestamp (microseconds since UNIX epoch) in UTC. 0 for unknown. Commonly filled by the precision time source of a GPS receiver.
*/
static inline uint64_t mavlink_msg_local_position_ned_cov_get_time_utc(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint64_t(msg, 0);
}
/**
* @brief Get field estimator_type from local_position_ned_cov message
*
* @return Class id of the estimator this estimate originated from.
*/
static inline uint8_t mavlink_msg_local_position_ned_cov_get_estimator_type(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 228);
}
/**
* @brief Get field x from local_position_ned_cov message
*
* @return X Position
*/
static inline float mavlink_msg_local_position_ned_cov_get_x(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 12);
}
/**
* @brief Get field y from local_position_ned_cov message
*
* @return Y Position
*/
static inline float mavlink_msg_local_position_ned_cov_get_y(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 16);
}
/**
* @brief Get field z from local_position_ned_cov message
*
* @return Z Position
*/
static inline float mavlink_msg_local_position_ned_cov_get_z(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 20);
}
/**
* @brief Get field vx from local_position_ned_cov message
*
* @return X Speed (m/s)
*/
static inline float mavlink_msg_local_position_ned_cov_get_vx(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 24);
}
/**
* @brief Get field vy from local_position_ned_cov message
*
* @return Y Speed (m/s)
*/
static inline float mavlink_msg_local_position_ned_cov_get_vy(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 28);
}
/**
* @brief Get field vz from local_position_ned_cov message
*
* @return Z Speed (m/s)
*/
static inline float mavlink_msg_local_position_ned_cov_get_vz(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 32);
}
/**
* @brief Get field ax from local_position_ned_cov message
*
* @return X Acceleration (m/s^2)
*/
static inline float mavlink_msg_local_position_ned_cov_get_ax(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 36);
}
/**
* @brief Get field ay from local_position_ned_cov message
*
* @return Y Acceleration (m/s^2)
*/
static inline float mavlink_msg_local_position_ned_cov_get_ay(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 40);
}
/**
* @brief Get field az from local_position_ned_cov message
*
* @return Z Acceleration (m/s^2)
*/
static inline float mavlink_msg_local_position_ned_cov_get_az(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 44);
}
/**
* @brief Get field covariance from local_position_ned_cov message
*
* @return Covariance matrix upper right triangular (first nine entries are the first ROW, next eight entries are the second row, etc.)
*/
static inline uint16_t mavlink_msg_local_position_ned_cov_get_covariance(const mavlink_message_t* msg, float *covariance)
{
return _MAV_RETURN_float_array(msg, covariance, 45, 48);
}
/**
* @brief Decode a local_position_ned_cov message into a struct
*
* @param msg The message to decode
* @param local_position_ned_cov C-struct to decode the message contents into
*/
static inline void mavlink_msg_local_position_ned_cov_decode(const mavlink_message_t* msg, mavlink_local_position_ned_cov_t* local_position_ned_cov)
{
#if MAVLINK_NEED_BYTE_SWAP
local_position_ned_cov->time_utc = mavlink_msg_local_position_ned_cov_get_time_utc(msg);
local_position_ned_cov->time_boot_ms = mavlink_msg_local_position_ned_cov_get_time_boot_ms(msg);
local_position_ned_cov->x = mavlink_msg_local_position_ned_cov_get_x(msg);
local_position_ned_cov->y = mavlink_msg_local_position_ned_cov_get_y(msg);
local_position_ned_cov->z = mavlink_msg_local_position_ned_cov_get_z(msg);
local_position_ned_cov->vx = mavlink_msg_local_position_ned_cov_get_vx(msg);
local_position_ned_cov->vy = mavlink_msg_local_position_ned_cov_get_vy(msg);
local_position_ned_cov->vz = mavlink_msg_local_position_ned_cov_get_vz(msg);
local_position_ned_cov->ax = mavlink_msg_local_position_ned_cov_get_ax(msg);
local_position_ned_cov->ay = mavlink_msg_local_position_ned_cov_get_ay(msg);
local_position_ned_cov->az = mavlink_msg_local_position_ned_cov_get_az(msg);
mavlink_msg_local_position_ned_cov_get_covariance(msg, local_position_ned_cov->covariance);
local_position_ned_cov->estimator_type = mavlink_msg_local_position_ned_cov_get_estimator_type(msg);
#else
memcpy(local_position_ned_cov, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_LOCAL_POSITION_NED_COV_LEN);
#endif
}

View file

@ -0,0 +1,353 @@
// 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_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_CRC 231
#define MAVLINK_MSG_ID_89_CRC 231
#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[MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN];
_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, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN);
#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, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_CRC);
#else
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN);
#endif
}
/**
* @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 will be 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[MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN];
_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, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN);
#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, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_CRC);
#else
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN);
#endif
}
/**
* @brief Encode a local_position_ned_system_global_offset struct
*
* @param system_id ID of this 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 Encode a local_position_ned_system_global_offset struct 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 will be sent over
* @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_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, 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_chan(system_id, component_id, chan, 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[MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN];
_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);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET, buf, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET, buf, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN);
#endif
#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;
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET, (const char *)&packet, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET, (const char *)&packet, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN);
#endif
#endif
}
#if MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This varient of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_local_position_ned_system_global_offset_send_buf(mavlink_message_t *msgbuf, 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 = (char *)msgbuf;
_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);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET, buf, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET, buf, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN);
#endif
#else
mavlink_local_position_ned_system_global_offset_t *packet = (mavlink_local_position_ned_system_global_offset_t *)msgbuf;
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;
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET, (const char *)packet, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET, (const char *)packet, MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN);
#endif
#endif
}
#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), MAVLINK_MSG_ID_LOCAL_POSITION_NED_SYSTEM_GLOBAL_OFFSET_LEN);
#endif
}

View file

@ -0,0 +1,273 @@
// MESSAGE LOG_DATA PACKING
#define MAVLINK_MSG_ID_LOG_DATA 120
typedef struct __mavlink_log_data_t
{
uint32_t ofs; ///< Offset into the log
uint16_t id; ///< Log id (from LOG_ENTRY reply)
uint8_t count; ///< Number of bytes (zero for end of log)
uint8_t data[90]; ///< log data
} mavlink_log_data_t;
#define MAVLINK_MSG_ID_LOG_DATA_LEN 97
#define MAVLINK_MSG_ID_120_LEN 97
#define MAVLINK_MSG_ID_LOG_DATA_CRC 134
#define MAVLINK_MSG_ID_120_CRC 134
#define MAVLINK_MSG_LOG_DATA_FIELD_DATA_LEN 90
#define MAVLINK_MESSAGE_INFO_LOG_DATA { \
"LOG_DATA", \
4, \
{ { "ofs", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_log_data_t, ofs) }, \
{ "id", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_log_data_t, id) }, \
{ "count", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_log_data_t, count) }, \
{ "data", NULL, MAVLINK_TYPE_UINT8_T, 90, 7, offsetof(mavlink_log_data_t, data) }, \
} \
}
/**
* @brief Pack a log_data message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param id Log id (from LOG_ENTRY reply)
* @param ofs Offset into the log
* @param count Number of bytes (zero for end of log)
* @param data log data
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_log_data_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint16_t id, uint32_t ofs, uint8_t count, const uint8_t *data)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_LOG_DATA_LEN];
_mav_put_uint32_t(buf, 0, ofs);
_mav_put_uint16_t(buf, 4, id);
_mav_put_uint8_t(buf, 6, count);
_mav_put_uint8_t_array(buf, 7, data, 90);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOG_DATA_LEN);
#else
mavlink_log_data_t packet;
packet.ofs = ofs;
packet.id = id;
packet.count = count;
mav_array_memcpy(packet.data, data, sizeof(uint8_t)*90);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOG_DATA_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_LOG_DATA;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LOG_DATA_LEN, MAVLINK_MSG_ID_LOG_DATA_CRC);
#else
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LOG_DATA_LEN);
#endif
}
/**
* @brief Pack a log_data 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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param id Log id (from LOG_ENTRY reply)
* @param ofs Offset into the log
* @param count Number of bytes (zero for end of log)
* @param data log data
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_log_data_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint16_t id,uint32_t ofs,uint8_t count,const uint8_t *data)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_LOG_DATA_LEN];
_mav_put_uint32_t(buf, 0, ofs);
_mav_put_uint16_t(buf, 4, id);
_mav_put_uint8_t(buf, 6, count);
_mav_put_uint8_t_array(buf, 7, data, 90);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOG_DATA_LEN);
#else
mavlink_log_data_t packet;
packet.ofs = ofs;
packet.id = id;
packet.count = count;
mav_array_memcpy(packet.data, data, sizeof(uint8_t)*90);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOG_DATA_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_LOG_DATA;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LOG_DATA_LEN, MAVLINK_MSG_ID_LOG_DATA_CRC);
#else
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LOG_DATA_LEN);
#endif
}
/**
* @brief Encode a log_data struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param log_data C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_log_data_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_log_data_t* log_data)
{
return mavlink_msg_log_data_pack(system_id, component_id, msg, log_data->id, log_data->ofs, log_data->count, log_data->data);
}
/**
* @brief Encode a log_data struct 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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param log_data C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_log_data_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_log_data_t* log_data)
{
return mavlink_msg_log_data_pack_chan(system_id, component_id, chan, msg, log_data->id, log_data->ofs, log_data->count, log_data->data);
}
/**
* @brief Send a log_data message
* @param chan MAVLink channel to send the message
*
* @param id Log id (from LOG_ENTRY reply)
* @param ofs Offset into the log
* @param count Number of bytes (zero for end of log)
* @param data log data
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_log_data_send(mavlink_channel_t chan, uint16_t id, uint32_t ofs, uint8_t count, const uint8_t *data)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_LOG_DATA_LEN];
_mav_put_uint32_t(buf, 0, ofs);
_mav_put_uint16_t(buf, 4, id);
_mav_put_uint8_t(buf, 6, count);
_mav_put_uint8_t_array(buf, 7, data, 90);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_DATA, buf, MAVLINK_MSG_ID_LOG_DATA_LEN, MAVLINK_MSG_ID_LOG_DATA_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_DATA, buf, MAVLINK_MSG_ID_LOG_DATA_LEN);
#endif
#else
mavlink_log_data_t packet;
packet.ofs = ofs;
packet.id = id;
packet.count = count;
mav_array_memcpy(packet.data, data, sizeof(uint8_t)*90);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_DATA, (const char *)&packet, MAVLINK_MSG_ID_LOG_DATA_LEN, MAVLINK_MSG_ID_LOG_DATA_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_DATA, (const char *)&packet, MAVLINK_MSG_ID_LOG_DATA_LEN);
#endif
#endif
}
#if MAVLINK_MSG_ID_LOG_DATA_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This varient of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_log_data_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint16_t id, uint32_t ofs, uint8_t count, const uint8_t *data)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
_mav_put_uint32_t(buf, 0, ofs);
_mav_put_uint16_t(buf, 4, id);
_mav_put_uint8_t(buf, 6, count);
_mav_put_uint8_t_array(buf, 7, data, 90);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_DATA, buf, MAVLINK_MSG_ID_LOG_DATA_LEN, MAVLINK_MSG_ID_LOG_DATA_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_DATA, buf, MAVLINK_MSG_ID_LOG_DATA_LEN);
#endif
#else
mavlink_log_data_t *packet = (mavlink_log_data_t *)msgbuf;
packet->ofs = ofs;
packet->id = id;
packet->count = count;
mav_array_memcpy(packet->data, data, sizeof(uint8_t)*90);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_DATA, (const char *)packet, MAVLINK_MSG_ID_LOG_DATA_LEN, MAVLINK_MSG_ID_LOG_DATA_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_DATA, (const char *)packet, MAVLINK_MSG_ID_LOG_DATA_LEN);
#endif
#endif
}
#endif
#endif
// MESSAGE LOG_DATA UNPACKING
/**
* @brief Get field id from log_data message
*
* @return Log id (from LOG_ENTRY reply)
*/
static inline uint16_t mavlink_msg_log_data_get_id(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 4);
}
/**
* @brief Get field ofs from log_data message
*
* @return Offset into the log
*/
static inline uint32_t mavlink_msg_log_data_get_ofs(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint32_t(msg, 0);
}
/**
* @brief Get field count from log_data message
*
* @return Number of bytes (zero for end of log)
*/
static inline uint8_t mavlink_msg_log_data_get_count(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 6);
}
/**
* @brief Get field data from log_data message
*
* @return log data
*/
static inline uint16_t mavlink_msg_log_data_get_data(const mavlink_message_t* msg, uint8_t *data)
{
return _MAV_RETURN_uint8_t_array(msg, data, 90, 7);
}
/**
* @brief Decode a log_data message into a struct
*
* @param msg The message to decode
* @param log_data C-struct to decode the message contents into
*/
static inline void mavlink_msg_log_data_decode(const mavlink_message_t* msg, mavlink_log_data_t* log_data)
{
#if MAVLINK_NEED_BYTE_SWAP
log_data->ofs = mavlink_msg_log_data_get_ofs(msg);
log_data->id = mavlink_msg_log_data_get_id(msg);
log_data->count = mavlink_msg_log_data_get_count(msg);
mavlink_msg_log_data_get_data(msg, log_data->data);
#else
memcpy(log_data, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_LOG_DATA_LEN);
#endif
}

View file

@ -0,0 +1,305 @@
// MESSAGE LOG_ENTRY PACKING
#define MAVLINK_MSG_ID_LOG_ENTRY 118
typedef struct __mavlink_log_entry_t
{
uint32_t time_utc; ///< UTC timestamp of log in seconds since 1970, or 0 if not available
uint32_t size; ///< Size of the log (may be approximate) in bytes
uint16_t id; ///< Log id
uint16_t num_logs; ///< Total number of logs
uint16_t last_log_num; ///< High log number
} mavlink_log_entry_t;
#define MAVLINK_MSG_ID_LOG_ENTRY_LEN 14
#define MAVLINK_MSG_ID_118_LEN 14
#define MAVLINK_MSG_ID_LOG_ENTRY_CRC 56
#define MAVLINK_MSG_ID_118_CRC 56
#define MAVLINK_MESSAGE_INFO_LOG_ENTRY { \
"LOG_ENTRY", \
5, \
{ { "time_utc", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_log_entry_t, time_utc) }, \
{ "size", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_log_entry_t, size) }, \
{ "id", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_log_entry_t, id) }, \
{ "num_logs", NULL, MAVLINK_TYPE_UINT16_T, 0, 10, offsetof(mavlink_log_entry_t, num_logs) }, \
{ "last_log_num", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_log_entry_t, last_log_num) }, \
} \
}
/**
* @brief Pack a log_entry message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param id Log id
* @param num_logs Total number of logs
* @param last_log_num High log number
* @param time_utc UTC timestamp of log in seconds since 1970, or 0 if not available
* @param size Size of the log (may be approximate) in bytes
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_log_entry_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint16_t id, uint16_t num_logs, uint16_t last_log_num, uint32_t time_utc, uint32_t size)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_LOG_ENTRY_LEN];
_mav_put_uint32_t(buf, 0, time_utc);
_mav_put_uint32_t(buf, 4, size);
_mav_put_uint16_t(buf, 8, id);
_mav_put_uint16_t(buf, 10, num_logs);
_mav_put_uint16_t(buf, 12, last_log_num);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOG_ENTRY_LEN);
#else
mavlink_log_entry_t packet;
packet.time_utc = time_utc;
packet.size = size;
packet.id = id;
packet.num_logs = num_logs;
packet.last_log_num = last_log_num;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOG_ENTRY_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_LOG_ENTRY;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LOG_ENTRY_LEN, MAVLINK_MSG_ID_LOG_ENTRY_CRC);
#else
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LOG_ENTRY_LEN);
#endif
}
/**
* @brief Pack a log_entry 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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param id Log id
* @param num_logs Total number of logs
* @param last_log_num High log number
* @param time_utc UTC timestamp of log in seconds since 1970, or 0 if not available
* @param size Size of the log (may be approximate) in bytes
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_log_entry_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint16_t id,uint16_t num_logs,uint16_t last_log_num,uint32_t time_utc,uint32_t size)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_LOG_ENTRY_LEN];
_mav_put_uint32_t(buf, 0, time_utc);
_mav_put_uint32_t(buf, 4, size);
_mav_put_uint16_t(buf, 8, id);
_mav_put_uint16_t(buf, 10, num_logs);
_mav_put_uint16_t(buf, 12, last_log_num);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOG_ENTRY_LEN);
#else
mavlink_log_entry_t packet;
packet.time_utc = time_utc;
packet.size = size;
packet.id = id;
packet.num_logs = num_logs;
packet.last_log_num = last_log_num;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOG_ENTRY_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_LOG_ENTRY;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LOG_ENTRY_LEN, MAVLINK_MSG_ID_LOG_ENTRY_CRC);
#else
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LOG_ENTRY_LEN);
#endif
}
/**
* @brief Encode a log_entry struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param log_entry C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_log_entry_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_log_entry_t* log_entry)
{
return mavlink_msg_log_entry_pack(system_id, component_id, msg, log_entry->id, log_entry->num_logs, log_entry->last_log_num, log_entry->time_utc, log_entry->size);
}
/**
* @brief Encode a log_entry struct 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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param log_entry C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_log_entry_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_log_entry_t* log_entry)
{
return mavlink_msg_log_entry_pack_chan(system_id, component_id, chan, msg, log_entry->id, log_entry->num_logs, log_entry->last_log_num, log_entry->time_utc, log_entry->size);
}
/**
* @brief Send a log_entry message
* @param chan MAVLink channel to send the message
*
* @param id Log id
* @param num_logs Total number of logs
* @param last_log_num High log number
* @param time_utc UTC timestamp of log in seconds since 1970, or 0 if not available
* @param size Size of the log (may be approximate) in bytes
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_log_entry_send(mavlink_channel_t chan, uint16_t id, uint16_t num_logs, uint16_t last_log_num, uint32_t time_utc, uint32_t size)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_LOG_ENTRY_LEN];
_mav_put_uint32_t(buf, 0, time_utc);
_mav_put_uint32_t(buf, 4, size);
_mav_put_uint16_t(buf, 8, id);
_mav_put_uint16_t(buf, 10, num_logs);
_mav_put_uint16_t(buf, 12, last_log_num);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_ENTRY, buf, MAVLINK_MSG_ID_LOG_ENTRY_LEN, MAVLINK_MSG_ID_LOG_ENTRY_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_ENTRY, buf, MAVLINK_MSG_ID_LOG_ENTRY_LEN);
#endif
#else
mavlink_log_entry_t packet;
packet.time_utc = time_utc;
packet.size = size;
packet.id = id;
packet.num_logs = num_logs;
packet.last_log_num = last_log_num;
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_ENTRY, (const char *)&packet, MAVLINK_MSG_ID_LOG_ENTRY_LEN, MAVLINK_MSG_ID_LOG_ENTRY_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_ENTRY, (const char *)&packet, MAVLINK_MSG_ID_LOG_ENTRY_LEN);
#endif
#endif
}
#if MAVLINK_MSG_ID_LOG_ENTRY_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This varient of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_log_entry_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint16_t id, uint16_t num_logs, uint16_t last_log_num, uint32_t time_utc, uint32_t size)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
_mav_put_uint32_t(buf, 0, time_utc);
_mav_put_uint32_t(buf, 4, size);
_mav_put_uint16_t(buf, 8, id);
_mav_put_uint16_t(buf, 10, num_logs);
_mav_put_uint16_t(buf, 12, last_log_num);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_ENTRY, buf, MAVLINK_MSG_ID_LOG_ENTRY_LEN, MAVLINK_MSG_ID_LOG_ENTRY_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_ENTRY, buf, MAVLINK_MSG_ID_LOG_ENTRY_LEN);
#endif
#else
mavlink_log_entry_t *packet = (mavlink_log_entry_t *)msgbuf;
packet->time_utc = time_utc;
packet->size = size;
packet->id = id;
packet->num_logs = num_logs;
packet->last_log_num = last_log_num;
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_ENTRY, (const char *)packet, MAVLINK_MSG_ID_LOG_ENTRY_LEN, MAVLINK_MSG_ID_LOG_ENTRY_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_ENTRY, (const char *)packet, MAVLINK_MSG_ID_LOG_ENTRY_LEN);
#endif
#endif
}
#endif
#endif
// MESSAGE LOG_ENTRY UNPACKING
/**
* @brief Get field id from log_entry message
*
* @return Log id
*/
static inline uint16_t mavlink_msg_log_entry_get_id(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 8);
}
/**
* @brief Get field num_logs from log_entry message
*
* @return Total number of logs
*/
static inline uint16_t mavlink_msg_log_entry_get_num_logs(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 10);
}
/**
* @brief Get field last_log_num from log_entry message
*
* @return High log number
*/
static inline uint16_t mavlink_msg_log_entry_get_last_log_num(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 12);
}
/**
* @brief Get field time_utc from log_entry message
*
* @return UTC timestamp of log in seconds since 1970, or 0 if not available
*/
static inline uint32_t mavlink_msg_log_entry_get_time_utc(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint32_t(msg, 0);
}
/**
* @brief Get field size from log_entry message
*
* @return Size of the log (may be approximate) in bytes
*/
static inline uint32_t mavlink_msg_log_entry_get_size(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint32_t(msg, 4);
}
/**
* @brief Decode a log_entry message into a struct
*
* @param msg The message to decode
* @param log_entry C-struct to decode the message contents into
*/
static inline void mavlink_msg_log_entry_decode(const mavlink_message_t* msg, mavlink_log_entry_t* log_entry)
{
#if MAVLINK_NEED_BYTE_SWAP
log_entry->time_utc = mavlink_msg_log_entry_get_time_utc(msg);
log_entry->size = mavlink_msg_log_entry_get_size(msg);
log_entry->id = mavlink_msg_log_entry_get_id(msg);
log_entry->num_logs = mavlink_msg_log_entry_get_num_logs(msg);
log_entry->last_log_num = mavlink_msg_log_entry_get_last_log_num(msg);
#else
memcpy(log_entry, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_LOG_ENTRY_LEN);
#endif
}

View file

@ -0,0 +1,233 @@
// MESSAGE LOG_ERASE PACKING
#define MAVLINK_MSG_ID_LOG_ERASE 121
typedef struct __mavlink_log_erase_t
{
uint8_t target_system; ///< System ID
uint8_t target_component; ///< Component ID
} mavlink_log_erase_t;
#define MAVLINK_MSG_ID_LOG_ERASE_LEN 2
#define MAVLINK_MSG_ID_121_LEN 2
#define MAVLINK_MSG_ID_LOG_ERASE_CRC 237
#define MAVLINK_MSG_ID_121_CRC 237
#define MAVLINK_MESSAGE_INFO_LOG_ERASE { \
"LOG_ERASE", \
2, \
{ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_log_erase_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_log_erase_t, target_component) }, \
} \
}
/**
* @brief Pack a log_erase message
* @param system_id ID of this 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_log_erase_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[MAVLINK_MSG_ID_LOG_ERASE_LEN];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOG_ERASE_LEN);
#else
mavlink_log_erase_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOG_ERASE_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_LOG_ERASE;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LOG_ERASE_LEN, MAVLINK_MSG_ID_LOG_ERASE_CRC);
#else
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LOG_ERASE_LEN);
#endif
}
/**
* @brief Pack a log_erase 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 will be 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_log_erase_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[MAVLINK_MSG_ID_LOG_ERASE_LEN];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOG_ERASE_LEN);
#else
mavlink_log_erase_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOG_ERASE_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_LOG_ERASE;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LOG_ERASE_LEN, MAVLINK_MSG_ID_LOG_ERASE_CRC);
#else
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LOG_ERASE_LEN);
#endif
}
/**
* @brief Encode a log_erase struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param log_erase C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_log_erase_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_log_erase_t* log_erase)
{
return mavlink_msg_log_erase_pack(system_id, component_id, msg, log_erase->target_system, log_erase->target_component);
}
/**
* @brief Encode a log_erase struct 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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param log_erase C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_log_erase_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_log_erase_t* log_erase)
{
return mavlink_msg_log_erase_pack_chan(system_id, component_id, chan, msg, log_erase->target_system, log_erase->target_component);
}
/**
* @brief Send a log_erase 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_log_erase_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_LOG_ERASE_LEN];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_ERASE, buf, MAVLINK_MSG_ID_LOG_ERASE_LEN, MAVLINK_MSG_ID_LOG_ERASE_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_ERASE, buf, MAVLINK_MSG_ID_LOG_ERASE_LEN);
#endif
#else
mavlink_log_erase_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_ERASE, (const char *)&packet, MAVLINK_MSG_ID_LOG_ERASE_LEN, MAVLINK_MSG_ID_LOG_ERASE_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_ERASE, (const char *)&packet, MAVLINK_MSG_ID_LOG_ERASE_LEN);
#endif
#endif
}
#if MAVLINK_MSG_ID_LOG_ERASE_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This varient of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_log_erase_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_ERASE, buf, MAVLINK_MSG_ID_LOG_ERASE_LEN, MAVLINK_MSG_ID_LOG_ERASE_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_ERASE, buf, MAVLINK_MSG_ID_LOG_ERASE_LEN);
#endif
#else
mavlink_log_erase_t *packet = (mavlink_log_erase_t *)msgbuf;
packet->target_system = target_system;
packet->target_component = target_component;
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_ERASE, (const char *)packet, MAVLINK_MSG_ID_LOG_ERASE_LEN, MAVLINK_MSG_ID_LOG_ERASE_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_ERASE, (const char *)packet, MAVLINK_MSG_ID_LOG_ERASE_LEN);
#endif
#endif
}
#endif
#endif
// MESSAGE LOG_ERASE UNPACKING
/**
* @brief Get field target_system from log_erase message
*
* @return System ID
*/
static inline uint8_t mavlink_msg_log_erase_get_target_system(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 0);
}
/**
* @brief Get field target_component from log_erase message
*
* @return Component ID
*/
static inline uint8_t mavlink_msg_log_erase_get_target_component(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 1);
}
/**
* @brief Decode a log_erase message into a struct
*
* @param msg The message to decode
* @param log_erase C-struct to decode the message contents into
*/
static inline void mavlink_msg_log_erase_decode(const mavlink_message_t* msg, mavlink_log_erase_t* log_erase)
{
#if MAVLINK_NEED_BYTE_SWAP
log_erase->target_system = mavlink_msg_log_erase_get_target_system(msg);
log_erase->target_component = mavlink_msg_log_erase_get_target_component(msg);
#else
memcpy(log_erase, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_LOG_ERASE_LEN);
#endif
}

View file

@ -0,0 +1,305 @@
// MESSAGE LOG_REQUEST_DATA PACKING
#define MAVLINK_MSG_ID_LOG_REQUEST_DATA 119
typedef struct __mavlink_log_request_data_t
{
uint32_t ofs; ///< Offset into the log
uint32_t count; ///< Number of bytes
uint16_t id; ///< Log id (from LOG_ENTRY reply)
uint8_t target_system; ///< System ID
uint8_t target_component; ///< Component ID
} mavlink_log_request_data_t;
#define MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN 12
#define MAVLINK_MSG_ID_119_LEN 12
#define MAVLINK_MSG_ID_LOG_REQUEST_DATA_CRC 116
#define MAVLINK_MSG_ID_119_CRC 116
#define MAVLINK_MESSAGE_INFO_LOG_REQUEST_DATA { \
"LOG_REQUEST_DATA", \
5, \
{ { "ofs", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_log_request_data_t, ofs) }, \
{ "count", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_log_request_data_t, count) }, \
{ "id", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_log_request_data_t, id) }, \
{ "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_log_request_data_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 11, offsetof(mavlink_log_request_data_t, target_component) }, \
} \
}
/**
* @brief Pack a log_request_data message
* @param system_id ID of this 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 id Log id (from LOG_ENTRY reply)
* @param ofs Offset into the log
* @param count Number of bytes
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_log_request_data_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t target_system, uint8_t target_component, uint16_t id, uint32_t ofs, uint32_t count)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN];
_mav_put_uint32_t(buf, 0, ofs);
_mav_put_uint32_t(buf, 4, count);
_mav_put_uint16_t(buf, 8, id);
_mav_put_uint8_t(buf, 10, target_system);
_mav_put_uint8_t(buf, 11, target_component);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN);
#else
mavlink_log_request_data_t packet;
packet.ofs = ofs;
packet.count = count;
packet.id = id;
packet.target_system = target_system;
packet.target_component = target_component;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_LOG_REQUEST_DATA;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN, MAVLINK_MSG_ID_LOG_REQUEST_DATA_CRC);
#else
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN);
#endif
}
/**
* @brief Pack a log_request_data 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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param target_system System ID
* @param target_component Component ID
* @param id Log id (from LOG_ENTRY reply)
* @param ofs Offset into the log
* @param count Number of bytes
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_log_request_data_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint8_t target_system,uint8_t target_component,uint16_t id,uint32_t ofs,uint32_t count)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN];
_mav_put_uint32_t(buf, 0, ofs);
_mav_put_uint32_t(buf, 4, count);
_mav_put_uint16_t(buf, 8, id);
_mav_put_uint8_t(buf, 10, target_system);
_mav_put_uint8_t(buf, 11, target_component);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN);
#else
mavlink_log_request_data_t packet;
packet.ofs = ofs;
packet.count = count;
packet.id = id;
packet.target_system = target_system;
packet.target_component = target_component;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_LOG_REQUEST_DATA;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN, MAVLINK_MSG_ID_LOG_REQUEST_DATA_CRC);
#else
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN);
#endif
}
/**
* @brief Encode a log_request_data struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param log_request_data C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_log_request_data_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_log_request_data_t* log_request_data)
{
return mavlink_msg_log_request_data_pack(system_id, component_id, msg, log_request_data->target_system, log_request_data->target_component, log_request_data->id, log_request_data->ofs, log_request_data->count);
}
/**
* @brief Encode a log_request_data struct 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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param log_request_data C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_log_request_data_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_log_request_data_t* log_request_data)
{
return mavlink_msg_log_request_data_pack_chan(system_id, component_id, chan, msg, log_request_data->target_system, log_request_data->target_component, log_request_data->id, log_request_data->ofs, log_request_data->count);
}
/**
* @brief Send a log_request_data message
* @param chan MAVLink channel to send the message
*
* @param target_system System ID
* @param target_component Component ID
* @param id Log id (from LOG_ENTRY reply)
* @param ofs Offset into the log
* @param count Number of bytes
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_log_request_data_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t id, uint32_t ofs, uint32_t count)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN];
_mav_put_uint32_t(buf, 0, ofs);
_mav_put_uint32_t(buf, 4, count);
_mav_put_uint16_t(buf, 8, id);
_mav_put_uint8_t(buf, 10, target_system);
_mav_put_uint8_t(buf, 11, target_component);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_DATA, buf, MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN, MAVLINK_MSG_ID_LOG_REQUEST_DATA_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_DATA, buf, MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN);
#endif
#else
mavlink_log_request_data_t packet;
packet.ofs = ofs;
packet.count = count;
packet.id = id;
packet.target_system = target_system;
packet.target_component = target_component;
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_DATA, (const char *)&packet, MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN, MAVLINK_MSG_ID_LOG_REQUEST_DATA_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_DATA, (const char *)&packet, MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN);
#endif
#endif
}
#if MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This varient of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_log_request_data_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t id, uint32_t ofs, uint32_t count)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
_mav_put_uint32_t(buf, 0, ofs);
_mav_put_uint32_t(buf, 4, count);
_mav_put_uint16_t(buf, 8, id);
_mav_put_uint8_t(buf, 10, target_system);
_mav_put_uint8_t(buf, 11, target_component);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_DATA, buf, MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN, MAVLINK_MSG_ID_LOG_REQUEST_DATA_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_DATA, buf, MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN);
#endif
#else
mavlink_log_request_data_t *packet = (mavlink_log_request_data_t *)msgbuf;
packet->ofs = ofs;
packet->count = count;
packet->id = id;
packet->target_system = target_system;
packet->target_component = target_component;
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_DATA, (const char *)packet, MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN, MAVLINK_MSG_ID_LOG_REQUEST_DATA_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_DATA, (const char *)packet, MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN);
#endif
#endif
}
#endif
#endif
// MESSAGE LOG_REQUEST_DATA UNPACKING
/**
* @brief Get field target_system from log_request_data message
*
* @return System ID
*/
static inline uint8_t mavlink_msg_log_request_data_get_target_system(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 10);
}
/**
* @brief Get field target_component from log_request_data message
*
* @return Component ID
*/
static inline uint8_t mavlink_msg_log_request_data_get_target_component(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 11);
}
/**
* @brief Get field id from log_request_data message
*
* @return Log id (from LOG_ENTRY reply)
*/
static inline uint16_t mavlink_msg_log_request_data_get_id(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 8);
}
/**
* @brief Get field ofs from log_request_data message
*
* @return Offset into the log
*/
static inline uint32_t mavlink_msg_log_request_data_get_ofs(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint32_t(msg, 0);
}
/**
* @brief Get field count from log_request_data message
*
* @return Number of bytes
*/
static inline uint32_t mavlink_msg_log_request_data_get_count(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint32_t(msg, 4);
}
/**
* @brief Decode a log_request_data message into a struct
*
* @param msg The message to decode
* @param log_request_data C-struct to decode the message contents into
*/
static inline void mavlink_msg_log_request_data_decode(const mavlink_message_t* msg, mavlink_log_request_data_t* log_request_data)
{
#if MAVLINK_NEED_BYTE_SWAP
log_request_data->ofs = mavlink_msg_log_request_data_get_ofs(msg);
log_request_data->count = mavlink_msg_log_request_data_get_count(msg);
log_request_data->id = mavlink_msg_log_request_data_get_id(msg);
log_request_data->target_system = mavlink_msg_log_request_data_get_target_system(msg);
log_request_data->target_component = mavlink_msg_log_request_data_get_target_component(msg);
#else
memcpy(log_request_data, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_LOG_REQUEST_DATA_LEN);
#endif
}

View file

@ -0,0 +1,233 @@
// MESSAGE LOG_REQUEST_END PACKING
#define MAVLINK_MSG_ID_LOG_REQUEST_END 122
typedef struct __mavlink_log_request_end_t
{
uint8_t target_system; ///< System ID
uint8_t target_component; ///< Component ID
} mavlink_log_request_end_t;
#define MAVLINK_MSG_ID_LOG_REQUEST_END_LEN 2
#define MAVLINK_MSG_ID_122_LEN 2
#define MAVLINK_MSG_ID_LOG_REQUEST_END_CRC 203
#define MAVLINK_MSG_ID_122_CRC 203
#define MAVLINK_MESSAGE_INFO_LOG_REQUEST_END { \
"LOG_REQUEST_END", \
2, \
{ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_log_request_end_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_log_request_end_t, target_component) }, \
} \
}
/**
* @brief Pack a log_request_end message
* @param system_id ID of this 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_log_request_end_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[MAVLINK_MSG_ID_LOG_REQUEST_END_LEN];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOG_REQUEST_END_LEN);
#else
mavlink_log_request_end_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOG_REQUEST_END_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_LOG_REQUEST_END;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LOG_REQUEST_END_LEN, MAVLINK_MSG_ID_LOG_REQUEST_END_CRC);
#else
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LOG_REQUEST_END_LEN);
#endif
}
/**
* @brief Pack a log_request_end 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 will be 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_log_request_end_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[MAVLINK_MSG_ID_LOG_REQUEST_END_LEN];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOG_REQUEST_END_LEN);
#else
mavlink_log_request_end_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOG_REQUEST_END_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_LOG_REQUEST_END;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LOG_REQUEST_END_LEN, MAVLINK_MSG_ID_LOG_REQUEST_END_CRC);
#else
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LOG_REQUEST_END_LEN);
#endif
}
/**
* @brief Encode a log_request_end struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param log_request_end C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_log_request_end_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_log_request_end_t* log_request_end)
{
return mavlink_msg_log_request_end_pack(system_id, component_id, msg, log_request_end->target_system, log_request_end->target_component);
}
/**
* @brief Encode a log_request_end struct 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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param log_request_end C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_log_request_end_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_log_request_end_t* log_request_end)
{
return mavlink_msg_log_request_end_pack_chan(system_id, component_id, chan, msg, log_request_end->target_system, log_request_end->target_component);
}
/**
* @brief Send a log_request_end 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_log_request_end_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_LOG_REQUEST_END_LEN];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_END, buf, MAVLINK_MSG_ID_LOG_REQUEST_END_LEN, MAVLINK_MSG_ID_LOG_REQUEST_END_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_END, buf, MAVLINK_MSG_ID_LOG_REQUEST_END_LEN);
#endif
#else
mavlink_log_request_end_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_END, (const char *)&packet, MAVLINK_MSG_ID_LOG_REQUEST_END_LEN, MAVLINK_MSG_ID_LOG_REQUEST_END_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_END, (const char *)&packet, MAVLINK_MSG_ID_LOG_REQUEST_END_LEN);
#endif
#endif
}
#if MAVLINK_MSG_ID_LOG_REQUEST_END_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This varient of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_log_request_end_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_END, buf, MAVLINK_MSG_ID_LOG_REQUEST_END_LEN, MAVLINK_MSG_ID_LOG_REQUEST_END_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_END, buf, MAVLINK_MSG_ID_LOG_REQUEST_END_LEN);
#endif
#else
mavlink_log_request_end_t *packet = (mavlink_log_request_end_t *)msgbuf;
packet->target_system = target_system;
packet->target_component = target_component;
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_END, (const char *)packet, MAVLINK_MSG_ID_LOG_REQUEST_END_LEN, MAVLINK_MSG_ID_LOG_REQUEST_END_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_END, (const char *)packet, MAVLINK_MSG_ID_LOG_REQUEST_END_LEN);
#endif
#endif
}
#endif
#endif
// MESSAGE LOG_REQUEST_END UNPACKING
/**
* @brief Get field target_system from log_request_end message
*
* @return System ID
*/
static inline uint8_t mavlink_msg_log_request_end_get_target_system(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 0);
}
/**
* @brief Get field target_component from log_request_end message
*
* @return Component ID
*/
static inline uint8_t mavlink_msg_log_request_end_get_target_component(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 1);
}
/**
* @brief Decode a log_request_end message into a struct
*
* @param msg The message to decode
* @param log_request_end C-struct to decode the message contents into
*/
static inline void mavlink_msg_log_request_end_decode(const mavlink_message_t* msg, mavlink_log_request_end_t* log_request_end)
{
#if MAVLINK_NEED_BYTE_SWAP
log_request_end->target_system = mavlink_msg_log_request_end_get_target_system(msg);
log_request_end->target_component = mavlink_msg_log_request_end_get_target_component(msg);
#else
memcpy(log_request_end, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_LOG_REQUEST_END_LEN);
#endif
}

View file

@ -0,0 +1,281 @@
// MESSAGE LOG_REQUEST_LIST PACKING
#define MAVLINK_MSG_ID_LOG_REQUEST_LIST 117
typedef struct __mavlink_log_request_list_t
{
uint16_t start; ///< First log id (0 for first available)
uint16_t end; ///< Last log id (0xffff for last available)
uint8_t target_system; ///< System ID
uint8_t target_component; ///< Component ID
} mavlink_log_request_list_t;
#define MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN 6
#define MAVLINK_MSG_ID_117_LEN 6
#define MAVLINK_MSG_ID_LOG_REQUEST_LIST_CRC 128
#define MAVLINK_MSG_ID_117_CRC 128
#define MAVLINK_MESSAGE_INFO_LOG_REQUEST_LIST { \
"LOG_REQUEST_LIST", \
4, \
{ { "start", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_log_request_list_t, start) }, \
{ "end", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_log_request_list_t, end) }, \
{ "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_log_request_list_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_log_request_list_t, target_component) }, \
} \
}
/**
* @brief Pack a log_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
* @param start First log id (0 for first available)
* @param end Last log id (0xffff for last available)
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_log_request_list_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t target_system, uint8_t target_component, uint16_t start, uint16_t end)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN];
_mav_put_uint16_t(buf, 0, start);
_mav_put_uint16_t(buf, 2, end);
_mav_put_uint8_t(buf, 4, target_system);
_mav_put_uint8_t(buf, 5, target_component);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN);
#else
mavlink_log_request_list_t packet;
packet.start = start;
packet.end = end;
packet.target_system = target_system;
packet.target_component = target_component;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_LOG_REQUEST_LIST;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN, MAVLINK_MSG_ID_LOG_REQUEST_LIST_CRC);
#else
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN);
#endif
}
/**
* @brief Pack a log_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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param target_system System ID
* @param target_component Component ID
* @param start First log id (0 for first available)
* @param end Last log id (0xffff for last available)
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_log_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,uint16_t start,uint16_t end)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN];
_mav_put_uint16_t(buf, 0, start);
_mav_put_uint16_t(buf, 2, end);
_mav_put_uint8_t(buf, 4, target_system);
_mav_put_uint8_t(buf, 5, target_component);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN);
#else
mavlink_log_request_list_t packet;
packet.start = start;
packet.end = end;
packet.target_system = target_system;
packet.target_component = target_component;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_LOG_REQUEST_LIST;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN, MAVLINK_MSG_ID_LOG_REQUEST_LIST_CRC);
#else
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN);
#endif
}
/**
* @brief Encode a log_request_list struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param log_request_list C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_log_request_list_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_log_request_list_t* log_request_list)
{
return mavlink_msg_log_request_list_pack(system_id, component_id, msg, log_request_list->target_system, log_request_list->target_component, log_request_list->start, log_request_list->end);
}
/**
* @brief Encode a log_request_list struct 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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param log_request_list C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_log_request_list_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_log_request_list_t* log_request_list)
{
return mavlink_msg_log_request_list_pack_chan(system_id, component_id, chan, msg, log_request_list->target_system, log_request_list->target_component, log_request_list->start, log_request_list->end);
}
/**
* @brief Send a log_request_list message
* @param chan MAVLink channel to send the message
*
* @param target_system System ID
* @param target_component Component ID
* @param start First log id (0 for first available)
* @param end Last log id (0xffff for last available)
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_log_request_list_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t start, uint16_t end)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN];
_mav_put_uint16_t(buf, 0, start);
_mav_put_uint16_t(buf, 2, end);
_mav_put_uint8_t(buf, 4, target_system);
_mav_put_uint8_t(buf, 5, target_component);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_LIST, buf, MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN, MAVLINK_MSG_ID_LOG_REQUEST_LIST_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_LIST, buf, MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN);
#endif
#else
mavlink_log_request_list_t packet;
packet.start = start;
packet.end = end;
packet.target_system = target_system;
packet.target_component = target_component;
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_LIST, (const char *)&packet, MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN, MAVLINK_MSG_ID_LOG_REQUEST_LIST_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_LIST, (const char *)&packet, MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN);
#endif
#endif
}
#if MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This varient of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_log_request_list_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t start, uint16_t end)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
_mav_put_uint16_t(buf, 0, start);
_mav_put_uint16_t(buf, 2, end);
_mav_put_uint8_t(buf, 4, target_system);
_mav_put_uint8_t(buf, 5, target_component);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_LIST, buf, MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN, MAVLINK_MSG_ID_LOG_REQUEST_LIST_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_LIST, buf, MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN);
#endif
#else
mavlink_log_request_list_t *packet = (mavlink_log_request_list_t *)msgbuf;
packet->start = start;
packet->end = end;
packet->target_system = target_system;
packet->target_component = target_component;
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_LIST, (const char *)packet, MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN, MAVLINK_MSG_ID_LOG_REQUEST_LIST_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOG_REQUEST_LIST, (const char *)packet, MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN);
#endif
#endif
}
#endif
#endif
// MESSAGE LOG_REQUEST_LIST UNPACKING
/**
* @brief Get field target_system from log_request_list message
*
* @return System ID
*/
static inline uint8_t mavlink_msg_log_request_list_get_target_system(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 4);
}
/**
* @brief Get field target_component from log_request_list message
*
* @return Component ID
*/
static inline uint8_t mavlink_msg_log_request_list_get_target_component(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 5);
}
/**
* @brief Get field start from log_request_list message
*
* @return First log id (0 for first available)
*/
static inline uint16_t mavlink_msg_log_request_list_get_start(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 0);
}
/**
* @brief Get field end from log_request_list message
*
* @return Last log id (0xffff for last available)
*/
static inline uint16_t mavlink_msg_log_request_list_get_end(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 2);
}
/**
* @brief Decode a log_request_list message into a struct
*
* @param msg The message to decode
* @param log_request_list C-struct to decode the message contents into
*/
static inline void mavlink_msg_log_request_list_decode(const mavlink_message_t* msg, mavlink_log_request_list_t* log_request_list)
{
#if MAVLINK_NEED_BYTE_SWAP
log_request_list->start = mavlink_msg_log_request_list_get_start(msg);
log_request_list->end = mavlink_msg_log_request_list_get_end(msg);
log_request_list->target_system = mavlink_msg_log_request_list_get_target_system(msg);
log_request_list->target_component = mavlink_msg_log_request_list_get_target_component(msg);
#else
memcpy(log_request_list, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_LOG_REQUEST_LIST_LEN);
#endif
}

View file

@ -0,0 +1,329 @@
// MESSAGE MANUAL_CONTROL PACKING
#define MAVLINK_MSG_ID_MANUAL_CONTROL 69
typedef struct __mavlink_manual_control_t
{
int16_t x; ///< X-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to forward(1000)-backward(-1000) movement on a joystick and the pitch of a vehicle.
int16_t y; ///< Y-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to left(-1000)-right(1000) movement on a joystick and the roll of a vehicle.
int16_t z; ///< Z-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a separate slider movement with maximum being 1000 and minimum being -1000 on a joystick and the thrust of a vehicle.
int16_t r; ///< R-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a twisting of the joystick, with counter-clockwise being 1000 and clockwise being -1000, and the yaw of a vehicle.
uint16_t buttons; ///< A bitfield corresponding to the joystick buttons' current state, 1 for pressed, 0 for released. The lowest bit corresponds to Button 1.
uint8_t target; ///< The system to be controlled.
} mavlink_manual_control_t;
#define MAVLINK_MSG_ID_MANUAL_CONTROL_LEN 11
#define MAVLINK_MSG_ID_69_LEN 11
#define MAVLINK_MSG_ID_MANUAL_CONTROL_CRC 243
#define MAVLINK_MSG_ID_69_CRC 243
#define MAVLINK_MESSAGE_INFO_MANUAL_CONTROL { \
"MANUAL_CONTROL", \
6, \
{ { "x", NULL, MAVLINK_TYPE_INT16_T, 0, 0, offsetof(mavlink_manual_control_t, x) }, \
{ "y", NULL, MAVLINK_TYPE_INT16_T, 0, 2, offsetof(mavlink_manual_control_t, y) }, \
{ "z", NULL, MAVLINK_TYPE_INT16_T, 0, 4, offsetof(mavlink_manual_control_t, z) }, \
{ "r", NULL, MAVLINK_TYPE_INT16_T, 0, 6, offsetof(mavlink_manual_control_t, r) }, \
{ "buttons", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_manual_control_t, buttons) }, \
{ "target", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_manual_control_t, target) }, \
} \
}
/**
* @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 x X-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to forward(1000)-backward(-1000) movement on a joystick and the pitch of a vehicle.
* @param y Y-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to left(-1000)-right(1000) movement on a joystick and the roll of a vehicle.
* @param z Z-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a separate slider movement with maximum being 1000 and minimum being -1000 on a joystick and the thrust of a vehicle.
* @param r R-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a twisting of the joystick, with counter-clockwise being 1000 and clockwise being -1000, and the yaw of a vehicle.
* @param buttons A bitfield corresponding to the joystick buttons' current state, 1 for pressed, 0 for released. The lowest bit corresponds to Button 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, int16_t x, int16_t y, int16_t z, int16_t r, uint16_t buttons)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_MANUAL_CONTROL_LEN];
_mav_put_int16_t(buf, 0, x);
_mav_put_int16_t(buf, 2, y);
_mav_put_int16_t(buf, 4, z);
_mav_put_int16_t(buf, 6, r);
_mav_put_uint16_t(buf, 8, buttons);
_mav_put_uint8_t(buf, 10, target);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MANUAL_CONTROL_LEN);
#else
mavlink_manual_control_t packet;
packet.x = x;
packet.y = y;
packet.z = z;
packet.r = r;
packet.buttons = buttons;
packet.target = target;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MANUAL_CONTROL_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_MANUAL_CONTROL;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MANUAL_CONTROL_LEN, MAVLINK_MSG_ID_MANUAL_CONTROL_CRC);
#else
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MANUAL_CONTROL_LEN);
#endif
}
/**
* @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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param target The system to be controlled.
* @param x X-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to forward(1000)-backward(-1000) movement on a joystick and the pitch of a vehicle.
* @param y Y-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to left(-1000)-right(1000) movement on a joystick and the roll of a vehicle.
* @param z Z-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a separate slider movement with maximum being 1000 and minimum being -1000 on a joystick and the thrust of a vehicle.
* @param r R-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a twisting of the joystick, with counter-clockwise being 1000 and clockwise being -1000, and the yaw of a vehicle.
* @param buttons A bitfield corresponding to the joystick buttons' current state, 1 for pressed, 0 for released. The lowest bit corresponds to Button 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,int16_t x,int16_t y,int16_t z,int16_t r,uint16_t buttons)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_MANUAL_CONTROL_LEN];
_mav_put_int16_t(buf, 0, x);
_mav_put_int16_t(buf, 2, y);
_mav_put_int16_t(buf, 4, z);
_mav_put_int16_t(buf, 6, r);
_mav_put_uint16_t(buf, 8, buttons);
_mav_put_uint8_t(buf, 10, target);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MANUAL_CONTROL_LEN);
#else
mavlink_manual_control_t packet;
packet.x = x;
packet.y = y;
packet.z = z;
packet.r = r;
packet.buttons = buttons;
packet.target = target;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MANUAL_CONTROL_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_MANUAL_CONTROL;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MANUAL_CONTROL_LEN, MAVLINK_MSG_ID_MANUAL_CONTROL_CRC);
#else
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MANUAL_CONTROL_LEN);
#endif
}
/**
* @brief Encode a manual_control struct
*
* @param system_id ID of this 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->x, manual_control->y, manual_control->z, manual_control->r, manual_control->buttons);
}
/**
* @brief Encode a manual_control struct 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 will be sent over
* @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_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_manual_control_t* manual_control)
{
return mavlink_msg_manual_control_pack_chan(system_id, component_id, chan, msg, manual_control->target, manual_control->x, manual_control->y, manual_control->z, manual_control->r, manual_control->buttons);
}
/**
* @brief Send a manual_control message
* @param chan MAVLink channel to send the message
*
* @param target The system to be controlled.
* @param x X-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to forward(1000)-backward(-1000) movement on a joystick and the pitch of a vehicle.
* @param y Y-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to left(-1000)-right(1000) movement on a joystick and the roll of a vehicle.
* @param z Z-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a separate slider movement with maximum being 1000 and minimum being -1000 on a joystick and the thrust of a vehicle.
* @param r R-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a twisting of the joystick, with counter-clockwise being 1000 and clockwise being -1000, and the yaw of a vehicle.
* @param buttons A bitfield corresponding to the joystick buttons' current state, 1 for pressed, 0 for released. The lowest bit corresponds to Button 1.
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_manual_control_send(mavlink_channel_t chan, uint8_t target, int16_t x, int16_t y, int16_t z, int16_t r, uint16_t buttons)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_MANUAL_CONTROL_LEN];
_mav_put_int16_t(buf, 0, x);
_mav_put_int16_t(buf, 2, y);
_mav_put_int16_t(buf, 4, z);
_mav_put_int16_t(buf, 6, r);
_mav_put_uint16_t(buf, 8, buttons);
_mav_put_uint8_t(buf, 10, target);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MANUAL_CONTROL, buf, MAVLINK_MSG_ID_MANUAL_CONTROL_LEN, MAVLINK_MSG_ID_MANUAL_CONTROL_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MANUAL_CONTROL, buf, MAVLINK_MSG_ID_MANUAL_CONTROL_LEN);
#endif
#else
mavlink_manual_control_t packet;
packet.x = x;
packet.y = y;
packet.z = z;
packet.r = r;
packet.buttons = buttons;
packet.target = target;
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MANUAL_CONTROL, (const char *)&packet, MAVLINK_MSG_ID_MANUAL_CONTROL_LEN, MAVLINK_MSG_ID_MANUAL_CONTROL_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MANUAL_CONTROL, (const char *)&packet, MAVLINK_MSG_ID_MANUAL_CONTROL_LEN);
#endif
#endif
}
#if MAVLINK_MSG_ID_MANUAL_CONTROL_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This varient of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_manual_control_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target, int16_t x, int16_t y, int16_t z, int16_t r, uint16_t buttons)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
_mav_put_int16_t(buf, 0, x);
_mav_put_int16_t(buf, 2, y);
_mav_put_int16_t(buf, 4, z);
_mav_put_int16_t(buf, 6, r);
_mav_put_uint16_t(buf, 8, buttons);
_mav_put_uint8_t(buf, 10, target);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MANUAL_CONTROL, buf, MAVLINK_MSG_ID_MANUAL_CONTROL_LEN, MAVLINK_MSG_ID_MANUAL_CONTROL_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MANUAL_CONTROL, buf, MAVLINK_MSG_ID_MANUAL_CONTROL_LEN);
#endif
#else
mavlink_manual_control_t *packet = (mavlink_manual_control_t *)msgbuf;
packet->x = x;
packet->y = y;
packet->z = z;
packet->r = r;
packet->buttons = buttons;
packet->target = target;
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MANUAL_CONTROL, (const char *)packet, MAVLINK_MSG_ID_MANUAL_CONTROL_LEN, MAVLINK_MSG_ID_MANUAL_CONTROL_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MANUAL_CONTROL, (const char *)packet, MAVLINK_MSG_ID_MANUAL_CONTROL_LEN);
#endif
#endif
}
#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, 10);
}
/**
* @brief Get field x from manual_control message
*
* @return X-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to forward(1000)-backward(-1000) movement on a joystick and the pitch of a vehicle.
*/
static inline int16_t mavlink_msg_manual_control_get_x(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 0);
}
/**
* @brief Get field y from manual_control message
*
* @return Y-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to left(-1000)-right(1000) movement on a joystick and the roll of a vehicle.
*/
static inline int16_t mavlink_msg_manual_control_get_y(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 2);
}
/**
* @brief Get field z from manual_control message
*
* @return Z-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a separate slider movement with maximum being 1000 and minimum being -1000 on a joystick and the thrust of a vehicle.
*/
static inline int16_t mavlink_msg_manual_control_get_z(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 4);
}
/**
* @brief Get field r from manual_control message
*
* @return R-axis, normalized to the range [-1000,1000]. A value of INT16_MAX indicates that this axis is invalid. Generally corresponds to a twisting of the joystick, with counter-clockwise being 1000 and clockwise being -1000, and the yaw of a vehicle.
*/
static inline int16_t mavlink_msg_manual_control_get_r(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 6);
}
/**
* @brief Get field buttons from manual_control message
*
* @return A bitfield corresponding to the joystick buttons' current state, 1 for pressed, 0 for released. The lowest bit corresponds to Button 1.
*/
static inline uint16_t mavlink_msg_manual_control_get_buttons(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 8);
}
/**
* @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->x = mavlink_msg_manual_control_get_x(msg);
manual_control->y = mavlink_msg_manual_control_get_y(msg);
manual_control->z = mavlink_msg_manual_control_get_z(msg);
manual_control->r = mavlink_msg_manual_control_get_r(msg);
manual_control->buttons = mavlink_msg_manual_control_get_buttons(msg);
manual_control->target = mavlink_msg_manual_control_get_target(msg);
#else
memcpy(manual_control, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_MANUAL_CONTROL_LEN);
#endif
}

View file

@ -0,0 +1,353 @@
// MESSAGE MANUAL_SETPOINT PACKING
#define MAVLINK_MSG_ID_MANUAL_SETPOINT 81
typedef struct __mavlink_manual_setpoint_t
{
uint32_t time_boot_ms; ///< Timestamp in milliseconds since system boot
float roll; ///< Desired roll rate in radians per second
float pitch; ///< Desired pitch rate in radians per second
float yaw; ///< Desired yaw rate in radians per second
float thrust; ///< Collective thrust, normalized to 0 .. 1
uint8_t mode_switch; ///< Flight mode switch position, 0.. 255
uint8_t manual_override_switch; ///< Override mode switch position, 0.. 255
} mavlink_manual_setpoint_t;
#define MAVLINK_MSG_ID_MANUAL_SETPOINT_LEN 22
#define MAVLINK_MSG_ID_81_LEN 22
#define MAVLINK_MSG_ID_MANUAL_SETPOINT_CRC 106
#define MAVLINK_MSG_ID_81_CRC 106
#define MAVLINK_MESSAGE_INFO_MANUAL_SETPOINT { \
"MANUAL_SETPOINT", \
7, \
{ { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_manual_setpoint_t, time_boot_ms) }, \
{ "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_manual_setpoint_t, roll) }, \
{ "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_manual_setpoint_t, pitch) }, \
{ "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_manual_setpoint_t, yaw) }, \
{ "thrust", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_manual_setpoint_t, thrust) }, \
{ "mode_switch", NULL, MAVLINK_TYPE_UINT8_T, 0, 20, offsetof(mavlink_manual_setpoint_t, mode_switch) }, \
{ "manual_override_switch", NULL, MAVLINK_TYPE_UINT8_T, 0, 21, offsetof(mavlink_manual_setpoint_t, manual_override_switch) }, \
} \
}
/**
* @brief Pack a manual_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 rate in radians per second
* @param pitch Desired pitch rate in radians per second
* @param yaw Desired yaw rate in radians per second
* @param thrust Collective thrust, normalized to 0 .. 1
* @param mode_switch Flight mode switch position, 0.. 255
* @param manual_override_switch Override mode switch position, 0.. 255
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_manual_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, uint8_t mode_switch, uint8_t manual_override_switch)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_MANUAL_SETPOINT_LEN];
_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_put_uint8_t(buf, 20, mode_switch);
_mav_put_uint8_t(buf, 21, manual_override_switch);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MANUAL_SETPOINT_LEN);
#else
mavlink_manual_setpoint_t packet;
packet.time_boot_ms = time_boot_ms;
packet.roll = roll;
packet.pitch = pitch;
packet.yaw = yaw;
packet.thrust = thrust;
packet.mode_switch = mode_switch;
packet.manual_override_switch = manual_override_switch;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MANUAL_SETPOINT_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_MANUAL_SETPOINT;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MANUAL_SETPOINT_LEN, MAVLINK_MSG_ID_MANUAL_SETPOINT_CRC);
#else
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MANUAL_SETPOINT_LEN);
#endif
}
/**
* @brief Pack a manual_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 will be 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 rate in radians per second
* @param pitch Desired pitch rate in radians per second
* @param yaw Desired yaw rate in radians per second
* @param thrust Collective thrust, normalized to 0 .. 1
* @param mode_switch Flight mode switch position, 0.. 255
* @param manual_override_switch Override mode switch position, 0.. 255
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_manual_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,uint8_t mode_switch,uint8_t manual_override_switch)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_MANUAL_SETPOINT_LEN];
_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_put_uint8_t(buf, 20, mode_switch);
_mav_put_uint8_t(buf, 21, manual_override_switch);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MANUAL_SETPOINT_LEN);
#else
mavlink_manual_setpoint_t packet;
packet.time_boot_ms = time_boot_ms;
packet.roll = roll;
packet.pitch = pitch;
packet.yaw = yaw;
packet.thrust = thrust;
packet.mode_switch = mode_switch;
packet.manual_override_switch = manual_override_switch;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MANUAL_SETPOINT_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_MANUAL_SETPOINT;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MANUAL_SETPOINT_LEN, MAVLINK_MSG_ID_MANUAL_SETPOINT_CRC);
#else
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MANUAL_SETPOINT_LEN);
#endif
}
/**
* @brief Encode a manual_setpoint struct
*
* @param system_id ID of this 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_setpoint C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_manual_setpoint_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_manual_setpoint_t* manual_setpoint)
{
return mavlink_msg_manual_setpoint_pack(system_id, component_id, msg, manual_setpoint->time_boot_ms, manual_setpoint->roll, manual_setpoint->pitch, manual_setpoint->yaw, manual_setpoint->thrust, manual_setpoint->mode_switch, manual_setpoint->manual_override_switch);
}
/**
* @brief Encode a manual_setpoint struct 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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param manual_setpoint C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_manual_setpoint_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_manual_setpoint_t* manual_setpoint)
{
return mavlink_msg_manual_setpoint_pack_chan(system_id, component_id, chan, msg, manual_setpoint->time_boot_ms, manual_setpoint->roll, manual_setpoint->pitch, manual_setpoint->yaw, manual_setpoint->thrust, manual_setpoint->mode_switch, manual_setpoint->manual_override_switch);
}
/**
* @brief Send a manual_setpoint message
* @param chan MAVLink channel to send the message
*
* @param time_boot_ms Timestamp in milliseconds since system boot
* @param roll Desired roll rate in radians per second
* @param pitch Desired pitch rate in radians per second
* @param yaw Desired yaw rate in radians per second
* @param thrust Collective thrust, normalized to 0 .. 1
* @param mode_switch Flight mode switch position, 0.. 255
* @param manual_override_switch Override mode switch position, 0.. 255
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_manual_setpoint_send(mavlink_channel_t chan, uint32_t time_boot_ms, float roll, float pitch, float yaw, float thrust, uint8_t mode_switch, uint8_t manual_override_switch)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_MANUAL_SETPOINT_LEN];
_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_put_uint8_t(buf, 20, mode_switch);
_mav_put_uint8_t(buf, 21, manual_override_switch);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MANUAL_SETPOINT, buf, MAVLINK_MSG_ID_MANUAL_SETPOINT_LEN, MAVLINK_MSG_ID_MANUAL_SETPOINT_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MANUAL_SETPOINT, buf, MAVLINK_MSG_ID_MANUAL_SETPOINT_LEN);
#endif
#else
mavlink_manual_setpoint_t packet;
packet.time_boot_ms = time_boot_ms;
packet.roll = roll;
packet.pitch = pitch;
packet.yaw = yaw;
packet.thrust = thrust;
packet.mode_switch = mode_switch;
packet.manual_override_switch = manual_override_switch;
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MANUAL_SETPOINT, (const char *)&packet, MAVLINK_MSG_ID_MANUAL_SETPOINT_LEN, MAVLINK_MSG_ID_MANUAL_SETPOINT_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MANUAL_SETPOINT, (const char *)&packet, MAVLINK_MSG_ID_MANUAL_SETPOINT_LEN);
#endif
#endif
}
#if MAVLINK_MSG_ID_MANUAL_SETPOINT_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This varient of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_manual_setpoint_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, float roll, float pitch, float yaw, float thrust, uint8_t mode_switch, uint8_t manual_override_switch)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
_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_put_uint8_t(buf, 20, mode_switch);
_mav_put_uint8_t(buf, 21, manual_override_switch);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MANUAL_SETPOINT, buf, MAVLINK_MSG_ID_MANUAL_SETPOINT_LEN, MAVLINK_MSG_ID_MANUAL_SETPOINT_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MANUAL_SETPOINT, buf, MAVLINK_MSG_ID_MANUAL_SETPOINT_LEN);
#endif
#else
mavlink_manual_setpoint_t *packet = (mavlink_manual_setpoint_t *)msgbuf;
packet->time_boot_ms = time_boot_ms;
packet->roll = roll;
packet->pitch = pitch;
packet->yaw = yaw;
packet->thrust = thrust;
packet->mode_switch = mode_switch;
packet->manual_override_switch = manual_override_switch;
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MANUAL_SETPOINT, (const char *)packet, MAVLINK_MSG_ID_MANUAL_SETPOINT_LEN, MAVLINK_MSG_ID_MANUAL_SETPOINT_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MANUAL_SETPOINT, (const char *)packet, MAVLINK_MSG_ID_MANUAL_SETPOINT_LEN);
#endif
#endif
}
#endif
#endif
// MESSAGE MANUAL_SETPOINT UNPACKING
/**
* @brief Get field time_boot_ms from manual_setpoint message
*
* @return Timestamp in milliseconds since system boot
*/
static inline uint32_t mavlink_msg_manual_setpoint_get_time_boot_ms(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint32_t(msg, 0);
}
/**
* @brief Get field roll from manual_setpoint message
*
* @return Desired roll rate in radians per second
*/
static inline float mavlink_msg_manual_setpoint_get_roll(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 4);
}
/**
* @brief Get field pitch from manual_setpoint message
*
* @return Desired pitch rate in radians per second
*/
static inline float mavlink_msg_manual_setpoint_get_pitch(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 8);
}
/**
* @brief Get field yaw from manual_setpoint message
*
* @return Desired yaw rate in radians per second
*/
static inline float mavlink_msg_manual_setpoint_get_yaw(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 12);
}
/**
* @brief Get field thrust from manual_setpoint message
*
* @return Collective thrust, normalized to 0 .. 1
*/
static inline float mavlink_msg_manual_setpoint_get_thrust(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 16);
}
/**
* @brief Get field mode_switch from manual_setpoint message
*
* @return Flight mode switch position, 0.. 255
*/
static inline uint8_t mavlink_msg_manual_setpoint_get_mode_switch(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 20);
}
/**
* @brief Get field manual_override_switch from manual_setpoint message
*
* @return Override mode switch position, 0.. 255
*/
static inline uint8_t mavlink_msg_manual_setpoint_get_manual_override_switch(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 21);
}
/**
* @brief Decode a manual_setpoint message into a struct
*
* @param msg The message to decode
* @param manual_setpoint C-struct to decode the message contents into
*/
static inline void mavlink_msg_manual_setpoint_decode(const mavlink_message_t* msg, mavlink_manual_setpoint_t* manual_setpoint)
{
#if MAVLINK_NEED_BYTE_SWAP
manual_setpoint->time_boot_ms = mavlink_msg_manual_setpoint_get_time_boot_ms(msg);
manual_setpoint->roll = mavlink_msg_manual_setpoint_get_roll(msg);
manual_setpoint->pitch = mavlink_msg_manual_setpoint_get_pitch(msg);
manual_setpoint->yaw = mavlink_msg_manual_setpoint_get_yaw(msg);
manual_setpoint->thrust = mavlink_msg_manual_setpoint_get_thrust(msg);
manual_setpoint->mode_switch = mavlink_msg_manual_setpoint_get_mode_switch(msg);
manual_setpoint->manual_override_switch = mavlink_msg_manual_setpoint_get_manual_override_switch(msg);
#else
memcpy(manual_setpoint, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_MANUAL_SETPOINT_LEN);
#endif
}

View file

@ -0,0 +1,273 @@
// 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_ID_MEMORY_VECT_CRC 204
#define MAVLINK_MSG_ID_249_CRC 204
#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[MAVLINK_MSG_ID_MEMORY_VECT_LEN];
_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, MAVLINK_MSG_ID_MEMORY_VECT_LEN);
#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, MAVLINK_MSG_ID_MEMORY_VECT_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_MEMORY_VECT;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MEMORY_VECT_LEN, MAVLINK_MSG_ID_MEMORY_VECT_CRC);
#else
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MEMORY_VECT_LEN);
#endif
}
/**
* @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 will be 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[MAVLINK_MSG_ID_MEMORY_VECT_LEN];
_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, MAVLINK_MSG_ID_MEMORY_VECT_LEN);
#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, MAVLINK_MSG_ID_MEMORY_VECT_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_MEMORY_VECT;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MEMORY_VECT_LEN, MAVLINK_MSG_ID_MEMORY_VECT_CRC);
#else
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MEMORY_VECT_LEN);
#endif
}
/**
* @brief Encode a memory_vect struct
*
* @param system_id ID of this 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 Encode a memory_vect struct 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 will be sent over
* @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_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_memory_vect_t* memory_vect)
{
return mavlink_msg_memory_vect_pack_chan(system_id, component_id, chan, 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[MAVLINK_MSG_ID_MEMORY_VECT_LEN];
_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);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MEMORY_VECT, buf, MAVLINK_MSG_ID_MEMORY_VECT_LEN, MAVLINK_MSG_ID_MEMORY_VECT_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MEMORY_VECT, buf, MAVLINK_MSG_ID_MEMORY_VECT_LEN);
#endif
#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);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MEMORY_VECT, (const char *)&packet, MAVLINK_MSG_ID_MEMORY_VECT_LEN, MAVLINK_MSG_ID_MEMORY_VECT_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MEMORY_VECT, (const char *)&packet, MAVLINK_MSG_ID_MEMORY_VECT_LEN);
#endif
#endif
}
#if MAVLINK_MSG_ID_MEMORY_VECT_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This varient of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_memory_vect_send_buf(mavlink_message_t *msgbuf, 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 = (char *)msgbuf;
_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);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MEMORY_VECT, buf, MAVLINK_MSG_ID_MEMORY_VECT_LEN, MAVLINK_MSG_ID_MEMORY_VECT_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MEMORY_VECT, buf, MAVLINK_MSG_ID_MEMORY_VECT_LEN);
#endif
#else
mavlink_memory_vect_t *packet = (mavlink_memory_vect_t *)msgbuf;
packet->address = address;
packet->ver = ver;
packet->type = type;
mav_array_memcpy(packet->value, value, sizeof(int8_t)*32);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MEMORY_VECT, (const char *)packet, MAVLINK_MSG_ID_MEMORY_VECT_LEN, MAVLINK_MSG_ID_MEMORY_VECT_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MEMORY_VECT, (const char *)packet, MAVLINK_MSG_ID_MEMORY_VECT_LEN);
#endif
#endif
}
#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), MAVLINK_MSG_ID_MEMORY_VECT_LEN);
#endif
}

View file

@ -0,0 +1,257 @@
// 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_MSG_ID_MISSION_ACK_CRC 153
#define MAVLINK_MSG_ID_47_CRC 153
#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[MAVLINK_MSG_ID_MISSION_ACK_LEN];
_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, MAVLINK_MSG_ID_MISSION_ACK_LEN);
#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, MAVLINK_MSG_ID_MISSION_ACK_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_MISSION_ACK;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MISSION_ACK_LEN, MAVLINK_MSG_ID_MISSION_ACK_CRC);
#else
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MISSION_ACK_LEN);
#endif
}
/**
* @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 will be 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[MAVLINK_MSG_ID_MISSION_ACK_LEN];
_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, MAVLINK_MSG_ID_MISSION_ACK_LEN);
#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, MAVLINK_MSG_ID_MISSION_ACK_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_MISSION_ACK;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MISSION_ACK_LEN, MAVLINK_MSG_ID_MISSION_ACK_CRC);
#else
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MISSION_ACK_LEN);
#endif
}
/**
* @brief Encode a mission_ack struct
*
* @param system_id ID of this 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 Encode a mission_ack struct 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 will be sent over
* @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_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_mission_ack_t* mission_ack)
{
return mavlink_msg_mission_ack_pack_chan(system_id, component_id, chan, 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[MAVLINK_MSG_ID_MISSION_ACK_LEN];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
_mav_put_uint8_t(buf, 2, type);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ACK, buf, MAVLINK_MSG_ID_MISSION_ACK_LEN, MAVLINK_MSG_ID_MISSION_ACK_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ACK, buf, MAVLINK_MSG_ID_MISSION_ACK_LEN);
#endif
#else
mavlink_mission_ack_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
packet.type = type;
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ACK, (const char *)&packet, MAVLINK_MSG_ID_MISSION_ACK_LEN, MAVLINK_MSG_ID_MISSION_ACK_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ACK, (const char *)&packet, MAVLINK_MSG_ID_MISSION_ACK_LEN);
#endif
#endif
}
#if MAVLINK_MSG_ID_MISSION_ACK_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This varient of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_mission_ack_send_buf(mavlink_message_t *msgbuf, 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 = (char *)msgbuf;
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
_mav_put_uint8_t(buf, 2, type);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ACK, buf, MAVLINK_MSG_ID_MISSION_ACK_LEN, MAVLINK_MSG_ID_MISSION_ACK_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ACK, buf, MAVLINK_MSG_ID_MISSION_ACK_LEN);
#endif
#else
mavlink_mission_ack_t *packet = (mavlink_mission_ack_t *)msgbuf;
packet->target_system = target_system;
packet->target_component = target_component;
packet->type = type;
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ACK, (const char *)packet, MAVLINK_MSG_ID_MISSION_ACK_LEN, MAVLINK_MSG_ID_MISSION_ACK_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ACK, (const char *)packet, MAVLINK_MSG_ID_MISSION_ACK_LEN);
#endif
#endif
}
#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), MAVLINK_MSG_ID_MISSION_ACK_LEN);
#endif
}

View file

@ -0,0 +1,233 @@
// 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_MSG_ID_MISSION_CLEAR_ALL_CRC 232
#define MAVLINK_MSG_ID_45_CRC 232
#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[MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN);
#else
mavlink_mission_clear_all_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_MISSION_CLEAR_ALL;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_CRC);
#else
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN);
#endif
}
/**
* @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 will be 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[MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN);
#else
mavlink_mission_clear_all_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_MISSION_CLEAR_ALL;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_CRC);
#else
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN);
#endif
}
/**
* @brief Encode a mission_clear_all struct
*
* @param system_id ID of this 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 Encode a mission_clear_all struct 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 will be sent over
* @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_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_mission_clear_all_t* mission_clear_all)
{
return mavlink_msg_mission_clear_all_pack_chan(system_id, component_id, chan, 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[MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_CLEAR_ALL, buf, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_CLEAR_ALL, buf, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN);
#endif
#else
mavlink_mission_clear_all_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_CLEAR_ALL, (const char *)&packet, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_CLEAR_ALL, (const char *)&packet, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN);
#endif
#endif
}
#if MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This varient of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_mission_clear_all_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_CLEAR_ALL, buf, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_CLEAR_ALL, buf, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN);
#endif
#else
mavlink_mission_clear_all_t *packet = (mavlink_mission_clear_all_t *)msgbuf;
packet->target_system = target_system;
packet->target_component = target_component;
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_CLEAR_ALL, (const char *)packet, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_CLEAR_ALL, (const char *)packet, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN);
#endif
#endif
}
#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), MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN);
#endif
}

View file

@ -0,0 +1,257 @@
// 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_MSG_ID_MISSION_COUNT_CRC 221
#define MAVLINK_MSG_ID_44_CRC 221
#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[MAVLINK_MSG_ID_MISSION_COUNT_LEN];
_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, MAVLINK_MSG_ID_MISSION_COUNT_LEN);
#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, MAVLINK_MSG_ID_MISSION_COUNT_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_MISSION_COUNT;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MISSION_COUNT_LEN, MAVLINK_MSG_ID_MISSION_COUNT_CRC);
#else
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MISSION_COUNT_LEN);
#endif
}
/**
* @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 will be 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[MAVLINK_MSG_ID_MISSION_COUNT_LEN];
_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, MAVLINK_MSG_ID_MISSION_COUNT_LEN);
#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, MAVLINK_MSG_ID_MISSION_COUNT_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_MISSION_COUNT;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MISSION_COUNT_LEN, MAVLINK_MSG_ID_MISSION_COUNT_CRC);
#else
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MISSION_COUNT_LEN);
#endif
}
/**
* @brief Encode a mission_count struct
*
* @param system_id ID of this 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 Encode a mission_count struct 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 will be sent over
* @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_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_mission_count_t* mission_count)
{
return mavlink_msg_mission_count_pack_chan(system_id, component_id, chan, 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[MAVLINK_MSG_ID_MISSION_COUNT_LEN];
_mav_put_uint16_t(buf, 0, count);
_mav_put_uint8_t(buf, 2, target_system);
_mav_put_uint8_t(buf, 3, target_component);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_COUNT, buf, MAVLINK_MSG_ID_MISSION_COUNT_LEN, MAVLINK_MSG_ID_MISSION_COUNT_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_COUNT, buf, MAVLINK_MSG_ID_MISSION_COUNT_LEN);
#endif
#else
mavlink_mission_count_t packet;
packet.count = count;
packet.target_system = target_system;
packet.target_component = target_component;
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_COUNT, (const char *)&packet, MAVLINK_MSG_ID_MISSION_COUNT_LEN, MAVLINK_MSG_ID_MISSION_COUNT_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_COUNT, (const char *)&packet, MAVLINK_MSG_ID_MISSION_COUNT_LEN);
#endif
#endif
}
#if MAVLINK_MSG_ID_MISSION_COUNT_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This varient of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_mission_count_send_buf(mavlink_message_t *msgbuf, 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 = (char *)msgbuf;
_mav_put_uint16_t(buf, 0, count);
_mav_put_uint8_t(buf, 2, target_system);
_mav_put_uint8_t(buf, 3, target_component);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_COUNT, buf, MAVLINK_MSG_ID_MISSION_COUNT_LEN, MAVLINK_MSG_ID_MISSION_COUNT_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_COUNT, buf, MAVLINK_MSG_ID_MISSION_COUNT_LEN);
#endif
#else
mavlink_mission_count_t *packet = (mavlink_mission_count_t *)msgbuf;
packet->count = count;
packet->target_system = target_system;
packet->target_component = target_component;
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_COUNT, (const char *)packet, MAVLINK_MSG_ID_MISSION_COUNT_LEN, MAVLINK_MSG_ID_MISSION_COUNT_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_COUNT, (const char *)packet, MAVLINK_MSG_ID_MISSION_COUNT_LEN);
#endif
#endif
}
#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), MAVLINK_MSG_ID_MISSION_COUNT_LEN);
#endif
}

View file

@ -0,0 +1,209 @@
// 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_MSG_ID_MISSION_CURRENT_CRC 28
#define MAVLINK_MSG_ID_42_CRC 28
#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[MAVLINK_MSG_ID_MISSION_CURRENT_LEN];
_mav_put_uint16_t(buf, 0, seq);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_CURRENT_LEN);
#else
mavlink_mission_current_t packet;
packet.seq = seq;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_CURRENT_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_MISSION_CURRENT;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MISSION_CURRENT_LEN, MAVLINK_MSG_ID_MISSION_CURRENT_CRC);
#else
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MISSION_CURRENT_LEN);
#endif
}
/**
* @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 will be 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[MAVLINK_MSG_ID_MISSION_CURRENT_LEN];
_mav_put_uint16_t(buf, 0, seq);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_CURRENT_LEN);
#else
mavlink_mission_current_t packet;
packet.seq = seq;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_CURRENT_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_MISSION_CURRENT;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MISSION_CURRENT_LEN, MAVLINK_MSG_ID_MISSION_CURRENT_CRC);
#else
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MISSION_CURRENT_LEN);
#endif
}
/**
* @brief Encode a mission_current struct
*
* @param system_id ID of this 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 Encode a mission_current struct 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 will be sent over
* @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_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_mission_current_t* mission_current)
{
return mavlink_msg_mission_current_pack_chan(system_id, component_id, chan, 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[MAVLINK_MSG_ID_MISSION_CURRENT_LEN];
_mav_put_uint16_t(buf, 0, seq);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_CURRENT, buf, MAVLINK_MSG_ID_MISSION_CURRENT_LEN, MAVLINK_MSG_ID_MISSION_CURRENT_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_CURRENT, buf, MAVLINK_MSG_ID_MISSION_CURRENT_LEN);
#endif
#else
mavlink_mission_current_t packet;
packet.seq = seq;
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_CURRENT, (const char *)&packet, MAVLINK_MSG_ID_MISSION_CURRENT_LEN, MAVLINK_MSG_ID_MISSION_CURRENT_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_CURRENT, (const char *)&packet, MAVLINK_MSG_ID_MISSION_CURRENT_LEN);
#endif
#endif
}
#if MAVLINK_MSG_ID_MISSION_CURRENT_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This varient of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_mission_current_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint16_t seq)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
_mav_put_uint16_t(buf, 0, seq);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_CURRENT, buf, MAVLINK_MSG_ID_MISSION_CURRENT_LEN, MAVLINK_MSG_ID_MISSION_CURRENT_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_CURRENT, buf, MAVLINK_MSG_ID_MISSION_CURRENT_LEN);
#endif
#else
mavlink_mission_current_t *packet = (mavlink_mission_current_t *)msgbuf;
packet->seq = seq;
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_CURRENT, (const char *)packet, MAVLINK_MSG_ID_MISSION_CURRENT_LEN, MAVLINK_MSG_ID_MISSION_CURRENT_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_CURRENT, (const char *)packet, MAVLINK_MSG_ID_MISSION_CURRENT_LEN);
#endif
#endif
}
#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), MAVLINK_MSG_ID_MISSION_CURRENT_LEN);
#endif
}

View file

@ -0,0 +1,521 @@
// MESSAGE MISSION_ITEM PACKING
#define MAVLINK_MSG_ID_MISSION_ITEM 39
typedef struct __mavlink_mission_item_t
{
float param1; ///< PARAM1, see MAV_CMD enum
float param2; ///< PARAM2, see MAV_CMD enum
float param3; ///< PARAM3, see MAV_CMD enum
float param4; ///< PARAM4, see MAV_CMD enum
float x; ///< PARAM5 / local: x position, global: latitude
float y; ///< PARAM6 / y position: global: longitude
float z; ///< PARAM7 / z position: global: altitude (relative or absolute, depending on frame.
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_MSG_ID_MISSION_ITEM_CRC 254
#define MAVLINK_MSG_ID_39_CRC 254
#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, see MAV_CMD enum
* @param param2 PARAM2, see MAV_CMD enum
* @param param3 PARAM3, see MAV_CMD enum
* @param param4 PARAM4, see MAV_CMD enum
* @param x PARAM5 / local: x position, global: latitude
* @param y PARAM6 / y position: global: longitude
* @param z PARAM7 / z position: global: altitude (relative or absolute, depending on frame.
* @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[MAVLINK_MSG_ID_MISSION_ITEM_LEN];
_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, MAVLINK_MSG_ID_MISSION_ITEM_LEN);
#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, MAVLINK_MSG_ID_MISSION_ITEM_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_MISSION_ITEM;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MISSION_ITEM_LEN, MAVLINK_MSG_ID_MISSION_ITEM_CRC);
#else
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MISSION_ITEM_LEN);
#endif
}
/**
* @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 will be 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, see MAV_CMD enum
* @param param2 PARAM2, see MAV_CMD enum
* @param param3 PARAM3, see MAV_CMD enum
* @param param4 PARAM4, see MAV_CMD enum
* @param x PARAM5 / local: x position, global: latitude
* @param y PARAM6 / y position: global: longitude
* @param z PARAM7 / z position: global: altitude (relative or absolute, depending on frame.
* @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[MAVLINK_MSG_ID_MISSION_ITEM_LEN];
_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, MAVLINK_MSG_ID_MISSION_ITEM_LEN);
#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, MAVLINK_MSG_ID_MISSION_ITEM_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_MISSION_ITEM;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MISSION_ITEM_LEN, MAVLINK_MSG_ID_MISSION_ITEM_CRC);
#else
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MISSION_ITEM_LEN);
#endif
}
/**
* @brief Encode a mission_item struct
*
* @param system_id ID of this 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 Encode a mission_item struct 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 will be sent over
* @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_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_mission_item_t* mission_item)
{
return mavlink_msg_mission_item_pack_chan(system_id, component_id, chan, 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, see MAV_CMD enum
* @param param2 PARAM2, see MAV_CMD enum
* @param param3 PARAM3, see MAV_CMD enum
* @param param4 PARAM4, see MAV_CMD enum
* @param x PARAM5 / local: x position, global: latitude
* @param y PARAM6 / y position: global: longitude
* @param z PARAM7 / z position: global: altitude (relative or absolute, depending on frame.
*/
#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[MAVLINK_MSG_ID_MISSION_ITEM_LEN];
_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);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM, buf, MAVLINK_MSG_ID_MISSION_ITEM_LEN, MAVLINK_MSG_ID_MISSION_ITEM_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM, buf, MAVLINK_MSG_ID_MISSION_ITEM_LEN);
#endif
#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;
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM, (const char *)&packet, MAVLINK_MSG_ID_MISSION_ITEM_LEN, MAVLINK_MSG_ID_MISSION_ITEM_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM, (const char *)&packet, MAVLINK_MSG_ID_MISSION_ITEM_LEN);
#endif
#endif
}
#if MAVLINK_MSG_ID_MISSION_ITEM_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This varient of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_mission_item_send_buf(mavlink_message_t *msgbuf, 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 = (char *)msgbuf;
_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);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM, buf, MAVLINK_MSG_ID_MISSION_ITEM_LEN, MAVLINK_MSG_ID_MISSION_ITEM_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM, buf, MAVLINK_MSG_ID_MISSION_ITEM_LEN);
#endif
#else
mavlink_mission_item_t *packet = (mavlink_mission_item_t *)msgbuf;
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;
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM, (const char *)packet, MAVLINK_MSG_ID_MISSION_ITEM_LEN, MAVLINK_MSG_ID_MISSION_ITEM_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM, (const char *)packet, MAVLINK_MSG_ID_MISSION_ITEM_LEN);
#endif
#endif
}
#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, see MAV_CMD enum
*/
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, see MAV_CMD enum
*/
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, see MAV_CMD enum
*/
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, see MAV_CMD enum
*/
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 (relative or absolute, depending on frame.
*/
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), MAVLINK_MSG_ID_MISSION_ITEM_LEN);
#endif
}

View file

@ -0,0 +1,521 @@
// MESSAGE MISSION_ITEM_INT PACKING
#define MAVLINK_MSG_ID_MISSION_ITEM_INT 73
typedef struct __mavlink_mission_item_int_t
{
float param1; ///< PARAM1, see MAV_CMD enum
float param2; ///< PARAM2, see MAV_CMD enum
float param3; ///< PARAM3, see MAV_CMD enum
float param4; ///< PARAM4, see MAV_CMD enum
int32_t x; ///< PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7
int32_t y; ///< PARAM6 / y position: local: x position in meters * 1e4, global: longitude in degrees *10^7
float z; ///< PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame.
uint16_t seq; ///< Waypoint ID (sequence number). Starts at zero. Increases monotonically for each waypoint, no gaps in the sequence (0,1,2,3,4).
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_int_t;
#define MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN 37
#define MAVLINK_MSG_ID_73_LEN 37
#define MAVLINK_MSG_ID_MISSION_ITEM_INT_CRC 38
#define MAVLINK_MSG_ID_73_CRC 38
#define MAVLINK_MESSAGE_INFO_MISSION_ITEM_INT { \
"MISSION_ITEM_INT", \
14, \
{ { "param1", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_mission_item_int_t, param1) }, \
{ "param2", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_mission_item_int_t, param2) }, \
{ "param3", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_mission_item_int_t, param3) }, \
{ "param4", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_mission_item_int_t, param4) }, \
{ "x", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_mission_item_int_t, x) }, \
{ "y", NULL, MAVLINK_TYPE_INT32_T, 0, 20, offsetof(mavlink_mission_item_int_t, y) }, \
{ "z", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_mission_item_int_t, z) }, \
{ "seq", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_mission_item_int_t, seq) }, \
{ "command", NULL, MAVLINK_TYPE_UINT16_T, 0, 30, offsetof(mavlink_mission_item_int_t, command) }, \
{ "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_mission_item_int_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_mission_item_int_t, target_component) }, \
{ "frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_mission_item_int_t, frame) }, \
{ "current", NULL, MAVLINK_TYPE_UINT8_T, 0, 35, offsetof(mavlink_mission_item_int_t, current) }, \
{ "autocontinue", NULL, MAVLINK_TYPE_UINT8_T, 0, 36, offsetof(mavlink_mission_item_int_t, autocontinue) }, \
} \
}
/**
* @brief Pack a mission_item_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 target_system System ID
* @param target_component Component ID
* @param seq Waypoint ID (sequence number). Starts at zero. Increases monotonically for each waypoint, no gaps in the sequence (0,1,2,3,4).
* @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, see MAV_CMD enum
* @param param2 PARAM2, see MAV_CMD enum
* @param param3 PARAM3, see MAV_CMD enum
* @param param4 PARAM4, see MAV_CMD enum
* @param x PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7
* @param y PARAM6 / y position: local: x position in meters * 1e4, global: longitude in degrees *10^7
* @param z PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_mission_item_int_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, int32_t x, int32_t y, float z)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN];
_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_int32_t(buf, 16, x);
_mav_put_int32_t(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, MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN);
#else
mavlink_mission_item_int_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, MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_MISSION_ITEM_INT;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN, MAVLINK_MSG_ID_MISSION_ITEM_INT_CRC);
#else
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN);
#endif
}
/**
* @brief Pack a mission_item_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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param target_system System ID
* @param target_component Component ID
* @param seq Waypoint ID (sequence number). Starts at zero. Increases monotonically for each waypoint, no gaps in the sequence (0,1,2,3,4).
* @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, see MAV_CMD enum
* @param param2 PARAM2, see MAV_CMD enum
* @param param3 PARAM3, see MAV_CMD enum
* @param param4 PARAM4, see MAV_CMD enum
* @param x PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7
* @param y PARAM6 / y position: local: x position in meters * 1e4, global: longitude in degrees *10^7
* @param z PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_mission_item_int_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,int32_t x,int32_t y,float z)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN];
_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_int32_t(buf, 16, x);
_mav_put_int32_t(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, MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN);
#else
mavlink_mission_item_int_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, MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_MISSION_ITEM_INT;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN, MAVLINK_MSG_ID_MISSION_ITEM_INT_CRC);
#else
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN);
#endif
}
/**
* @brief Encode a mission_item_int struct
*
* @param system_id ID of this 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_int C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_mission_item_int_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mission_item_int_t* mission_item_int)
{
return mavlink_msg_mission_item_int_pack(system_id, component_id, msg, mission_item_int->target_system, mission_item_int->target_component, mission_item_int->seq, mission_item_int->frame, mission_item_int->command, mission_item_int->current, mission_item_int->autocontinue, mission_item_int->param1, mission_item_int->param2, mission_item_int->param3, mission_item_int->param4, mission_item_int->x, mission_item_int->y, mission_item_int->z);
}
/**
* @brief Encode a mission_item_int struct 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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param mission_item_int C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_mission_item_int_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_mission_item_int_t* mission_item_int)
{
return mavlink_msg_mission_item_int_pack_chan(system_id, component_id, chan, msg, mission_item_int->target_system, mission_item_int->target_component, mission_item_int->seq, mission_item_int->frame, mission_item_int->command, mission_item_int->current, mission_item_int->autocontinue, mission_item_int->param1, mission_item_int->param2, mission_item_int->param3, mission_item_int->param4, mission_item_int->x, mission_item_int->y, mission_item_int->z);
}
/**
* @brief Send a mission_item_int message
* @param chan MAVLink channel to send the message
*
* @param target_system System ID
* @param target_component Component ID
* @param seq Waypoint ID (sequence number). Starts at zero. Increases monotonically for each waypoint, no gaps in the sequence (0,1,2,3,4).
* @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, see MAV_CMD enum
* @param param2 PARAM2, see MAV_CMD enum
* @param param3 PARAM3, see MAV_CMD enum
* @param param4 PARAM4, see MAV_CMD enum
* @param x PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7
* @param y PARAM6 / y position: local: x position in meters * 1e4, global: longitude in degrees *10^7
* @param z PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame.
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_mission_item_int_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, int32_t x, int32_t y, float z)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN];
_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_int32_t(buf, 16, x);
_mav_put_int32_t(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);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM_INT, buf, MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN, MAVLINK_MSG_ID_MISSION_ITEM_INT_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM_INT, buf, MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN);
#endif
#else
mavlink_mission_item_int_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;
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM_INT, (const char *)&packet, MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN, MAVLINK_MSG_ID_MISSION_ITEM_INT_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM_INT, (const char *)&packet, MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN);
#endif
#endif
}
#if MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This varient of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_mission_item_int_send_buf(mavlink_message_t *msgbuf, 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, int32_t x, int32_t y, float z)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
_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_int32_t(buf, 16, x);
_mav_put_int32_t(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);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM_INT, buf, MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN, MAVLINK_MSG_ID_MISSION_ITEM_INT_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM_INT, buf, MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN);
#endif
#else
mavlink_mission_item_int_t *packet = (mavlink_mission_item_int_t *)msgbuf;
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;
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM_INT, (const char *)packet, MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN, MAVLINK_MSG_ID_MISSION_ITEM_INT_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM_INT, (const char *)packet, MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN);
#endif
#endif
}
#endif
#endif
// MESSAGE MISSION_ITEM_INT UNPACKING
/**
* @brief Get field target_system from mission_item_int message
*
* @return System ID
*/
static inline uint8_t mavlink_msg_mission_item_int_get_target_system(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 32);
}
/**
* @brief Get field target_component from mission_item_int message
*
* @return Component ID
*/
static inline uint8_t mavlink_msg_mission_item_int_get_target_component(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 33);
}
/**
* @brief Get field seq from mission_item_int message
*
* @return Waypoint ID (sequence number). Starts at zero. Increases monotonically for each waypoint, no gaps in the sequence (0,1,2,3,4).
*/
static inline uint16_t mavlink_msg_mission_item_int_get_seq(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 28);
}
/**
* @brief Get field frame from mission_item_int message
*
* @return The coordinate system of the MISSION. see MAV_FRAME in mavlink_types.h
*/
static inline uint8_t mavlink_msg_mission_item_int_get_frame(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 34);
}
/**
* @brief Get field command from mission_item_int message
*
* @return The scheduled action for the MISSION. see MAV_CMD in common.xml MAVLink specs
*/
static inline uint16_t mavlink_msg_mission_item_int_get_command(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 30);
}
/**
* @brief Get field current from mission_item_int message
*
* @return false:0, true:1
*/
static inline uint8_t mavlink_msg_mission_item_int_get_current(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 35);
}
/**
* @brief Get field autocontinue from mission_item_int message
*
* @return autocontinue to next wp
*/
static inline uint8_t mavlink_msg_mission_item_int_get_autocontinue(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 36);
}
/**
* @brief Get field param1 from mission_item_int message
*
* @return PARAM1, see MAV_CMD enum
*/
static inline float mavlink_msg_mission_item_int_get_param1(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 0);
}
/**
* @brief Get field param2 from mission_item_int message
*
* @return PARAM2, see MAV_CMD enum
*/
static inline float mavlink_msg_mission_item_int_get_param2(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 4);
}
/**
* @brief Get field param3 from mission_item_int message
*
* @return PARAM3, see MAV_CMD enum
*/
static inline float mavlink_msg_mission_item_int_get_param3(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 8);
}
/**
* @brief Get field param4 from mission_item_int message
*
* @return PARAM4, see MAV_CMD enum
*/
static inline float mavlink_msg_mission_item_int_get_param4(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 12);
}
/**
* @brief Get field x from mission_item_int message
*
* @return PARAM5 / local: x position in meters * 1e4, global: latitude in degrees * 10^7
*/
static inline int32_t mavlink_msg_mission_item_int_get_x(const mavlink_message_t* msg)
{
return _MAV_RETURN_int32_t(msg, 16);
}
/**
* @brief Get field y from mission_item_int message
*
* @return PARAM6 / y position: local: x position in meters * 1e4, global: longitude in degrees *10^7
*/
static inline int32_t mavlink_msg_mission_item_int_get_y(const mavlink_message_t* msg)
{
return _MAV_RETURN_int32_t(msg, 20);
}
/**
* @brief Get field z from mission_item_int message
*
* @return PARAM7 / z position: global: altitude in meters (relative or absolute, depending on frame.
*/
static inline float mavlink_msg_mission_item_int_get_z(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 24);
}
/**
* @brief Decode a mission_item_int message into a struct
*
* @param msg The message to decode
* @param mission_item_int C-struct to decode the message contents into
*/
static inline void mavlink_msg_mission_item_int_decode(const mavlink_message_t* msg, mavlink_mission_item_int_t* mission_item_int)
{
#if MAVLINK_NEED_BYTE_SWAP
mission_item_int->param1 = mavlink_msg_mission_item_int_get_param1(msg);
mission_item_int->param2 = mavlink_msg_mission_item_int_get_param2(msg);
mission_item_int->param3 = mavlink_msg_mission_item_int_get_param3(msg);
mission_item_int->param4 = mavlink_msg_mission_item_int_get_param4(msg);
mission_item_int->x = mavlink_msg_mission_item_int_get_x(msg);
mission_item_int->y = mavlink_msg_mission_item_int_get_y(msg);
mission_item_int->z = mavlink_msg_mission_item_int_get_z(msg);
mission_item_int->seq = mavlink_msg_mission_item_int_get_seq(msg);
mission_item_int->command = mavlink_msg_mission_item_int_get_command(msg);
mission_item_int->target_system = mavlink_msg_mission_item_int_get_target_system(msg);
mission_item_int->target_component = mavlink_msg_mission_item_int_get_target_component(msg);
mission_item_int->frame = mavlink_msg_mission_item_int_get_frame(msg);
mission_item_int->current = mavlink_msg_mission_item_int_get_current(msg);
mission_item_int->autocontinue = mavlink_msg_mission_item_int_get_autocontinue(msg);
#else
memcpy(mission_item_int, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN);
#endif
}

View file

@ -0,0 +1,209 @@
// 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_MSG_ID_MISSION_ITEM_REACHED_CRC 11
#define MAVLINK_MSG_ID_46_CRC 11
#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[MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN];
_mav_put_uint16_t(buf, 0, seq);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN);
#else
mavlink_mission_item_reached_t packet;
packet.seq = seq;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_MISSION_ITEM_REACHED;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_CRC);
#else
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN);
#endif
}
/**
* @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 will be 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[MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN];
_mav_put_uint16_t(buf, 0, seq);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN);
#else
mavlink_mission_item_reached_t packet;
packet.seq = seq;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_MISSION_ITEM_REACHED;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_CRC);
#else
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN);
#endif
}
/**
* @brief Encode a mission_item_reached struct
*
* @param system_id ID of this 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 Encode a mission_item_reached struct 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 will be sent over
* @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_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_mission_item_reached_t* mission_item_reached)
{
return mavlink_msg_mission_item_reached_pack_chan(system_id, component_id, chan, 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[MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN];
_mav_put_uint16_t(buf, 0, seq);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM_REACHED, buf, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM_REACHED, buf, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN);
#endif
#else
mavlink_mission_item_reached_t packet;
packet.seq = seq;
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM_REACHED, (const char *)&packet, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM_REACHED, (const char *)&packet, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN);
#endif
#endif
}
#if MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This varient of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_mission_item_reached_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint16_t seq)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
_mav_put_uint16_t(buf, 0, seq);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM_REACHED, buf, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM_REACHED, buf, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN);
#endif
#else
mavlink_mission_item_reached_t *packet = (mavlink_mission_item_reached_t *)msgbuf;
packet->seq = seq;
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM_REACHED, (const char *)packet, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM_REACHED, (const char *)packet, MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN);
#endif
#endif
}
#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), MAVLINK_MSG_ID_MISSION_ITEM_REACHED_LEN);
#endif
}

View file

@ -0,0 +1,257 @@
// 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_MSG_ID_MISSION_REQUEST_CRC 230
#define MAVLINK_MSG_ID_40_CRC 230
#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[MAVLINK_MSG_ID_MISSION_REQUEST_LEN];
_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, MAVLINK_MSG_ID_MISSION_REQUEST_LEN);
#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, MAVLINK_MSG_ID_MISSION_REQUEST_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_MISSION_REQUEST;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MISSION_REQUEST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_CRC);
#else
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MISSION_REQUEST_LEN);
#endif
}
/**
* @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 will be 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[MAVLINK_MSG_ID_MISSION_REQUEST_LEN];
_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, MAVLINK_MSG_ID_MISSION_REQUEST_LEN);
#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, MAVLINK_MSG_ID_MISSION_REQUEST_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_MISSION_REQUEST;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MISSION_REQUEST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_CRC);
#else
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MISSION_REQUEST_LEN);
#endif
}
/**
* @brief Encode a mission_request struct
*
* @param system_id ID of this 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 Encode a mission_request struct 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 will be sent over
* @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_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_mission_request_t* mission_request)
{
return mavlink_msg_mission_request_pack_chan(system_id, component_id, chan, 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[MAVLINK_MSG_ID_MISSION_REQUEST_LEN];
_mav_put_uint16_t(buf, 0, seq);
_mav_put_uint8_t(buf, 2, target_system);
_mav_put_uint8_t(buf, 3, target_component);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST, buf, MAVLINK_MSG_ID_MISSION_REQUEST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST, buf, MAVLINK_MSG_ID_MISSION_REQUEST_LEN);
#endif
#else
mavlink_mission_request_t packet;
packet.seq = seq;
packet.target_system = target_system;
packet.target_component = target_component;
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST, (const char *)&packet, MAVLINK_MSG_ID_MISSION_REQUEST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST, (const char *)&packet, MAVLINK_MSG_ID_MISSION_REQUEST_LEN);
#endif
#endif
}
#if MAVLINK_MSG_ID_MISSION_REQUEST_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This varient of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_mission_request_send_buf(mavlink_message_t *msgbuf, 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 = (char *)msgbuf;
_mav_put_uint16_t(buf, 0, seq);
_mav_put_uint8_t(buf, 2, target_system);
_mav_put_uint8_t(buf, 3, target_component);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST, buf, MAVLINK_MSG_ID_MISSION_REQUEST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST, buf, MAVLINK_MSG_ID_MISSION_REQUEST_LEN);
#endif
#else
mavlink_mission_request_t *packet = (mavlink_mission_request_t *)msgbuf;
packet->seq = seq;
packet->target_system = target_system;
packet->target_component = target_component;
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST, (const char *)packet, MAVLINK_MSG_ID_MISSION_REQUEST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST, (const char *)packet, MAVLINK_MSG_ID_MISSION_REQUEST_LEN);
#endif
#endif
}
#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), MAVLINK_MSG_ID_MISSION_REQUEST_LEN);
#endif
}

View file

@ -0,0 +1,233 @@
// 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_MSG_ID_MISSION_REQUEST_LIST_CRC 132
#define MAVLINK_MSG_ID_43_CRC 132
#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[MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN);
#else
mavlink_mission_request_list_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_MISSION_REQUEST_LIST;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_CRC);
#else
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN);
#endif
}
/**
* @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 will be 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[MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN);
#else
mavlink_mission_request_list_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_MISSION_REQUEST_LIST;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_CRC);
#else
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN);
#endif
}
/**
* @brief Encode a mission_request_list struct
*
* @param system_id ID of this 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 Encode a mission_request_list struct 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 will be sent over
* @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_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_mission_request_list_t* mission_request_list)
{
return mavlink_msg_mission_request_list_pack_chan(system_id, component_id, chan, 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[MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_LIST, buf, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_LIST, buf, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN);
#endif
#else
mavlink_mission_request_list_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_LIST, (const char *)&packet, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_LIST, (const char *)&packet, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN);
#endif
#endif
}
#if MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This varient of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_mission_request_list_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_LIST, buf, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_LIST, buf, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN);
#endif
#else
mavlink_mission_request_list_t *packet = (mavlink_mission_request_list_t *)msgbuf;
packet->target_system = target_system;
packet->target_component = target_component;
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_LIST, (const char *)packet, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_LIST, (const char *)packet, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN);
#endif
#endif
}
#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), MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN);
#endif
}

View file

@ -0,0 +1,281 @@
// 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_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_CRC 212
#define MAVLINK_MSG_ID_37_CRC 212
#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[MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN];
_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, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN);
#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, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_CRC);
#else
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN);
#endif
}
/**
* @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 will be 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[MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN];
_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, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN);
#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, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_CRC);
#else
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN);
#endif
}
/**
* @brief Encode a mission_request_partial_list struct
*
* @param system_id ID of this 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 Encode a mission_request_partial_list struct 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 will be sent over
* @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_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_mission_request_partial_list_t* mission_request_partial_list)
{
return mavlink_msg_mission_request_partial_list_pack_chan(system_id, component_id, chan, 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[MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN];
_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);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST, buf, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST, buf, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN);
#endif
#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;
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST, (const char *)&packet, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST, (const char *)&packet, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN);
#endif
#endif
}
#if MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This varient of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_mission_request_partial_list_send_buf(mavlink_message_t *msgbuf, 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 = (char *)msgbuf;
_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);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST, buf, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST, buf, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN);
#endif
#else
mavlink_mission_request_partial_list_t *packet = (mavlink_mission_request_partial_list_t *)msgbuf;
packet->start_index = start_index;
packet->end_index = end_index;
packet->target_system = target_system;
packet->target_component = target_component;
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST, (const char *)packet, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST, (const char *)packet, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN);
#endif
#endif
}
#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), MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN);
#endif
}

View file

@ -0,0 +1,257 @@
// 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_MSG_ID_MISSION_SET_CURRENT_CRC 28
#define MAVLINK_MSG_ID_41_CRC 28
#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[MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN];
_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, MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN);
#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, MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_MISSION_SET_CURRENT;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN, MAVLINK_MSG_ID_MISSION_SET_CURRENT_CRC);
#else
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN);
#endif
}
/**
* @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 will be 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[MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN];
_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, MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN);
#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, MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_MISSION_SET_CURRENT;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN, MAVLINK_MSG_ID_MISSION_SET_CURRENT_CRC);
#else
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN);
#endif
}
/**
* @brief Encode a mission_set_current struct
*
* @param system_id ID of this 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 Encode a mission_set_current struct 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 will be sent over
* @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_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_mission_set_current_t* mission_set_current)
{
return mavlink_msg_mission_set_current_pack_chan(system_id, component_id, chan, 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[MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN];
_mav_put_uint16_t(buf, 0, seq);
_mav_put_uint8_t(buf, 2, target_system);
_mav_put_uint8_t(buf, 3, target_component);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_SET_CURRENT, buf, MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN, MAVLINK_MSG_ID_MISSION_SET_CURRENT_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_SET_CURRENT, buf, MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN);
#endif
#else
mavlink_mission_set_current_t packet;
packet.seq = seq;
packet.target_system = target_system;
packet.target_component = target_component;
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_SET_CURRENT, (const char *)&packet, MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN, MAVLINK_MSG_ID_MISSION_SET_CURRENT_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_SET_CURRENT, (const char *)&packet, MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN);
#endif
#endif
}
#if MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This varient of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_mission_set_current_send_buf(mavlink_message_t *msgbuf, 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 = (char *)msgbuf;
_mav_put_uint16_t(buf, 0, seq);
_mav_put_uint8_t(buf, 2, target_system);
_mav_put_uint8_t(buf, 3, target_component);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_SET_CURRENT, buf, MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN, MAVLINK_MSG_ID_MISSION_SET_CURRENT_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_SET_CURRENT, buf, MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN);
#endif
#else
mavlink_mission_set_current_t *packet = (mavlink_mission_set_current_t *)msgbuf;
packet->seq = seq;
packet->target_system = target_system;
packet->target_component = target_component;
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_SET_CURRENT, (const char *)packet, MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN, MAVLINK_MSG_ID_MISSION_SET_CURRENT_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_SET_CURRENT, (const char *)packet, MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN);
#endif
#endif
}
#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), MAVLINK_MSG_ID_MISSION_SET_CURRENT_LEN);
#endif
}

View file

@ -0,0 +1,281 @@
// 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_MSG_ID_MISSION_WRITE_PARTIAL_LIST_CRC 9
#define MAVLINK_MSG_ID_38_CRC 9
#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[MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN];
_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, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN);
#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, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_CRC);
#else
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN);
#endif
}
/**
* @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 will be 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[MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN];
_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, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN);
#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, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_CRC);
#else
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN);
#endif
}
/**
* @brief Encode a mission_write_partial_list struct
*
* @param system_id ID of this 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 Encode a mission_write_partial_list struct 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 will be sent over
* @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_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_mission_write_partial_list_t* mission_write_partial_list)
{
return mavlink_msg_mission_write_partial_list_pack_chan(system_id, component_id, chan, 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[MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN];
_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);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST, buf, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST, buf, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN);
#endif
#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;
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST, (const char *)&packet, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST, (const char *)&packet, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN);
#endif
#endif
}
#if MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This varient of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_mission_write_partial_list_send_buf(mavlink_message_t *msgbuf, 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 = (char *)msgbuf;
_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);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST, buf, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST, buf, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN);
#endif
#else
mavlink_mission_write_partial_list_t *packet = (mavlink_mission_write_partial_list_t *)msgbuf;
packet->start_index = start_index;
packet->end_index = end_index;
packet->target_system = target_system;
packet->target_component = target_component;
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST, (const char *)packet, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST, (const char *)packet, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN);
#endif
#endif
}
#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), MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN);
#endif
}

View file

@ -0,0 +1,249 @@
// 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_ID_NAMED_VALUE_FLOAT_CRC 170
#define MAVLINK_MSG_ID_251_CRC 170
#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[MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN];
_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, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN);
#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, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_NAMED_VALUE_FLOAT;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_CRC);
#else
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN);
#endif
}
/**
* @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 will be 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[MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN];
_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, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN);
#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, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_NAMED_VALUE_FLOAT;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_CRC);
#else
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN);
#endif
}
/**
* @brief Encode a named_value_float struct
*
* @param system_id ID of this 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 Encode a named_value_float struct 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 will be sent over
* @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_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_named_value_float_t* named_value_float)
{
return mavlink_msg_named_value_float_pack_chan(system_id, component_id, chan, 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[MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN];
_mav_put_uint32_t(buf, 0, time_boot_ms);
_mav_put_float(buf, 4, value);
_mav_put_char_array(buf, 8, name, 10);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT, buf, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT, buf, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN);
#endif
#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);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT, (const char *)&packet, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT, (const char *)&packet, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN);
#endif
#endif
}
#if MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This varient of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_named_value_float_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, const char *name, float value)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
_mav_put_uint32_t(buf, 0, time_boot_ms);
_mav_put_float(buf, 4, value);
_mav_put_char_array(buf, 8, name, 10);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT, buf, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT, buf, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN);
#endif
#else
mavlink_named_value_float_t *packet = (mavlink_named_value_float_t *)msgbuf;
packet->time_boot_ms = time_boot_ms;
packet->value = value;
mav_array_memcpy(packet->name, name, sizeof(char)*10);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT, (const char *)packet, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT, (const char *)packet, MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN);
#endif
#endif
}
#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), MAVLINK_MSG_ID_NAMED_VALUE_FLOAT_LEN);
#endif
}

View file

@ -0,0 +1,249 @@
// 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_ID_NAMED_VALUE_INT_CRC 44
#define MAVLINK_MSG_ID_252_CRC 44
#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[MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN];
_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, MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN);
#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, MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_NAMED_VALUE_INT;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN, MAVLINK_MSG_ID_NAMED_VALUE_INT_CRC);
#else
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN);
#endif
}
/**
* @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 will be 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[MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN];
_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, MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN);
#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, MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_NAMED_VALUE_INT;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN, MAVLINK_MSG_ID_NAMED_VALUE_INT_CRC);
#else
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN);
#endif
}
/**
* @brief Encode a named_value_int struct
*
* @param system_id ID of this 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 Encode a named_value_int struct 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 will be sent over
* @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_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_named_value_int_t* named_value_int)
{
return mavlink_msg_named_value_int_pack_chan(system_id, component_id, chan, 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[MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN];
_mav_put_uint32_t(buf, 0, time_boot_ms);
_mav_put_int32_t(buf, 4, value);
_mav_put_char_array(buf, 8, name, 10);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAMED_VALUE_INT, buf, MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN, MAVLINK_MSG_ID_NAMED_VALUE_INT_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAMED_VALUE_INT, buf, MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN);
#endif
#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);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAMED_VALUE_INT, (const char *)&packet, MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN, MAVLINK_MSG_ID_NAMED_VALUE_INT_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAMED_VALUE_INT, (const char *)&packet, MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN);
#endif
#endif
}
#if MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This varient of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_named_value_int_send_buf(mavlink_message_t *msgbuf, 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 = (char *)msgbuf;
_mav_put_uint32_t(buf, 0, time_boot_ms);
_mav_put_int32_t(buf, 4, value);
_mav_put_char_array(buf, 8, name, 10);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAMED_VALUE_INT, buf, MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN, MAVLINK_MSG_ID_NAMED_VALUE_INT_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAMED_VALUE_INT, buf, MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN);
#endif
#else
mavlink_named_value_int_t *packet = (mavlink_named_value_int_t *)msgbuf;
packet->time_boot_ms = time_boot_ms;
packet->value = value;
mav_array_memcpy(packet->name, name, sizeof(char)*10);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAMED_VALUE_INT, (const char *)packet, MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN, MAVLINK_MSG_ID_NAMED_VALUE_INT_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAMED_VALUE_INT, (const char *)packet, MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN);
#endif
#endif
}
#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), MAVLINK_MSG_ID_NAMED_VALUE_INT_LEN);
#endif
}

View file

@ -0,0 +1,377 @@
// 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_MSG_ID_NAV_CONTROLLER_OUTPUT_CRC 183
#define MAVLINK_MSG_ID_62_CRC 183
#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[MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN];
_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, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN);
#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, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_CRC);
#else
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN);
#endif
}
/**
* @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 will be 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[MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN];
_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, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN);
#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, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_CRC);
#else
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN);
#endif
}
/**
* @brief Encode a nav_controller_output struct
*
* @param system_id ID of this 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 Encode a nav_controller_output struct 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 will be sent over
* @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_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_nav_controller_output_t* nav_controller_output)
{
return mavlink_msg_nav_controller_output_pack_chan(system_id, component_id, chan, 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[MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN];
_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);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT, buf, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT, buf, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN);
#endif
#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;
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT, (const char *)&packet, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT, (const char *)&packet, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN);
#endif
#endif
}
#if MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This varient of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_nav_controller_output_send_buf(mavlink_message_t *msgbuf, 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 = (char *)msgbuf;
_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);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT, buf, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT, buf, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN);
#endif
#else
mavlink_nav_controller_output_t *packet = (mavlink_nav_controller_output_t *)msgbuf;
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;
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT, (const char *)packet, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT, (const char *)packet, MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN);
#endif
#endif
}
#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), MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT_LEN);
#endif
}

View file

@ -0,0 +1,377 @@
// 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 * 10 in x-sensor direction (dezi-pixels)
int16_t flow_y; ///< Flow in pixels * 10 in y-sensor direction (dezi-pixels)
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_MSG_ID_OPTICAL_FLOW_CRC 175
#define MAVLINK_MSG_ID_100_CRC 175
#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 * 10 in x-sensor direction (dezi-pixels)
* @param flow_y Flow in pixels * 10 in y-sensor direction (dezi-pixels)
* @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[MAVLINK_MSG_ID_OPTICAL_FLOW_LEN];
_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, MAVLINK_MSG_ID_OPTICAL_FLOW_LEN);
#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, MAVLINK_MSG_ID_OPTICAL_FLOW_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_OPTICAL_FLOW;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_OPTICAL_FLOW_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_CRC);
#else
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_OPTICAL_FLOW_LEN);
#endif
}
/**
* @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 will be 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 * 10 in x-sensor direction (dezi-pixels)
* @param flow_y Flow in pixels * 10 in y-sensor direction (dezi-pixels)
* @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[MAVLINK_MSG_ID_OPTICAL_FLOW_LEN];
_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, MAVLINK_MSG_ID_OPTICAL_FLOW_LEN);
#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, MAVLINK_MSG_ID_OPTICAL_FLOW_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_OPTICAL_FLOW;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_OPTICAL_FLOW_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_CRC);
#else
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_OPTICAL_FLOW_LEN);
#endif
}
/**
* @brief Encode a optical_flow struct
*
* @param system_id ID of this 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 Encode a optical_flow struct 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 will be sent over
* @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_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_optical_flow_t* optical_flow)
{
return mavlink_msg_optical_flow_pack_chan(system_id, component_id, chan, 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 * 10 in x-sensor direction (dezi-pixels)
* @param flow_y Flow in pixels * 10 in y-sensor direction (dezi-pixels)
* @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[MAVLINK_MSG_ID_OPTICAL_FLOW_LEN];
_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);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPTICAL_FLOW, buf, MAVLINK_MSG_ID_OPTICAL_FLOW_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPTICAL_FLOW, buf, MAVLINK_MSG_ID_OPTICAL_FLOW_LEN);
#endif
#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;
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPTICAL_FLOW, (const char *)&packet, MAVLINK_MSG_ID_OPTICAL_FLOW_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPTICAL_FLOW, (const char *)&packet, MAVLINK_MSG_ID_OPTICAL_FLOW_LEN);
#endif
#endif
}
#if MAVLINK_MSG_ID_OPTICAL_FLOW_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This varient of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_optical_flow_send_buf(mavlink_message_t *msgbuf, 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 = (char *)msgbuf;
_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);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPTICAL_FLOW, buf, MAVLINK_MSG_ID_OPTICAL_FLOW_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPTICAL_FLOW, buf, MAVLINK_MSG_ID_OPTICAL_FLOW_LEN);
#endif
#else
mavlink_optical_flow_t *packet = (mavlink_optical_flow_t *)msgbuf;
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;
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPTICAL_FLOW, (const char *)packet, MAVLINK_MSG_ID_OPTICAL_FLOW_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPTICAL_FLOW, (const char *)packet, MAVLINK_MSG_ID_OPTICAL_FLOW_LEN);
#endif
#endif
}
#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 * 10 in x-sensor direction (dezi-pixels)
*/
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 * 10 in y-sensor direction (dezi-pixels)
*/
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), MAVLINK_MSG_ID_OPTICAL_FLOW_LEN);
#endif
}

View file

@ -0,0 +1,473 @@
// MESSAGE OPTICAL_FLOW_RAD PACKING
#define MAVLINK_MSG_ID_OPTICAL_FLOW_RAD 106
typedef struct __mavlink_optical_flow_rad_t
{
uint64_t time_usec; ///< Timestamp (microseconds, synced to UNIX time or since system boot)
uint32_t integration_time_us; ///< Integration time in microseconds. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the.
float integrated_x; ///< Flow in radians around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.)
float integrated_y; ///< Flow in radians around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.)
float integrated_xgyro; ///< RH rotation around X axis (rad)
float integrated_ygyro; ///< RH rotation around Y axis (rad)
float integrated_zgyro; ///< RH rotation around Z axis (rad)
uint32_t time_delta_distance_us; ///< Time in microseconds since the distance was sampled.
float distance; ///< Distance to the center of the flow field in meters. Positive value (including zero): distance known. Negative value: Unknown distance.
int16_t temperature; ///< Temperature * 100 in centi-degrees Celsius
uint8_t sensor_id; ///< Sensor ID
uint8_t quality; ///< Optical flow quality / confidence. 0: no valid flow, 255: maximum quality
} mavlink_optical_flow_rad_t;
#define MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN 44
#define MAVLINK_MSG_ID_106_LEN 44
#define MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_CRC 138
#define MAVLINK_MSG_ID_106_CRC 138
#define MAVLINK_MESSAGE_INFO_OPTICAL_FLOW_RAD { \
"OPTICAL_FLOW_RAD", \
12, \
{ { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_optical_flow_rad_t, time_usec) }, \
{ "integration_time_us", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_optical_flow_rad_t, integration_time_us) }, \
{ "integrated_x", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_optical_flow_rad_t, integrated_x) }, \
{ "integrated_y", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_optical_flow_rad_t, integrated_y) }, \
{ "integrated_xgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_optical_flow_rad_t, integrated_xgyro) }, \
{ "integrated_ygyro", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_optical_flow_rad_t, integrated_ygyro) }, \
{ "integrated_zgyro", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_optical_flow_rad_t, integrated_zgyro) }, \
{ "time_delta_distance_us", NULL, MAVLINK_TYPE_UINT32_T, 0, 32, offsetof(mavlink_optical_flow_rad_t, time_delta_distance_us) }, \
{ "distance", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_optical_flow_rad_t, distance) }, \
{ "temperature", NULL, MAVLINK_TYPE_INT16_T, 0, 40, offsetof(mavlink_optical_flow_rad_t, temperature) }, \
{ "sensor_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 42, offsetof(mavlink_optical_flow_rad_t, sensor_id) }, \
{ "quality", NULL, MAVLINK_TYPE_UINT8_T, 0, 43, offsetof(mavlink_optical_flow_rad_t, quality) }, \
} \
}
/**
* @brief Pack a optical_flow_rad message
* @param system_id ID of this 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, synced to UNIX time or since system boot)
* @param sensor_id Sensor ID
* @param integration_time_us Integration time in microseconds. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the.
* @param integrated_x Flow in radians around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.)
* @param integrated_y Flow in radians around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.)
* @param integrated_xgyro RH rotation around X axis (rad)
* @param integrated_ygyro RH rotation around Y axis (rad)
* @param integrated_zgyro RH rotation around Z axis (rad)
* @param temperature Temperature * 100 in centi-degrees Celsius
* @param quality Optical flow quality / confidence. 0: no valid flow, 255: maximum quality
* @param time_delta_distance_us Time in microseconds since the distance was sampled.
* @param distance Distance to the center of the flow field in meters. Positive value (including zero): 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_rad_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint64_t time_usec, uint8_t sensor_id, uint32_t integration_time_us, float integrated_x, float integrated_y, float integrated_xgyro, float integrated_ygyro, float integrated_zgyro, int16_t temperature, uint8_t quality, uint32_t time_delta_distance_us, float distance)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN];
_mav_put_uint64_t(buf, 0, time_usec);
_mav_put_uint32_t(buf, 8, integration_time_us);
_mav_put_float(buf, 12, integrated_x);
_mav_put_float(buf, 16, integrated_y);
_mav_put_float(buf, 20, integrated_xgyro);
_mav_put_float(buf, 24, integrated_ygyro);
_mav_put_float(buf, 28, integrated_zgyro);
_mav_put_uint32_t(buf, 32, time_delta_distance_us);
_mav_put_float(buf, 36, distance);
_mav_put_int16_t(buf, 40, temperature);
_mav_put_uint8_t(buf, 42, sensor_id);
_mav_put_uint8_t(buf, 43, quality);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN);
#else
mavlink_optical_flow_rad_t packet;
packet.time_usec = time_usec;
packet.integration_time_us = integration_time_us;
packet.integrated_x = integrated_x;
packet.integrated_y = integrated_y;
packet.integrated_xgyro = integrated_xgyro;
packet.integrated_ygyro = integrated_ygyro;
packet.integrated_zgyro = integrated_zgyro;
packet.time_delta_distance_us = time_delta_distance_us;
packet.distance = distance;
packet.temperature = temperature;
packet.sensor_id = sensor_id;
packet.quality = quality;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_OPTICAL_FLOW_RAD;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_CRC);
#else
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN);
#endif
}
/**
* @brief Pack a optical_flow_rad 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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param time_usec Timestamp (microseconds, synced to UNIX time or since system boot)
* @param sensor_id Sensor ID
* @param integration_time_us Integration time in microseconds. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the.
* @param integrated_x Flow in radians around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.)
* @param integrated_y Flow in radians around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.)
* @param integrated_xgyro RH rotation around X axis (rad)
* @param integrated_ygyro RH rotation around Y axis (rad)
* @param integrated_zgyro RH rotation around Z axis (rad)
* @param temperature Temperature * 100 in centi-degrees Celsius
* @param quality Optical flow quality / confidence. 0: no valid flow, 255: maximum quality
* @param time_delta_distance_us Time in microseconds since the distance was sampled.
* @param distance Distance to the center of the flow field in meters. Positive value (including zero): 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_rad_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,uint32_t integration_time_us,float integrated_x,float integrated_y,float integrated_xgyro,float integrated_ygyro,float integrated_zgyro,int16_t temperature,uint8_t quality,uint32_t time_delta_distance_us,float distance)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN];
_mav_put_uint64_t(buf, 0, time_usec);
_mav_put_uint32_t(buf, 8, integration_time_us);
_mav_put_float(buf, 12, integrated_x);
_mav_put_float(buf, 16, integrated_y);
_mav_put_float(buf, 20, integrated_xgyro);
_mav_put_float(buf, 24, integrated_ygyro);
_mav_put_float(buf, 28, integrated_zgyro);
_mav_put_uint32_t(buf, 32, time_delta_distance_us);
_mav_put_float(buf, 36, distance);
_mav_put_int16_t(buf, 40, temperature);
_mav_put_uint8_t(buf, 42, sensor_id);
_mav_put_uint8_t(buf, 43, quality);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN);
#else
mavlink_optical_flow_rad_t packet;
packet.time_usec = time_usec;
packet.integration_time_us = integration_time_us;
packet.integrated_x = integrated_x;
packet.integrated_y = integrated_y;
packet.integrated_xgyro = integrated_xgyro;
packet.integrated_ygyro = integrated_ygyro;
packet.integrated_zgyro = integrated_zgyro;
packet.time_delta_distance_us = time_delta_distance_us;
packet.distance = distance;
packet.temperature = temperature;
packet.sensor_id = sensor_id;
packet.quality = quality;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_OPTICAL_FLOW_RAD;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_CRC);
#else
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN);
#endif
}
/**
* @brief Encode a optical_flow_rad struct
*
* @param system_id ID of this 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_rad C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_optical_flow_rad_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_optical_flow_rad_t* optical_flow_rad)
{
return mavlink_msg_optical_flow_rad_pack(system_id, component_id, msg, optical_flow_rad->time_usec, optical_flow_rad->sensor_id, optical_flow_rad->integration_time_us, optical_flow_rad->integrated_x, optical_flow_rad->integrated_y, optical_flow_rad->integrated_xgyro, optical_flow_rad->integrated_ygyro, optical_flow_rad->integrated_zgyro, optical_flow_rad->temperature, optical_flow_rad->quality, optical_flow_rad->time_delta_distance_us, optical_flow_rad->distance);
}
/**
* @brief Encode a optical_flow_rad struct 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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param optical_flow_rad C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_optical_flow_rad_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_optical_flow_rad_t* optical_flow_rad)
{
return mavlink_msg_optical_flow_rad_pack_chan(system_id, component_id, chan, msg, optical_flow_rad->time_usec, optical_flow_rad->sensor_id, optical_flow_rad->integration_time_us, optical_flow_rad->integrated_x, optical_flow_rad->integrated_y, optical_flow_rad->integrated_xgyro, optical_flow_rad->integrated_ygyro, optical_flow_rad->integrated_zgyro, optical_flow_rad->temperature, optical_flow_rad->quality, optical_flow_rad->time_delta_distance_us, optical_flow_rad->distance);
}
/**
* @brief Send a optical_flow_rad message
* @param chan MAVLink channel to send the message
*
* @param time_usec Timestamp (microseconds, synced to UNIX time or since system boot)
* @param sensor_id Sensor ID
* @param integration_time_us Integration time in microseconds. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the.
* @param integrated_x Flow in radians around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.)
* @param integrated_y Flow in radians around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.)
* @param integrated_xgyro RH rotation around X axis (rad)
* @param integrated_ygyro RH rotation around Y axis (rad)
* @param integrated_zgyro RH rotation around Z axis (rad)
* @param temperature Temperature * 100 in centi-degrees Celsius
* @param quality Optical flow quality / confidence. 0: no valid flow, 255: maximum quality
* @param time_delta_distance_us Time in microseconds since the distance was sampled.
* @param distance Distance to the center of the flow field in meters. Positive value (including zero): distance known. Negative value: Unknown distance.
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_optical_flow_rad_send(mavlink_channel_t chan, uint64_t time_usec, uint8_t sensor_id, uint32_t integration_time_us, float integrated_x, float integrated_y, float integrated_xgyro, float integrated_ygyro, float integrated_zgyro, int16_t temperature, uint8_t quality, uint32_t time_delta_distance_us, float distance)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN];
_mav_put_uint64_t(buf, 0, time_usec);
_mav_put_uint32_t(buf, 8, integration_time_us);
_mav_put_float(buf, 12, integrated_x);
_mav_put_float(buf, 16, integrated_y);
_mav_put_float(buf, 20, integrated_xgyro);
_mav_put_float(buf, 24, integrated_ygyro);
_mav_put_float(buf, 28, integrated_zgyro);
_mav_put_uint32_t(buf, 32, time_delta_distance_us);
_mav_put_float(buf, 36, distance);
_mav_put_int16_t(buf, 40, temperature);
_mav_put_uint8_t(buf, 42, sensor_id);
_mav_put_uint8_t(buf, 43, quality);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD, buf, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD, buf, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN);
#endif
#else
mavlink_optical_flow_rad_t packet;
packet.time_usec = time_usec;
packet.integration_time_us = integration_time_us;
packet.integrated_x = integrated_x;
packet.integrated_y = integrated_y;
packet.integrated_xgyro = integrated_xgyro;
packet.integrated_ygyro = integrated_ygyro;
packet.integrated_zgyro = integrated_zgyro;
packet.time_delta_distance_us = time_delta_distance_us;
packet.distance = distance;
packet.temperature = temperature;
packet.sensor_id = sensor_id;
packet.quality = quality;
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD, (const char *)&packet, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD, (const char *)&packet, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN);
#endif
#endif
}
#if MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This varient of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_optical_flow_rad_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, uint8_t sensor_id, uint32_t integration_time_us, float integrated_x, float integrated_y, float integrated_xgyro, float integrated_ygyro, float integrated_zgyro, int16_t temperature, uint8_t quality, uint32_t time_delta_distance_us, float distance)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
_mav_put_uint64_t(buf, 0, time_usec);
_mav_put_uint32_t(buf, 8, integration_time_us);
_mav_put_float(buf, 12, integrated_x);
_mav_put_float(buf, 16, integrated_y);
_mav_put_float(buf, 20, integrated_xgyro);
_mav_put_float(buf, 24, integrated_ygyro);
_mav_put_float(buf, 28, integrated_zgyro);
_mav_put_uint32_t(buf, 32, time_delta_distance_us);
_mav_put_float(buf, 36, distance);
_mav_put_int16_t(buf, 40, temperature);
_mav_put_uint8_t(buf, 42, sensor_id);
_mav_put_uint8_t(buf, 43, quality);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD, buf, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD, buf, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN);
#endif
#else
mavlink_optical_flow_rad_t *packet = (mavlink_optical_flow_rad_t *)msgbuf;
packet->time_usec = time_usec;
packet->integration_time_us = integration_time_us;
packet->integrated_x = integrated_x;
packet->integrated_y = integrated_y;
packet->integrated_xgyro = integrated_xgyro;
packet->integrated_ygyro = integrated_ygyro;
packet->integrated_zgyro = integrated_zgyro;
packet->time_delta_distance_us = time_delta_distance_us;
packet->distance = distance;
packet->temperature = temperature;
packet->sensor_id = sensor_id;
packet->quality = quality;
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD, (const char *)packet, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD, (const char *)packet, MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN);
#endif
#endif
}
#endif
#endif
// MESSAGE OPTICAL_FLOW_RAD UNPACKING
/**
* @brief Get field time_usec from optical_flow_rad message
*
* @return Timestamp (microseconds, synced to UNIX time or since system boot)
*/
static inline uint64_t mavlink_msg_optical_flow_rad_get_time_usec(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint64_t(msg, 0);
}
/**
* @brief Get field sensor_id from optical_flow_rad message
*
* @return Sensor ID
*/
static inline uint8_t mavlink_msg_optical_flow_rad_get_sensor_id(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 42);
}
/**
* @brief Get field integration_time_us from optical_flow_rad message
*
* @return Integration time in microseconds. Divide integrated_x and integrated_y by the integration time to obtain average flow. The integration time also indicates the.
*/
static inline uint32_t mavlink_msg_optical_flow_rad_get_integration_time_us(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint32_t(msg, 8);
}
/**
* @brief Get field integrated_x from optical_flow_rad message
*
* @return Flow in radians around X axis (Sensor RH rotation about the X axis induces a positive flow. Sensor linear motion along the positive Y axis induces a negative flow.)
*/
static inline float mavlink_msg_optical_flow_rad_get_integrated_x(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 12);
}
/**
* @brief Get field integrated_y from optical_flow_rad message
*
* @return Flow in radians around Y axis (Sensor RH rotation about the Y axis induces a positive flow. Sensor linear motion along the positive X axis induces a positive flow.)
*/
static inline float mavlink_msg_optical_flow_rad_get_integrated_y(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 16);
}
/**
* @brief Get field integrated_xgyro from optical_flow_rad message
*
* @return RH rotation around X axis (rad)
*/
static inline float mavlink_msg_optical_flow_rad_get_integrated_xgyro(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 20);
}
/**
* @brief Get field integrated_ygyro from optical_flow_rad message
*
* @return RH rotation around Y axis (rad)
*/
static inline float mavlink_msg_optical_flow_rad_get_integrated_ygyro(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 24);
}
/**
* @brief Get field integrated_zgyro from optical_flow_rad message
*
* @return RH rotation around Z axis (rad)
*/
static inline float mavlink_msg_optical_flow_rad_get_integrated_zgyro(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 28);
}
/**
* @brief Get field temperature from optical_flow_rad message
*
* @return Temperature * 100 in centi-degrees Celsius
*/
static inline int16_t mavlink_msg_optical_flow_rad_get_temperature(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 40);
}
/**
* @brief Get field quality from optical_flow_rad message
*
* @return Optical flow quality / confidence. 0: no valid flow, 255: maximum quality
*/
static inline uint8_t mavlink_msg_optical_flow_rad_get_quality(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 43);
}
/**
* @brief Get field time_delta_distance_us from optical_flow_rad message
*
* @return Time in microseconds since the distance was sampled.
*/
static inline uint32_t mavlink_msg_optical_flow_rad_get_time_delta_distance_us(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint32_t(msg, 32);
}
/**
* @brief Get field distance from optical_flow_rad message
*
* @return Distance to the center of the flow field in meters. Positive value (including zero): distance known. Negative value: Unknown distance.
*/
static inline float mavlink_msg_optical_flow_rad_get_distance(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 36);
}
/**
* @brief Decode a optical_flow_rad message into a struct
*
* @param msg The message to decode
* @param optical_flow_rad C-struct to decode the message contents into
*/
static inline void mavlink_msg_optical_flow_rad_decode(const mavlink_message_t* msg, mavlink_optical_flow_rad_t* optical_flow_rad)
{
#if MAVLINK_NEED_BYTE_SWAP
optical_flow_rad->time_usec = mavlink_msg_optical_flow_rad_get_time_usec(msg);
optical_flow_rad->integration_time_us = mavlink_msg_optical_flow_rad_get_integration_time_us(msg);
optical_flow_rad->integrated_x = mavlink_msg_optical_flow_rad_get_integrated_x(msg);
optical_flow_rad->integrated_y = mavlink_msg_optical_flow_rad_get_integrated_y(msg);
optical_flow_rad->integrated_xgyro = mavlink_msg_optical_flow_rad_get_integrated_xgyro(msg);
optical_flow_rad->integrated_ygyro = mavlink_msg_optical_flow_rad_get_integrated_ygyro(msg);
optical_flow_rad->integrated_zgyro = mavlink_msg_optical_flow_rad_get_integrated_zgyro(msg);
optical_flow_rad->time_delta_distance_us = mavlink_msg_optical_flow_rad_get_time_delta_distance_us(msg);
optical_flow_rad->distance = mavlink_msg_optical_flow_rad_get_distance(msg);
optical_flow_rad->temperature = mavlink_msg_optical_flow_rad_get_temperature(msg);
optical_flow_rad->sensor_id = mavlink_msg_optical_flow_rad_get_sensor_id(msg);
optical_flow_rad->quality = mavlink_msg_optical_flow_rad_get_quality(msg);
#else
memcpy(optical_flow_rad, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_OPTICAL_FLOW_RAD_LEN);
#endif
}

View file

@ -0,0 +1,393 @@
// MESSAGE PARAM_MAP_RC PACKING
#define MAVLINK_MSG_ID_PARAM_MAP_RC 50
typedef struct __mavlink_param_map_rc_t
{
float param_value0; ///< Initial parameter value
float scale; ///< Scale, maps the RC range [-1, 1] to a parameter value
float param_value_min; ///< Minimum param value. The protocol does not define if this overwrites an onboard minimum value. (Depends on implementation)
float param_value_max; ///< Maximum param value. The protocol does not define if this overwrites an onboard maximum value. (Depends on implementation)
int16_t param_index; ///< Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored), send -2 to disable any existing map for this rc_channel_index.
uint8_t target_system; ///< System ID
uint8_t target_component; ///< Component ID
char param_id[16]; ///< Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string
uint8_t parameter_rc_channel_index; ///< Index of parameter RC channel. Not equal to the RC channel id. Typically correpsonds to a potentiometer-knob on the RC.
} mavlink_param_map_rc_t;
#define MAVLINK_MSG_ID_PARAM_MAP_RC_LEN 37
#define MAVLINK_MSG_ID_50_LEN 37
#define MAVLINK_MSG_ID_PARAM_MAP_RC_CRC 78
#define MAVLINK_MSG_ID_50_CRC 78
#define MAVLINK_MSG_PARAM_MAP_RC_FIELD_PARAM_ID_LEN 16
#define MAVLINK_MESSAGE_INFO_PARAM_MAP_RC { \
"PARAM_MAP_RC", \
9, \
{ { "param_value0", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_param_map_rc_t, param_value0) }, \
{ "scale", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_param_map_rc_t, scale) }, \
{ "param_value_min", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_param_map_rc_t, param_value_min) }, \
{ "param_value_max", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_param_map_rc_t, param_value_max) }, \
{ "param_index", NULL, MAVLINK_TYPE_INT16_T, 0, 16, offsetof(mavlink_param_map_rc_t, param_index) }, \
{ "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 18, offsetof(mavlink_param_map_rc_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 19, offsetof(mavlink_param_map_rc_t, target_component) }, \
{ "param_id", NULL, MAVLINK_TYPE_CHAR, 16, 20, offsetof(mavlink_param_map_rc_t, param_id) }, \
{ "parameter_rc_channel_index", NULL, MAVLINK_TYPE_UINT8_T, 0, 36, offsetof(mavlink_param_map_rc_t, parameter_rc_channel_index) }, \
} \
}
/**
* @brief Pack a param_map_rc message
* @param system_id ID of this 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, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string
* @param param_index Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored), send -2 to disable any existing map for this rc_channel_index.
* @param parameter_rc_channel_index Index of parameter RC channel. Not equal to the RC channel id. Typically correpsonds to a potentiometer-knob on the RC.
* @param param_value0 Initial parameter value
* @param scale Scale, maps the RC range [-1, 1] to a parameter value
* @param param_value_min Minimum param value. The protocol does not define if this overwrites an onboard minimum value. (Depends on implementation)
* @param param_value_max Maximum param value. The protocol does not define if this overwrites an onboard maximum value. (Depends on implementation)
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_param_map_rc_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, uint8_t parameter_rc_channel_index, float param_value0, float scale, float param_value_min, float param_value_max)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_PARAM_MAP_RC_LEN];
_mav_put_float(buf, 0, param_value0);
_mav_put_float(buf, 4, scale);
_mav_put_float(buf, 8, param_value_min);
_mav_put_float(buf, 12, param_value_max);
_mav_put_int16_t(buf, 16, param_index);
_mav_put_uint8_t(buf, 18, target_system);
_mav_put_uint8_t(buf, 19, target_component);
_mav_put_uint8_t(buf, 36, parameter_rc_channel_index);
_mav_put_char_array(buf, 20, param_id, 16);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PARAM_MAP_RC_LEN);
#else
mavlink_param_map_rc_t packet;
packet.param_value0 = param_value0;
packet.scale = scale;
packet.param_value_min = param_value_min;
packet.param_value_max = param_value_max;
packet.param_index = param_index;
packet.target_system = target_system;
packet.target_component = target_component;
packet.parameter_rc_channel_index = parameter_rc_channel_index;
mav_array_memcpy(packet.param_id, param_id, sizeof(char)*16);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PARAM_MAP_RC_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_PARAM_MAP_RC;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_PARAM_MAP_RC_LEN, MAVLINK_MSG_ID_PARAM_MAP_RC_CRC);
#else
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_PARAM_MAP_RC_LEN);
#endif
}
/**
* @brief Pack a param_map_rc 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 will be 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, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string
* @param param_index Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored), send -2 to disable any existing map for this rc_channel_index.
* @param parameter_rc_channel_index Index of parameter RC channel. Not equal to the RC channel id. Typically correpsonds to a potentiometer-knob on the RC.
* @param param_value0 Initial parameter value
* @param scale Scale, maps the RC range [-1, 1] to a parameter value
* @param param_value_min Minimum param value. The protocol does not define if this overwrites an onboard minimum value. (Depends on implementation)
* @param param_value_max Maximum param value. The protocol does not define if this overwrites an onboard maximum value. (Depends on implementation)
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_param_map_rc_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,uint8_t parameter_rc_channel_index,float param_value0,float scale,float param_value_min,float param_value_max)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_PARAM_MAP_RC_LEN];
_mav_put_float(buf, 0, param_value0);
_mav_put_float(buf, 4, scale);
_mav_put_float(buf, 8, param_value_min);
_mav_put_float(buf, 12, param_value_max);
_mav_put_int16_t(buf, 16, param_index);
_mav_put_uint8_t(buf, 18, target_system);
_mav_put_uint8_t(buf, 19, target_component);
_mav_put_uint8_t(buf, 36, parameter_rc_channel_index);
_mav_put_char_array(buf, 20, param_id, 16);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PARAM_MAP_RC_LEN);
#else
mavlink_param_map_rc_t packet;
packet.param_value0 = param_value0;
packet.scale = scale;
packet.param_value_min = param_value_min;
packet.param_value_max = param_value_max;
packet.param_index = param_index;
packet.target_system = target_system;
packet.target_component = target_component;
packet.parameter_rc_channel_index = parameter_rc_channel_index;
mav_array_memcpy(packet.param_id, param_id, sizeof(char)*16);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PARAM_MAP_RC_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_PARAM_MAP_RC;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_PARAM_MAP_RC_LEN, MAVLINK_MSG_ID_PARAM_MAP_RC_CRC);
#else
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_PARAM_MAP_RC_LEN);
#endif
}
/**
* @brief Encode a param_map_rc struct
*
* @param system_id ID of this 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_map_rc C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_param_map_rc_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_param_map_rc_t* param_map_rc)
{
return mavlink_msg_param_map_rc_pack(system_id, component_id, msg, param_map_rc->target_system, param_map_rc->target_component, param_map_rc->param_id, param_map_rc->param_index, param_map_rc->parameter_rc_channel_index, param_map_rc->param_value0, param_map_rc->scale, param_map_rc->param_value_min, param_map_rc->param_value_max);
}
/**
* @brief Encode a param_map_rc struct 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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param param_map_rc C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_param_map_rc_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_param_map_rc_t* param_map_rc)
{
return mavlink_msg_param_map_rc_pack_chan(system_id, component_id, chan, msg, param_map_rc->target_system, param_map_rc->target_component, param_map_rc->param_id, param_map_rc->param_index, param_map_rc->parameter_rc_channel_index, param_map_rc->param_value0, param_map_rc->scale, param_map_rc->param_value_min, param_map_rc->param_value_max);
}
/**
* @brief Send a param_map_rc 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, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string
* @param param_index Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored), send -2 to disable any existing map for this rc_channel_index.
* @param parameter_rc_channel_index Index of parameter RC channel. Not equal to the RC channel id. Typically correpsonds to a potentiometer-knob on the RC.
* @param param_value0 Initial parameter value
* @param scale Scale, maps the RC range [-1, 1] to a parameter value
* @param param_value_min Minimum param value. The protocol does not define if this overwrites an onboard minimum value. (Depends on implementation)
* @param param_value_max Maximum param value. The protocol does not define if this overwrites an onboard maximum value. (Depends on implementation)
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_param_map_rc_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, const char *param_id, int16_t param_index, uint8_t parameter_rc_channel_index, float param_value0, float scale, float param_value_min, float param_value_max)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_PARAM_MAP_RC_LEN];
_mav_put_float(buf, 0, param_value0);
_mav_put_float(buf, 4, scale);
_mav_put_float(buf, 8, param_value_min);
_mav_put_float(buf, 12, param_value_max);
_mav_put_int16_t(buf, 16, param_index);
_mav_put_uint8_t(buf, 18, target_system);
_mav_put_uint8_t(buf, 19, target_component);
_mav_put_uint8_t(buf, 36, parameter_rc_channel_index);
_mav_put_char_array(buf, 20, param_id, 16);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_MAP_RC, buf, MAVLINK_MSG_ID_PARAM_MAP_RC_LEN, MAVLINK_MSG_ID_PARAM_MAP_RC_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_MAP_RC, buf, MAVLINK_MSG_ID_PARAM_MAP_RC_LEN);
#endif
#else
mavlink_param_map_rc_t packet;
packet.param_value0 = param_value0;
packet.scale = scale;
packet.param_value_min = param_value_min;
packet.param_value_max = param_value_max;
packet.param_index = param_index;
packet.target_system = target_system;
packet.target_component = target_component;
packet.parameter_rc_channel_index = parameter_rc_channel_index;
mav_array_memcpy(packet.param_id, param_id, sizeof(char)*16);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_MAP_RC, (const char *)&packet, MAVLINK_MSG_ID_PARAM_MAP_RC_LEN, MAVLINK_MSG_ID_PARAM_MAP_RC_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_MAP_RC, (const char *)&packet, MAVLINK_MSG_ID_PARAM_MAP_RC_LEN);
#endif
#endif
}
#if MAVLINK_MSG_ID_PARAM_MAP_RC_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This varient of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_param_map_rc_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, const char *param_id, int16_t param_index, uint8_t parameter_rc_channel_index, float param_value0, float scale, float param_value_min, float param_value_max)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
_mav_put_float(buf, 0, param_value0);
_mav_put_float(buf, 4, scale);
_mav_put_float(buf, 8, param_value_min);
_mav_put_float(buf, 12, param_value_max);
_mav_put_int16_t(buf, 16, param_index);
_mav_put_uint8_t(buf, 18, target_system);
_mav_put_uint8_t(buf, 19, target_component);
_mav_put_uint8_t(buf, 36, parameter_rc_channel_index);
_mav_put_char_array(buf, 20, param_id, 16);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_MAP_RC, buf, MAVLINK_MSG_ID_PARAM_MAP_RC_LEN, MAVLINK_MSG_ID_PARAM_MAP_RC_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_MAP_RC, buf, MAVLINK_MSG_ID_PARAM_MAP_RC_LEN);
#endif
#else
mavlink_param_map_rc_t *packet = (mavlink_param_map_rc_t *)msgbuf;
packet->param_value0 = param_value0;
packet->scale = scale;
packet->param_value_min = param_value_min;
packet->param_value_max = param_value_max;
packet->param_index = param_index;
packet->target_system = target_system;
packet->target_component = target_component;
packet->parameter_rc_channel_index = parameter_rc_channel_index;
mav_array_memcpy(packet->param_id, param_id, sizeof(char)*16);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_MAP_RC, (const char *)packet, MAVLINK_MSG_ID_PARAM_MAP_RC_LEN, MAVLINK_MSG_ID_PARAM_MAP_RC_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_MAP_RC, (const char *)packet, MAVLINK_MSG_ID_PARAM_MAP_RC_LEN);
#endif
#endif
}
#endif
#endif
// MESSAGE PARAM_MAP_RC UNPACKING
/**
* @brief Get field target_system from param_map_rc message
*
* @return System ID
*/
static inline uint8_t mavlink_msg_param_map_rc_get_target_system(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 18);
}
/**
* @brief Get field target_component from param_map_rc message
*
* @return Component ID
*/
static inline uint8_t mavlink_msg_param_map_rc_get_target_component(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 19);
}
/**
* @brief Get field param_id from param_map_rc message
*
* @return Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string
*/
static inline uint16_t mavlink_msg_param_map_rc_get_param_id(const mavlink_message_t* msg, char *param_id)
{
return _MAV_RETURN_char_array(msg, param_id, 16, 20);
}
/**
* @brief Get field param_index from param_map_rc message
*
* @return Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored), send -2 to disable any existing map for this rc_channel_index.
*/
static inline int16_t mavlink_msg_param_map_rc_get_param_index(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 16);
}
/**
* @brief Get field parameter_rc_channel_index from param_map_rc message
*
* @return Index of parameter RC channel. Not equal to the RC channel id. Typically correpsonds to a potentiometer-knob on the RC.
*/
static inline uint8_t mavlink_msg_param_map_rc_get_parameter_rc_channel_index(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 36);
}
/**
* @brief Get field param_value0 from param_map_rc message
*
* @return Initial parameter value
*/
static inline float mavlink_msg_param_map_rc_get_param_value0(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 0);
}
/**
* @brief Get field scale from param_map_rc message
*
* @return Scale, maps the RC range [-1, 1] to a parameter value
*/
static inline float mavlink_msg_param_map_rc_get_scale(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 4);
}
/**
* @brief Get field param_value_min from param_map_rc message
*
* @return Minimum param value. The protocol does not define if this overwrites an onboard minimum value. (Depends on implementation)
*/
static inline float mavlink_msg_param_map_rc_get_param_value_min(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 8);
}
/**
* @brief Get field param_value_max from param_map_rc message
*
* @return Maximum param value. The protocol does not define if this overwrites an onboard maximum value. (Depends on implementation)
*/
static inline float mavlink_msg_param_map_rc_get_param_value_max(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 12);
}
/**
* @brief Decode a param_map_rc message into a struct
*
* @param msg The message to decode
* @param param_map_rc C-struct to decode the message contents into
*/
static inline void mavlink_msg_param_map_rc_decode(const mavlink_message_t* msg, mavlink_param_map_rc_t* param_map_rc)
{
#if MAVLINK_NEED_BYTE_SWAP
param_map_rc->param_value0 = mavlink_msg_param_map_rc_get_param_value0(msg);
param_map_rc->scale = mavlink_msg_param_map_rc_get_scale(msg);
param_map_rc->param_value_min = mavlink_msg_param_map_rc_get_param_value_min(msg);
param_map_rc->param_value_max = mavlink_msg_param_map_rc_get_param_value_max(msg);
param_map_rc->param_index = mavlink_msg_param_map_rc_get_param_index(msg);
param_map_rc->target_system = mavlink_msg_param_map_rc_get_target_system(msg);
param_map_rc->target_component = mavlink_msg_param_map_rc_get_target_component(msg);
mavlink_msg_param_map_rc_get_param_id(msg, param_map_rc->param_id);
param_map_rc->parameter_rc_channel_index = mavlink_msg_param_map_rc_get_parameter_rc_channel_index(msg);
#else
memcpy(param_map_rc, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_PARAM_MAP_RC_LEN);
#endif
}

View file

@ -0,0 +1,233 @@
// 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_MSG_ID_PARAM_REQUEST_LIST_CRC 159
#define MAVLINK_MSG_ID_21_CRC 159
#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[MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN);
#else
mavlink_param_request_list_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_PARAM_REQUEST_LIST;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_CRC);
#else
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN);
#endif
}
/**
* @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 will be 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[MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN);
#else
mavlink_param_request_list_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_PARAM_REQUEST_LIST;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_CRC);
#else
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN);
#endif
}
/**
* @brief Encode a param_request_list struct
*
* @param system_id ID of this 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 Encode a param_request_list struct 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 will be sent over
* @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_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_param_request_list_t* param_request_list)
{
return mavlink_msg_param_request_list_pack_chan(system_id, component_id, chan, 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[MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_REQUEST_LIST, buf, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_REQUEST_LIST, buf, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN);
#endif
#else
mavlink_param_request_list_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_REQUEST_LIST, (const char *)&packet, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_REQUEST_LIST, (const char *)&packet, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN);
#endif
#endif
}
#if MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This varient of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_param_request_list_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_REQUEST_LIST, buf, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_REQUEST_LIST, buf, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN);
#endif
#else
mavlink_param_request_list_t *packet = (mavlink_param_request_list_t *)msgbuf;
packet->target_system = target_system;
packet->target_component = target_component;
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_REQUEST_LIST, (const char *)packet, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_REQUEST_LIST, (const char *)packet, MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN);
#endif
#endif
}
#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), MAVLINK_MSG_ID_PARAM_REQUEST_LIST_LEN);
#endif
}

View file

@ -0,0 +1,273 @@
// 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 (else the param id will be ignored)
uint8_t target_system; ///< System ID
uint8_t target_component; ///< Component ID
char param_id[16]; ///< Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string
} mavlink_param_request_read_t;
#define MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN 20
#define MAVLINK_MSG_ID_20_LEN 20
#define MAVLINK_MSG_ID_PARAM_REQUEST_READ_CRC 214
#define MAVLINK_MSG_ID_20_CRC 214
#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, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string
* @param param_index Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored)
* @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[MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN];
_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, MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN);
#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, MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_PARAM_REQUEST_READ;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN, MAVLINK_MSG_ID_PARAM_REQUEST_READ_CRC);
#else
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN);
#endif
}
/**
* @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 will be 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, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string
* @param param_index Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored)
* @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[MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN];
_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, MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN);
#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, MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_PARAM_REQUEST_READ;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN, MAVLINK_MSG_ID_PARAM_REQUEST_READ_CRC);
#else
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN);
#endif
}
/**
* @brief Encode a param_request_read struct
*
* @param system_id ID of this 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 Encode a param_request_read struct 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 will be sent over
* @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_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_param_request_read_t* param_request_read)
{
return mavlink_msg_param_request_read_pack_chan(system_id, component_id, chan, 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, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string
* @param param_index Parameter index. Send -1 to use the param ID field as identifier (else the param id will be ignored)
*/
#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[MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN];
_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);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_REQUEST_READ, buf, MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN, MAVLINK_MSG_ID_PARAM_REQUEST_READ_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_REQUEST_READ, buf, MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN);
#endif
#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);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_REQUEST_READ, (const char *)&packet, MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN, MAVLINK_MSG_ID_PARAM_REQUEST_READ_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_REQUEST_READ, (const char *)&packet, MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN);
#endif
#endif
}
#if MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This varient of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_param_request_read_send_buf(mavlink_message_t *msgbuf, 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 = (char *)msgbuf;
_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);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_REQUEST_READ, buf, MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN, MAVLINK_MSG_ID_PARAM_REQUEST_READ_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_REQUEST_READ, buf, MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN);
#endif
#else
mavlink_param_request_read_t *packet = (mavlink_param_request_read_t *)msgbuf;
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);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_REQUEST_READ, (const char *)packet, MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN, MAVLINK_MSG_ID_PARAM_REQUEST_READ_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_REQUEST_READ, (const char *)packet, MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN);
#endif
#endif
}
#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, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string
*/
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 (else the param id will be ignored)
*/
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), MAVLINK_MSG_ID_PARAM_REQUEST_READ_LEN);
#endif
}

View file

@ -0,0 +1,297 @@
// 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, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string
uint8_t param_type; ///< Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types.
} mavlink_param_set_t;
#define MAVLINK_MSG_ID_PARAM_SET_LEN 23
#define MAVLINK_MSG_ID_23_LEN 23
#define MAVLINK_MSG_ID_PARAM_SET_CRC 168
#define MAVLINK_MSG_ID_23_CRC 168
#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, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string
* @param param_value Onboard parameter value
* @param param_type Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types.
* @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[MAVLINK_MSG_ID_PARAM_SET_LEN];
_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, MAVLINK_MSG_ID_PARAM_SET_LEN);
#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, MAVLINK_MSG_ID_PARAM_SET_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_PARAM_SET;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_PARAM_SET_LEN, MAVLINK_MSG_ID_PARAM_SET_CRC);
#else
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_PARAM_SET_LEN);
#endif
}
/**
* @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 will be 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, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string
* @param param_value Onboard parameter value
* @param param_type Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types.
* @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[MAVLINK_MSG_ID_PARAM_SET_LEN];
_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, MAVLINK_MSG_ID_PARAM_SET_LEN);
#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, MAVLINK_MSG_ID_PARAM_SET_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_PARAM_SET;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_PARAM_SET_LEN, MAVLINK_MSG_ID_PARAM_SET_CRC);
#else
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_PARAM_SET_LEN);
#endif
}
/**
* @brief Encode a param_set struct
*
* @param system_id ID of this 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 Encode a param_set struct 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 will be sent over
* @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_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_param_set_t* param_set)
{
return mavlink_msg_param_set_pack_chan(system_id, component_id, chan, 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, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string
* @param param_value Onboard parameter value
* @param param_type Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types.
*/
#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[MAVLINK_MSG_ID_PARAM_SET_LEN];
_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);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_SET, buf, MAVLINK_MSG_ID_PARAM_SET_LEN, MAVLINK_MSG_ID_PARAM_SET_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_SET, buf, MAVLINK_MSG_ID_PARAM_SET_LEN);
#endif
#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);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_SET, (const char *)&packet, MAVLINK_MSG_ID_PARAM_SET_LEN, MAVLINK_MSG_ID_PARAM_SET_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_SET, (const char *)&packet, MAVLINK_MSG_ID_PARAM_SET_LEN);
#endif
#endif
}
#if MAVLINK_MSG_ID_PARAM_SET_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This varient of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_param_set_send_buf(mavlink_message_t *msgbuf, 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 = (char *)msgbuf;
_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);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_SET, buf, MAVLINK_MSG_ID_PARAM_SET_LEN, MAVLINK_MSG_ID_PARAM_SET_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_SET, buf, MAVLINK_MSG_ID_PARAM_SET_LEN);
#endif
#else
mavlink_param_set_t *packet = (mavlink_param_set_t *)msgbuf;
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);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_SET, (const char *)packet, MAVLINK_MSG_ID_PARAM_SET_LEN, MAVLINK_MSG_ID_PARAM_SET_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_SET, (const char *)packet, MAVLINK_MSG_ID_PARAM_SET_LEN);
#endif
#endif
}
#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, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string
*/
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 the MAV_PARAM_TYPE enum for supported data types.
*/
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), MAVLINK_MSG_ID_PARAM_SET_LEN);
#endif
}

View file

@ -0,0 +1,297 @@
// 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, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string
uint8_t param_type; ///< Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types.
} mavlink_param_value_t;
#define MAVLINK_MSG_ID_PARAM_VALUE_LEN 25
#define MAVLINK_MSG_ID_22_LEN 25
#define MAVLINK_MSG_ID_PARAM_VALUE_CRC 220
#define MAVLINK_MSG_ID_22_CRC 220
#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, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string
* @param param_value Onboard parameter value
* @param param_type Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types.
* @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[MAVLINK_MSG_ID_PARAM_VALUE_LEN];
_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, MAVLINK_MSG_ID_PARAM_VALUE_LEN);
#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, MAVLINK_MSG_ID_PARAM_VALUE_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_PARAM_VALUE;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_PARAM_VALUE_LEN, MAVLINK_MSG_ID_PARAM_VALUE_CRC);
#else
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_PARAM_VALUE_LEN);
#endif
}
/**
* @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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param param_id Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string
* @param param_value Onboard parameter value
* @param param_type Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types.
* @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[MAVLINK_MSG_ID_PARAM_VALUE_LEN];
_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, MAVLINK_MSG_ID_PARAM_VALUE_LEN);
#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, MAVLINK_MSG_ID_PARAM_VALUE_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_PARAM_VALUE;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_PARAM_VALUE_LEN, MAVLINK_MSG_ID_PARAM_VALUE_CRC);
#else
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_PARAM_VALUE_LEN);
#endif
}
/**
* @brief Encode a param_value struct
*
* @param system_id ID of this 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 Encode a param_value struct 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 will be sent over
* @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_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_param_value_t* param_value)
{
return mavlink_msg_param_value_pack_chan(system_id, component_id, chan, 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, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string
* @param param_value Onboard parameter value
* @param param_type Onboard parameter type: see the MAV_PARAM_TYPE enum for supported data types.
* @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[MAVLINK_MSG_ID_PARAM_VALUE_LEN];
_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);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_VALUE, buf, MAVLINK_MSG_ID_PARAM_VALUE_LEN, MAVLINK_MSG_ID_PARAM_VALUE_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_VALUE, buf, MAVLINK_MSG_ID_PARAM_VALUE_LEN);
#endif
#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);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_VALUE, (const char *)&packet, MAVLINK_MSG_ID_PARAM_VALUE_LEN, MAVLINK_MSG_ID_PARAM_VALUE_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_VALUE, (const char *)&packet, MAVLINK_MSG_ID_PARAM_VALUE_LEN);
#endif
#endif
}
#if MAVLINK_MSG_ID_PARAM_VALUE_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This varient of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_param_value_send_buf(mavlink_message_t *msgbuf, 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 = (char *)msgbuf;
_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);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_VALUE, buf, MAVLINK_MSG_ID_PARAM_VALUE_LEN, MAVLINK_MSG_ID_PARAM_VALUE_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_VALUE, buf, MAVLINK_MSG_ID_PARAM_VALUE_LEN);
#endif
#else
mavlink_param_value_t *packet = (mavlink_param_value_t *)msgbuf;
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);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_VALUE, (const char *)packet, MAVLINK_MSG_ID_PARAM_VALUE_LEN, MAVLINK_MSG_ID_PARAM_VALUE_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_VALUE, (const char *)packet, MAVLINK_MSG_ID_PARAM_VALUE_LEN);
#endif
#endif
}
#endif
#endif
// MESSAGE PARAM_VALUE UNPACKING
/**
* @brief Get field param_id from param_value message
*
* @return Onboard parameter id, terminated by NULL if the length is less than 16 human-readable chars and WITHOUT null termination (NULL) byte if the length is exactly 16 chars - applications have to provide 16+1 bytes storage if the ID is stored as string
*/
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 the MAV_PARAM_TYPE enum for supported data types.
*/
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), MAVLINK_MSG_ID_PARAM_VALUE_LEN);
#endif
}

View file

@ -0,0 +1,281 @@
// MESSAGE PING PACKING
#define MAVLINK_MSG_ID_PING 4
typedef struct __mavlink_ping_t
{
uint64_t time_usec; ///< Unix timestamp in microseconds or since system boot if smaller than MAVLink epoch (1.1.2009)
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_MSG_ID_PING_CRC 237
#define MAVLINK_MSG_ID_4_CRC 237
#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 or since system boot if smaller than MAVLink epoch (1.1.2009)
* @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[MAVLINK_MSG_ID_PING_LEN];
_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, MAVLINK_MSG_ID_PING_LEN);
#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, MAVLINK_MSG_ID_PING_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_PING;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_PING_LEN, MAVLINK_MSG_ID_PING_CRC);
#else
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_PING_LEN);
#endif
}
/**
* @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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param time_usec Unix timestamp in microseconds or since system boot if smaller than MAVLink epoch (1.1.2009)
* @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[MAVLINK_MSG_ID_PING_LEN];
_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, MAVLINK_MSG_ID_PING_LEN);
#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, MAVLINK_MSG_ID_PING_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_PING;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_PING_LEN, MAVLINK_MSG_ID_PING_CRC);
#else
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_PING_LEN);
#endif
}
/**
* @brief Encode a ping struct
*
* @param system_id ID of this 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 Encode a ping struct 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 will be sent over
* @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_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_ping_t* ping)
{
return mavlink_msg_ping_pack_chan(system_id, component_id, chan, 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 or since system boot if smaller than MAVLink epoch (1.1.2009)
* @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[MAVLINK_MSG_ID_PING_LEN];
_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);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PING, buf, MAVLINK_MSG_ID_PING_LEN, MAVLINK_MSG_ID_PING_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PING, buf, MAVLINK_MSG_ID_PING_LEN);
#endif
#else
mavlink_ping_t packet;
packet.time_usec = time_usec;
packet.seq = seq;
packet.target_system = target_system;
packet.target_component = target_component;
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PING, (const char *)&packet, MAVLINK_MSG_ID_PING_LEN, MAVLINK_MSG_ID_PING_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PING, (const char *)&packet, MAVLINK_MSG_ID_PING_LEN);
#endif
#endif
}
#if MAVLINK_MSG_ID_PING_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This varient of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_ping_send_buf(mavlink_message_t *msgbuf, 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 = (char *)msgbuf;
_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);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PING, buf, MAVLINK_MSG_ID_PING_LEN, MAVLINK_MSG_ID_PING_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PING, buf, MAVLINK_MSG_ID_PING_LEN);
#endif
#else
mavlink_ping_t *packet = (mavlink_ping_t *)msgbuf;
packet->time_usec = time_usec;
packet->seq = seq;
packet->target_system = target_system;
packet->target_component = target_component;
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PING, (const char *)packet, MAVLINK_MSG_ID_PING_LEN, MAVLINK_MSG_ID_PING_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PING, (const char *)packet, MAVLINK_MSG_ID_PING_LEN);
#endif
#endif
}
#endif
#endif
// MESSAGE PING UNPACKING
/**
* @brief Get field time_usec from ping message
*
* @return Unix timestamp in microseconds or since system boot if smaller than MAVLink epoch (1.1.2009)
*/
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), MAVLINK_MSG_ID_PING_LEN);
#endif
}

View file

@ -0,0 +1,521 @@
// MESSAGE POSITION_TARGET_GLOBAL_INT PACKING
#define MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT 87
typedef struct __mavlink_position_target_global_int_t
{
uint32_t time_boot_ms; ///< Timestamp in milliseconds since system boot. The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency.
int32_t lat_int; ///< X Position in WGS84 frame in 1e7 * meters
int32_t lon_int; ///< Y Position in WGS84 frame in 1e7 * meters
float alt; ///< Altitude in meters in AMSL altitude, not WGS84 if absolute or relative, above terrain if GLOBAL_TERRAIN_ALT_INT
float vx; ///< X velocity in NED frame in meter / s
float vy; ///< Y velocity in NED frame in meter / s
float vz; ///< Z velocity in NED frame in meter / s
float afx; ///< X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
float afy; ///< Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
float afz; ///< Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
float yaw; ///< yaw setpoint in rad
float yaw_rate; ///< yaw rate setpoint in rad/s
uint16_t type_mask; ///< Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate
uint8_t coordinate_frame; ///< Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11
} mavlink_position_target_global_int_t;
#define MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN 51
#define MAVLINK_MSG_ID_87_LEN 51
#define MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_CRC 150
#define MAVLINK_MSG_ID_87_CRC 150
#define MAVLINK_MESSAGE_INFO_POSITION_TARGET_GLOBAL_INT { \
"POSITION_TARGET_GLOBAL_INT", \
14, \
{ { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_position_target_global_int_t, time_boot_ms) }, \
{ "lat_int", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_position_target_global_int_t, lat_int) }, \
{ "lon_int", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_position_target_global_int_t, lon_int) }, \
{ "alt", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_position_target_global_int_t, alt) }, \
{ "vx", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_position_target_global_int_t, vx) }, \
{ "vy", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_position_target_global_int_t, vy) }, \
{ "vz", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_position_target_global_int_t, vz) }, \
{ "afx", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_position_target_global_int_t, afx) }, \
{ "afy", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_position_target_global_int_t, afy) }, \
{ "afz", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_position_target_global_int_t, afz) }, \
{ "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_position_target_global_int_t, yaw) }, \
{ "yaw_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_position_target_global_int_t, yaw_rate) }, \
{ "type_mask", NULL, MAVLINK_TYPE_UINT16_T, 0, 48, offsetof(mavlink_position_target_global_int_t, type_mask) }, \
{ "coordinate_frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 50, offsetof(mavlink_position_target_global_int_t, coordinate_frame) }, \
} \
}
/**
* @brief Pack a position_target_global_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 in milliseconds since system boot. The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency.
* @param coordinate_frame Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11
* @param type_mask Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate
* @param lat_int X Position in WGS84 frame in 1e7 * meters
* @param lon_int Y Position in WGS84 frame in 1e7 * meters
* @param alt Altitude in meters in AMSL altitude, not WGS84 if absolute or relative, above terrain if GLOBAL_TERRAIN_ALT_INT
* @param vx X velocity in NED frame in meter / s
* @param vy Y velocity in NED frame in meter / s
* @param vz Z velocity in NED frame in meter / s
* @param afx X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
* @param afy Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
* @param afz Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
* @param yaw yaw setpoint in rad
* @param yaw_rate yaw rate setpoint in rad/s
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_position_target_global_int_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint32_t time_boot_ms, uint8_t coordinate_frame, uint16_t type_mask, int32_t lat_int, int32_t lon_int, float alt, float vx, float vy, float vz, float afx, float afy, float afz, float yaw, float yaw_rate)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN];
_mav_put_uint32_t(buf, 0, time_boot_ms);
_mav_put_int32_t(buf, 4, lat_int);
_mav_put_int32_t(buf, 8, lon_int);
_mav_put_float(buf, 12, alt);
_mav_put_float(buf, 16, vx);
_mav_put_float(buf, 20, vy);
_mav_put_float(buf, 24, vz);
_mav_put_float(buf, 28, afx);
_mav_put_float(buf, 32, afy);
_mav_put_float(buf, 36, afz);
_mav_put_float(buf, 40, yaw);
_mav_put_float(buf, 44, yaw_rate);
_mav_put_uint16_t(buf, 48, type_mask);
_mav_put_uint8_t(buf, 50, coordinate_frame);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN);
#else
mavlink_position_target_global_int_t packet;
packet.time_boot_ms = time_boot_ms;
packet.lat_int = lat_int;
packet.lon_int = lon_int;
packet.alt = alt;
packet.vx = vx;
packet.vy = vy;
packet.vz = vz;
packet.afx = afx;
packet.afy = afy;
packet.afz = afz;
packet.yaw = yaw;
packet.yaw_rate = yaw_rate;
packet.type_mask = type_mask;
packet.coordinate_frame = coordinate_frame;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_CRC);
#else
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN);
#endif
}
/**
* @brief Pack a position_target_global_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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param time_boot_ms Timestamp in milliseconds since system boot. The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency.
* @param coordinate_frame Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11
* @param type_mask Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate
* @param lat_int X Position in WGS84 frame in 1e7 * meters
* @param lon_int Y Position in WGS84 frame in 1e7 * meters
* @param alt Altitude in meters in AMSL altitude, not WGS84 if absolute or relative, above terrain if GLOBAL_TERRAIN_ALT_INT
* @param vx X velocity in NED frame in meter / s
* @param vy Y velocity in NED frame in meter / s
* @param vz Z velocity in NED frame in meter / s
* @param afx X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
* @param afy Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
* @param afz Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
* @param yaw yaw setpoint in rad
* @param yaw_rate yaw rate setpoint in rad/s
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_position_target_global_int_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint32_t time_boot_ms,uint8_t coordinate_frame,uint16_t type_mask,int32_t lat_int,int32_t lon_int,float alt,float vx,float vy,float vz,float afx,float afy,float afz,float yaw,float yaw_rate)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN];
_mav_put_uint32_t(buf, 0, time_boot_ms);
_mav_put_int32_t(buf, 4, lat_int);
_mav_put_int32_t(buf, 8, lon_int);
_mav_put_float(buf, 12, alt);
_mav_put_float(buf, 16, vx);
_mav_put_float(buf, 20, vy);
_mav_put_float(buf, 24, vz);
_mav_put_float(buf, 28, afx);
_mav_put_float(buf, 32, afy);
_mav_put_float(buf, 36, afz);
_mav_put_float(buf, 40, yaw);
_mav_put_float(buf, 44, yaw_rate);
_mav_put_uint16_t(buf, 48, type_mask);
_mav_put_uint8_t(buf, 50, coordinate_frame);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN);
#else
mavlink_position_target_global_int_t packet;
packet.time_boot_ms = time_boot_ms;
packet.lat_int = lat_int;
packet.lon_int = lon_int;
packet.alt = alt;
packet.vx = vx;
packet.vy = vy;
packet.vz = vz;
packet.afx = afx;
packet.afy = afy;
packet.afz = afz;
packet.yaw = yaw;
packet.yaw_rate = yaw_rate;
packet.type_mask = type_mask;
packet.coordinate_frame = coordinate_frame;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_CRC);
#else
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN);
#endif
}
/**
* @brief Encode a position_target_global_int struct
*
* @param system_id ID of this 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_global_int C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_position_target_global_int_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_position_target_global_int_t* position_target_global_int)
{
return mavlink_msg_position_target_global_int_pack(system_id, component_id, msg, position_target_global_int->time_boot_ms, position_target_global_int->coordinate_frame, position_target_global_int->type_mask, position_target_global_int->lat_int, position_target_global_int->lon_int, position_target_global_int->alt, position_target_global_int->vx, position_target_global_int->vy, position_target_global_int->vz, position_target_global_int->afx, position_target_global_int->afy, position_target_global_int->afz, position_target_global_int->yaw, position_target_global_int->yaw_rate);
}
/**
* @brief Encode a position_target_global_int struct 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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param position_target_global_int C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_position_target_global_int_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_position_target_global_int_t* position_target_global_int)
{
return mavlink_msg_position_target_global_int_pack_chan(system_id, component_id, chan, msg, position_target_global_int->time_boot_ms, position_target_global_int->coordinate_frame, position_target_global_int->type_mask, position_target_global_int->lat_int, position_target_global_int->lon_int, position_target_global_int->alt, position_target_global_int->vx, position_target_global_int->vy, position_target_global_int->vz, position_target_global_int->afx, position_target_global_int->afy, position_target_global_int->afz, position_target_global_int->yaw, position_target_global_int->yaw_rate);
}
/**
* @brief Send a position_target_global_int message
* @param chan MAVLink channel to send the message
*
* @param time_boot_ms Timestamp in milliseconds since system boot. The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency.
* @param coordinate_frame Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11
* @param type_mask Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate
* @param lat_int X Position in WGS84 frame in 1e7 * meters
* @param lon_int Y Position in WGS84 frame in 1e7 * meters
* @param alt Altitude in meters in AMSL altitude, not WGS84 if absolute or relative, above terrain if GLOBAL_TERRAIN_ALT_INT
* @param vx X velocity in NED frame in meter / s
* @param vy Y velocity in NED frame in meter / s
* @param vz Z velocity in NED frame in meter / s
* @param afx X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
* @param afy Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
* @param afz Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
* @param yaw yaw setpoint in rad
* @param yaw_rate yaw rate setpoint in rad/s
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_position_target_global_int_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t coordinate_frame, uint16_t type_mask, int32_t lat_int, int32_t lon_int, float alt, float vx, float vy, float vz, float afx, float afy, float afz, float yaw, float yaw_rate)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN];
_mav_put_uint32_t(buf, 0, time_boot_ms);
_mav_put_int32_t(buf, 4, lat_int);
_mav_put_int32_t(buf, 8, lon_int);
_mav_put_float(buf, 12, alt);
_mav_put_float(buf, 16, vx);
_mav_put_float(buf, 20, vy);
_mav_put_float(buf, 24, vz);
_mav_put_float(buf, 28, afx);
_mav_put_float(buf, 32, afy);
_mav_put_float(buf, 36, afz);
_mav_put_float(buf, 40, yaw);
_mav_put_float(buf, 44, yaw_rate);
_mav_put_uint16_t(buf, 48, type_mask);
_mav_put_uint8_t(buf, 50, coordinate_frame);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT, buf, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT, buf, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN);
#endif
#else
mavlink_position_target_global_int_t packet;
packet.time_boot_ms = time_boot_ms;
packet.lat_int = lat_int;
packet.lon_int = lon_int;
packet.alt = alt;
packet.vx = vx;
packet.vy = vy;
packet.vz = vz;
packet.afx = afx;
packet.afy = afy;
packet.afz = afz;
packet.yaw = yaw;
packet.yaw_rate = yaw_rate;
packet.type_mask = type_mask;
packet.coordinate_frame = coordinate_frame;
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT, (const char *)&packet, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT, (const char *)&packet, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN);
#endif
#endif
}
#if MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This varient of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_position_target_global_int_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t coordinate_frame, uint16_t type_mask, int32_t lat_int, int32_t lon_int, float alt, float vx, float vy, float vz, float afx, float afy, float afz, float yaw, float yaw_rate)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
_mav_put_uint32_t(buf, 0, time_boot_ms);
_mav_put_int32_t(buf, 4, lat_int);
_mav_put_int32_t(buf, 8, lon_int);
_mav_put_float(buf, 12, alt);
_mav_put_float(buf, 16, vx);
_mav_put_float(buf, 20, vy);
_mav_put_float(buf, 24, vz);
_mav_put_float(buf, 28, afx);
_mav_put_float(buf, 32, afy);
_mav_put_float(buf, 36, afz);
_mav_put_float(buf, 40, yaw);
_mav_put_float(buf, 44, yaw_rate);
_mav_put_uint16_t(buf, 48, type_mask);
_mav_put_uint8_t(buf, 50, coordinate_frame);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT, buf, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT, buf, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN);
#endif
#else
mavlink_position_target_global_int_t *packet = (mavlink_position_target_global_int_t *)msgbuf;
packet->time_boot_ms = time_boot_ms;
packet->lat_int = lat_int;
packet->lon_int = lon_int;
packet->alt = alt;
packet->vx = vx;
packet->vy = vy;
packet->vz = vz;
packet->afx = afx;
packet->afy = afy;
packet->afz = afz;
packet->yaw = yaw;
packet->yaw_rate = yaw_rate;
packet->type_mask = type_mask;
packet->coordinate_frame = coordinate_frame;
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT, (const char *)packet, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT, (const char *)packet, MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN);
#endif
#endif
}
#endif
#endif
// MESSAGE POSITION_TARGET_GLOBAL_INT UNPACKING
/**
* @brief Get field time_boot_ms from position_target_global_int message
*
* @return Timestamp in milliseconds since system boot. The rationale for the timestamp in the setpoint is to allow the system to compensate for the transport delay of the setpoint. This allows the system to compensate processing latency.
*/
static inline uint32_t mavlink_msg_position_target_global_int_get_time_boot_ms(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint32_t(msg, 0);
}
/**
* @brief Get field coordinate_frame from position_target_global_int message
*
* @return Valid options are: MAV_FRAME_GLOBAL_INT = 5, MAV_FRAME_GLOBAL_RELATIVE_ALT_INT = 6, MAV_FRAME_GLOBAL_TERRAIN_ALT_INT = 11
*/
static inline uint8_t mavlink_msg_position_target_global_int_get_coordinate_frame(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 50);
}
/**
* @brief Get field type_mask from position_target_global_int message
*
* @return Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate
*/
static inline uint16_t mavlink_msg_position_target_global_int_get_type_mask(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 48);
}
/**
* @brief Get field lat_int from position_target_global_int message
*
* @return X Position in WGS84 frame in 1e7 * meters
*/
static inline int32_t mavlink_msg_position_target_global_int_get_lat_int(const mavlink_message_t* msg)
{
return _MAV_RETURN_int32_t(msg, 4);
}
/**
* @brief Get field lon_int from position_target_global_int message
*
* @return Y Position in WGS84 frame in 1e7 * meters
*/
static inline int32_t mavlink_msg_position_target_global_int_get_lon_int(const mavlink_message_t* msg)
{
return _MAV_RETURN_int32_t(msg, 8);
}
/**
* @brief Get field alt from position_target_global_int message
*
* @return Altitude in meters in AMSL altitude, not WGS84 if absolute or relative, above terrain if GLOBAL_TERRAIN_ALT_INT
*/
static inline float mavlink_msg_position_target_global_int_get_alt(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 12);
}
/**
* @brief Get field vx from position_target_global_int message
*
* @return X velocity in NED frame in meter / s
*/
static inline float mavlink_msg_position_target_global_int_get_vx(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 16);
}
/**
* @brief Get field vy from position_target_global_int message
*
* @return Y velocity in NED frame in meter / s
*/
static inline float mavlink_msg_position_target_global_int_get_vy(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 20);
}
/**
* @brief Get field vz from position_target_global_int message
*
* @return Z velocity in NED frame in meter / s
*/
static inline float mavlink_msg_position_target_global_int_get_vz(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 24);
}
/**
* @brief Get field afx from position_target_global_int message
*
* @return X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
*/
static inline float mavlink_msg_position_target_global_int_get_afx(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 28);
}
/**
* @brief Get field afy from position_target_global_int message
*
* @return Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
*/
static inline float mavlink_msg_position_target_global_int_get_afy(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 32);
}
/**
* @brief Get field afz from position_target_global_int message
*
* @return Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
*/
static inline float mavlink_msg_position_target_global_int_get_afz(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 36);
}
/**
* @brief Get field yaw from position_target_global_int message
*
* @return yaw setpoint in rad
*/
static inline float mavlink_msg_position_target_global_int_get_yaw(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 40);
}
/**
* @brief Get field yaw_rate from position_target_global_int message
*
* @return yaw rate setpoint in rad/s
*/
static inline float mavlink_msg_position_target_global_int_get_yaw_rate(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 44);
}
/**
* @brief Decode a position_target_global_int message into a struct
*
* @param msg The message to decode
* @param position_target_global_int C-struct to decode the message contents into
*/
static inline void mavlink_msg_position_target_global_int_decode(const mavlink_message_t* msg, mavlink_position_target_global_int_t* position_target_global_int)
{
#if MAVLINK_NEED_BYTE_SWAP
position_target_global_int->time_boot_ms = mavlink_msg_position_target_global_int_get_time_boot_ms(msg);
position_target_global_int->lat_int = mavlink_msg_position_target_global_int_get_lat_int(msg);
position_target_global_int->lon_int = mavlink_msg_position_target_global_int_get_lon_int(msg);
position_target_global_int->alt = mavlink_msg_position_target_global_int_get_alt(msg);
position_target_global_int->vx = mavlink_msg_position_target_global_int_get_vx(msg);
position_target_global_int->vy = mavlink_msg_position_target_global_int_get_vy(msg);
position_target_global_int->vz = mavlink_msg_position_target_global_int_get_vz(msg);
position_target_global_int->afx = mavlink_msg_position_target_global_int_get_afx(msg);
position_target_global_int->afy = mavlink_msg_position_target_global_int_get_afy(msg);
position_target_global_int->afz = mavlink_msg_position_target_global_int_get_afz(msg);
position_target_global_int->yaw = mavlink_msg_position_target_global_int_get_yaw(msg);
position_target_global_int->yaw_rate = mavlink_msg_position_target_global_int_get_yaw_rate(msg);
position_target_global_int->type_mask = mavlink_msg_position_target_global_int_get_type_mask(msg);
position_target_global_int->coordinate_frame = mavlink_msg_position_target_global_int_get_coordinate_frame(msg);
#else
memcpy(position_target_global_int, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_POSITION_TARGET_GLOBAL_INT_LEN);
#endif
}

View file

@ -0,0 +1,521 @@
// MESSAGE POSITION_TARGET_LOCAL_NED PACKING
#define MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED 85
typedef struct __mavlink_position_target_local_ned_t
{
uint32_t time_boot_ms; ///< Timestamp in milliseconds since system boot
float x; ///< X Position in NED frame in meters
float y; ///< Y Position in NED frame in meters
float z; ///< Z Position in NED frame in meters (note, altitude is negative in NED)
float vx; ///< X velocity in NED frame in meter / s
float vy; ///< Y velocity in NED frame in meter / s
float vz; ///< Z velocity in NED frame in meter / s
float afx; ///< X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
float afy; ///< Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
float afz; ///< Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
float yaw; ///< yaw setpoint in rad
float yaw_rate; ///< yaw rate setpoint in rad/s
uint16_t type_mask; ///< Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate
uint8_t coordinate_frame; ///< Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9
} mavlink_position_target_local_ned_t;
#define MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN 51
#define MAVLINK_MSG_ID_85_LEN 51
#define MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_CRC 140
#define MAVLINK_MSG_ID_85_CRC 140
#define MAVLINK_MESSAGE_INFO_POSITION_TARGET_LOCAL_NED { \
"POSITION_TARGET_LOCAL_NED", \
14, \
{ { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_position_target_local_ned_t, time_boot_ms) }, \
{ "x", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_position_target_local_ned_t, x) }, \
{ "y", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_position_target_local_ned_t, y) }, \
{ "z", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_position_target_local_ned_t, z) }, \
{ "vx", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_position_target_local_ned_t, vx) }, \
{ "vy", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_position_target_local_ned_t, vy) }, \
{ "vz", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_position_target_local_ned_t, vz) }, \
{ "afx", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_position_target_local_ned_t, afx) }, \
{ "afy", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_position_target_local_ned_t, afy) }, \
{ "afz", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_position_target_local_ned_t, afz) }, \
{ "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_position_target_local_ned_t, yaw) }, \
{ "yaw_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_position_target_local_ned_t, yaw_rate) }, \
{ "type_mask", NULL, MAVLINK_TYPE_UINT16_T, 0, 48, offsetof(mavlink_position_target_local_ned_t, type_mask) }, \
{ "coordinate_frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 50, offsetof(mavlink_position_target_local_ned_t, coordinate_frame) }, \
} \
}
/**
* @brief Pack a position_target_local_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 in milliseconds since system boot
* @param coordinate_frame Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9
* @param type_mask Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate
* @param x X Position in NED frame in meters
* @param y Y Position in NED frame in meters
* @param z Z Position in NED frame in meters (note, altitude is negative in NED)
* @param vx X velocity in NED frame in meter / s
* @param vy Y velocity in NED frame in meter / s
* @param vz Z velocity in NED frame in meter / s
* @param afx X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
* @param afy Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
* @param afz Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
* @param yaw yaw setpoint in rad
* @param yaw_rate yaw rate setpoint in rad/s
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_position_target_local_ned_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint32_t time_boot_ms, uint8_t coordinate_frame, uint16_t type_mask, float x, float y, float z, float vx, float vy, float vz, float afx, float afy, float afz, float yaw, float yaw_rate)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN];
_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_put_float(buf, 28, afx);
_mav_put_float(buf, 32, afy);
_mav_put_float(buf, 36, afz);
_mav_put_float(buf, 40, yaw);
_mav_put_float(buf, 44, yaw_rate);
_mav_put_uint16_t(buf, 48, type_mask);
_mav_put_uint8_t(buf, 50, coordinate_frame);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN);
#else
mavlink_position_target_local_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;
packet.afx = afx;
packet.afy = afy;
packet.afz = afz;
packet.yaw = yaw;
packet.yaw_rate = yaw_rate;
packet.type_mask = type_mask;
packet.coordinate_frame = coordinate_frame;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_CRC);
#else
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN);
#endif
}
/**
* @brief Pack a position_target_local_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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param time_boot_ms Timestamp in milliseconds since system boot
* @param coordinate_frame Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9
* @param type_mask Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate
* @param x X Position in NED frame in meters
* @param y Y Position in NED frame in meters
* @param z Z Position in NED frame in meters (note, altitude is negative in NED)
* @param vx X velocity in NED frame in meter / s
* @param vy Y velocity in NED frame in meter / s
* @param vz Z velocity in NED frame in meter / s
* @param afx X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
* @param afy Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
* @param afz Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
* @param yaw yaw setpoint in rad
* @param yaw_rate yaw rate setpoint in rad/s
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_position_target_local_ned_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint32_t time_boot_ms,uint8_t coordinate_frame,uint16_t type_mask,float x,float y,float z,float vx,float vy,float vz,float afx,float afy,float afz,float yaw,float yaw_rate)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN];
_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_put_float(buf, 28, afx);
_mav_put_float(buf, 32, afy);
_mav_put_float(buf, 36, afz);
_mav_put_float(buf, 40, yaw);
_mav_put_float(buf, 44, yaw_rate);
_mav_put_uint16_t(buf, 48, type_mask);
_mav_put_uint8_t(buf, 50, coordinate_frame);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN);
#else
mavlink_position_target_local_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;
packet.afx = afx;
packet.afy = afy;
packet.afz = afz;
packet.yaw = yaw;
packet.yaw_rate = yaw_rate;
packet.type_mask = type_mask;
packet.coordinate_frame = coordinate_frame;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_CRC);
#else
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN);
#endif
}
/**
* @brief Encode a position_target_local_ned struct
*
* @param system_id ID of this 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_local_ned C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_position_target_local_ned_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_position_target_local_ned_t* position_target_local_ned)
{
return mavlink_msg_position_target_local_ned_pack(system_id, component_id, msg, position_target_local_ned->time_boot_ms, position_target_local_ned->coordinate_frame, position_target_local_ned->type_mask, position_target_local_ned->x, position_target_local_ned->y, position_target_local_ned->z, position_target_local_ned->vx, position_target_local_ned->vy, position_target_local_ned->vz, position_target_local_ned->afx, position_target_local_ned->afy, position_target_local_ned->afz, position_target_local_ned->yaw, position_target_local_ned->yaw_rate);
}
/**
* @brief Encode a position_target_local_ned struct 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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param position_target_local_ned C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_position_target_local_ned_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_position_target_local_ned_t* position_target_local_ned)
{
return mavlink_msg_position_target_local_ned_pack_chan(system_id, component_id, chan, msg, position_target_local_ned->time_boot_ms, position_target_local_ned->coordinate_frame, position_target_local_ned->type_mask, position_target_local_ned->x, position_target_local_ned->y, position_target_local_ned->z, position_target_local_ned->vx, position_target_local_ned->vy, position_target_local_ned->vz, position_target_local_ned->afx, position_target_local_ned->afy, position_target_local_ned->afz, position_target_local_ned->yaw, position_target_local_ned->yaw_rate);
}
/**
* @brief Send a position_target_local_ned message
* @param chan MAVLink channel to send the message
*
* @param time_boot_ms Timestamp in milliseconds since system boot
* @param coordinate_frame Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9
* @param type_mask Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate
* @param x X Position in NED frame in meters
* @param y Y Position in NED frame in meters
* @param z Z Position in NED frame in meters (note, altitude is negative in NED)
* @param vx X velocity in NED frame in meter / s
* @param vy Y velocity in NED frame in meter / s
* @param vz Z velocity in NED frame in meter / s
* @param afx X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
* @param afy Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
* @param afz Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
* @param yaw yaw setpoint in rad
* @param yaw_rate yaw rate setpoint in rad/s
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_position_target_local_ned_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t coordinate_frame, uint16_t type_mask, float x, float y, float z, float vx, float vy, float vz, float afx, float afy, float afz, float yaw, float yaw_rate)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN];
_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_put_float(buf, 28, afx);
_mav_put_float(buf, 32, afy);
_mav_put_float(buf, 36, afz);
_mav_put_float(buf, 40, yaw);
_mav_put_float(buf, 44, yaw_rate);
_mav_put_uint16_t(buf, 48, type_mask);
_mav_put_uint8_t(buf, 50, coordinate_frame);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED, buf, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED, buf, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN);
#endif
#else
mavlink_position_target_local_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;
packet.afx = afx;
packet.afy = afy;
packet.afz = afz;
packet.yaw = yaw;
packet.yaw_rate = yaw_rate;
packet.type_mask = type_mask;
packet.coordinate_frame = coordinate_frame;
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED, (const char *)&packet, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED, (const char *)&packet, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN);
#endif
#endif
}
#if MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This varient of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_position_target_local_ned_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t coordinate_frame, uint16_t type_mask, float x, float y, float z, float vx, float vy, float vz, float afx, float afy, float afz, float yaw, float yaw_rate)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
_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_put_float(buf, 28, afx);
_mav_put_float(buf, 32, afy);
_mav_put_float(buf, 36, afz);
_mav_put_float(buf, 40, yaw);
_mav_put_float(buf, 44, yaw_rate);
_mav_put_uint16_t(buf, 48, type_mask);
_mav_put_uint8_t(buf, 50, coordinate_frame);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED, buf, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED, buf, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN);
#endif
#else
mavlink_position_target_local_ned_t *packet = (mavlink_position_target_local_ned_t *)msgbuf;
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;
packet->afx = afx;
packet->afy = afy;
packet->afz = afz;
packet->yaw = yaw;
packet->yaw_rate = yaw_rate;
packet->type_mask = type_mask;
packet->coordinate_frame = coordinate_frame;
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED, (const char *)packet, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED, (const char *)packet, MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN);
#endif
#endif
}
#endif
#endif
// MESSAGE POSITION_TARGET_LOCAL_NED UNPACKING
/**
* @brief Get field time_boot_ms from position_target_local_ned message
*
* @return Timestamp in milliseconds since system boot
*/
static inline uint32_t mavlink_msg_position_target_local_ned_get_time_boot_ms(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint32_t(msg, 0);
}
/**
* @brief Get field coordinate_frame from position_target_local_ned message
*
* @return Valid options are: MAV_FRAME_LOCAL_NED = 1, MAV_FRAME_LOCAL_OFFSET_NED = 7, MAV_FRAME_BODY_NED = 8, MAV_FRAME_BODY_OFFSET_NED = 9
*/
static inline uint8_t mavlink_msg_position_target_local_ned_get_coordinate_frame(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 50);
}
/**
* @brief Get field type_mask from position_target_local_ned message
*
* @return Bitmask to indicate which dimensions should be ignored by the vehicle: a value of 0b0000000000000000 or 0b0000001000000000 indicates that none of the setpoint dimensions should be ignored. If bit 10 is set the floats afx afy afz should be interpreted as force instead of acceleration. Mapping: bit 1: x, bit 2: y, bit 3: z, bit 4: vx, bit 5: vy, bit 6: vz, bit 7: ax, bit 8: ay, bit 9: az, bit 10: is force setpoint, bit 11: yaw, bit 12: yaw rate
*/
static inline uint16_t mavlink_msg_position_target_local_ned_get_type_mask(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 48);
}
/**
* @brief Get field x from position_target_local_ned message
*
* @return X Position in NED frame in meters
*/
static inline float mavlink_msg_position_target_local_ned_get_x(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 4);
}
/**
* @brief Get field y from position_target_local_ned message
*
* @return Y Position in NED frame in meters
*/
static inline float mavlink_msg_position_target_local_ned_get_y(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 8);
}
/**
* @brief Get field z from position_target_local_ned message
*
* @return Z Position in NED frame in meters (note, altitude is negative in NED)
*/
static inline float mavlink_msg_position_target_local_ned_get_z(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 12);
}
/**
* @brief Get field vx from position_target_local_ned message
*
* @return X velocity in NED frame in meter / s
*/
static inline float mavlink_msg_position_target_local_ned_get_vx(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 16);
}
/**
* @brief Get field vy from position_target_local_ned message
*
* @return Y velocity in NED frame in meter / s
*/
static inline float mavlink_msg_position_target_local_ned_get_vy(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 20);
}
/**
* @brief Get field vz from position_target_local_ned message
*
* @return Z velocity in NED frame in meter / s
*/
static inline float mavlink_msg_position_target_local_ned_get_vz(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 24);
}
/**
* @brief Get field afx from position_target_local_ned message
*
* @return X acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
*/
static inline float mavlink_msg_position_target_local_ned_get_afx(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 28);
}
/**
* @brief Get field afy from position_target_local_ned message
*
* @return Y acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
*/
static inline float mavlink_msg_position_target_local_ned_get_afy(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 32);
}
/**
* @brief Get field afz from position_target_local_ned message
*
* @return Z acceleration or force (if bit 10 of type_mask is set) in NED frame in meter / s^2 or N
*/
static inline float mavlink_msg_position_target_local_ned_get_afz(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 36);
}
/**
* @brief Get field yaw from position_target_local_ned message
*
* @return yaw setpoint in rad
*/
static inline float mavlink_msg_position_target_local_ned_get_yaw(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 40);
}
/**
* @brief Get field yaw_rate from position_target_local_ned message
*
* @return yaw rate setpoint in rad/s
*/
static inline float mavlink_msg_position_target_local_ned_get_yaw_rate(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 44);
}
/**
* @brief Decode a position_target_local_ned message into a struct
*
* @param msg The message to decode
* @param position_target_local_ned C-struct to decode the message contents into
*/
static inline void mavlink_msg_position_target_local_ned_decode(const mavlink_message_t* msg, mavlink_position_target_local_ned_t* position_target_local_ned)
{
#if MAVLINK_NEED_BYTE_SWAP
position_target_local_ned->time_boot_ms = mavlink_msg_position_target_local_ned_get_time_boot_ms(msg);
position_target_local_ned->x = mavlink_msg_position_target_local_ned_get_x(msg);
position_target_local_ned->y = mavlink_msg_position_target_local_ned_get_y(msg);
position_target_local_ned->z = mavlink_msg_position_target_local_ned_get_z(msg);
position_target_local_ned->vx = mavlink_msg_position_target_local_ned_get_vx(msg);
position_target_local_ned->vy = mavlink_msg_position_target_local_ned_get_vy(msg);
position_target_local_ned->vz = mavlink_msg_position_target_local_ned_get_vz(msg);
position_target_local_ned->afx = mavlink_msg_position_target_local_ned_get_afx(msg);
position_target_local_ned->afy = mavlink_msg_position_target_local_ned_get_afy(msg);
position_target_local_ned->afz = mavlink_msg_position_target_local_ned_get_afz(msg);
position_target_local_ned->yaw = mavlink_msg_position_target_local_ned_get_yaw(msg);
position_target_local_ned->yaw_rate = mavlink_msg_position_target_local_ned_get_yaw_rate(msg);
position_target_local_ned->type_mask = mavlink_msg_position_target_local_ned_get_type_mask(msg);
position_target_local_ned->coordinate_frame = mavlink_msg_position_target_local_ned_get_coordinate_frame(msg);
#else
memcpy(position_target_local_ned, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_POSITION_TARGET_LOCAL_NED_LEN);
#endif
}

View file

@ -0,0 +1,257 @@
// MESSAGE POWER_STATUS PACKING
#define MAVLINK_MSG_ID_POWER_STATUS 125
typedef struct __mavlink_power_status_t
{
uint16_t Vcc; ///< 5V rail voltage in millivolts
uint16_t Vservo; ///< servo rail voltage in millivolts
uint16_t flags; ///< power supply status flags (see MAV_POWER_STATUS enum)
} mavlink_power_status_t;
#define MAVLINK_MSG_ID_POWER_STATUS_LEN 6
#define MAVLINK_MSG_ID_125_LEN 6
#define MAVLINK_MSG_ID_POWER_STATUS_CRC 203
#define MAVLINK_MSG_ID_125_CRC 203
#define MAVLINK_MESSAGE_INFO_POWER_STATUS { \
"POWER_STATUS", \
3, \
{ { "Vcc", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_power_status_t, Vcc) }, \
{ "Vservo", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_power_status_t, Vservo) }, \
{ "flags", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_power_status_t, flags) }, \
} \
}
/**
* @brief Pack a power_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 Vcc 5V rail voltage in millivolts
* @param Vservo servo rail voltage in millivolts
* @param flags power supply status flags (see MAV_POWER_STATUS enum)
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_power_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint16_t Vcc, uint16_t Vservo, uint16_t flags)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_POWER_STATUS_LEN];
_mav_put_uint16_t(buf, 0, Vcc);
_mav_put_uint16_t(buf, 2, Vservo);
_mav_put_uint16_t(buf, 4, flags);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_POWER_STATUS_LEN);
#else
mavlink_power_status_t packet;
packet.Vcc = Vcc;
packet.Vservo = Vservo;
packet.flags = flags;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_POWER_STATUS_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_POWER_STATUS;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_POWER_STATUS_LEN, MAVLINK_MSG_ID_POWER_STATUS_CRC);
#else
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_POWER_STATUS_LEN);
#endif
}
/**
* @brief Pack a power_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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param Vcc 5V rail voltage in millivolts
* @param Vservo servo rail voltage in millivolts
* @param flags power supply status flags (see MAV_POWER_STATUS enum)
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_power_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint16_t Vcc,uint16_t Vservo,uint16_t flags)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_POWER_STATUS_LEN];
_mav_put_uint16_t(buf, 0, Vcc);
_mav_put_uint16_t(buf, 2, Vservo);
_mav_put_uint16_t(buf, 4, flags);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_POWER_STATUS_LEN);
#else
mavlink_power_status_t packet;
packet.Vcc = Vcc;
packet.Vservo = Vservo;
packet.flags = flags;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_POWER_STATUS_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_POWER_STATUS;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_POWER_STATUS_LEN, MAVLINK_MSG_ID_POWER_STATUS_CRC);
#else
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_POWER_STATUS_LEN);
#endif
}
/**
* @brief Encode a power_status struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param power_status C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_power_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_power_status_t* power_status)
{
return mavlink_msg_power_status_pack(system_id, component_id, msg, power_status->Vcc, power_status->Vservo, power_status->flags);
}
/**
* @brief Encode a power_status struct 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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param power_status C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_power_status_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_power_status_t* power_status)
{
return mavlink_msg_power_status_pack_chan(system_id, component_id, chan, msg, power_status->Vcc, power_status->Vservo, power_status->flags);
}
/**
* @brief Send a power_status message
* @param chan MAVLink channel to send the message
*
* @param Vcc 5V rail voltage in millivolts
* @param Vservo servo rail voltage in millivolts
* @param flags power supply status flags (see MAV_POWER_STATUS enum)
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_power_status_send(mavlink_channel_t chan, uint16_t Vcc, uint16_t Vservo, uint16_t flags)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_POWER_STATUS_LEN];
_mav_put_uint16_t(buf, 0, Vcc);
_mav_put_uint16_t(buf, 2, Vservo);
_mav_put_uint16_t(buf, 4, flags);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POWER_STATUS, buf, MAVLINK_MSG_ID_POWER_STATUS_LEN, MAVLINK_MSG_ID_POWER_STATUS_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POWER_STATUS, buf, MAVLINK_MSG_ID_POWER_STATUS_LEN);
#endif
#else
mavlink_power_status_t packet;
packet.Vcc = Vcc;
packet.Vservo = Vservo;
packet.flags = flags;
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POWER_STATUS, (const char *)&packet, MAVLINK_MSG_ID_POWER_STATUS_LEN, MAVLINK_MSG_ID_POWER_STATUS_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POWER_STATUS, (const char *)&packet, MAVLINK_MSG_ID_POWER_STATUS_LEN);
#endif
#endif
}
#if MAVLINK_MSG_ID_POWER_STATUS_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This varient of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_power_status_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint16_t Vcc, uint16_t Vservo, uint16_t flags)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
_mav_put_uint16_t(buf, 0, Vcc);
_mav_put_uint16_t(buf, 2, Vservo);
_mav_put_uint16_t(buf, 4, flags);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POWER_STATUS, buf, MAVLINK_MSG_ID_POWER_STATUS_LEN, MAVLINK_MSG_ID_POWER_STATUS_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POWER_STATUS, buf, MAVLINK_MSG_ID_POWER_STATUS_LEN);
#endif
#else
mavlink_power_status_t *packet = (mavlink_power_status_t *)msgbuf;
packet->Vcc = Vcc;
packet->Vservo = Vservo;
packet->flags = flags;
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POWER_STATUS, (const char *)packet, MAVLINK_MSG_ID_POWER_STATUS_LEN, MAVLINK_MSG_ID_POWER_STATUS_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_POWER_STATUS, (const char *)packet, MAVLINK_MSG_ID_POWER_STATUS_LEN);
#endif
#endif
}
#endif
#endif
// MESSAGE POWER_STATUS UNPACKING
/**
* @brief Get field Vcc from power_status message
*
* @return 5V rail voltage in millivolts
*/
static inline uint16_t mavlink_msg_power_status_get_Vcc(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 0);
}
/**
* @brief Get field Vservo from power_status message
*
* @return servo rail voltage in millivolts
*/
static inline uint16_t mavlink_msg_power_status_get_Vservo(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 2);
}
/**
* @brief Get field flags from power_status message
*
* @return power supply status flags (see MAV_POWER_STATUS enum)
*/
static inline uint16_t mavlink_msg_power_status_get_flags(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 4);
}
/**
* @brief Decode a power_status message into a struct
*
* @param msg The message to decode
* @param power_status C-struct to decode the message contents into
*/
static inline void mavlink_msg_power_status_decode(const mavlink_message_t* msg, mavlink_power_status_t* power_status)
{
#if MAVLINK_NEED_BYTE_SWAP
power_status->Vcc = mavlink_msg_power_status_get_Vcc(msg);
power_status->Vservo = mavlink_msg_power_status_get_Vservo(msg);
power_status->flags = mavlink_msg_power_status_get_flags(msg);
#else
memcpy(power_status, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_POWER_STATUS_LEN);
#endif
}

View file

@ -0,0 +1,353 @@
// MESSAGE RADIO_STATUS PACKING
#define MAVLINK_MSG_ID_RADIO_STATUS 109
typedef struct __mavlink_radio_status_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; ///< Remaining free buffer space in percent.
uint8_t noise; ///< Background noise level
uint8_t remnoise; ///< Remote background noise level
} mavlink_radio_status_t;
#define MAVLINK_MSG_ID_RADIO_STATUS_LEN 9
#define MAVLINK_MSG_ID_109_LEN 9
#define MAVLINK_MSG_ID_RADIO_STATUS_CRC 185
#define MAVLINK_MSG_ID_109_CRC 185
#define MAVLINK_MESSAGE_INFO_RADIO_STATUS { \
"RADIO_STATUS", \
7, \
{ { "rxerrors", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_radio_status_t, rxerrors) }, \
{ "fixed", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_radio_status_t, fixed) }, \
{ "rssi", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_radio_status_t, rssi) }, \
{ "remrssi", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_radio_status_t, remrssi) }, \
{ "txbuf", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_radio_status_t, txbuf) }, \
{ "noise", NULL, MAVLINK_TYPE_UINT8_T, 0, 7, offsetof(mavlink_radio_status_t, noise) }, \
{ "remnoise", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_radio_status_t, remnoise) }, \
} \
}
/**
* @brief Pack a radio_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 rssi Local signal strength
* @param remrssi Remote signal strength
* @param txbuf Remaining free buffer space in percent.
* @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_status_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[MAVLINK_MSG_ID_RADIO_STATUS_LEN];
_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, MAVLINK_MSG_ID_RADIO_STATUS_LEN);
#else
mavlink_radio_status_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, MAVLINK_MSG_ID_RADIO_STATUS_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_RADIO_STATUS;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_RADIO_STATUS_LEN, MAVLINK_MSG_ID_RADIO_STATUS_CRC);
#else
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_RADIO_STATUS_LEN);
#endif
}
/**
* @brief Pack a radio_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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param rssi Local signal strength
* @param remrssi Remote signal strength
* @param txbuf Remaining free buffer space in percent.
* @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_status_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[MAVLINK_MSG_ID_RADIO_STATUS_LEN];
_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, MAVLINK_MSG_ID_RADIO_STATUS_LEN);
#else
mavlink_radio_status_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, MAVLINK_MSG_ID_RADIO_STATUS_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_RADIO_STATUS;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_RADIO_STATUS_LEN, MAVLINK_MSG_ID_RADIO_STATUS_CRC);
#else
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_RADIO_STATUS_LEN);
#endif
}
/**
* @brief Encode a radio_status struct
*
* @param system_id ID of this 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_status C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_radio_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_radio_status_t* radio_status)
{
return mavlink_msg_radio_status_pack(system_id, component_id, msg, radio_status->rssi, radio_status->remrssi, radio_status->txbuf, radio_status->noise, radio_status->remnoise, radio_status->rxerrors, radio_status->fixed);
}
/**
* @brief Encode a radio_status struct 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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param radio_status C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_radio_status_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_radio_status_t* radio_status)
{
return mavlink_msg_radio_status_pack_chan(system_id, component_id, chan, msg, radio_status->rssi, radio_status->remrssi, radio_status->txbuf, radio_status->noise, radio_status->remnoise, radio_status->rxerrors, radio_status->fixed);
}
/**
* @brief Send a radio_status message
* @param chan MAVLink channel to send the message
*
* @param rssi Local signal strength
* @param remrssi Remote signal strength
* @param txbuf Remaining free buffer space in percent.
* @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_status_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[MAVLINK_MSG_ID_RADIO_STATUS_LEN];
_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);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RADIO_STATUS, buf, MAVLINK_MSG_ID_RADIO_STATUS_LEN, MAVLINK_MSG_ID_RADIO_STATUS_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RADIO_STATUS, buf, MAVLINK_MSG_ID_RADIO_STATUS_LEN);
#endif
#else
mavlink_radio_status_t packet;
packet.rxerrors = rxerrors;
packet.fixed = fixed;
packet.rssi = rssi;
packet.remrssi = remrssi;
packet.txbuf = txbuf;
packet.noise = noise;
packet.remnoise = remnoise;
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RADIO_STATUS, (const char *)&packet, MAVLINK_MSG_ID_RADIO_STATUS_LEN, MAVLINK_MSG_ID_RADIO_STATUS_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RADIO_STATUS, (const char *)&packet, MAVLINK_MSG_ID_RADIO_STATUS_LEN);
#endif
#endif
}
#if MAVLINK_MSG_ID_RADIO_STATUS_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This varient of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_radio_status_send_buf(mavlink_message_t *msgbuf, 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 = (char *)msgbuf;
_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);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RADIO_STATUS, buf, MAVLINK_MSG_ID_RADIO_STATUS_LEN, MAVLINK_MSG_ID_RADIO_STATUS_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RADIO_STATUS, buf, MAVLINK_MSG_ID_RADIO_STATUS_LEN);
#endif
#else
mavlink_radio_status_t *packet = (mavlink_radio_status_t *)msgbuf;
packet->rxerrors = rxerrors;
packet->fixed = fixed;
packet->rssi = rssi;
packet->remrssi = remrssi;
packet->txbuf = txbuf;
packet->noise = noise;
packet->remnoise = remnoise;
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RADIO_STATUS, (const char *)packet, MAVLINK_MSG_ID_RADIO_STATUS_LEN, MAVLINK_MSG_ID_RADIO_STATUS_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RADIO_STATUS, (const char *)packet, MAVLINK_MSG_ID_RADIO_STATUS_LEN);
#endif
#endif
}
#endif
#endif
// MESSAGE RADIO_STATUS UNPACKING
/**
* @brief Get field rssi from radio_status message
*
* @return Local signal strength
*/
static inline uint8_t mavlink_msg_radio_status_get_rssi(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 4);
}
/**
* @brief Get field remrssi from radio_status message
*
* @return Remote signal strength
*/
static inline uint8_t mavlink_msg_radio_status_get_remrssi(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 5);
}
/**
* @brief Get field txbuf from radio_status message
*
* @return Remaining free buffer space in percent.
*/
static inline uint8_t mavlink_msg_radio_status_get_txbuf(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 6);
}
/**
* @brief Get field noise from radio_status message
*
* @return Background noise level
*/
static inline uint8_t mavlink_msg_radio_status_get_noise(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 7);
}
/**
* @brief Get field remnoise from radio_status message
*
* @return Remote background noise level
*/
static inline uint8_t mavlink_msg_radio_status_get_remnoise(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 8);
}
/**
* @brief Get field rxerrors from radio_status message
*
* @return Receive errors
*/
static inline uint16_t mavlink_msg_radio_status_get_rxerrors(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 0);
}
/**
* @brief Get field fixed from radio_status message
*
* @return Count of error corrected packets
*/
static inline uint16_t mavlink_msg_radio_status_get_fixed(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 2);
}
/**
* @brief Decode a radio_status message into a struct
*
* @param msg The message to decode
* @param radio_status C-struct to decode the message contents into
*/
static inline void mavlink_msg_radio_status_decode(const mavlink_message_t* msg, mavlink_radio_status_t* radio_status)
{
#if MAVLINK_NEED_BYTE_SWAP
radio_status->rxerrors = mavlink_msg_radio_status_get_rxerrors(msg);
radio_status->fixed = mavlink_msg_radio_status_get_fixed(msg);
radio_status->rssi = mavlink_msg_radio_status_get_rssi(msg);
radio_status->remrssi = mavlink_msg_radio_status_get_remrssi(msg);
radio_status->txbuf = mavlink_msg_radio_status_get_txbuf(msg);
radio_status->noise = mavlink_msg_radio_status_get_noise(msg);
radio_status->remnoise = mavlink_msg_radio_status_get_remnoise(msg);
#else
memcpy(radio_status, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_RADIO_STATUS_LEN);
#endif
}

View file

@ -0,0 +1,425 @@
// 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_MSG_ID_RAW_IMU_CRC 144
#define MAVLINK_MSG_ID_27_CRC 144
#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[MAVLINK_MSG_ID_RAW_IMU_LEN];
_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, MAVLINK_MSG_ID_RAW_IMU_LEN);
#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, MAVLINK_MSG_ID_RAW_IMU_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_RAW_IMU;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_RAW_IMU_LEN, MAVLINK_MSG_ID_RAW_IMU_CRC);
#else
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_RAW_IMU_LEN);
#endif
}
/**
* @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 will be 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[MAVLINK_MSG_ID_RAW_IMU_LEN];
_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, MAVLINK_MSG_ID_RAW_IMU_LEN);
#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, MAVLINK_MSG_ID_RAW_IMU_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_RAW_IMU;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_RAW_IMU_LEN, MAVLINK_MSG_ID_RAW_IMU_CRC);
#else
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_RAW_IMU_LEN);
#endif
}
/**
* @brief Encode a raw_imu struct
*
* @param system_id ID of this 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 Encode a raw_imu struct 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 will be sent over
* @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_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_raw_imu_t* raw_imu)
{
return mavlink_msg_raw_imu_pack_chan(system_id, component_id, chan, 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[MAVLINK_MSG_ID_RAW_IMU_LEN];
_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);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_IMU, buf, MAVLINK_MSG_ID_RAW_IMU_LEN, MAVLINK_MSG_ID_RAW_IMU_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_IMU, buf, MAVLINK_MSG_ID_RAW_IMU_LEN);
#endif
#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;
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_IMU, (const char *)&packet, MAVLINK_MSG_ID_RAW_IMU_LEN, MAVLINK_MSG_ID_RAW_IMU_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_IMU, (const char *)&packet, MAVLINK_MSG_ID_RAW_IMU_LEN);
#endif
#endif
}
#if MAVLINK_MSG_ID_RAW_IMU_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This varient of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_raw_imu_send_buf(mavlink_message_t *msgbuf, 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 = (char *)msgbuf;
_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);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_IMU, buf, MAVLINK_MSG_ID_RAW_IMU_LEN, MAVLINK_MSG_ID_RAW_IMU_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_IMU, buf, MAVLINK_MSG_ID_RAW_IMU_LEN);
#endif
#else
mavlink_raw_imu_t *packet = (mavlink_raw_imu_t *)msgbuf;
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;
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_IMU, (const char *)packet, MAVLINK_MSG_ID_RAW_IMU_LEN, MAVLINK_MSG_ID_RAW_IMU_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_IMU, (const char *)packet, MAVLINK_MSG_ID_RAW_IMU_LEN);
#endif
#endif
}
#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), MAVLINK_MSG_ID_RAW_IMU_LEN);
#endif
}

View file

@ -0,0 +1,305 @@
// 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_MSG_ID_RAW_PRESSURE_CRC 67
#define MAVLINK_MSG_ID_28_CRC 67
#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[MAVLINK_MSG_ID_RAW_PRESSURE_LEN];
_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, MAVLINK_MSG_ID_RAW_PRESSURE_LEN);
#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, MAVLINK_MSG_ID_RAW_PRESSURE_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_RAW_PRESSURE;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_RAW_PRESSURE_LEN, MAVLINK_MSG_ID_RAW_PRESSURE_CRC);
#else
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_RAW_PRESSURE_LEN);
#endif
}
/**
* @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 will be 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[MAVLINK_MSG_ID_RAW_PRESSURE_LEN];
_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, MAVLINK_MSG_ID_RAW_PRESSURE_LEN);
#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, MAVLINK_MSG_ID_RAW_PRESSURE_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_RAW_PRESSURE;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_RAW_PRESSURE_LEN, MAVLINK_MSG_ID_RAW_PRESSURE_CRC);
#else
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_RAW_PRESSURE_LEN);
#endif
}
/**
* @brief Encode a raw_pressure struct
*
* @param system_id ID of this 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 Encode a raw_pressure struct 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 will be sent over
* @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_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_raw_pressure_t* raw_pressure)
{
return mavlink_msg_raw_pressure_pack_chan(system_id, component_id, chan, 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[MAVLINK_MSG_ID_RAW_PRESSURE_LEN];
_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);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_PRESSURE, buf, MAVLINK_MSG_ID_RAW_PRESSURE_LEN, MAVLINK_MSG_ID_RAW_PRESSURE_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_PRESSURE, buf, MAVLINK_MSG_ID_RAW_PRESSURE_LEN);
#endif
#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;
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_PRESSURE, (const char *)&packet, MAVLINK_MSG_ID_RAW_PRESSURE_LEN, MAVLINK_MSG_ID_RAW_PRESSURE_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_PRESSURE, (const char *)&packet, MAVLINK_MSG_ID_RAW_PRESSURE_LEN);
#endif
#endif
}
#if MAVLINK_MSG_ID_RAW_PRESSURE_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This varient of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_raw_pressure_send_buf(mavlink_message_t *msgbuf, 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 = (char *)msgbuf;
_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);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_PRESSURE, buf, MAVLINK_MSG_ID_RAW_PRESSURE_LEN, MAVLINK_MSG_ID_RAW_PRESSURE_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_PRESSURE, buf, MAVLINK_MSG_ID_RAW_PRESSURE_LEN);
#endif
#else
mavlink_raw_pressure_t *packet = (mavlink_raw_pressure_t *)msgbuf;
packet->time_usec = time_usec;
packet->press_abs = press_abs;
packet->press_diff1 = press_diff1;
packet->press_diff2 = press_diff2;
packet->temperature = temperature;
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_PRESSURE, (const char *)packet, MAVLINK_MSG_ID_RAW_PRESSURE_LEN, MAVLINK_MSG_ID_RAW_PRESSURE_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RAW_PRESSURE, (const char *)packet, MAVLINK_MSG_ID_RAW_PRESSURE_LEN);
#endif
#endif
}
#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), MAVLINK_MSG_ID_RAW_PRESSURE_LEN);
#endif
}

View file

@ -0,0 +1,689 @@
// MESSAGE RC_CHANNELS PACKING
#define MAVLINK_MSG_ID_RC_CHANNELS 65
typedef struct __mavlink_rc_channels_t
{
uint32_t time_boot_ms; ///< Timestamp (milliseconds since system boot)
uint16_t chan1_raw; ///< RC channel 1 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
uint16_t chan2_raw; ///< RC channel 2 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
uint16_t chan3_raw; ///< RC channel 3 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
uint16_t chan4_raw; ///< RC channel 4 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
uint16_t chan5_raw; ///< RC channel 5 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
uint16_t chan6_raw; ///< RC channel 6 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
uint16_t chan7_raw; ///< RC channel 7 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
uint16_t chan8_raw; ///< RC channel 8 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
uint16_t chan9_raw; ///< RC channel 9 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
uint16_t chan10_raw; ///< RC channel 10 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
uint16_t chan11_raw; ///< RC channel 11 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
uint16_t chan12_raw; ///< RC channel 12 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
uint16_t chan13_raw; ///< RC channel 13 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
uint16_t chan14_raw; ///< RC channel 14 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
uint16_t chan15_raw; ///< RC channel 15 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
uint16_t chan16_raw; ///< RC channel 16 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
uint16_t chan17_raw; ///< RC channel 17 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
uint16_t chan18_raw; ///< RC channel 18 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
uint8_t chancount; ///< Total number of RC channels being received. This can be larger than 18, indicating that more channels are available but not given in this message. This value should be 0 when no RC channels are available.
uint8_t rssi; ///< Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown.
} mavlink_rc_channels_t;
#define MAVLINK_MSG_ID_RC_CHANNELS_LEN 42
#define MAVLINK_MSG_ID_65_LEN 42
#define MAVLINK_MSG_ID_RC_CHANNELS_CRC 118
#define MAVLINK_MSG_ID_65_CRC 118
#define MAVLINK_MESSAGE_INFO_RC_CHANNELS { \
"RC_CHANNELS", \
21, \
{ { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_rc_channels_t, time_boot_ms) }, \
{ "chan1_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_rc_channels_t, chan1_raw) }, \
{ "chan2_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 6, offsetof(mavlink_rc_channels_t, chan2_raw) }, \
{ "chan3_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_rc_channels_t, chan3_raw) }, \
{ "chan4_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 10, offsetof(mavlink_rc_channels_t, chan4_raw) }, \
{ "chan5_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_rc_channels_t, chan5_raw) }, \
{ "chan6_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 14, offsetof(mavlink_rc_channels_t, chan6_raw) }, \
{ "chan7_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_rc_channels_t, chan7_raw) }, \
{ "chan8_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_rc_channels_t, chan8_raw) }, \
{ "chan9_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 20, offsetof(mavlink_rc_channels_t, chan9_raw) }, \
{ "chan10_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 22, offsetof(mavlink_rc_channels_t, chan10_raw) }, \
{ "chan11_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_rc_channels_t, chan11_raw) }, \
{ "chan12_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 26, offsetof(mavlink_rc_channels_t, chan12_raw) }, \
{ "chan13_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_rc_channels_t, chan13_raw) }, \
{ "chan14_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 30, offsetof(mavlink_rc_channels_t, chan14_raw) }, \
{ "chan15_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 32, offsetof(mavlink_rc_channels_t, chan15_raw) }, \
{ "chan16_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 34, offsetof(mavlink_rc_channels_t, chan16_raw) }, \
{ "chan17_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 36, offsetof(mavlink_rc_channels_t, chan17_raw) }, \
{ "chan18_raw", NULL, MAVLINK_TYPE_UINT16_T, 0, 38, offsetof(mavlink_rc_channels_t, chan18_raw) }, \
{ "chancount", NULL, MAVLINK_TYPE_UINT8_T, 0, 40, offsetof(mavlink_rc_channels_t, chancount) }, \
{ "rssi", NULL, MAVLINK_TYPE_UINT8_T, 0, 41, offsetof(mavlink_rc_channels_t, rssi) }, \
} \
}
/**
* @brief Pack a rc_channels message
* @param system_id ID of this 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 chancount Total number of RC channels being received. This can be larger than 18, indicating that more channels are available but not given in this message. This value should be 0 when no RC channels are available.
* @param chan1_raw RC channel 1 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
* @param chan2_raw RC channel 2 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
* @param chan3_raw RC channel 3 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
* @param chan4_raw RC channel 4 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
* @param chan5_raw RC channel 5 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
* @param chan6_raw RC channel 6 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
* @param chan7_raw RC channel 7 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
* @param chan8_raw RC channel 8 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
* @param chan9_raw RC channel 9 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
* @param chan10_raw RC channel 10 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
* @param chan11_raw RC channel 11 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
* @param chan12_raw RC channel 12 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
* @param chan13_raw RC channel 13 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
* @param chan14_raw RC channel 14 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
* @param chan15_raw RC channel 15 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
* @param chan16_raw RC channel 16 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
* @param chan17_raw RC channel 17 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
* @param chan18_raw RC channel 18 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
* @param rssi Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_rc_channels_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint32_t time_boot_ms, uint8_t chancount, 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, uint16_t chan13_raw, uint16_t chan14_raw, uint16_t chan15_raw, uint16_t chan16_raw, uint16_t chan17_raw, uint16_t chan18_raw, uint8_t rssi)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_RC_CHANNELS_LEN];
_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_uint16_t(buf, 20, chan9_raw);
_mav_put_uint16_t(buf, 22, chan10_raw);
_mav_put_uint16_t(buf, 24, chan11_raw);
_mav_put_uint16_t(buf, 26, chan12_raw);
_mav_put_uint16_t(buf, 28, chan13_raw);
_mav_put_uint16_t(buf, 30, chan14_raw);
_mav_put_uint16_t(buf, 32, chan15_raw);
_mav_put_uint16_t(buf, 34, chan16_raw);
_mav_put_uint16_t(buf, 36, chan17_raw);
_mav_put_uint16_t(buf, 38, chan18_raw);
_mav_put_uint8_t(buf, 40, chancount);
_mav_put_uint8_t(buf, 41, rssi);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RC_CHANNELS_LEN);
#else
mavlink_rc_channels_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.chan9_raw = chan9_raw;
packet.chan10_raw = chan10_raw;
packet.chan11_raw = chan11_raw;
packet.chan12_raw = chan12_raw;
packet.chan13_raw = chan13_raw;
packet.chan14_raw = chan14_raw;
packet.chan15_raw = chan15_raw;
packet.chan16_raw = chan16_raw;
packet.chan17_raw = chan17_raw;
packet.chan18_raw = chan18_raw;
packet.chancount = chancount;
packet.rssi = rssi;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RC_CHANNELS_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_RC_CHANNELS;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_RC_CHANNELS_LEN, MAVLINK_MSG_ID_RC_CHANNELS_CRC);
#else
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_RC_CHANNELS_LEN);
#endif
}
/**
* @brief Pack a rc_channels 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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param time_boot_ms Timestamp (milliseconds since system boot)
* @param chancount Total number of RC channels being received. This can be larger than 18, indicating that more channels are available but not given in this message. This value should be 0 when no RC channels are available.
* @param chan1_raw RC channel 1 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
* @param chan2_raw RC channel 2 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
* @param chan3_raw RC channel 3 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
* @param chan4_raw RC channel 4 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
* @param chan5_raw RC channel 5 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
* @param chan6_raw RC channel 6 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
* @param chan7_raw RC channel 7 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
* @param chan8_raw RC channel 8 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
* @param chan9_raw RC channel 9 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
* @param chan10_raw RC channel 10 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
* @param chan11_raw RC channel 11 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
* @param chan12_raw RC channel 12 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
* @param chan13_raw RC channel 13 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
* @param chan14_raw RC channel 14 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
* @param chan15_raw RC channel 15 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
* @param chan16_raw RC channel 16 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
* @param chan17_raw RC channel 17 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
* @param chan18_raw RC channel 18 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
* @param rssi Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_rc_channels_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint32_t time_boot_ms,uint8_t chancount,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,uint16_t chan13_raw,uint16_t chan14_raw,uint16_t chan15_raw,uint16_t chan16_raw,uint16_t chan17_raw,uint16_t chan18_raw,uint8_t rssi)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_RC_CHANNELS_LEN];
_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_uint16_t(buf, 20, chan9_raw);
_mav_put_uint16_t(buf, 22, chan10_raw);
_mav_put_uint16_t(buf, 24, chan11_raw);
_mav_put_uint16_t(buf, 26, chan12_raw);
_mav_put_uint16_t(buf, 28, chan13_raw);
_mav_put_uint16_t(buf, 30, chan14_raw);
_mav_put_uint16_t(buf, 32, chan15_raw);
_mav_put_uint16_t(buf, 34, chan16_raw);
_mav_put_uint16_t(buf, 36, chan17_raw);
_mav_put_uint16_t(buf, 38, chan18_raw);
_mav_put_uint8_t(buf, 40, chancount);
_mav_put_uint8_t(buf, 41, rssi);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_RC_CHANNELS_LEN);
#else
mavlink_rc_channels_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.chan9_raw = chan9_raw;
packet.chan10_raw = chan10_raw;
packet.chan11_raw = chan11_raw;
packet.chan12_raw = chan12_raw;
packet.chan13_raw = chan13_raw;
packet.chan14_raw = chan14_raw;
packet.chan15_raw = chan15_raw;
packet.chan16_raw = chan16_raw;
packet.chan17_raw = chan17_raw;
packet.chan18_raw = chan18_raw;
packet.chancount = chancount;
packet.rssi = rssi;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_RC_CHANNELS_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_RC_CHANNELS;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_RC_CHANNELS_LEN, MAVLINK_MSG_ID_RC_CHANNELS_CRC);
#else
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_RC_CHANNELS_LEN);
#endif
}
/**
* @brief Encode a rc_channels struct
*
* @param system_id ID of this 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 C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_rc_channels_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_rc_channels_t* rc_channels)
{
return mavlink_msg_rc_channels_pack(system_id, component_id, msg, rc_channels->time_boot_ms, rc_channels->chancount, rc_channels->chan1_raw, rc_channels->chan2_raw, rc_channels->chan3_raw, rc_channels->chan4_raw, rc_channels->chan5_raw, rc_channels->chan6_raw, rc_channels->chan7_raw, rc_channels->chan8_raw, rc_channels->chan9_raw, rc_channels->chan10_raw, rc_channels->chan11_raw, rc_channels->chan12_raw, rc_channels->chan13_raw, rc_channels->chan14_raw, rc_channels->chan15_raw, rc_channels->chan16_raw, rc_channels->chan17_raw, rc_channels->chan18_raw, rc_channels->rssi);
}
/**
* @brief Encode a rc_channels struct 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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param rc_channels C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_rc_channels_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_rc_channels_t* rc_channels)
{
return mavlink_msg_rc_channels_pack_chan(system_id, component_id, chan, msg, rc_channels->time_boot_ms, rc_channels->chancount, rc_channels->chan1_raw, rc_channels->chan2_raw, rc_channels->chan3_raw, rc_channels->chan4_raw, rc_channels->chan5_raw, rc_channels->chan6_raw, rc_channels->chan7_raw, rc_channels->chan8_raw, rc_channels->chan9_raw, rc_channels->chan10_raw, rc_channels->chan11_raw, rc_channels->chan12_raw, rc_channels->chan13_raw, rc_channels->chan14_raw, rc_channels->chan15_raw, rc_channels->chan16_raw, rc_channels->chan17_raw, rc_channels->chan18_raw, rc_channels->rssi);
}
/**
* @brief Send a rc_channels message
* @param chan MAVLink channel to send the message
*
* @param time_boot_ms Timestamp (milliseconds since system boot)
* @param chancount Total number of RC channels being received. This can be larger than 18, indicating that more channels are available but not given in this message. This value should be 0 when no RC channels are available.
* @param chan1_raw RC channel 1 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
* @param chan2_raw RC channel 2 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
* @param chan3_raw RC channel 3 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
* @param chan4_raw RC channel 4 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
* @param chan5_raw RC channel 5 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
* @param chan6_raw RC channel 6 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
* @param chan7_raw RC channel 7 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
* @param chan8_raw RC channel 8 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
* @param chan9_raw RC channel 9 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
* @param chan10_raw RC channel 10 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
* @param chan11_raw RC channel 11 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
* @param chan12_raw RC channel 12 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
* @param chan13_raw RC channel 13 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
* @param chan14_raw RC channel 14 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
* @param chan15_raw RC channel 15 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
* @param chan16_raw RC channel 16 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
* @param chan17_raw RC channel 17 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
* @param chan18_raw RC channel 18 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
* @param rssi Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown.
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_rc_channels_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t chancount, 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, uint16_t chan13_raw, uint16_t chan14_raw, uint16_t chan15_raw, uint16_t chan16_raw, uint16_t chan17_raw, uint16_t chan18_raw, uint8_t rssi)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_RC_CHANNELS_LEN];
_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_uint16_t(buf, 20, chan9_raw);
_mav_put_uint16_t(buf, 22, chan10_raw);
_mav_put_uint16_t(buf, 24, chan11_raw);
_mav_put_uint16_t(buf, 26, chan12_raw);
_mav_put_uint16_t(buf, 28, chan13_raw);
_mav_put_uint16_t(buf, 30, chan14_raw);
_mav_put_uint16_t(buf, 32, chan15_raw);
_mav_put_uint16_t(buf, 34, chan16_raw);
_mav_put_uint16_t(buf, 36, chan17_raw);
_mav_put_uint16_t(buf, 38, chan18_raw);
_mav_put_uint8_t(buf, 40, chancount);
_mav_put_uint8_t(buf, 41, rssi);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS, buf, MAVLINK_MSG_ID_RC_CHANNELS_LEN, MAVLINK_MSG_ID_RC_CHANNELS_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS, buf, MAVLINK_MSG_ID_RC_CHANNELS_LEN);
#endif
#else
mavlink_rc_channels_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.chan9_raw = chan9_raw;
packet.chan10_raw = chan10_raw;
packet.chan11_raw = chan11_raw;
packet.chan12_raw = chan12_raw;
packet.chan13_raw = chan13_raw;
packet.chan14_raw = chan14_raw;
packet.chan15_raw = chan15_raw;
packet.chan16_raw = chan16_raw;
packet.chan17_raw = chan17_raw;
packet.chan18_raw = chan18_raw;
packet.chancount = chancount;
packet.rssi = rssi;
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS, (const char *)&packet, MAVLINK_MSG_ID_RC_CHANNELS_LEN, MAVLINK_MSG_ID_RC_CHANNELS_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS, (const char *)&packet, MAVLINK_MSG_ID_RC_CHANNELS_LEN);
#endif
#endif
}
#if MAVLINK_MSG_ID_RC_CHANNELS_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This varient of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_rc_channels_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t chancount, 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, uint16_t chan13_raw, uint16_t chan14_raw, uint16_t chan15_raw, uint16_t chan16_raw, uint16_t chan17_raw, uint16_t chan18_raw, uint8_t rssi)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
_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_uint16_t(buf, 20, chan9_raw);
_mav_put_uint16_t(buf, 22, chan10_raw);
_mav_put_uint16_t(buf, 24, chan11_raw);
_mav_put_uint16_t(buf, 26, chan12_raw);
_mav_put_uint16_t(buf, 28, chan13_raw);
_mav_put_uint16_t(buf, 30, chan14_raw);
_mav_put_uint16_t(buf, 32, chan15_raw);
_mav_put_uint16_t(buf, 34, chan16_raw);
_mav_put_uint16_t(buf, 36, chan17_raw);
_mav_put_uint16_t(buf, 38, chan18_raw);
_mav_put_uint8_t(buf, 40, chancount);
_mav_put_uint8_t(buf, 41, rssi);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS, buf, MAVLINK_MSG_ID_RC_CHANNELS_LEN, MAVLINK_MSG_ID_RC_CHANNELS_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS, buf, MAVLINK_MSG_ID_RC_CHANNELS_LEN);
#endif
#else
mavlink_rc_channels_t *packet = (mavlink_rc_channels_t *)msgbuf;
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->chan9_raw = chan9_raw;
packet->chan10_raw = chan10_raw;
packet->chan11_raw = chan11_raw;
packet->chan12_raw = chan12_raw;
packet->chan13_raw = chan13_raw;
packet->chan14_raw = chan14_raw;
packet->chan15_raw = chan15_raw;
packet->chan16_raw = chan16_raw;
packet->chan17_raw = chan17_raw;
packet->chan18_raw = chan18_raw;
packet->chancount = chancount;
packet->rssi = rssi;
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS, (const char *)packet, MAVLINK_MSG_ID_RC_CHANNELS_LEN, MAVLINK_MSG_ID_RC_CHANNELS_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS, (const char *)packet, MAVLINK_MSG_ID_RC_CHANNELS_LEN);
#endif
#endif
}
#endif
#endif
// MESSAGE RC_CHANNELS UNPACKING
/**
* @brief Get field time_boot_ms from rc_channels message
*
* @return Timestamp (milliseconds since system boot)
*/
static inline uint32_t mavlink_msg_rc_channels_get_time_boot_ms(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint32_t(msg, 0);
}
/**
* @brief Get field chancount from rc_channels message
*
* @return Total number of RC channels being received. This can be larger than 18, indicating that more channels are available but not given in this message. This value should be 0 when no RC channels are available.
*/
static inline uint8_t mavlink_msg_rc_channels_get_chancount(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 40);
}
/**
* @brief Get field chan1_raw from rc_channels message
*
* @return RC channel 1 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
*/
static inline uint16_t mavlink_msg_rc_channels_get_chan1_raw(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 4);
}
/**
* @brief Get field chan2_raw from rc_channels message
*
* @return RC channel 2 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
*/
static inline uint16_t mavlink_msg_rc_channels_get_chan2_raw(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 6);
}
/**
* @brief Get field chan3_raw from rc_channels message
*
* @return RC channel 3 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
*/
static inline uint16_t mavlink_msg_rc_channels_get_chan3_raw(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 8);
}
/**
* @brief Get field chan4_raw from rc_channels message
*
* @return RC channel 4 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
*/
static inline uint16_t mavlink_msg_rc_channels_get_chan4_raw(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 10);
}
/**
* @brief Get field chan5_raw from rc_channels message
*
* @return RC channel 5 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
*/
static inline uint16_t mavlink_msg_rc_channels_get_chan5_raw(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 12);
}
/**
* @brief Get field chan6_raw from rc_channels message
*
* @return RC channel 6 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
*/
static inline uint16_t mavlink_msg_rc_channels_get_chan6_raw(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 14);
}
/**
* @brief Get field chan7_raw from rc_channels message
*
* @return RC channel 7 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
*/
static inline uint16_t mavlink_msg_rc_channels_get_chan7_raw(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 16);
}
/**
* @brief Get field chan8_raw from rc_channels message
*
* @return RC channel 8 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
*/
static inline uint16_t mavlink_msg_rc_channels_get_chan8_raw(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 18);
}
/**
* @brief Get field chan9_raw from rc_channels message
*
* @return RC channel 9 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
*/
static inline uint16_t mavlink_msg_rc_channels_get_chan9_raw(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 20);
}
/**
* @brief Get field chan10_raw from rc_channels message
*
* @return RC channel 10 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
*/
static inline uint16_t mavlink_msg_rc_channels_get_chan10_raw(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 22);
}
/**
* @brief Get field chan11_raw from rc_channels message
*
* @return RC channel 11 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
*/
static inline uint16_t mavlink_msg_rc_channels_get_chan11_raw(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 24);
}
/**
* @brief Get field chan12_raw from rc_channels message
*
* @return RC channel 12 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
*/
static inline uint16_t mavlink_msg_rc_channels_get_chan12_raw(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 26);
}
/**
* @brief Get field chan13_raw from rc_channels message
*
* @return RC channel 13 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
*/
static inline uint16_t mavlink_msg_rc_channels_get_chan13_raw(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 28);
}
/**
* @brief Get field chan14_raw from rc_channels message
*
* @return RC channel 14 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
*/
static inline uint16_t mavlink_msg_rc_channels_get_chan14_raw(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 30);
}
/**
* @brief Get field chan15_raw from rc_channels message
*
* @return RC channel 15 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
*/
static inline uint16_t mavlink_msg_rc_channels_get_chan15_raw(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 32);
}
/**
* @brief Get field chan16_raw from rc_channels message
*
* @return RC channel 16 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
*/
static inline uint16_t mavlink_msg_rc_channels_get_chan16_raw(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 34);
}
/**
* @brief Get field chan17_raw from rc_channels message
*
* @return RC channel 17 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
*/
static inline uint16_t mavlink_msg_rc_channels_get_chan17_raw(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 36);
}
/**
* @brief Get field chan18_raw from rc_channels message
*
* @return RC channel 18 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
*/
static inline uint16_t mavlink_msg_rc_channels_get_chan18_raw(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 38);
}
/**
* @brief Get field rssi from rc_channels message
*
* @return Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown.
*/
static inline uint8_t mavlink_msg_rc_channels_get_rssi(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 41);
}
/**
* @brief Decode a rc_channels message into a struct
*
* @param msg The message to decode
* @param rc_channels C-struct to decode the message contents into
*/
static inline void mavlink_msg_rc_channels_decode(const mavlink_message_t* msg, mavlink_rc_channels_t* rc_channels)
{
#if MAVLINK_NEED_BYTE_SWAP
rc_channels->time_boot_ms = mavlink_msg_rc_channels_get_time_boot_ms(msg);
rc_channels->chan1_raw = mavlink_msg_rc_channels_get_chan1_raw(msg);
rc_channels->chan2_raw = mavlink_msg_rc_channels_get_chan2_raw(msg);
rc_channels->chan3_raw = mavlink_msg_rc_channels_get_chan3_raw(msg);
rc_channels->chan4_raw = mavlink_msg_rc_channels_get_chan4_raw(msg);
rc_channels->chan5_raw = mavlink_msg_rc_channels_get_chan5_raw(msg);
rc_channels->chan6_raw = mavlink_msg_rc_channels_get_chan6_raw(msg);
rc_channels->chan7_raw = mavlink_msg_rc_channels_get_chan7_raw(msg);
rc_channels->chan8_raw = mavlink_msg_rc_channels_get_chan8_raw(msg);
rc_channels->chan9_raw = mavlink_msg_rc_channels_get_chan9_raw(msg);
rc_channels->chan10_raw = mavlink_msg_rc_channels_get_chan10_raw(msg);
rc_channels->chan11_raw = mavlink_msg_rc_channels_get_chan11_raw(msg);
rc_channels->chan12_raw = mavlink_msg_rc_channels_get_chan12_raw(msg);
rc_channels->chan13_raw = mavlink_msg_rc_channels_get_chan13_raw(msg);
rc_channels->chan14_raw = mavlink_msg_rc_channels_get_chan14_raw(msg);
rc_channels->chan15_raw = mavlink_msg_rc_channels_get_chan15_raw(msg);
rc_channels->chan16_raw = mavlink_msg_rc_channels_get_chan16_raw(msg);
rc_channels->chan17_raw = mavlink_msg_rc_channels_get_chan17_raw(msg);
rc_channels->chan18_raw = mavlink_msg_rc_channels_get_chan18_raw(msg);
rc_channels->chancount = mavlink_msg_rc_channels_get_chancount(msg);
rc_channels->rssi = mavlink_msg_rc_channels_get_rssi(msg);
#else
memcpy(rc_channels, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_RC_CHANNELS_LEN);
#endif
}

View file

@ -0,0 +1,425 @@
// 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. A value of UINT16_MAX means to ignore this field.
uint16_t chan2_raw; ///< RC channel 2 value, in microseconds. A value of UINT16_MAX means to ignore this field.
uint16_t chan3_raw; ///< RC channel 3 value, in microseconds. A value of UINT16_MAX means to ignore this field.
uint16_t chan4_raw; ///< RC channel 4 value, in microseconds. A value of UINT16_MAX means to ignore this field.
uint16_t chan5_raw; ///< RC channel 5 value, in microseconds. A value of UINT16_MAX means to ignore this field.
uint16_t chan6_raw; ///< RC channel 6 value, in microseconds. A value of UINT16_MAX means to ignore this field.
uint16_t chan7_raw; ///< RC channel 7 value, in microseconds. A value of UINT16_MAX means to ignore this field.
uint16_t chan8_raw; ///< RC channel 8 value, in microseconds. A value of UINT16_MAX means to ignore this field.
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_MSG_ID_RC_CHANNELS_OVERRIDE_CRC 124
#define MAVLINK_MSG_ID_70_CRC 124
#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. A value of UINT16_MAX means to ignore this field.
* @param chan2_raw RC channel 2 value, in microseconds. A value of UINT16_MAX means to ignore this field.
* @param chan3_raw RC channel 3 value, in microseconds. A value of UINT16_MAX means to ignore this field.
* @param chan4_raw RC channel 4 value, in microseconds. A value of UINT16_MAX means to ignore this field.
* @param chan5_raw RC channel 5 value, in microseconds. A value of UINT16_MAX means to ignore this field.
* @param chan6_raw RC channel 6 value, in microseconds. A value of UINT16_MAX means to ignore this field.
* @param chan7_raw RC channel 7 value, in microseconds. A value of UINT16_MAX means to ignore this field.
* @param chan8_raw RC channel 8 value, in microseconds. A value of UINT16_MAX means to ignore this field.
* @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[MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN];
_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, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN);
#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, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_CRC);
#else
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN);
#endif
}
/**
* @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 will be 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. A value of UINT16_MAX means to ignore this field.
* @param chan2_raw RC channel 2 value, in microseconds. A value of UINT16_MAX means to ignore this field.
* @param chan3_raw RC channel 3 value, in microseconds. A value of UINT16_MAX means to ignore this field.
* @param chan4_raw RC channel 4 value, in microseconds. A value of UINT16_MAX means to ignore this field.
* @param chan5_raw RC channel 5 value, in microseconds. A value of UINT16_MAX means to ignore this field.
* @param chan6_raw RC channel 6 value, in microseconds. A value of UINT16_MAX means to ignore this field.
* @param chan7_raw RC channel 7 value, in microseconds. A value of UINT16_MAX means to ignore this field.
* @param chan8_raw RC channel 8 value, in microseconds. A value of UINT16_MAX means to ignore this field.
* @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[MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN];
_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, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN);
#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, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_CRC);
#else
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN);
#endif
}
/**
* @brief Encode a rc_channels_override struct
*
* @param system_id ID of this 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 Encode a rc_channels_override struct 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 will be sent over
* @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_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_rc_channels_override_t* rc_channels_override)
{
return mavlink_msg_rc_channels_override_pack_chan(system_id, component_id, chan, 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. A value of UINT16_MAX means to ignore this field.
* @param chan2_raw RC channel 2 value, in microseconds. A value of UINT16_MAX means to ignore this field.
* @param chan3_raw RC channel 3 value, in microseconds. A value of UINT16_MAX means to ignore this field.
* @param chan4_raw RC channel 4 value, in microseconds. A value of UINT16_MAX means to ignore this field.
* @param chan5_raw RC channel 5 value, in microseconds. A value of UINT16_MAX means to ignore this field.
* @param chan6_raw RC channel 6 value, in microseconds. A value of UINT16_MAX means to ignore this field.
* @param chan7_raw RC channel 7 value, in microseconds. A value of UINT16_MAX means to ignore this field.
* @param chan8_raw RC channel 8 value, in microseconds. A value of UINT16_MAX means to ignore this field.
*/
#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[MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN];
_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);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE, buf, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE, buf, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN);
#endif
#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;
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE, (const char *)&packet, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE, (const char *)&packet, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN);
#endif
#endif
}
#if MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This varient of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_rc_channels_override_send_buf(mavlink_message_t *msgbuf, 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 = (char *)msgbuf;
_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);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE, buf, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE, buf, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN);
#endif
#else
mavlink_rc_channels_override_t *packet = (mavlink_rc_channels_override_t *)msgbuf;
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;
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE, (const char *)packet, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE, (const char *)packet, MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN);
#endif
#endif
}
#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. A value of UINT16_MAX means to ignore this field.
*/
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. A value of UINT16_MAX means to ignore this field.
*/
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. A value of UINT16_MAX means to ignore this field.
*/
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. A value of UINT16_MAX means to ignore this field.
*/
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. A value of UINT16_MAX means to ignore this field.
*/
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. A value of UINT16_MAX means to ignore this field.
*/
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. A value of UINT16_MAX means to ignore this field.
*/
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. A value of UINT16_MAX means to ignore this field.
*/
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), MAVLINK_MSG_ID_RC_CHANNELS_OVERRIDE_LEN);
#endif
}

View file

@ -0,0 +1,449 @@
// 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. A value of UINT16_MAX implies the channel is unused.
uint16_t chan2_raw; ///< RC channel 2 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
uint16_t chan3_raw; ///< RC channel 3 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
uint16_t chan4_raw; ///< RC channel 4 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
uint16_t chan5_raw; ///< RC channel 5 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
uint16_t chan6_raw; ///< RC channel 6 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
uint16_t chan7_raw; ///< RC channel 7 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
uint16_t chan8_raw; ///< RC channel 8 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
uint8_t port; ///< Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows for more than 8 servos.
uint8_t rssi; ///< Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown.
} mavlink_rc_channels_raw_t;
#define MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN 22
#define MAVLINK_MSG_ID_35_LEN 22
#define MAVLINK_MSG_ID_RC_CHANNELS_RAW_CRC 244
#define MAVLINK_MSG_ID_35_CRC 244
#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 for more than 8 servos.
* @param chan1_raw RC channel 1 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
* @param chan2_raw RC channel 2 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
* @param chan3_raw RC channel 3 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
* @param chan4_raw RC channel 4 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
* @param chan5_raw RC channel 5 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
* @param chan6_raw RC channel 6 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
* @param chan7_raw RC channel 7 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
* @param chan8_raw RC channel 8 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
* @param rssi Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown.
* @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[MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN];
_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, MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN);
#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, MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_RC_CHANNELS_RAW;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN, MAVLINK_MSG_ID_RC_CHANNELS_RAW_CRC);
#else
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN);
#endif
}
/**
* @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 will be 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 for more than 8 servos.
* @param chan1_raw RC channel 1 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
* @param chan2_raw RC channel 2 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
* @param chan3_raw RC channel 3 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
* @param chan4_raw RC channel 4 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
* @param chan5_raw RC channel 5 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
* @param chan6_raw RC channel 6 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
* @param chan7_raw RC channel 7 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
* @param chan8_raw RC channel 8 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
* @param rssi Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown.
* @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[MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN];
_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, MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN);
#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, MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_RC_CHANNELS_RAW;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN, MAVLINK_MSG_ID_RC_CHANNELS_RAW_CRC);
#else
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN);
#endif
}
/**
* @brief Encode a rc_channels_raw struct
*
* @param system_id ID of this 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 Encode a rc_channels_raw struct 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 will be sent over
* @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_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_rc_channels_raw_t* rc_channels_raw)
{
return mavlink_msg_rc_channels_raw_pack_chan(system_id, component_id, chan, 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 for more than 8 servos.
* @param chan1_raw RC channel 1 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
* @param chan2_raw RC channel 2 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
* @param chan3_raw RC channel 3 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
* @param chan4_raw RC channel 4 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
* @param chan5_raw RC channel 5 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
* @param chan6_raw RC channel 6 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
* @param chan7_raw RC channel 7 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
* @param chan8_raw RC channel 8 value, in microseconds. A value of UINT16_MAX implies the channel is unused.
* @param rssi Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown.
*/
#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[MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN];
_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);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_RAW, buf, MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN, MAVLINK_MSG_ID_RC_CHANNELS_RAW_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_RAW, buf, MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN);
#endif
#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;
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_RAW, (const char *)&packet, MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN, MAVLINK_MSG_ID_RC_CHANNELS_RAW_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_RAW, (const char *)&packet, MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN);
#endif
#endif
}
#if MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This varient of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_rc_channels_raw_send_buf(mavlink_message_t *msgbuf, 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 = (char *)msgbuf;
_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);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_RAW, buf, MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN, MAVLINK_MSG_ID_RC_CHANNELS_RAW_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_RAW, buf, MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN);
#endif
#else
mavlink_rc_channels_raw_t *packet = (mavlink_rc_channels_raw_t *)msgbuf;
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;
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_RAW, (const char *)packet, MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN, MAVLINK_MSG_ID_RC_CHANNELS_RAW_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_RAW, (const char *)packet, MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN);
#endif
#endif
}
#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 for 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. A value of UINT16_MAX implies the channel is unused.
*/
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. A value of UINT16_MAX implies the channel is unused.
*/
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. A value of UINT16_MAX implies the channel is unused.
*/
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. A value of UINT16_MAX implies the channel is unused.
*/
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. A value of UINT16_MAX implies the channel is unused.
*/
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. A value of UINT16_MAX implies the channel is unused.
*/
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. A value of UINT16_MAX implies the channel is unused.
*/
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. A value of UINT16_MAX implies the channel is unused.
*/
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%, 100: 100%, 255: invalid/unknown.
*/
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), MAVLINK_MSG_ID_RC_CHANNELS_RAW_LEN);
#endif
}

View file

@ -0,0 +1,449 @@
// 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, (invalid) INT16_MAX.
int16_t chan2_scaled; ///< RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.
int16_t chan3_scaled; ///< RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.
int16_t chan4_scaled; ///< RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.
int16_t chan5_scaled; ///< RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.
int16_t chan6_scaled; ///< RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.
int16_t chan7_scaled; ///< RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.
int16_t chan8_scaled; ///< RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.
uint8_t port; ///< Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows for more than 8 servos.
uint8_t rssi; ///< Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown.
} mavlink_rc_channels_scaled_t;
#define MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN 22
#define MAVLINK_MSG_ID_34_LEN 22
#define MAVLINK_MSG_ID_RC_CHANNELS_SCALED_CRC 237
#define MAVLINK_MSG_ID_34_CRC 237
#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 for more than 8 servos.
* @param chan1_scaled RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.
* @param chan2_scaled RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.
* @param chan3_scaled RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.
* @param chan4_scaled RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.
* @param chan5_scaled RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.
* @param chan6_scaled RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.
* @param chan7_scaled RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.
* @param chan8_scaled RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.
* @param rssi Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown.
* @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[MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN];
_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, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN);
#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, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_RC_CHANNELS_SCALED;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_CRC);
#else
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN);
#endif
}
/**
* @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 will be 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 for more than 8 servos.
* @param chan1_scaled RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.
* @param chan2_scaled RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.
* @param chan3_scaled RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.
* @param chan4_scaled RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.
* @param chan5_scaled RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.
* @param chan6_scaled RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.
* @param chan7_scaled RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.
* @param chan8_scaled RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.
* @param rssi Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown.
* @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[MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN];
_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, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN);
#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, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_RC_CHANNELS_SCALED;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_CRC);
#else
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN);
#endif
}
/**
* @brief Encode a rc_channels_scaled struct
*
* @param system_id ID of this 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 Encode a rc_channels_scaled struct 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 will be sent over
* @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_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_rc_channels_scaled_t* rc_channels_scaled)
{
return mavlink_msg_rc_channels_scaled_pack_chan(system_id, component_id, chan, 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 for more than 8 servos.
* @param chan1_scaled RC channel 1 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.
* @param chan2_scaled RC channel 2 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.
* @param chan3_scaled RC channel 3 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.
* @param chan4_scaled RC channel 4 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.
* @param chan5_scaled RC channel 5 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.
* @param chan6_scaled RC channel 6 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.
* @param chan7_scaled RC channel 7 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.
* @param chan8_scaled RC channel 8 value scaled, (-100%) -10000, (0%) 0, (100%) 10000, (invalid) INT16_MAX.
* @param rssi Receive signal strength indicator, 0: 0%, 100: 100%, 255: invalid/unknown.
*/
#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[MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN];
_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);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_SCALED, buf, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_SCALED, buf, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN);
#endif
#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;
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_SCALED, (const char *)&packet, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_SCALED, (const char *)&packet, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN);
#endif
#endif
}
#if MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This varient of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_rc_channels_scaled_send_buf(mavlink_message_t *msgbuf, 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 = (char *)msgbuf;
_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);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_SCALED, buf, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_SCALED, buf, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN);
#endif
#else
mavlink_rc_channels_scaled_t *packet = (mavlink_rc_channels_scaled_t *)msgbuf;
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;
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_SCALED, (const char *)packet, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_RC_CHANNELS_SCALED, (const char *)packet, MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN);
#endif
#endif
}
#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 for 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, (invalid) INT16_MAX.
*/
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, (invalid) INT16_MAX.
*/
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, (invalid) INT16_MAX.
*/
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, (invalid) INT16_MAX.
*/
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, (invalid) INT16_MAX.
*/
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, (invalid) INT16_MAX.
*/
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, (invalid) INT16_MAX.
*/
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, (invalid) INT16_MAX.
*/
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%, 100: 100%, 255: invalid/unknown.
*/
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), MAVLINK_MSG_ID_RC_CHANNELS_SCALED_LEN);
#endif
}

View file

@ -0,0 +1,305 @@
// 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_MSG_ID_REQUEST_DATA_STREAM_CRC 148
#define MAVLINK_MSG_ID_66_CRC 148
#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[MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN];
_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, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN);
#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, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_REQUEST_DATA_STREAM;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_CRC);
#else
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN);
#endif
}
/**
* @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 will be 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[MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN];
_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, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN);
#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, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_REQUEST_DATA_STREAM;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_CRC);
#else
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN);
#endif
}
/**
* @brief Encode a request_data_stream struct
*
* @param system_id ID of this 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 Encode a request_data_stream struct 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 will be sent over
* @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_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_request_data_stream_t* request_data_stream)
{
return mavlink_msg_request_data_stream_pack_chan(system_id, component_id, chan, 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[MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN];
_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);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_REQUEST_DATA_STREAM, buf, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_REQUEST_DATA_STREAM, buf, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN);
#endif
#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;
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_REQUEST_DATA_STREAM, (const char *)&packet, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_REQUEST_DATA_STREAM, (const char *)&packet, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN);
#endif
#endif
}
#if MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This varient of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_request_data_stream_send_buf(mavlink_message_t *msgbuf, 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 = (char *)msgbuf;
_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);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_REQUEST_DATA_STREAM, buf, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_REQUEST_DATA_STREAM, buf, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN);
#endif
#else
mavlink_request_data_stream_t *packet = (mavlink_request_data_stream_t *)msgbuf;
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;
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_REQUEST_DATA_STREAM, (const char *)packet, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_REQUEST_DATA_STREAM, (const char *)packet, MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN);
#endif
#endif
}
#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), MAVLINK_MSG_ID_REQUEST_DATA_STREAM_LEN);
#endif
}

View file

@ -0,0 +1,353 @@
// 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_MSG_ID_SAFETY_ALLOWED_AREA_CRC 3
#define MAVLINK_MSG_ID_55_CRC 3
#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[MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN];
_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, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN);
#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, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_CRC);
#else
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN);
#endif
}
/**
* @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 will be 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[MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN];
_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, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN);
#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, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_CRC);
#else
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN);
#endif
}
/**
* @brief Encode a safety_allowed_area struct
*
* @param system_id ID of this 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 Encode a safety_allowed_area struct 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 will be sent over
* @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_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_safety_allowed_area_t* safety_allowed_area)
{
return mavlink_msg_safety_allowed_area_pack_chan(system_id, component_id, chan, 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[MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN];
_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);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA, buf, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA, buf, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN);
#endif
#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;
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA, (const char *)&packet, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA, (const char *)&packet, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN);
#endif
#endif
}
#if MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This varient of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_safety_allowed_area_send_buf(mavlink_message_t *msgbuf, 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 = (char *)msgbuf;
_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);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA, buf, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA, buf, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN);
#endif
#else
mavlink_safety_allowed_area_t *packet = (mavlink_safety_allowed_area_t *)msgbuf;
packet->p1x = p1x;
packet->p1y = p1y;
packet->p1z = p1z;
packet->p2x = p2x;
packet->p2y = p2y;
packet->p2z = p2z;
packet->frame = frame;
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA, (const char *)packet, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA, (const char *)packet, MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN);
#endif
#endif
}
#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), MAVLINK_MSG_ID_SAFETY_ALLOWED_AREA_LEN);
#endif
}

View file

@ -0,0 +1,401 @@
// 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_MSG_ID_SAFETY_SET_ALLOWED_AREA_CRC 15
#define MAVLINK_MSG_ID_54_CRC 15
#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[MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN];
_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, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN);
#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, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_CRC);
#else
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN);
#endif
}
/**
* @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 will be 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[MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN];
_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, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN);
#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, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_CRC);
#else
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN);
#endif
}
/**
* @brief Encode a safety_set_allowed_area struct
*
* @param system_id ID of this 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 Encode a safety_set_allowed_area struct 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 will be sent over
* @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_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_safety_set_allowed_area_t* safety_set_allowed_area)
{
return mavlink_msg_safety_set_allowed_area_pack_chan(system_id, component_id, chan, 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[MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN];
_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);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA, buf, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA, buf, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN);
#endif
#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;
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA, (const char *)&packet, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA, (const char *)&packet, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN);
#endif
#endif
}
#if MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This varient of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_safety_set_allowed_area_send_buf(mavlink_message_t *msgbuf, 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 = (char *)msgbuf;
_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);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA, buf, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA, buf, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN);
#endif
#else
mavlink_safety_set_allowed_area_t *packet = (mavlink_safety_set_allowed_area_t *)msgbuf;
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;
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA, (const char *)packet, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA, (const char *)packet, MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN);
#endif
#endif
}
#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), MAVLINK_MSG_ID_SAFETY_SET_ALLOWED_AREA_LEN);
#endif
}

View file

@ -0,0 +1,425 @@
// 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_MSG_ID_SCALED_IMU_CRC 170
#define MAVLINK_MSG_ID_26_CRC 170
#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[MAVLINK_MSG_ID_SCALED_IMU_LEN];
_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, MAVLINK_MSG_ID_SCALED_IMU_LEN);
#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, MAVLINK_MSG_ID_SCALED_IMU_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_SCALED_IMU;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SCALED_IMU_LEN, MAVLINK_MSG_ID_SCALED_IMU_CRC);
#else
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SCALED_IMU_LEN);
#endif
}
/**
* @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 will be 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[MAVLINK_MSG_ID_SCALED_IMU_LEN];
_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, MAVLINK_MSG_ID_SCALED_IMU_LEN);
#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, MAVLINK_MSG_ID_SCALED_IMU_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_SCALED_IMU;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SCALED_IMU_LEN, MAVLINK_MSG_ID_SCALED_IMU_CRC);
#else
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SCALED_IMU_LEN);
#endif
}
/**
* @brief Encode a scaled_imu struct
*
* @param system_id ID of this 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 Encode a scaled_imu struct 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 will be sent over
* @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_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_scaled_imu_t* scaled_imu)
{
return mavlink_msg_scaled_imu_pack_chan(system_id, component_id, chan, 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[MAVLINK_MSG_ID_SCALED_IMU_LEN];
_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);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU, buf, MAVLINK_MSG_ID_SCALED_IMU_LEN, MAVLINK_MSG_ID_SCALED_IMU_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU, buf, MAVLINK_MSG_ID_SCALED_IMU_LEN);
#endif
#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;
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU, (const char *)&packet, MAVLINK_MSG_ID_SCALED_IMU_LEN, MAVLINK_MSG_ID_SCALED_IMU_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU, (const char *)&packet, MAVLINK_MSG_ID_SCALED_IMU_LEN);
#endif
#endif
}
#if MAVLINK_MSG_ID_SCALED_IMU_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This varient of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_scaled_imu_send_buf(mavlink_message_t *msgbuf, 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 = (char *)msgbuf;
_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);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU, buf, MAVLINK_MSG_ID_SCALED_IMU_LEN, MAVLINK_MSG_ID_SCALED_IMU_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU, buf, MAVLINK_MSG_ID_SCALED_IMU_LEN);
#endif
#else
mavlink_scaled_imu_t *packet = (mavlink_scaled_imu_t *)msgbuf;
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;
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU, (const char *)packet, MAVLINK_MSG_ID_SCALED_IMU_LEN, MAVLINK_MSG_ID_SCALED_IMU_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU, (const char *)packet, MAVLINK_MSG_ID_SCALED_IMU_LEN);
#endif
#endif
}
#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), MAVLINK_MSG_ID_SCALED_IMU_LEN);
#endif
}

View file

@ -0,0 +1,425 @@
// MESSAGE SCALED_IMU2 PACKING
#define MAVLINK_MSG_ID_SCALED_IMU2 116
typedef struct __mavlink_scaled_imu2_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_imu2_t;
#define MAVLINK_MSG_ID_SCALED_IMU2_LEN 22
#define MAVLINK_MSG_ID_116_LEN 22
#define MAVLINK_MSG_ID_SCALED_IMU2_CRC 76
#define MAVLINK_MSG_ID_116_CRC 76
#define MAVLINK_MESSAGE_INFO_SCALED_IMU2 { \
"SCALED_IMU2", \
10, \
{ { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_scaled_imu2_t, time_boot_ms) }, \
{ "xacc", NULL, MAVLINK_TYPE_INT16_T, 0, 4, offsetof(mavlink_scaled_imu2_t, xacc) }, \
{ "yacc", NULL, MAVLINK_TYPE_INT16_T, 0, 6, offsetof(mavlink_scaled_imu2_t, yacc) }, \
{ "zacc", NULL, MAVLINK_TYPE_INT16_T, 0, 8, offsetof(mavlink_scaled_imu2_t, zacc) }, \
{ "xgyro", NULL, MAVLINK_TYPE_INT16_T, 0, 10, offsetof(mavlink_scaled_imu2_t, xgyro) }, \
{ "ygyro", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_scaled_imu2_t, ygyro) }, \
{ "zgyro", NULL, MAVLINK_TYPE_INT16_T, 0, 14, offsetof(mavlink_scaled_imu2_t, zgyro) }, \
{ "xmag", NULL, MAVLINK_TYPE_INT16_T, 0, 16, offsetof(mavlink_scaled_imu2_t, xmag) }, \
{ "ymag", NULL, MAVLINK_TYPE_INT16_T, 0, 18, offsetof(mavlink_scaled_imu2_t, ymag) }, \
{ "zmag", NULL, MAVLINK_TYPE_INT16_T, 0, 20, offsetof(mavlink_scaled_imu2_t, zmag) }, \
} \
}
/**
* @brief Pack a scaled_imu2 message
* @param system_id ID of this 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_imu2_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[MAVLINK_MSG_ID_SCALED_IMU2_LEN];
_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, MAVLINK_MSG_ID_SCALED_IMU2_LEN);
#else
mavlink_scaled_imu2_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, MAVLINK_MSG_ID_SCALED_IMU2_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_SCALED_IMU2;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SCALED_IMU2_LEN, MAVLINK_MSG_ID_SCALED_IMU2_CRC);
#else
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SCALED_IMU2_LEN);
#endif
}
/**
* @brief Pack a scaled_imu2 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 will be 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_imu2_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[MAVLINK_MSG_ID_SCALED_IMU2_LEN];
_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, MAVLINK_MSG_ID_SCALED_IMU2_LEN);
#else
mavlink_scaled_imu2_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, MAVLINK_MSG_ID_SCALED_IMU2_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_SCALED_IMU2;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SCALED_IMU2_LEN, MAVLINK_MSG_ID_SCALED_IMU2_CRC);
#else
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SCALED_IMU2_LEN);
#endif
}
/**
* @brief Encode a scaled_imu2 struct
*
* @param system_id ID of this 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_imu2 C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_scaled_imu2_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_scaled_imu2_t* scaled_imu2)
{
return mavlink_msg_scaled_imu2_pack(system_id, component_id, msg, scaled_imu2->time_boot_ms, scaled_imu2->xacc, scaled_imu2->yacc, scaled_imu2->zacc, scaled_imu2->xgyro, scaled_imu2->ygyro, scaled_imu2->zgyro, scaled_imu2->xmag, scaled_imu2->ymag, scaled_imu2->zmag);
}
/**
* @brief Encode a scaled_imu2 struct 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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param scaled_imu2 C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_scaled_imu2_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_scaled_imu2_t* scaled_imu2)
{
return mavlink_msg_scaled_imu2_pack_chan(system_id, component_id, chan, msg, scaled_imu2->time_boot_ms, scaled_imu2->xacc, scaled_imu2->yacc, scaled_imu2->zacc, scaled_imu2->xgyro, scaled_imu2->ygyro, scaled_imu2->zgyro, scaled_imu2->xmag, scaled_imu2->ymag, scaled_imu2->zmag);
}
/**
* @brief Send a scaled_imu2 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_imu2_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[MAVLINK_MSG_ID_SCALED_IMU2_LEN];
_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);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU2, buf, MAVLINK_MSG_ID_SCALED_IMU2_LEN, MAVLINK_MSG_ID_SCALED_IMU2_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU2, buf, MAVLINK_MSG_ID_SCALED_IMU2_LEN);
#endif
#else
mavlink_scaled_imu2_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;
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU2, (const char *)&packet, MAVLINK_MSG_ID_SCALED_IMU2_LEN, MAVLINK_MSG_ID_SCALED_IMU2_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU2, (const char *)&packet, MAVLINK_MSG_ID_SCALED_IMU2_LEN);
#endif
#endif
}
#if MAVLINK_MSG_ID_SCALED_IMU2_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This varient of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_scaled_imu2_send_buf(mavlink_message_t *msgbuf, 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 = (char *)msgbuf;
_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);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU2, buf, MAVLINK_MSG_ID_SCALED_IMU2_LEN, MAVLINK_MSG_ID_SCALED_IMU2_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU2, buf, MAVLINK_MSG_ID_SCALED_IMU2_LEN);
#endif
#else
mavlink_scaled_imu2_t *packet = (mavlink_scaled_imu2_t *)msgbuf;
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;
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU2, (const char *)packet, MAVLINK_MSG_ID_SCALED_IMU2_LEN, MAVLINK_MSG_ID_SCALED_IMU2_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU2, (const char *)packet, MAVLINK_MSG_ID_SCALED_IMU2_LEN);
#endif
#endif
}
#endif
#endif
// MESSAGE SCALED_IMU2 UNPACKING
/**
* @brief Get field time_boot_ms from scaled_imu2 message
*
* @return Timestamp (milliseconds since system boot)
*/
static inline uint32_t mavlink_msg_scaled_imu2_get_time_boot_ms(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint32_t(msg, 0);
}
/**
* @brief Get field xacc from scaled_imu2 message
*
* @return X acceleration (mg)
*/
static inline int16_t mavlink_msg_scaled_imu2_get_xacc(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 4);
}
/**
* @brief Get field yacc from scaled_imu2 message
*
* @return Y acceleration (mg)
*/
static inline int16_t mavlink_msg_scaled_imu2_get_yacc(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 6);
}
/**
* @brief Get field zacc from scaled_imu2 message
*
* @return Z acceleration (mg)
*/
static inline int16_t mavlink_msg_scaled_imu2_get_zacc(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 8);
}
/**
* @brief Get field xgyro from scaled_imu2 message
*
* @return Angular speed around X axis (millirad /sec)
*/
static inline int16_t mavlink_msg_scaled_imu2_get_xgyro(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 10);
}
/**
* @brief Get field ygyro from scaled_imu2 message
*
* @return Angular speed around Y axis (millirad /sec)
*/
static inline int16_t mavlink_msg_scaled_imu2_get_ygyro(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 12);
}
/**
* @brief Get field zgyro from scaled_imu2 message
*
* @return Angular speed around Z axis (millirad /sec)
*/
static inline int16_t mavlink_msg_scaled_imu2_get_zgyro(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 14);
}
/**
* @brief Get field xmag from scaled_imu2 message
*
* @return X Magnetic field (milli tesla)
*/
static inline int16_t mavlink_msg_scaled_imu2_get_xmag(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 16);
}
/**
* @brief Get field ymag from scaled_imu2 message
*
* @return Y Magnetic field (milli tesla)
*/
static inline int16_t mavlink_msg_scaled_imu2_get_ymag(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 18);
}
/**
* @brief Get field zmag from scaled_imu2 message
*
* @return Z Magnetic field (milli tesla)
*/
static inline int16_t mavlink_msg_scaled_imu2_get_zmag(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 20);
}
/**
* @brief Decode a scaled_imu2 message into a struct
*
* @param msg The message to decode
* @param scaled_imu2 C-struct to decode the message contents into
*/
static inline void mavlink_msg_scaled_imu2_decode(const mavlink_message_t* msg, mavlink_scaled_imu2_t* scaled_imu2)
{
#if MAVLINK_NEED_BYTE_SWAP
scaled_imu2->time_boot_ms = mavlink_msg_scaled_imu2_get_time_boot_ms(msg);
scaled_imu2->xacc = mavlink_msg_scaled_imu2_get_xacc(msg);
scaled_imu2->yacc = mavlink_msg_scaled_imu2_get_yacc(msg);
scaled_imu2->zacc = mavlink_msg_scaled_imu2_get_zacc(msg);
scaled_imu2->xgyro = mavlink_msg_scaled_imu2_get_xgyro(msg);
scaled_imu2->ygyro = mavlink_msg_scaled_imu2_get_ygyro(msg);
scaled_imu2->zgyro = mavlink_msg_scaled_imu2_get_zgyro(msg);
scaled_imu2->xmag = mavlink_msg_scaled_imu2_get_xmag(msg);
scaled_imu2->ymag = mavlink_msg_scaled_imu2_get_ymag(msg);
scaled_imu2->zmag = mavlink_msg_scaled_imu2_get_zmag(msg);
#else
memcpy(scaled_imu2, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_SCALED_IMU2_LEN);
#endif
}

View file

@ -0,0 +1,425 @@
// MESSAGE SCALED_IMU3 PACKING
#define MAVLINK_MSG_ID_SCALED_IMU3 129
typedef struct __mavlink_scaled_imu3_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_imu3_t;
#define MAVLINK_MSG_ID_SCALED_IMU3_LEN 22
#define MAVLINK_MSG_ID_129_LEN 22
#define MAVLINK_MSG_ID_SCALED_IMU3_CRC 46
#define MAVLINK_MSG_ID_129_CRC 46
#define MAVLINK_MESSAGE_INFO_SCALED_IMU3 { \
"SCALED_IMU3", \
10, \
{ { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_scaled_imu3_t, time_boot_ms) }, \
{ "xacc", NULL, MAVLINK_TYPE_INT16_T, 0, 4, offsetof(mavlink_scaled_imu3_t, xacc) }, \
{ "yacc", NULL, MAVLINK_TYPE_INT16_T, 0, 6, offsetof(mavlink_scaled_imu3_t, yacc) }, \
{ "zacc", NULL, MAVLINK_TYPE_INT16_T, 0, 8, offsetof(mavlink_scaled_imu3_t, zacc) }, \
{ "xgyro", NULL, MAVLINK_TYPE_INT16_T, 0, 10, offsetof(mavlink_scaled_imu3_t, xgyro) }, \
{ "ygyro", NULL, MAVLINK_TYPE_INT16_T, 0, 12, offsetof(mavlink_scaled_imu3_t, ygyro) }, \
{ "zgyro", NULL, MAVLINK_TYPE_INT16_T, 0, 14, offsetof(mavlink_scaled_imu3_t, zgyro) }, \
{ "xmag", NULL, MAVLINK_TYPE_INT16_T, 0, 16, offsetof(mavlink_scaled_imu3_t, xmag) }, \
{ "ymag", NULL, MAVLINK_TYPE_INT16_T, 0, 18, offsetof(mavlink_scaled_imu3_t, ymag) }, \
{ "zmag", NULL, MAVLINK_TYPE_INT16_T, 0, 20, offsetof(mavlink_scaled_imu3_t, zmag) }, \
} \
}
/**
* @brief Pack a scaled_imu3 message
* @param system_id ID of this 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_imu3_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[MAVLINK_MSG_ID_SCALED_IMU3_LEN];
_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, MAVLINK_MSG_ID_SCALED_IMU3_LEN);
#else
mavlink_scaled_imu3_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, MAVLINK_MSG_ID_SCALED_IMU3_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_SCALED_IMU3;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SCALED_IMU3_LEN, MAVLINK_MSG_ID_SCALED_IMU3_CRC);
#else
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SCALED_IMU3_LEN);
#endif
}
/**
* @brief Pack a scaled_imu3 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 will be 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_imu3_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[MAVLINK_MSG_ID_SCALED_IMU3_LEN];
_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, MAVLINK_MSG_ID_SCALED_IMU3_LEN);
#else
mavlink_scaled_imu3_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, MAVLINK_MSG_ID_SCALED_IMU3_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_SCALED_IMU3;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SCALED_IMU3_LEN, MAVLINK_MSG_ID_SCALED_IMU3_CRC);
#else
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SCALED_IMU3_LEN);
#endif
}
/**
* @brief Encode a scaled_imu3 struct
*
* @param system_id ID of this 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_imu3 C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_scaled_imu3_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_scaled_imu3_t* scaled_imu3)
{
return mavlink_msg_scaled_imu3_pack(system_id, component_id, msg, scaled_imu3->time_boot_ms, scaled_imu3->xacc, scaled_imu3->yacc, scaled_imu3->zacc, scaled_imu3->xgyro, scaled_imu3->ygyro, scaled_imu3->zgyro, scaled_imu3->xmag, scaled_imu3->ymag, scaled_imu3->zmag);
}
/**
* @brief Encode a scaled_imu3 struct 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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param scaled_imu3 C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_scaled_imu3_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_scaled_imu3_t* scaled_imu3)
{
return mavlink_msg_scaled_imu3_pack_chan(system_id, component_id, chan, msg, scaled_imu3->time_boot_ms, scaled_imu3->xacc, scaled_imu3->yacc, scaled_imu3->zacc, scaled_imu3->xgyro, scaled_imu3->ygyro, scaled_imu3->zgyro, scaled_imu3->xmag, scaled_imu3->ymag, scaled_imu3->zmag);
}
/**
* @brief Send a scaled_imu3 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_imu3_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[MAVLINK_MSG_ID_SCALED_IMU3_LEN];
_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);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU3, buf, MAVLINK_MSG_ID_SCALED_IMU3_LEN, MAVLINK_MSG_ID_SCALED_IMU3_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU3, buf, MAVLINK_MSG_ID_SCALED_IMU3_LEN);
#endif
#else
mavlink_scaled_imu3_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;
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU3, (const char *)&packet, MAVLINK_MSG_ID_SCALED_IMU3_LEN, MAVLINK_MSG_ID_SCALED_IMU3_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU3, (const char *)&packet, MAVLINK_MSG_ID_SCALED_IMU3_LEN);
#endif
#endif
}
#if MAVLINK_MSG_ID_SCALED_IMU3_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This varient of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_scaled_imu3_send_buf(mavlink_message_t *msgbuf, 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 = (char *)msgbuf;
_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);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU3, buf, MAVLINK_MSG_ID_SCALED_IMU3_LEN, MAVLINK_MSG_ID_SCALED_IMU3_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU3, buf, MAVLINK_MSG_ID_SCALED_IMU3_LEN);
#endif
#else
mavlink_scaled_imu3_t *packet = (mavlink_scaled_imu3_t *)msgbuf;
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;
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU3, (const char *)packet, MAVLINK_MSG_ID_SCALED_IMU3_LEN, MAVLINK_MSG_ID_SCALED_IMU3_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_IMU3, (const char *)packet, MAVLINK_MSG_ID_SCALED_IMU3_LEN);
#endif
#endif
}
#endif
#endif
// MESSAGE SCALED_IMU3 UNPACKING
/**
* @brief Get field time_boot_ms from scaled_imu3 message
*
* @return Timestamp (milliseconds since system boot)
*/
static inline uint32_t mavlink_msg_scaled_imu3_get_time_boot_ms(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint32_t(msg, 0);
}
/**
* @brief Get field xacc from scaled_imu3 message
*
* @return X acceleration (mg)
*/
static inline int16_t mavlink_msg_scaled_imu3_get_xacc(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 4);
}
/**
* @brief Get field yacc from scaled_imu3 message
*
* @return Y acceleration (mg)
*/
static inline int16_t mavlink_msg_scaled_imu3_get_yacc(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 6);
}
/**
* @brief Get field zacc from scaled_imu3 message
*
* @return Z acceleration (mg)
*/
static inline int16_t mavlink_msg_scaled_imu3_get_zacc(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 8);
}
/**
* @brief Get field xgyro from scaled_imu3 message
*
* @return Angular speed around X axis (millirad /sec)
*/
static inline int16_t mavlink_msg_scaled_imu3_get_xgyro(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 10);
}
/**
* @brief Get field ygyro from scaled_imu3 message
*
* @return Angular speed around Y axis (millirad /sec)
*/
static inline int16_t mavlink_msg_scaled_imu3_get_ygyro(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 12);
}
/**
* @brief Get field zgyro from scaled_imu3 message
*
* @return Angular speed around Z axis (millirad /sec)
*/
static inline int16_t mavlink_msg_scaled_imu3_get_zgyro(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 14);
}
/**
* @brief Get field xmag from scaled_imu3 message
*
* @return X Magnetic field (milli tesla)
*/
static inline int16_t mavlink_msg_scaled_imu3_get_xmag(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 16);
}
/**
* @brief Get field ymag from scaled_imu3 message
*
* @return Y Magnetic field (milli tesla)
*/
static inline int16_t mavlink_msg_scaled_imu3_get_ymag(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 18);
}
/**
* @brief Get field zmag from scaled_imu3 message
*
* @return Z Magnetic field (milli tesla)
*/
static inline int16_t mavlink_msg_scaled_imu3_get_zmag(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 20);
}
/**
* @brief Decode a scaled_imu3 message into a struct
*
* @param msg The message to decode
* @param scaled_imu3 C-struct to decode the message contents into
*/
static inline void mavlink_msg_scaled_imu3_decode(const mavlink_message_t* msg, mavlink_scaled_imu3_t* scaled_imu3)
{
#if MAVLINK_NEED_BYTE_SWAP
scaled_imu3->time_boot_ms = mavlink_msg_scaled_imu3_get_time_boot_ms(msg);
scaled_imu3->xacc = mavlink_msg_scaled_imu3_get_xacc(msg);
scaled_imu3->yacc = mavlink_msg_scaled_imu3_get_yacc(msg);
scaled_imu3->zacc = mavlink_msg_scaled_imu3_get_zacc(msg);
scaled_imu3->xgyro = mavlink_msg_scaled_imu3_get_xgyro(msg);
scaled_imu3->ygyro = mavlink_msg_scaled_imu3_get_ygyro(msg);
scaled_imu3->zgyro = mavlink_msg_scaled_imu3_get_zgyro(msg);
scaled_imu3->xmag = mavlink_msg_scaled_imu3_get_xmag(msg);
scaled_imu3->ymag = mavlink_msg_scaled_imu3_get_ymag(msg);
scaled_imu3->zmag = mavlink_msg_scaled_imu3_get_zmag(msg);
#else
memcpy(scaled_imu3, _MAV_PAYLOAD(msg), MAVLINK_MSG_ID_SCALED_IMU3_LEN);
#endif
}

View file

@ -0,0 +1,281 @@
// MESSAGE SCALED_PRESSURE PACKING
#define MAVLINK_MSG_ID_SCALED_PRESSURE 29
typedef struct __mavlink_scaled_pressure_t
{
uint32_t time_boot_ms; ///< Timestamp (milliseconds 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_MSG_ID_SCALED_PRESSURE_CRC 115
#define MAVLINK_MSG_ID_29_CRC 115
#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 (milliseconds 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[MAVLINK_MSG_ID_SCALED_PRESSURE_LEN];
_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, MAVLINK_MSG_ID_SCALED_PRESSURE_LEN);
#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, MAVLINK_MSG_ID_SCALED_PRESSURE_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_SCALED_PRESSURE;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SCALED_PRESSURE_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE_CRC);
#else
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_SCALED_PRESSURE_LEN);
#endif
}
/**
* @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 will be sent over
* @param msg The MAVLink message to compress the data into
* @param time_boot_ms Timestamp (milliseconds 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[MAVLINK_MSG_ID_SCALED_PRESSURE_LEN];
_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, MAVLINK_MSG_ID_SCALED_PRESSURE_LEN);
#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, MAVLINK_MSG_ID_SCALED_PRESSURE_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_SCALED_PRESSURE;
#if MAVLINK_CRC_EXTRA
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SCALED_PRESSURE_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE_CRC);
#else
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_SCALED_PRESSURE_LEN);
#endif
}
/**
* @brief Encode a scaled_pressure struct
*
* @param system_id ID of this 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 Encode a scaled_pressure struct 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 will be sent over
* @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_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_scaled_pressure_t* scaled_pressure)
{
return mavlink_msg_scaled_pressure_pack_chan(system_id, component_id, chan, 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 (milliseconds 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[MAVLINK_MSG_ID_SCALED_PRESSURE_LEN];
_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);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_PRESSURE, buf, MAVLINK_MSG_ID_SCALED_PRESSURE_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_PRESSURE, buf, MAVLINK_MSG_ID_SCALED_PRESSURE_LEN);
#endif
#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;
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_PRESSURE, (const char *)&packet, MAVLINK_MSG_ID_SCALED_PRESSURE_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_PRESSURE, (const char *)&packet, MAVLINK_MSG_ID_SCALED_PRESSURE_LEN);
#endif
#endif
}
#if MAVLINK_MSG_ID_SCALED_PRESSURE_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This varient of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_scaled_pressure_send_buf(mavlink_message_t *msgbuf, 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 = (char *)msgbuf;
_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);
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_PRESSURE, buf, MAVLINK_MSG_ID_SCALED_PRESSURE_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_PRESSURE, buf, MAVLINK_MSG_ID_SCALED_PRESSURE_LEN);
#endif
#else
mavlink_scaled_pressure_t *packet = (mavlink_scaled_pressure_t *)msgbuf;
packet->time_boot_ms = time_boot_ms;
packet->press_abs = press_abs;
packet->press_diff = press_diff;
packet->temperature = temperature;
#if MAVLINK_CRC_EXTRA
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_PRESSURE, (const char *)packet, MAVLINK_MSG_ID_SCALED_PRESSURE_LEN, MAVLINK_MSG_ID_SCALED_PRESSURE_CRC);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_SCALED_PRESSURE, (const char *)packet, MAVLINK_MSG_ID_SCALED_PRESSURE_LEN);
#endif
#endif
}
#endif
#endif
// MESSAGE SCALED_PRESSURE UNPACKING
/**
* @brief Get field time_boot_ms from scaled_pressure message
*
* @return Timestamp (milliseconds 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), MAVLINK_MSG_ID_SCALED_PRESSURE_LEN);
#endif
}

Some files were not shown because too many files have changed in this diff Show more