1
0
Fork 0
mirror of https://github.com/iNavFlight/inav.git synced 2025-07-18 13:55:16 +03:00

Merge remote-tracking branch 'upstream/master' into abo_fix_man_mode_WP_mission

This commit is contained in:
breadoven 2021-05-03 13:34:41 +01:00
commit 2f30d96f30
383 changed files with 44637 additions and 5754 deletions

View file

@ -22,6 +22,14 @@ endif()
option(COMPILER_VERSION_CHECK "Ensure the compiler matches the expected version" ON)
include(GetGitRevisionDescription)
get_git_head_revision(GIT_REFSPEC GIT_SHA1)
string(SUBSTRING ${GIT_SHA1} 0 8 GIT_REV)
# Load settings related functions, so the tests can use them
include(main)
include(settings)
if(TOOLCHAIN STREQUAL none)
add_subdirectory(src/test)
else()
@ -29,7 +37,7 @@ else()
include("${CMAKE_CURRENT_SOURCE_DIR}/cmake/${TOOLCHAIN}-checks.cmake")
endif()
project(INAV VERSION 2.7.0)
project(INAV VERSION 3.0.0)
enable_language(ASM)
@ -49,10 +57,6 @@ if(CMAKE_BUILD_TYPE STREQUAL "Release" OR CMAKE_BUILD_TYPE STREQUAL "RelWithDebI
set(IS_RELEASE_BUILD ON)
endif()
include(GetGitRevisionDescription)
get_git_head_revision(GIT_REFSPEC GIT_SHA1)
string(SUBSTRING ${GIT_SHA1} 0 8 GIT_REV)
set(FIRMWARE_VERSION ${PROJECT_VERSION})
option(WARNINGS_AS_ERRORS "Make all warnings into errors")
@ -64,10 +68,8 @@ set(COMMON_COMPILE_DEFINITIONS
FC_VERSION_PATCH_LEVEL=${CMAKE_PROJECT_VERSION_PATCH}
)
include(settings)
include(openocd)
include(svd)
include(main)
include(stm32)
add_subdirectory(src)

View file

@ -4,6 +4,7 @@ set(SETTINGS_GENERATED_H "${SETTINGS_GENERATED}.h")
set(SETTINGS_FILE "${MAIN_SRC_DIR}/fc/settings.yaml")
set(SETTINGS_GENERATOR "${MAIN_UTILS_DIR}/settings.rb")
include(CMakeParseArguments)
function(enable_settings exe name)
get_generated_files_dir(dir ${name})
@ -15,11 +16,26 @@ function(enable_settings exe name)
list(APPEND cflags ${options})
list(APPEND cflags ${includes})
list(APPEND cflags ${defs})
cmake_parse_arguments(
args
# Boolean arguments
""
# Single value arguments
"OUTPUTS;SETTINGS_CXX"
# Multi-value arguments
""
# Start parsing after the known arguments
${ARGN}
)
set(output ${dir}/${SETTINGS_GENERATED_H} ${dir}/${SETTINGS_GENERATED_C})
add_custom_command(
OUTPUT ${dir}/${SETTINGS_GENERATED_H} ${dir}/${SETTINGS_GENERATED_C}
OUTPUT ${output}
COMMAND
${CMAKE_COMMAND} -E env CFLAGS="${cflags}" TARGET=${name} PATH=$ENV{PATH}
${CMAKE_COMMAND} -E env CFLAGS="${cflags}" TARGET=${name} PATH=$ENV{PATH} SETTINGS_CXX=${args_SETTINGS_CXX}
${RUBY_EXECUTABLE} ${SETTINGS_GENERATOR} ${MAIN_DIR} ${SETTINGS_FILE} -o "${dir}"
DEPENDS ${SETTINGS_GENERATOR} ${SETTINGS_FILE}
)
set(${args_OUTPUTS} ${output} PARENT_SCOPE)
endfunction()

View file

@ -1,88 +0,0 @@
## Connections
Board orientation.
These notes assume that when the board is placed with the header pins facing up, the bottom right of the board is next to the 8 sets of INPUT pin headers.
Inner means between the two rows of header sockets, outer means between the left/right board edges and the header sockets.
### SPI2 / External SPI
sclk GPIOB 13
miso GPIOB 14
mosi GPIOB 15
There are 4 pins, labelled CS1-4 next to a label that reads Ext SPI. The 3rd pin is connected to the flash chip on
the bottom right inner of the board. The other pins on the flash chip are wired up to PB3/4/5
### SPI3 / SPI
sclk GPIOB 3
miso GPIOB 4
mosi GPIOB 5
ssel 1 GPIOB 10 / Ext SPI CS1
ssel 2 GPIOB 11 / Ext SPI CS2
ssel 3 GPIOB 12 / Ext SPI CS3 - wired up to Slave Select of M25P16 15MBitFlash chip
ssel 4 GPIOB 13 / Ext SPI CS4 - not usable since it is used for SPI2 sclk
### RC Input
INPUT
PA8 / CH1 - TIM1_CH1
PB8 / CH2 - TIM16_CH1
PB9 / CH3 - TIM17_CH1
PC6 / CH4 - TIM8_CH1
PC7 / CH5 - TIM8_CH2
PC8 / CH6 - TIM8_CH3
PF9 / CH7 - TIM15_CH1
PF10 / CH8 - TIM15_CH2
### PWM Outputs
OUTPUT
PD12 / CH1 - TIM4_CH1
PD13 / CH2 - TIM4_CH2
PD14 / CH3 - TIM4_CH3
PD15 / CH4 - TIM4_CH4
PA1 / CH5 - TIM2_CH2
PA2 / CH6 - TIM2_CH3
PA3 / CH7 - TIM2_CH4
PB0 / CH8 - TIM3_CH3
PB1 / CH9 - TIM3_CH4
PA4 / CH10 - TIM3_CH2
### Other ports
There is space for a MS5611 pressure sensor at the top left inner of the board.
There is an I2C socket on the left outer of the board which connects to a PCA9306 I2C level shifter directly opposite (inner).
The PCA9306 is not populated on some boards and thus the I2C socket is unusable.
There is a CAN socket on the top right outer of the board which connects to a MAX3015 CAN Tranceiver.
The MAX3015 is not populated on some boards and thus the CAN socket is unusable.
There are some solder pads labelled Ext 1-4 at the top right inner of the board.
GPIOE 6 / PE6 / Ext 1
GPIOD 3 / PD3 / Ext 2
GPIOD 4 / PD4 / Ext 3
GPIOB 3 / PB3 / Ext 4
There are some solder pads labelled ADC0-3 & Diff Press at the top left inner of the board
They are connected to the ADC socket at the top left outer of the board
PC3 / Diff Press - ADC12_IN9 (Differential Pressure)
PC2 / ADC2 - ADC12_IN8
PC1 / ADC1 - ADC12_IN7
PC0 / ADC0 - ADC12_IN6
There is space for a MPXV5004/MPVZ5004 differential pressure sensor, if populated it's analog pin connects to PC3.
There are sockets for 5 UARTs labelled USART1-5.
There is a socket labelled RX_IN.
GPIOD 2 / PD2 / RX_IN

View file

@ -1,126 +0,0 @@
# Board - Colibri RACE
The Colibri RACE is a STM32F3 based flight control designed specifically to work with the TBS POWERCUBE multi rotor stack.
## Hardware Features:
* STM32F303 based chipset for ultimate performance
* PPM, SBUS, DSM, DSMX input (5V and 3.3V provided over internal BUS). No inverters or hacks needed.
* 6 PWM ESC output channels (autoconnect, internal BUS)
* RGB LED strip support incl. power management
* Extension port for GPS / external compass / pressure sensor
* UART port for peripherals (Blackbox, FrSky telemetry etc.)
* Choose between plug & play sockets or solder pads for R/C and buzzer
* 5V buzzer output
* MPU6500 new generation accelerometer/gyro
* 3x status LED (DCDC pwr/ 3.3V pwr/ status)
* Battery monitoring for 12V, 5V and VBat supply
* Size: 36mmx36mm (30.5mm standard raster)
* Weight: 4.4g
For more details please visit:
http://www.team-blacksheep.com/powercube
## Serial Ports
| Value | Identifier | Board Markings | Notes |
| ----- | ------------ | -------------- | ------------------------------------------|
| 1 | VCP | USB PORT | Main Port For MSP |
| 2 | USART1 | FREE PORT | PC4 and PC5(Tx and Rx respectively) |
| 3 | USART2 | PPM Serial | PA15 |
| 4 | USART3 | GPS PORT | PB10 and PB11(Tx and Rx respectively) |
## Pinouts
Full pinout details are available in the manual, here:
http://www.team-blacksheep.com/colibri_race
### SWD - ICSP
| Pin | Function | Notes |
| --- | -------------- | -------------------------------------------- |
| 1 | VCC_IN | 3.3 Volt |
| 2 | SWDIO | |
| 3 | nRESET | |
| 4 | SWCLK | |
| 5 | Ground | |
| 6 | SWO/TDO | |
### Internal Bus
| Pin | Function | Notes |
| --- | -------------- | -------------------------------------------- |
| 1 | PWM1 | MOTOR 1 |
| 2 | PWM2 | MOTOR 2 |
| 3 | PWM3 | MOTOR 3 |
| 4 | PWM4 | MOTOR 4 |
| 5 | PWM5 | MOTOR 5 (For Y6 or Hex X) |
| 6 | PWM6 | MOTOR 6 (For Y6 or Hex X) |
| 7 | BST SDA | Use For TBS CorePro Control Device |
| 8 | BST SCL | Use For TBS CorePro Control Device |
| 9 | PWM7 | Can be a normal GPIO (PA1) or PWM |
| 10 | PWM8 | Can be a normal GPIO (PA2) or PWM |
| 11 | 12.2V DCDC | If 12v is detected, the Blue LED will turn on|
| 12 | 5.1V DCDC | Voltage for MCU |
### Servo
| Pin | Function | Notes |
| --- | -------------- | -------------------------------------------- |
| 1 | Ground | |
| 2 | VCC_OUT | 5.1 Volt output to LCD Strip |
| 3 | PWM Servo | PB14 - PWM10 |
### IO_1 - LED Strip
| Pin | Function | Notes |
| --- | ----------------- | -------------------------------------------- |
| 1 | LED_STRIP | Enable `feature LED_STRIP` |
| 2 | VCC_OUT | 5.1 Volt output to LCD Strip |
| 3 | Ground | |
### IO_2 - Sensor Interface
| Pin | Function | Notes |
| --- | ----------------- | -------------------------------------------- |
| 1 | VCC_OUT | 4.7 Volt output to the device |
| 2 | Ground | |
| 3 | UART3 TX | GPS |
| 4 | UART3 RX | GPS |
| 5 | SDA | mag, pressure, or other i2c device |
| 6 | SCL | mag, pressure, or other i2c device |
### IO_3 - RC input
IO_3 is used for RX_PPM/RX_SERIAL. Under the `PORT` tab, set RX_SERIAL to UART2 when using RX_SERIAL.
| Pin | Function | Notes |
| --- | ----------------- | -------------------------------------------- |
| 1 | PPM/Serial | Can PPM or Serial input |
| 2 | VCC_OUT | 3.3 Volt output to the device |
| 3 | Ground | |
| 4 | VCC_OUT | 5.1 Volt output to the device |
### IO_4 - Buzzer
| Pin | Function | Notes |
| --- | ----------------- | -------------------------------------------- |
| 1 | BUZZER | Normal high (5.1v) |
| 2 | VCC_OUT | 5.1 Volt output to the device |
### IO_5 - Free UART
| Pin | Function | Notes |
| --- | ----------------- | -------------------------------------------- |
| 1 | UART1 TX | Free UART |
| 2 | UART1 RX | Free UART |
| 3 | Ground | |
| 4 | VCC_OUT | 4.7 Volt output to the device |
### IO_6 - IR TX (extension)
| Pin | Function | Notes |
| --- | ----------------- | -------------------------------------------- |
| 1 | IR TX | |
| 2 | Ground | |

View file

@ -1,101 +0,0 @@
# Board - MotoLab
The MOTOLAB build target supports the STM32F3-based boards provided by MotoLab.
At present this includes the TornadoFC and MotoF3. The TornadoFC is described here:
http://www.rcgroups.com/forums/showthread.php?t=2473157
The MotoF3 documentation will be provided when the board is available.
Both boards use the STM32F303 microcontroller and have the following features:
* 256K bytes of flash memory
* Floating point math coprocessor
* Three hardware serial port UARTs
* USB using the built-in USB phy that does not interfere with any hadware UART
* Stable voltage regulation
* High-current buzzer/LED output
* Serial LED interface
* Low-pass filtered VBAT input with 1/10 divider ratio
* 8 short-circuit protected PWM outputs, with 5V buffering on the TornadoFC
* On-board 6S-compatible switching regulator (MotoF3)
* Direct mounting option for a Pololu switching regulator for up to 6S lipo operation (TornadoFC)
# Flashing
The MotoLab boards use the internal DFU USB interface on the STM32F3 microcontroller which is not compatible with the INAV configurator flashing tool.
Instead, on Windows you can use the Impulse Flashing Utility from ImpulseRC, available here:
http://www.warpquad.com/ImpulseFlash.zip
Download and unzip the program. Start the program, plug in the USB on the target board, and drag and drop the intended binary file onto the program icon. The program will put the STM32F3 into bootloader mode automatically and load the binary file to the flash.
For programming on Linux, use the dfu-util program which is installed by default on Ubuntu-based systems. Connect the boot pins on the board and plug in the USB.
Verify that the system identifies the DFU device with this command:
```
dfu-util -l
```
The output should list a "Found DFU" device, something like this:
```
dfu-util 0.5
(C) 2005-2008 by Weston Schmidt, Harald Welte and OpenMoko Inc.
(C) 2010-2011 Tormod Volden (DfuSe support)
This program is Free Software and has ABSOLUTELY NO WARRANTY
dfu-util does currently only support DFU version 1.0
Found DFU: [0483:df11] devnum=0, cfg=1, intf=0, alt=0, name="@Internal Flash /0x08000000/128*0002Kg"
Found DFU: [0483:df11] devnum=0, cfg=1, intf=0, alt=1, name="@Option Bytes /0x1FFFF800/01*016 e"
```
Use this command to load the binary file to the flash memory on the board:
```
dfu-util --alt 0 -s 0x08000000 -D <binfile>
```
The output should look something like this:
```
dfu-util 0.5
(C) 2005-2008 by Weston Schmidt, Harald Welte and OpenMoko Inc.
(C) 2010-2011 Tormod Volden (DfuSe support)
This program is Free Software and has ABSOLUTELY NO WARRANTY
dfu-util does currently only support DFU version 1.0
Opening DFU USB device... ID 0483:df11
Run-time device DFU version 011a
Found DFU: [0483:df11] devnum=0, cfg=1, intf=0, alt=0, name="@Internal Flash /0x08000000/128*0002Kg"
Claiming USB DFU Interface...
Setting Alternate Setting #0 ...
Determining device status: state = dfuDNLOAD-IDLE, status = 0
aborting previous incomplete transfer
Determining device status: state = dfuIDLE, status = 0
dfuIDLE, continuing
DFU mode device DFU version 011a
Device returned transfer size 2048
No valid DFU suffix signature
Warning: File has no DFU suffix
DfuSe interface name: "Internal Flash "
```
A binary file is required for the Impulse flashing Utility and dfu-util. The binary file can be built as follows:
```
make TARGET=MOTOLAB clean
make TARGET=MOTOLAB binary
```
To completely erase the flash, create an all-zero file with this command on linux:
```
dd if=/dev/zero of=zero.bin bs=1 count=262144
```
## Todo
Pinout documentation

View file

@ -1,87 +0,0 @@
# Board - OMNIBUS F3
> This board is not supported in recent INAV releases
## Hardware Features
Refer to the product web page:
[OMNIBUS AIO F3 Flight Control](http://shop.myairbot.com/index.php/flight-control/cleanflight-baseflight/omnibusv11.html)
### Hardware Notes
There are few things to note on how things are connected on the board.
1. VBAT (J4)
This is a battery input to the board, and is also a input to voltage sensor.
2. J11 Power distribution
The RAM is user defined power rail, and all RAM through holes (J6, J7 and J11) are connected together. By connecting 5V or VBAT to RAM at J11, the RAM becomes 5V or VBAT power rail respectively. The VBAT on J11 can also be used to power the Board if necessary.
3. RSSI (J4)
The pin is labelled as RSSI, but it will not be used for RSSI input for a hardware configuration limitation. In this document, the "RSSI" is used to indicate the pin location, not the function.
4. UART1 in boot-loader/DFU mode
The UART1 is scanned during boot-loader/DFU mode, together with USB for possible interaction with a host PC. It is observed that devices that autonomously transmits some data, such as GPS, will prevent the MCU to talk to the USB. It is advised not to connect or disconnect such devices to/from UART1. UART2 is safe from this catch.
## iNav Specific Target Configuration
The first support for the OMNIBUS F3 appeared in BetaFlight.
The OMNIBUS target in iNav has different configuration from the BetaFlight support, to maximize the hardware resource utilization for navigation oriented use cases.
[PIN CONFIGURATION PIC HERE]
### PWM Outputs
Six PWM outputs (PWM1~PWM6) are supported, but PWM5 and PWM6 is not available when UART3 is in use.
PWM7 and PWM8 are dedicated for I2C; in this document, they are used to indicate the pin location, not the function.
If servos are used on a multirotor mixer (i.e. Tricopter) PWM1 is remapped to servo and motor 1 is moved to PWM2 etc.
Note: Tested only for QUAD-X configuration.
### Hardware UART Ports
PPM/SBUS jumper for J8 is assumed to be configured for PPM (SBUS=R18 removed). With newer boards (the 1.1 Version) you don't have to swap an smd resistor to use SBUS anymore. It just works out of the box.
| UART | Location | Note |
|-------|----------|-------------------|
| UART1 |J13 | |
| UART2 |J12 | |
| UART3 |J22 | PWM5=TX3,PWM6=RX3 |
All UARTs are Serial RX capable.
### I2C
I2C is available on J22 PWM7 and PWM8
|signal | Location | Alt. Location |
|-------|------------|---------------|
|SCL | J22 (PWM8) | J3 (SCL) |
|SDA | J22 (PWM7) | J3 (SDA) |
### RANGEFINDER
HC-SR04 rangefinder is supported when NOT using PPM.
|signal | Location |
|-------|------------|
|TRIG | J8 (PPM) |
|ECHO | J4 (RSSI) |
5V rangefinder can be connected directly without inline resistors.
### OSD
Integrated OSD is supported.
### RSSI Sensor Input
The RSSI sensor adc is not supported due to the hardware configuration limitation.
## Usage in a Fixed Wing
Due to the way INAV handles PWM outputs the first 2 PWM outputs are reserved for the motor outputs. When using SBUS on UART3 as recommended this leaves only 2 additional outputs for the servos, as output 5 and 6 are blocked by UART3 serial for SBUS and 7 and 8 are used for I2C.
You can free PWM outputs 5 and 6 by simply connecting SBUS up to UART1. For FrSky there is no hardware inverter needed as the F3 chip UARTs can handle this without additional hardware. Just make sure that `sbus_inversion = ON` is set. However, you will not be able to use UART3, e.G. for telemetry.
This allows to control a standard airplane with rudder, ailerons and elevator. If you use flaps or a servo gimbal, you can bypass the FC by connecting it up to the receiver directly.

View file

@ -1,46 +0,0 @@
# Board - Paris Air Hero 32
This is the AIR3 PARIS Sirius AirHERO 32 F3 board from MultiWiiCopter
Source: http://www.multiwiicopter.com/products/inav-air3-fixed-wing
## Sensors
MPU6500 via SPI interface.
BMP280 via SPI interface
## Ports
6 x 3pin ESC / Servo outputs
1 x 8pin JST connector (PPM/PWM/UART2)
1 x 4pin JST connector (UART3)
## I2C bus
I2C bus is made available with a special target - AIRHEROF3_QUAD. This target limits motor outputs to 4 and adds I2C bus at M5/M6 connectors.
## Pinouts
The 10 pin RC I/O connector has the following pinouts when used in RX_PPM/RX_SERIAL mode.
From right to left when looking at the socket from the edge of the board.
| Pin | Function | Notes |
| --- | -------------- | -------------------------------- |
| 1 | Ground | |
| 2 | +5V | |
| 3 | RX_PPM | Enable `feature RX_PPM` |
| 4 | AIRSPEED | Airspeed sensor (3.3V max) |
| 5 | USART2 TX | |
| 6 | USART2 RX | |
| 7 | SS1 RX | Enable `feature SOFT_SERIAL` |
| 8 | SS1 TX | |
## Serial Ports
| Value | Identifier | RX | TX | Notes |
| ----- | ------------ | ---------- | ------------------ | ------------------------------------------------------------------------------------------- |
| 1 | USART1 | RX / PA10 | TX / PA9 | Internally connected to USB port via CP2102 IC |
| 2 | USART2 | RC4 / PA3 | RC3 / PA2 | |
| 3 | USART3 | F3 / PB11 | F2 / PB10 | |

View file

@ -1,46 +0,0 @@
# Board - Paris Air Hero 32
## Sensors
MPU6500 via SPI interface.
## Ports
6 x 3pin ESC / Servo outputs
1 x 8pin JST connector (PPM/PWM/UART2)
1 x 4pin JST connector (UART3/I2C)
## Pinouts
The 10 pin RC I/O connector has the following pinouts when used in RX_PPM/RX_SERIAL mode.
From right to left when looking at the socket from the edge of the board.
| Pin | Function | Notes |
| --- | -------------- | -------------------------------- |
| 1 | Ground | |
| 2 | +5V | |
| 3 | RX_PPM | Enable `feature RX_PPM` |
| 4 | RSSI_ADC | Enable `feature RSSI_ADC`. Connect to the output of a PWM-RSSI conditioner, 0v-3.3v input |
| 5 | USART2 TX | |
| 6 | USART2 RX | Built-in inverter |
| 7 | LED_STRIP | Enable `feature LED_STRIP` |
| 8 | unused | |
When SOFTSERIAL is enabled, LED_STRIP and CURRENT_METER are unavailable, but one SoftSerial port is made available to use instead.
| Pin | Function | Notes |
| --- | -------------- | -------------------------------- |
| 7 | SOFTSERIAL1 RX | Enable `feature SOFTSERIAL` |
| 8 | SOFTSERIAL1 TX | |
## Serial Ports
| Value | Identifier | RX | TX | Notes |
| ----- | ------------ | ---------- | ------------------ | ------------------------------------------------------------------------------------------- |
| 1 | USART1 | RX / PA10 | TX / PA9 / TELEM | TELEM output is always inverted (for FrSky). Internally connected to USB port via CP2102 IC |
| 2 | USART2 | RC4 / PA3 | RC3 / PA2 | |
| 3 | USART3 | F3 / PB11 | F2 / PB10 | Flex port is configured as UART3 when port is configured |
| 4 | SOFTSERIAL1 | RC5 / PA6 | RC6 / PA7 | |

View file

@ -1,12 +0,0 @@
# Board - RMDO
The DoDo board is a clone of the SPRacingF3 board in terms of CPU pin mappings. See the SPRacingF3 documentation.
Hardware differences compared to SPRacingF3 are as follows:
* Rev 1 and Rev 2: the CPU is the cheaper version of the F3 with only 128KB FLASH. Rev 3: the CPU is a F3 version with 256KB FLASH.
* 2MBit flash size
* The barometer is the cheaper BMP280.
* It does not have any compass sensor.
* Onboard BEC.
* Different physical connectors/pins/pads/ports.

View file

@ -1,97 +0,0 @@
# Board - SPRacingF3
The Seriously Pro Racing MOF3 board (SPRacingF3) is the first board designed specifically for INAV.
Full details available on the website, here:
http://seriouslypro.com/spracingf3
## Hardware Features
* No compromise I/O. Use all the features all the time; e.g. Connect your OSD + SmartPort + SBus + GPS + LED Strip + Battery Monitoring + HC-SR04 + 8 motors - all at the same time!
* On-board high-capacity black box flight log recorder - optimize your tuning and see the results of your setup without guesswork. (Acro and Deluxe)
* Next-generation STM32 F3 processor with hardware floating point unit for efficient flight calculations and faster ARM-Cortex M4 core.
* Stackable design - perfect for integrating with OSDs and power distribution boards.
* 16 PWM I/O lines for ESCs, Servos and legacy receivers. 8 available on standard pin headers. 8 via side mounted connectors.
* Supports SBus, SumH, SumD, Spektrum1024/2048, XBus, PPM, PWM receivers. No external inverters required (built-in).
* Dedicated output for programmable LEDs - great for orientation, racing and night flying.
* Dedicated I2C port for connection of OLED display without needing flight battery.
* Battery monitoring ports for voltage and current.
* Buzzer port for audible warnings and notifications.
* Solder pads in addition to connectors for HC-SR04, PPM, RSSI, Current, GPIO, LED Strip, 3.3v,
* Developer friendly debugging port (SWD) and boot mode selection, unbrickable bootloader.
* Symmetrical design for a super tidy wiring.
* Wire up using using pin headers, JST-SH sockets or solder pads. Use either right-angled or straight pin-headers.
* Barometer mounted on the bottom of the board for easy wind isolation.
## Serial Ports
| Value | Identifier | RX | TX | 5v Tolerant | Notes |
| ----- | ------------ | ------------ | ------------ | ----------- | ------------------------------------------------------------------------------------------- |
| 1 | USART1 | PA10 | PA9 | YES | Internally connected to USB port via CP2102 IC. Also available on a USART1 JST connector and on through hole pins. |
| 2 | USART2 | PA15 | PA14 | YES | Available on USART2 JST port only. |
| 3 | USART3 | PB11 / IO2_3 | PB10 / IO2_4 | NO | Available on IO_2, USART3 JST port and through hole pins. |
* You cannot use SWD and USART2 at the same time.
* You may encounter flashing problems if you have something connected to the USART1 RX/TX pins. Power other devices of and/or disconnect them.
## Pinouts
Full pinout details are available in the manual, here:
http://seriouslypro.com/spracingf3#manual
### IO_1
| Pin | Function | Notes |
| --- | -------------- | -------------------------------------------- |
| 1 | Ground | |
| 2 | VCC_IN | Voltage as-supplied by BEC. |
| 3 | RX_PPM | Enable `feature RX_PPM` |
| 4 | GPIO | |
| 5 | SoftSerial1_RX | |
| 6 | SoftSerial1_TX | |
| 7 | LED_STRIP | Enable `feature LED_STRIP` |
| 8 | VCC | 3.3v output for LOW CURRENT application only |
### IO_2
| Pin | Function | Notes |
| --- | ------------------------- | -------------------------------------------- |
| 1 | Ground | |
| 2 | VCC_IN | Voltage as-supplied by BEC. |
| 3 | RX_SERIAL | UART3 RX |
| 4 | | UART3_TX |
| 5 | HC-SR04_TRIG/SoftSerial2_RX | Enable `feature SOFTSERIAL` or HC-SR04 rangefinder |
| 6 | HC-SR04_ECHO/SoftSerial2_TX | Enable `feature SOFTSERIAL` or HC-SR04 rangefinder |
| 7 | ADC_1 | Current Sensor |
| 8 | ADC_2 | RSSI |
### UART1/2/3
| Pin | Function | Notes |
| --- | -------------- | -------------------------------------------- |
| 1 | Ground | |
| 2 | VCC_IN | Voltage as-supplied by BEC. |
| 3 | TXD | |
| 4 | RXD | |
### I2C
| Pin | Function | Notes |
| --- | -------------- | -------------------------------------------- |
| 1 | Ground | |
| 2 | 5.0v | Voltage as-supplied by BEC OR USB, always on |
| 3 | SCL | |
| 4 | SDA | |
### SWD
The port cannot be used at the same time as UART2.
| Pin | Function | Notes |
| --- | -------------- | -------------------------------------------- |
| 1 | Ground | |
| 2 | NRST | Voltage as-supplied by BEC OR USB, always on |
| 3 | SWDIO | |
| 4 | SWDCLK | |

View file

@ -1,160 +0,0 @@
# Board - Seriously Pro SP Racing F3 EVO
The Seriously Pro Racing F3 Evo board (SPRacingF3EVO) is the evolution of the first board designed specifically for Cleanflight.
Purchasing boards directly from SeriouslyPro / SP Racing and official retailers helps fund Cleanflight development, it's the reason the Seriously Pro boards exist! Official retailers are always listed on the SeriouslyPro.com website.
Full details available on the website, here:
http://seriouslypro.com/spracingf3evo
## Hardware Features
* Next-generation STM32 F3 processor with hardware floating point unit for efficient flight calculations and faster ARM-Cortex M4 core.
* MicroSD-Card socket for black box flight log recorder - optimize your tuning and see the results of your setup without guesswork.
* Race transponder built in - just turn up at a race and have your lap times recorded.
* Features the latest Accelerometer, Gyro and Mag/Compass and Baro/Altitude sensor technology.
* Wire up using using pin headers for all major connections for excellent crash-durability. Use either right-angled or straight pin-headers.
* No compromise I/O. Use all the features all the time; e.g. Connect your USB + OSD + SmartPort + SBus + GPS + LED Strip + Battery Monitoring + 8 motors - all at the same time!
* 8 PWM output lines for ESCs and Servos. Arranged for easy wiring on standard pin headers.
* Supports direct connection of SBus, SumH, SumD, Spektrum1024/2048, XBus receivers. No external inverters required (built-in).
* Supports direct connection of 3.3v Spektrum Satellite receivers via 3 pin through-hole JST-ZH connector.
* Dedicated PPM receiver input.
* 3 Serial Ports - NOT shared with the USB socket.
* Telemetry port
* Micro USB socket.
* Dedicated output for programmable LEDs - great for orientation, racing and night flying. (Currently mutually exclusive with the Transponder).
* Dedicated I2C port for connection of OLED display without needing flight battery.
* Battery monitoring for voltage and current.
* RSSI monitoring (analogue or PWM).
* Buzzer port for audible warnings and notifications.
* Developer friendly debugging port (SWD) and boot mode selection, unbrickable bootloader.
* Symmetrical design for a super tidy wiring.
* JST-SH sockets only for I2C, UART2 and SWD. UART2 also on through-hole pins.
* Flashing via USB or serial port.
* Stackable design - perfect for integrating with OSDs and power distribution boards.
* Standard mounting - 36x36mm with standard 30.5mm mounting holes.
* LEDs for 3v, 5v and Status for easy diagnostics.
* Copper-etched Cleanflight logo.
## Serial Ports
| Value | Identifier | RX | TX | 5v Tolerant | Notes |
| ----- | ------------ | ------------ | ------------ | ----------- | ------------------------------------------------------------------------------------------- |
| 1 | USART1 | PA10 | PA9 | YES | 2 through-hole pins. Use for connecting to OSD/GPS/BlueTooth. |
| 2 | USART2 | PA15 | PA14 / SWCLK | YES | JST socket and PPM header. Use to connect to RX. |
| 3 | USART3 | PB11 / AF7 | PB10 / AF7 | NO | Available on 4 through-hole pins. 3.3V signals only ! Use for GPS, Spektrum Satellite RX, SmartPort Telemetry, HoTT telemetry, etc. |
* You cannot use SWD and USART2 at the same time.
* When using a Serial RX receiver the TXD (T2) pin cannot be used for telemetry. Use UART3 TXD instead.
* Two SoftSerial is supported. Enabling SoftSerial disables Servo output 3,4,5,6
* Windows DFU Flashing requires Zadig (see configurator)
### SoftSerial
| Pin | Function | Notes |
| --- | -------------- | -------------------------------- |
| 5 | SOFTSERIAL1 RX | SoftSerial replaces Servo 3,4,5,6|
| 6 | SOFTSERIAL1 TX | |
| 7 | SOFTSERIAL2 RX | |
| 8 | SOFTSERIAL2 TX | |
## Pinouts
Full pinout details are available in the manual, here:
http://seriouslypro.com/files/SPRacingF3EVO-Manual-latest.pdf
### IO_1
The 6 pin IO_1 connector has the following pinouts when used in RX_SERIAL mode.
| Pin | Function | Notes |
| --- | -------------- | -------------------------------------------- |
| 1 | Ground | |
| 2 | VCC_IN | Voltage as-supplied by BEC. |
| 3 | RX_SERIAL | Enable `feature RX_SERIAL` |
| 4 | | |
| 5 | +V BATTERY | Voltage as-supplied by Battery. |
| 6 | -V BATTERY | Voltage as-supplied by Battery. |
When RX_PPM is used the IO_1 pinout is as follows.
| Pin | Function | Notes |
| --- | -------------- | -------------------------------------------- |
| 1 | Ground | |
| 2 | VCC_IN | Voltage as-supplied by BEC. |
| 3 | RX_PPM | Enable `feature RX_PPM` |
| 4 | TELEMETRY | Enable `feature TELEMETRY` |
| 5 | +V BATTERY | Voltage as-supplied by Battery. |
| 6 | -V BATTERY | Voltage as-supplied by Battery. |
### IO_2
When TRANSPONDER is used and the IR solder pads are shorted, the 6 pin IO_2 pinout is as follows.
| Pin | Function | Notes |
| --- | ------------------------- | -------------------------------------------- |
| 1 | IR- | Short leg of the IR LED |
| 2 | IR+ | Long leg of the IR LED |
| 3 | CURRENT | Current Sensor |
| 4 | RSSI | RSSI (PWM or Analog - select by solder pads) |
| 5 | BUZZER+ | 5V Source |
| 6 | BUZZER- | Buzzer signal |
When LEDSTRIP is used and the LED solder pads are shorted, the 6 pin IO_2 pinout is as follows.
| Pin | Function | Notes |
| --- | ------------------------- | -------------------------------------------- |
| 1 | | |
| 2 | LEDSTRIP | WS2812 Ledstrip data |
| 3 | CURRENT | Current Sensor |
| 4 | RSSI | RSSI (PWM or Analog - select by solder pads) |
| 5 | BUZZER+ | 5V Source |
| 6 | BUZZER- | Buzzer signal |
### UART1
| Pin | Function | Notes |
| --- | -------------- | -------------------------------------------- |
| 3 | TXD | |
| 4 | RXD | |
### UART2/3
| Pin | Function | Notes |
| --- | -------------- | -------------------------------------------- |
| 1 | Ground | |
| 2 | VCC_IN | Voltage as-supplied by BEC. |
| 3 | TXD | |
| 4 | RXD | |
### Spektrum Satellite
| Pin | Function | Notes |
| --- | -------------- | -------------------------------------------- |
| 3 | 3.3V | |
| 2 | Ground | |
| 1 | RXD | |
### I2C
| Pin | Function | Notes |
| --- | -------------- | -------------------------------------------- |
| 1 | Ground | |
| 2 | 5.0v | Voltage as-supplied by BEC OR USB, always on |
| 3 | SCL | 3.3V signals only |
| 4 | SDA | 3.3V signals only |
### SWD
The port cannot be used at the same time as UART2.
| Pin | Function | Notes |
| --- | -------------- | -------------------------------------------- |
| 1 | Ground | |
| 2 | NRST | |
| 3 | SWDIO | |
| 4 | SWDCLK | |

View file

@ -1,159 +0,0 @@
# Board - Seriously Pro SP Racing F3 EVO
The Seriously Pro Racing F3 Evo board (SPRacingF3EVO) is the evolution of the first board designed specifically for Cleanflight.
Purchasing boards directly from SeriouslyPro / SP Racing and official retailers helps fund Cleanflight development, it's the reason the Seriously Pro boards exist! Official retailers are always listed on the SeriouslyPro.com website.
Full details available on the website, here:
http://seriouslypro.com/spracingf3evo
## Hardware Features
* Next-generation STM32 F3 processor with hardware floating point unit for efficient flight calculations and faster ARM-Cortex M4 core.
* MicroSD-Card socket for black box flight log recorder - optimize your tuning and see the results of your setup without guesswork.
* Race transponder built in - just turn up at a race and have your lap times recorded.
* Features the latest Accelerometer, Gyro and Mag/Compass and Baro/Altitude sensor technology.
* Wire up using using pin headers for all major connections for excellent crash-durability. Use either right-angled or straight pin-headers.
* No compromise I/O. Use all the features all the time; e.g. Connect your USB + OSD + SmartPort + SBus + GPS + LED Strip + Battery Monitoring + 8 motors - all at the same time!
* 8 PWM output lines for ESCs and Servos. Arranged for easy wiring on standard pin headers.
* Supports direct connection of SBus, SumH, SumD, Spektrum1024/2048, XBus receivers. No external inverters required (built-in).
* Supports direct connection of 3.3v Spektrum Satellite receivers via 3 pin through-hole JST-ZH connector.
* Dedicated PPM receiver input.
* 3 Serial Ports - NOT shared with the USB socket.
* Telemetry port
* Micro USB socket.
* Dedicated output for programmable LEDs - great for orientation, racing and night flying. (Currently mutually exclusive with the Transponder).
* Dedicated I2C port for connection of OLED display without needing flight battery.
* Battery monitoring for voltage and current.
* RSSI monitoring (analogue or PWM).
* Buzzer port for audible warnings and notifications.
* Developer friendly debugging port (SWD) and boot mode selection, unbrickable bootloader.
* Symmetrical design for a super tidy wiring.
* JST-SH sockets only for I2C, UART2 and SWD. UART2 also on through-hole pins.
* Flashing via USB or serial port.
* Stackable design - perfect for integrating with OSDs and power distribution boards.
* Standard mounting - 36x36mm with standard 30.5mm mounting holes.
* LEDs for 3v, 5v and Status for easy diagnostics.
* Copper-etched Cleanflight logo.
## Serial Ports
| Value | Identifier | RX | TX | 5v Tolerant | Notes |
| ----- | ------------ | ------------ | ------------ | ----------- | ------------------------------------------------------------------------------------------- |
| 1 | USART1 | PA10 | PA9 | YES | 2 through-hole pins. Use for connecting to OSD/GPS/BlueTooth. |
| 2 | USART2 | PA15 | PA14 / SWCLK | YES | JST socket and PPM header. Use to connect to RX. |
| 3 | USART3 | PB11 / AF7 | PB10 / AF7 | NO | Available on 4 through-hole pins. 3.3V signals only ! Use for GPS, Spektrum Satellite RX, SmartPort Telemetry, HoTT telemetry, etc. |
* You cannot use SWD and USART2 at the same time.
* When using a Serial RX receiver the TXD (T2) pin cannot be used for telemetry. Use UART3 TXD instead.
* One Software serial is supported in th SPRacingF3EVO_1SS version, see table below
* Windows DFU Flashing requires Zadig (see configurator)
### SoftSerial
| Pin | Function | Notes |
| --- | -------------- | -------------------------------- |
| 7 | SOFTSERIAL1 RX | SoftSerial disables Servo 5,6 |
| 8 | SOFTSERIAL1 TX | |
## Pinouts
Full pinout details are available in the manual, here:
http://seriouslypro.com/files/SPRacingF3EVO-Manual-latest.pdf
### IO_1
The 6 pin IO_1 connector has the following pinouts when used in RX_SERIAL mode.
| Pin | Function | Notes |
| --- | -------------- | -------------------------------------------- |
| 1 | Ground | |
| 2 | VCC_IN | Voltage as-supplied by BEC. |
| 3 | RX_SERIAL | Enable `feature RX_SERIAL` |
| 4 | | |
| 5 | +V BATTERY | Voltage as-supplied by Battery. |
| 6 | -V BATTERY | Voltage as-supplied by Battery. |
When RX_PPM is used the IO_1 pinout is as follows.
| Pin | Function | Notes |
| --- | -------------- | -------------------------------------------- |
| 1 | Ground | |
| 2 | VCC_IN | Voltage as-supplied by BEC. |
| 3 | RX_PPM | Enable `feature RX_PPM` |
| 4 | TELEMETRY | Enable `feature TELEMETRY` |
| 5 | +V BATTERY | Voltage as-supplied by Battery. |
| 6 | -V BATTERY | Voltage as-supplied by Battery. |
### IO_2
When TRANSPONDER is used and the IR solder pads are shorted, the 6 pin IO_2 pinout is as follows.
| Pin | Function | Notes |
| --- | ------------------------- | -------------------------------------------- |
| 1 | IR- | Short leg of the IR LED |
| 2 | IR+ | Long leg of the IR LED |
| 3 | CURRENT | Current Sensor |
| 4 | RSSI | RSSI (PWM or Analog - select by solder pads) |
| 5 | BUZZER+ | 5V Source |
| 6 | BUZZER- | Buzzer signal |
When LEDSTRIP is used and the LED solder pads are shorted, the 6 pin IO_2 pinout is as follows.
| Pin | Function | Notes |
| --- | ------------------------- | -------------------------------------------- |
| 1 | | |
| 2 | LEDSTRIP | WS2812 Ledstrip data |
| 3 | CURRENT | Current Sensor |
| 4 | RSSI | RSSI (PWM or Analog - select by solder pads) |
| 5 | BUZZER+ | 5V Source |
| 6 | BUZZER- | Buzzer signal |
### UART1
| Pin | Function | Notes |
| --- | -------------- | -------------------------------------------- |
| 3 | TXD | |
| 4 | RXD | |
### UART2/3
| Pin | Function | Notes |
| --- | -------------- | -------------------------------------------- |
| 1 | Ground | |
| 2 | VCC_IN | Voltage as-supplied by BEC. |
| 3 | TXD | |
| 4 | RXD | |
### Spektrum Satellite
| Pin | Function | Notes |
| --- | -------------- | -------------------------------------------- |
| 3 | 3.3V | |
| 2 | Ground | |
| 1 | RXD | |
### I2C
| Pin | Function | Notes |
| --- | -------------- | -------------------------------------------- |
| 1 | Ground | |
| 2 | 5.0v | Voltage as-supplied by BEC OR USB, always on |
| 3 | SCL | 3.3V signals only |
| 4 | SDA | 3.3V signals only |
### SWD
The port cannot be used at the same time as UART2.
| Pin | Function | Notes |
| --- | -------------- | -------------------------------------------- |
| 1 | Ground | |
| 2 | NRST | |
| 3 | SWDIO | |
| 4 | SWDCLK | |

View file

@ -1,207 +0,0 @@
# Board - Sparky
The Sparky is a very low cost and very powerful board.
* 3 hardware serial ports.
* Built-in serial port inverters which allows S.BUS receivers to be used without external inverters.
* USB (can be used at the same time as the serial ports).
* 10 PWM outputs.
* Dedicated PPM/SerialRX input pin.
* MPU9150 I2C Acc/Gyro/Mag
* Baro
Tested with revision 1 & 2 boards.
## TODO
* Rangefinder
* Display (via Flex port)
* SoftSerial - though having 3 hardware serial ports makes it a little redundant.
* Airplane PWM mappings.
# Voltage and current monitoring (ADC support)
Voltage monitoring is possible when enabled via PWM9 pin and current can be monitored via PWM8 pin. The voltage divider and current sensor need to be connected externally. The vbatscale cli parameter need to be adjusted to fit the sensor specification. For more details regarding the sensor hardware you can check here: https://github.com/TauLabs/TauLabs/wiki/User-Guide:-Battery-Configuration
# Flashing
## Via Device Firmware Upload (DFU, USB) - Windows
These instructions are for flashing the Sparky board under Windows using DfuSE.
Credits go to Thomas Shue (Full video of the below steps can be found here: https://www.youtube.com/watch?v=I4yHiRVRY94)
Required Software:
DfuSE Version 3.0.2 (latest version 3.0.4 causes errors): http://code.google.com/p/multipilot32/downloads/detail?name=DfuSe.rar
STM VCP Driver 1.4.0: http://www.st.com/web/en/catalog/tools/PF257938
A binary file is required for DFU, not a .hex file. If one is not included in the release then build one as follows.
```
Unpack DfuSE and the STM VCP Drivers into a folder on your Hardrive
Download the latest Sparky release (inav_SPARKY.hex) from:
https://github.com/iNavFlight/inav/releases and store it on your Hardrive
In your DfuSE folder go to BIN and start DfuFileMgr.exe
Select: "I want to GENERATE a DFUfile from S19,HEX or BIN files" press OK
Press: "S19 or Hex.."
Go to the folder where you saved the inav_SPARKY.hex file, select it and press open
(you might need to change the filetype in the DfuSE explorer window to "hex Files (*.hex)" to be able to see the file)
Press: "Generate" and select the .dfu output file and location
If all worked well you should see " Success for 'Image for lternate Setting 00 (ST..)'!"
```
Put the device into DFU mode by powering on the sparky with the bootloader pins temporarily bridged. The only light that should come on is the blue PWR led.
Check the windows device manager to make sure the board is recognized correctly.
It should show up as "STM Device in DFU mode" under Universal Serial Bus Controllers
If it shows up as "STMicroelectronics Virtual COM" under Ports (COM & LPT) instead then the board is not in DFU mode. Disconnect the board, short the bootloader pins again while connecting the board.
If the board shows up as "STM 32 Bootloader" device in the device manager, the drivers need to be updated manually.
Select the device in the device manager, press "update drivers", select "manual update drivers" and choose the location where you extracted the STM VCP Drivers, select "let me choose which driver to install". You shoud now be able to select either the STM32 Bootloader driver or the STM in DFU mode driver. Select the later and install.
Then flash the binary as below.
```
In your DfuSE folder go to BIN and start DfuSeDemo.exe
Select the Sparky Board (STM in DFU Mode) from the Available DFU and compatible HID Devices drop down list
Press "Choose.." at the bootom of the window and select the .dfu file created in the previous step
"File correctly loaded" should appear in the status bar
Press "Upgrade" and confirm with "Yes"
The status bar will show the upload progress and confirm that the upload is complete at the end
```
Disconnect and reconnect the board from USB and continue to configure it via the INAV configurator as per normal
## Via Device Firmware Upload (DFU, USB) - Mac OS X / Linux
These instructions are for dfu-util, tested using dfu-util 0.7 for OSX from the OpenTX project.
http://www.open-tx.org/2013/07/15/dfu-util-07-for-mac-taranis-flashing-utility/
A binary file is required for DFU, not a .hex file. If one is not included in the release then build one as follows.
```
make TARGET=SPARKY clean
make TARGET=SPARKY binary
```
Put the device into DFU mode by powering on the sparky with the bootloader pins temporarily bridged. The only light that should come on is the blue PWR led.
Run 'dfu-util -l' to make sure the device is listed, as below.
```
$ dfu-util -l
dfu-util 0.7
Copyright 2005-2008 Weston Schmidt, Harald Welte and OpenMoko Inc.
Copyright 2010-2012 Tormod Volden and Stefan Schmidt
This program is Free Software and has ABSOLUTELY NO WARRANTY
Please report bugs to dfu-util@lists.gnumonks.org
Found DFU: [0483:df11] devnum=0, cfg=1, intf=0, alt=0, name="@Internal Flash /0x08000000/128*0002Kg"
Found DFU: [0483:df11] devnum=0, cfg=1, intf=0, alt=1, name="@Option Bytes /0x1FFFF800/01*016 e"
```
Then flash the binary as below.
```
dfu-util -D obj/inav_SPARKY.bin --alt 0 -R -s 0x08000000
```
The output should be similar to this:
```
dfu-util 0.7
Copyright 2005-2008 Weston Schmidt, Harald Welte and OpenMoko Inc.
Copyright 2010-2012 Tormod Volden and Stefan Schmidt
This program is Free Software and has ABSOLUTELY NO WARRANTY
Please report bugs to dfu-util@lists.gnumonks.org
Opening DFU capable USB device... ID 0483:df11
Run-time device DFU version 011a
Found DFU: [0483:df11] devnum=0, cfg=1, intf=0, alt=0, name="@Internal Flash /0x08000000/128*0002Kg"
Claiming USB DFU Interface...
Setting Alternate Setting #0 ...
Determining device status: state = dfuERROR, status = 10
dfuERROR, clearing status
Determining device status: state = dfuIDLE, status = 0
dfuIDLE, continuing
DFU mode device DFU version 011a
Device returned transfer size 2048
No valid DFU suffix signature
Warning: File has no DFU suffix
DfuSe interface name: "Internal Flash "
Downloading to address = 0x08000000, size = 76764
......................................
File downloaded successfully
can't detach
Resetting USB to switch back to runtime mode
```
On Linux you might want to take care that the modemmanager isn't trying to use your sparky as modem getting it into bootloader mode while doing so. In doubt you probably want to uninstall it. It could also be good idea to get udev fixed. It looks like teensy did just that -> http://www.pjrc.com/teensy/49-teensy.rules (untested)
To make a full chip erase you can use a file created by
```
dd if=/dev/zero of=zero.bin bs=1 count=262144
```
This can be used by dfu-util.
## Via SWD
On the bottom of the board there is an SWD header socket onto switch a JST-SH connector can be soldered.
Once you have SWD connected you can use the st-link or j-link tools to flash a binary.
See Sparky schematic for CONN2 pinouts.
## TauLabs bootloader
Flashing INAV will erase the TauLabs bootloader, this is not a problem and can easily be restored using the st flashloader tool.
# Serial Ports
| Value | Identifier | RX | TX | Notes |
| ----- | ------------ | --------- | ---------- | -------------------------------------------------------------- |
| 1 | USB VCP | RX (USB) | TX (USB) | |
| 2 | USART1 | RX / PB7 | TX / PB6 | Conn1 / Flexi Port. |
| 3 | USART2 | RX / PA3 | PWM6 / PA2 | On RX is on INPUT header. Best port for Serial RX input |
| 4 | USART3 | RX / PB11 | TX / PB10 | RX/TX is on one end of the 6-pin header about the PWM outputs. |
USB VCP *can* be used at the same time as other serial port.
All USART ports all support automatic hardware inversion which allows direct connection of serial rx receivers like the FrSky X4RSB - no external inverter needed.
# Battery Monitoring Connections
| Pin | Signal | Function |
| ---- | ------ | --------------- |
| PWM9 | PA4 | Battery Voltage |
| PWM8 | PA7 | Current Meter |
## Voltage Monitoring
The Sparky has no battery divider cricuit, PWM9 has an inline 10k resistor which has to be factored into the resistor calculations.
The divider circuit should eventally create a voltage between 0v and 3.3v (MAX) at the MCU input pin.
WARNING: Double check the output of your voltage divider using a voltmeter *before* connecting to the FC.
### Example Circuit
For a 3Cell battery divider the following circuit works:
`Battery (+) ---< R1 >--- PWM9 ---< R2 >--- Battery (-)`
* R1 = 8k2 (Grey Red Red)
* R2 = 2k0 (Red Black Red)
This gives a 2.2k for an 11.2v battery. The `vbat_scale` for this divider should be set around `52`.
## Current Monitoring
Connect a current sensor to PWM8/PA7 that gives a range between 0v and 3.3v out (MAX).

View file

@ -73,6 +73,7 @@ IPF can be edited using INAV Configurator user interface, of via CLI
| 37 | MAP_OUTPUT | Scales `Operand A` from [`0` : `1000`] to [`0` : `Operand B`]. Note: input will be constrained and then scaled |
| 38 | RC_CHANNEL_OVERRIDE | Overrides channel set by `Operand A` to value of `Operand B` |
| 39 | SET_HEADING_TARGET | Sets heading-hold target to `Operand A`, in degrees. Value wraps-around. |
| 40 | MOD | Divide `Operand A` by `Operand B` and returns the remainder |
### Operands
@ -124,7 +125,8 @@ IPF can be edited using INAV Configurator user interface, of via CLI
| 30 | ACTIVE_WAYPOINT_ACTION | See ACTIVE_WAYPOINT_ACTION paragraph |
| 31 | 3D HOME_DISTANCE | in `meters`, calculated from HOME_DISTANCE and ALTITUDE using Pythagorean theorem |
| 32 | CROSSFIRE LQ | Crossfire Link quality as returned by the CRSF protocol |
| 33 | CROSSFIRE SNR | Crossfire SNR as returned by the CRSF protocol |
| 33 | CROSSFIRE SNR | Crossfire SNR as returned by the CRSF protocol |
| 34 | GPS_VALID | boolean `0`/`1`. True when the GPS has a valid 3D Fix |
#### ACTIVE_WAYPOINT_ACTION
@ -260,4 +262,4 @@ Steps:
1. Normalize range [1000:2000] to [0:1000] by substracting `1000`
2. Scale range [0:1000] to [0:3]
3. Increase range by `1` to have the range of [1:4]
4. Assign LC#2 to VTX power function
4. Assign LC#2 to VTX power function

View file

@ -12,14 +12,20 @@ One potential risk when landing is that there might be buildings, trees and othe
## Safehome
Safehomes are a list of GPS coordinates that identify safe landing points. When the flight controller is armed, it checks the list of safehomes. The nearest safehome that is enabled and within ```safehome_max_distance``` (default 200m) of the current position will be selected. Otherwise, it reverts to the old behaviour of using your current GPS position as home.
Safehomes are a list of GPS coordinates that identify safe landing points. You can define up to 8 safehomes for different locations you fly at. When the flight controller is armed, it checks the list of safehomes. The nearest safehome that is enabled and within ```safehome_max_distance``` (default 200m) of the current position is identified. The arming home location remains as home.
Be aware that the safehome replaces your arming position as home. When flying, RTH will return to the safehome and OSD elements such as distance to home and direction to home will refer to the selected safehome.
When RTH is activated, whether by radio failsafe, or using the RTH radio control mode, the safehome identified during arming will replace the home location. If RTH is turned off, either by regaining radio control or turning off the RTH radio control mode, the home location will return back to arming point.
You can define up to 8 safehomes for different locations you fly at.
The safehome operating mode is set using ```safehome_usage_mode```. If ```OFF```, safehomes will not be used. If ```RTH```, the safehome will replace the arming location when RTH is activated, either manually or because of RX failsafe. If ```RTH_FS```, the safehome will only be used for RX failsafe. This option can be changed using the OSD menu.
If you frequently use RTH to return back to the arming point, you may not want the aircraft to fly to the safehome. Let it do this at least once to confirm safehomes is working as expected. Afterward, `set safehome_usage_mode = RTH_FS` and the safehome will only be used for failsafe.
When using mode `RTH_FS`, you should confirm that your radio's failsafe configuration triggers the iNav failsafe mode. With many receivers, you have the ability to specify what signal to output during failsafe conditions.
When you are choosing safehome locations, ensure that the location is clear of obstructions for a radius more than 50m (`nav_fw_loiter_radius`). As the plane descends, the circles aren't always symmetrical, as wind direction could result in some wider or tighter turns. Also, the direction and length of the final landing stage is also unknown. You want to choose a point that has provides a margin for variation and the final landing.
If your safehome is not visible from your current location, use extra caution. A visual check of the safehome is recommend prior to flying. If the safehome is in use, you can use the OSD menu to disable safehome usage prior to your flight.
## OSD Message when Armed
When the aircraft is armed, the OSD briefly shows `ARMED` and the current GPS position and current date and time.
@ -36,8 +42,14 @@ If a safehome is selected, an additional message appears:
CURRENT DATE
CURRENT TIME
```
The GPS details are those of the selected safehome.
To draw your attention to "HOME" being replaced, the message flashes and stays visible longer.
The GPS details are those of the arming location, not the safehome.
To draw your attention to a safehome being selected, the message flashes and stays visible longer.
If a safehome was found, but ``safehome_usage_mode``` is ```OFF```, the message ```SAFEHOME FOUND; MODE OFF``` will appear.
## OSD Message during RTH
If RTH is in progress to a safehome, the message "DIVERTING TO SAFEHOME" will be displayed.
## CLI command `safehome` to manage safehomes

File diff suppressed because it is too large Load diff

Binary file not shown.

Before

Width:  |  Height:  |  Size: 696 KiB

After

Width:  |  Height:  |  Size: 1,012 KiB

Before After
Before After

Binary file not shown.

After

Width:  |  Height:  |  Size: 696 KiB

1
lib/main/MAVLink/.gitignore vendored Normal file
View file

@ -0,0 +1 @@
mavlink-src/

View file

@ -0,0 +1,13 @@
# MAVLink Generator (`mavgen`)
This directory contains the MAVLink library and scripts to automatically generate it from MAVLink definitions.
In order to run it, you will need [Python and some other libraries installed](https://mavlink.io/en/getting_started/installation.html).
Then, run the appropriate script (`generate.sh` for Linux, `generate.bat` for Windows) to automatically re-generate the library.
## IMPORTANT NOTE
By default, the MAVLink library declares all of its functions as `inline`, which results in common functions being duplicated many times.
After generating the library, `protocol.h` must be modified, and all `inline` keywords removed.
This is performed automatically by `generate.sh`, but not by `generate.bat` as Windows batch files do not have an equivalent to `sed`. So, this must be done manually on Windows.

View file

@ -1,10 +1,11 @@
#ifdef __cplusplus
#pragma once
#if defined(MAVLINK_USE_CXX_NAMESPACE)
namespace mavlink {
#elif defined(__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"
@ -23,7 +24,7 @@ extern "C" {
#ifndef HAVE_CRC_ACCUMULATE
/**
* @brief Accumulate the X.25 CRC by adding one char at a time.
* @brief Accumulate the CRC16_MCRF4XX checksum 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).
@ -44,9 +45,9 @@ static inline void crc_accumulate(uint8_t data, uint16_t *crcAccum)
/**
* @brief Initiliaze the buffer for the X.25 CRC
* @brief Initiliaze the buffer for the MCRF4XX CRC16
*
* @param crcAccum the 16 bit X.25 CRC
* @param crcAccum the 16 bit MCRF4XX CRC16
*/
static inline void crc_init(uint16_t* crcAccum)
{
@ -55,7 +56,7 @@ static inline void crc_init(uint16_t* crcAccum)
/**
* @brief Calculates the X.25 checksum on a byte buffer
* @brief Calculates the CRC16_MCRF4XX checksum on a byte buffer
*
* @param pBuffer buffer containing the byte array to hash
* @param length length of the byte array
@ -73,7 +74,7 @@ static inline uint16_t crc_calculate(const uint8_t* pBuffer, uint16_t length)
/**
* @brief Accumulate the X.25 CRC by adding an array of bytes
* @brief Accumulate the MCRF4XX CRC16 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).
@ -89,8 +90,6 @@ static inline void crc_accumulate_buffer(uint16_t *crcAccum, const char *pBuffer
}
}
#endif /* _CHECKSUM_H_ */
#ifdef __cplusplus
#if defined(MAVLINK_USE_CXX_NAMESPACE) || defined(__cplusplus)
}
#endif

File diff suppressed because one or more lines are too long

View file

@ -9,7 +9,7 @@
#define MAVLINK_PRIMARY_XML_IDX 0
#ifndef MAVLINK_STX
#define MAVLINK_STX 254
#define MAVLINK_STX 253
#endif
#ifndef MAVLINK_ENDIAN
@ -25,7 +25,7 @@
#endif
#ifndef MAVLINK_COMMAND_24BIT
#define MAVLINK_COMMAND_24BIT 0
#define MAVLINK_COMMAND_24BIT 1
#endif
#include "version.h"

View file

@ -0,0 +1,255 @@
#pragma once
// MESSAGE ACTUATOR_OUTPUT_STATUS PACKING
#define MAVLINK_MSG_ID_ACTUATOR_OUTPUT_STATUS 375
typedef struct __mavlink_actuator_output_status_t {
uint64_t time_usec; /*< [us] Timestamp (since system boot).*/
uint32_t active; /*< Active outputs*/
float actuator[32]; /*< Servo / motor output array values. Zero values indicate unused channels.*/
} mavlink_actuator_output_status_t;
#define MAVLINK_MSG_ID_ACTUATOR_OUTPUT_STATUS_LEN 140
#define MAVLINK_MSG_ID_ACTUATOR_OUTPUT_STATUS_MIN_LEN 140
#define MAVLINK_MSG_ID_375_LEN 140
#define MAVLINK_MSG_ID_375_MIN_LEN 140
#define MAVLINK_MSG_ID_ACTUATOR_OUTPUT_STATUS_CRC 251
#define MAVLINK_MSG_ID_375_CRC 251
#define MAVLINK_MSG_ACTUATOR_OUTPUT_STATUS_FIELD_ACTUATOR_LEN 32
#if MAVLINK_COMMAND_24BIT
#define MAVLINK_MESSAGE_INFO_ACTUATOR_OUTPUT_STATUS { \
375, \
"ACTUATOR_OUTPUT_STATUS", \
3, \
{ { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_actuator_output_status_t, time_usec) }, \
{ "active", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_actuator_output_status_t, active) }, \
{ "actuator", NULL, MAVLINK_TYPE_FLOAT, 32, 12, offsetof(mavlink_actuator_output_status_t, actuator) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_ACTUATOR_OUTPUT_STATUS { \
"ACTUATOR_OUTPUT_STATUS", \
3, \
{ { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_actuator_output_status_t, time_usec) }, \
{ "active", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_actuator_output_status_t, active) }, \
{ "actuator", NULL, MAVLINK_TYPE_FLOAT, 32, 12, offsetof(mavlink_actuator_output_status_t, actuator) }, \
} \
}
#endif
/**
* @brief Pack a actuator_output_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 time_usec [us] Timestamp (since system boot).
* @param active Active outputs
* @param actuator Servo / motor output array values. Zero values indicate unused channels.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_actuator_output_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint64_t time_usec, uint32_t active, const float *actuator)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_ACTUATOR_OUTPUT_STATUS_LEN];
_mav_put_uint64_t(buf, 0, time_usec);
_mav_put_uint32_t(buf, 8, active);
_mav_put_float_array(buf, 12, actuator, 32);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ACTUATOR_OUTPUT_STATUS_LEN);
#else
mavlink_actuator_output_status_t packet;
packet.time_usec = time_usec;
packet.active = active;
mav_array_memcpy(packet.actuator, actuator, sizeof(float)*32);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ACTUATOR_OUTPUT_STATUS_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_ACTUATOR_OUTPUT_STATUS;
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ACTUATOR_OUTPUT_STATUS_MIN_LEN, MAVLINK_MSG_ID_ACTUATOR_OUTPUT_STATUS_LEN, MAVLINK_MSG_ID_ACTUATOR_OUTPUT_STATUS_CRC);
}
/**
* @brief Pack a actuator_output_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 time_usec [us] Timestamp (since system boot).
* @param active Active outputs
* @param actuator Servo / motor output array values. Zero values indicate unused channels.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_actuator_output_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint64_t time_usec,uint32_t active,const float *actuator)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_ACTUATOR_OUTPUT_STATUS_LEN];
_mav_put_uint64_t(buf, 0, time_usec);
_mav_put_uint32_t(buf, 8, active);
_mav_put_float_array(buf, 12, actuator, 32);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ACTUATOR_OUTPUT_STATUS_LEN);
#else
mavlink_actuator_output_status_t packet;
packet.time_usec = time_usec;
packet.active = active;
mav_array_memcpy(packet.actuator, actuator, sizeof(float)*32);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ACTUATOR_OUTPUT_STATUS_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_ACTUATOR_OUTPUT_STATUS;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ACTUATOR_OUTPUT_STATUS_MIN_LEN, MAVLINK_MSG_ID_ACTUATOR_OUTPUT_STATUS_LEN, MAVLINK_MSG_ID_ACTUATOR_OUTPUT_STATUS_CRC);
}
/**
* @brief Encode a actuator_output_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 actuator_output_status C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_actuator_output_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_actuator_output_status_t* actuator_output_status)
{
return mavlink_msg_actuator_output_status_pack(system_id, component_id, msg, actuator_output_status->time_usec, actuator_output_status->active, actuator_output_status->actuator);
}
/**
* @brief Encode a actuator_output_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 actuator_output_status C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_actuator_output_status_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_actuator_output_status_t* actuator_output_status)
{
return mavlink_msg_actuator_output_status_pack_chan(system_id, component_id, chan, msg, actuator_output_status->time_usec, actuator_output_status->active, actuator_output_status->actuator);
}
/**
* @brief Send a actuator_output_status message
* @param chan MAVLink channel to send the message
*
* @param time_usec [us] Timestamp (since system boot).
* @param active Active outputs
* @param actuator Servo / motor output array values. Zero values indicate unused channels.
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_actuator_output_status_send(mavlink_channel_t chan, uint64_t time_usec, uint32_t active, const float *actuator)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_ACTUATOR_OUTPUT_STATUS_LEN];
_mav_put_uint64_t(buf, 0, time_usec);
_mav_put_uint32_t(buf, 8, active);
_mav_put_float_array(buf, 12, actuator, 32);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ACTUATOR_OUTPUT_STATUS, buf, MAVLINK_MSG_ID_ACTUATOR_OUTPUT_STATUS_MIN_LEN, MAVLINK_MSG_ID_ACTUATOR_OUTPUT_STATUS_LEN, MAVLINK_MSG_ID_ACTUATOR_OUTPUT_STATUS_CRC);
#else
mavlink_actuator_output_status_t packet;
packet.time_usec = time_usec;
packet.active = active;
mav_array_memcpy(packet.actuator, actuator, sizeof(float)*32);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ACTUATOR_OUTPUT_STATUS, (const char *)&packet, MAVLINK_MSG_ID_ACTUATOR_OUTPUT_STATUS_MIN_LEN, MAVLINK_MSG_ID_ACTUATOR_OUTPUT_STATUS_LEN, MAVLINK_MSG_ID_ACTUATOR_OUTPUT_STATUS_CRC);
#endif
}
/**
* @brief Send a actuator_output_status message
* @param chan MAVLink channel to send the message
* @param struct The MAVLink struct to serialize
*/
static inline void mavlink_msg_actuator_output_status_send_struct(mavlink_channel_t chan, const mavlink_actuator_output_status_t* actuator_output_status)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mavlink_msg_actuator_output_status_send(chan, actuator_output_status->time_usec, actuator_output_status->active, actuator_output_status->actuator);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ACTUATOR_OUTPUT_STATUS, (const char *)actuator_output_status, MAVLINK_MSG_ID_ACTUATOR_OUTPUT_STATUS_MIN_LEN, MAVLINK_MSG_ID_ACTUATOR_OUTPUT_STATUS_LEN, MAVLINK_MSG_ID_ACTUATOR_OUTPUT_STATUS_CRC);
#endif
}
#if MAVLINK_MSG_ID_ACTUATOR_OUTPUT_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_actuator_output_status_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, uint32_t active, const float *actuator)
{
#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, active);
_mav_put_float_array(buf, 12, actuator, 32);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ACTUATOR_OUTPUT_STATUS, buf, MAVLINK_MSG_ID_ACTUATOR_OUTPUT_STATUS_MIN_LEN, MAVLINK_MSG_ID_ACTUATOR_OUTPUT_STATUS_LEN, MAVLINK_MSG_ID_ACTUATOR_OUTPUT_STATUS_CRC);
#else
mavlink_actuator_output_status_t *packet = (mavlink_actuator_output_status_t *)msgbuf;
packet->time_usec = time_usec;
packet->active = active;
mav_array_memcpy(packet->actuator, actuator, sizeof(float)*32);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ACTUATOR_OUTPUT_STATUS, (const char *)packet, MAVLINK_MSG_ID_ACTUATOR_OUTPUT_STATUS_MIN_LEN, MAVLINK_MSG_ID_ACTUATOR_OUTPUT_STATUS_LEN, MAVLINK_MSG_ID_ACTUATOR_OUTPUT_STATUS_CRC);
#endif
}
#endif
#endif
// MESSAGE ACTUATOR_OUTPUT_STATUS UNPACKING
/**
* @brief Get field time_usec from actuator_output_status message
*
* @return [us] Timestamp (since system boot).
*/
static inline uint64_t mavlink_msg_actuator_output_status_get_time_usec(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint64_t(msg, 0);
}
/**
* @brief Get field active from actuator_output_status message
*
* @return Active outputs
*/
static inline uint32_t mavlink_msg_actuator_output_status_get_active(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint32_t(msg, 8);
}
/**
* @brief Get field actuator from actuator_output_status message
*
* @return Servo / motor output array values. Zero values indicate unused channels.
*/
static inline uint16_t mavlink_msg_actuator_output_status_get_actuator(const mavlink_message_t* msg, float *actuator)
{
return _MAV_RETURN_float_array(msg, actuator, 32, 12);
}
/**
* @brief Decode a actuator_output_status message into a struct
*
* @param msg The message to decode
* @param actuator_output_status C-struct to decode the message contents into
*/
static inline void mavlink_msg_actuator_output_status_decode(const mavlink_message_t* msg, mavlink_actuator_output_status_t* actuator_output_status)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
actuator_output_status->time_usec = mavlink_msg_actuator_output_status_get_time_usec(msg);
actuator_output_status->active = mavlink_msg_actuator_output_status_get_active(msg);
mavlink_msg_actuator_output_status_get_actuator(msg, actuator_output_status->actuator);
#else
uint8_t len = msg->len < MAVLINK_MSG_ID_ACTUATOR_OUTPUT_STATUS_LEN? msg->len : MAVLINK_MSG_ID_ACTUATOR_OUTPUT_STATUS_LEN;
memset(actuator_output_status, 0, MAVLINK_MSG_ID_ACTUATOR_OUTPUT_STATUS_LEN);
memcpy(actuator_output_status, _MAV_PAYLOAD(msg), len);
#endif
}

View file

@ -0,0 +1,606 @@
#pragma once
// MESSAGE AIS_VESSEL PACKING
#define MAVLINK_MSG_ID_AIS_VESSEL 301
typedef struct __mavlink_ais_vessel_t {
uint32_t MMSI; /*< Mobile Marine Service Identifier, 9 decimal digits*/
int32_t lat; /*< [degE7] Latitude*/
int32_t lon; /*< [degE7] Longitude*/
uint16_t COG; /*< [cdeg] Course over ground*/
uint16_t heading; /*< [cdeg] True heading*/
uint16_t velocity; /*< [cm/s] Speed over ground*/
uint16_t dimension_bow; /*< [m] Distance from lat/lon location to bow*/
uint16_t dimension_stern; /*< [m] Distance from lat/lon location to stern*/
uint16_t tslc; /*< [s] Time since last communication in seconds*/
uint16_t flags; /*< Bitmask to indicate various statuses including valid data fields*/
int8_t turn_rate; /*< [cdeg/s] Turn rate*/
uint8_t navigational_status; /*< Navigational status*/
uint8_t type; /*< Type of vessels*/
uint8_t dimension_port; /*< [m] Distance from lat/lon location to port side*/
uint8_t dimension_starboard; /*< [m] Distance from lat/lon location to starboard side*/
char callsign[7]; /*< The vessel callsign*/
char name[20]; /*< The vessel name*/
} mavlink_ais_vessel_t;
#define MAVLINK_MSG_ID_AIS_VESSEL_LEN 58
#define MAVLINK_MSG_ID_AIS_VESSEL_MIN_LEN 58
#define MAVLINK_MSG_ID_301_LEN 58
#define MAVLINK_MSG_ID_301_MIN_LEN 58
#define MAVLINK_MSG_ID_AIS_VESSEL_CRC 243
#define MAVLINK_MSG_ID_301_CRC 243
#define MAVLINK_MSG_AIS_VESSEL_FIELD_CALLSIGN_LEN 7
#define MAVLINK_MSG_AIS_VESSEL_FIELD_NAME_LEN 20
#if MAVLINK_COMMAND_24BIT
#define MAVLINK_MESSAGE_INFO_AIS_VESSEL { \
301, \
"AIS_VESSEL", \
17, \
{ { "MMSI", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_ais_vessel_t, MMSI) }, \
{ "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_ais_vessel_t, lat) }, \
{ "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_ais_vessel_t, lon) }, \
{ "COG", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_ais_vessel_t, COG) }, \
{ "heading", NULL, MAVLINK_TYPE_UINT16_T, 0, 14, offsetof(mavlink_ais_vessel_t, heading) }, \
{ "velocity", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_ais_vessel_t, velocity) }, \
{ "turn_rate", NULL, MAVLINK_TYPE_INT8_T, 0, 26, offsetof(mavlink_ais_vessel_t, turn_rate) }, \
{ "navigational_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 27, offsetof(mavlink_ais_vessel_t, navigational_status) }, \
{ "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 28, offsetof(mavlink_ais_vessel_t, type) }, \
{ "dimension_bow", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_ais_vessel_t, dimension_bow) }, \
{ "dimension_stern", NULL, MAVLINK_TYPE_UINT16_T, 0, 20, offsetof(mavlink_ais_vessel_t, dimension_stern) }, \
{ "dimension_port", NULL, MAVLINK_TYPE_UINT8_T, 0, 29, offsetof(mavlink_ais_vessel_t, dimension_port) }, \
{ "dimension_starboard", NULL, MAVLINK_TYPE_UINT8_T, 0, 30, offsetof(mavlink_ais_vessel_t, dimension_starboard) }, \
{ "callsign", NULL, MAVLINK_TYPE_CHAR, 7, 31, offsetof(mavlink_ais_vessel_t, callsign) }, \
{ "name", NULL, MAVLINK_TYPE_CHAR, 20, 38, offsetof(mavlink_ais_vessel_t, name) }, \
{ "tslc", NULL, MAVLINK_TYPE_UINT16_T, 0, 22, offsetof(mavlink_ais_vessel_t, tslc) }, \
{ "flags", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_ais_vessel_t, flags) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_AIS_VESSEL { \
"AIS_VESSEL", \
17, \
{ { "MMSI", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_ais_vessel_t, MMSI) }, \
{ "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_ais_vessel_t, lat) }, \
{ "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_ais_vessel_t, lon) }, \
{ "COG", NULL, MAVLINK_TYPE_UINT16_T, 0, 12, offsetof(mavlink_ais_vessel_t, COG) }, \
{ "heading", NULL, MAVLINK_TYPE_UINT16_T, 0, 14, offsetof(mavlink_ais_vessel_t, heading) }, \
{ "velocity", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_ais_vessel_t, velocity) }, \
{ "turn_rate", NULL, MAVLINK_TYPE_INT8_T, 0, 26, offsetof(mavlink_ais_vessel_t, turn_rate) }, \
{ "navigational_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 27, offsetof(mavlink_ais_vessel_t, navigational_status) }, \
{ "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 28, offsetof(mavlink_ais_vessel_t, type) }, \
{ "dimension_bow", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_ais_vessel_t, dimension_bow) }, \
{ "dimension_stern", NULL, MAVLINK_TYPE_UINT16_T, 0, 20, offsetof(mavlink_ais_vessel_t, dimension_stern) }, \
{ "dimension_port", NULL, MAVLINK_TYPE_UINT8_T, 0, 29, offsetof(mavlink_ais_vessel_t, dimension_port) }, \
{ "dimension_starboard", NULL, MAVLINK_TYPE_UINT8_T, 0, 30, offsetof(mavlink_ais_vessel_t, dimension_starboard) }, \
{ "callsign", NULL, MAVLINK_TYPE_CHAR, 7, 31, offsetof(mavlink_ais_vessel_t, callsign) }, \
{ "name", NULL, MAVLINK_TYPE_CHAR, 20, 38, offsetof(mavlink_ais_vessel_t, name) }, \
{ "tslc", NULL, MAVLINK_TYPE_UINT16_T, 0, 22, offsetof(mavlink_ais_vessel_t, tslc) }, \
{ "flags", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_ais_vessel_t, flags) }, \
} \
}
#endif
/**
* @brief Pack a ais_vessel message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param MMSI Mobile Marine Service Identifier, 9 decimal digits
* @param lat [degE7] Latitude
* @param lon [degE7] Longitude
* @param COG [cdeg] Course over ground
* @param heading [cdeg] True heading
* @param velocity [cm/s] Speed over ground
* @param turn_rate [cdeg/s] Turn rate
* @param navigational_status Navigational status
* @param type Type of vessels
* @param dimension_bow [m] Distance from lat/lon location to bow
* @param dimension_stern [m] Distance from lat/lon location to stern
* @param dimension_port [m] Distance from lat/lon location to port side
* @param dimension_starboard [m] Distance from lat/lon location to starboard side
* @param callsign The vessel callsign
* @param name The vessel name
* @param tslc [s] Time since last communication in seconds
* @param flags Bitmask to indicate various statuses including valid data fields
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_ais_vessel_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint32_t MMSI, int32_t lat, int32_t lon, uint16_t COG, uint16_t heading, uint16_t velocity, int8_t turn_rate, uint8_t navigational_status, uint8_t type, uint16_t dimension_bow, uint16_t dimension_stern, uint8_t dimension_port, uint8_t dimension_starboard, const char *callsign, const char *name, uint16_t tslc, uint16_t flags)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_AIS_VESSEL_LEN];
_mav_put_uint32_t(buf, 0, MMSI);
_mav_put_int32_t(buf, 4, lat);
_mav_put_int32_t(buf, 8, lon);
_mav_put_uint16_t(buf, 12, COG);
_mav_put_uint16_t(buf, 14, heading);
_mav_put_uint16_t(buf, 16, velocity);
_mav_put_uint16_t(buf, 18, dimension_bow);
_mav_put_uint16_t(buf, 20, dimension_stern);
_mav_put_uint16_t(buf, 22, tslc);
_mav_put_uint16_t(buf, 24, flags);
_mav_put_int8_t(buf, 26, turn_rate);
_mav_put_uint8_t(buf, 27, navigational_status);
_mav_put_uint8_t(buf, 28, type);
_mav_put_uint8_t(buf, 29, dimension_port);
_mav_put_uint8_t(buf, 30, dimension_starboard);
_mav_put_char_array(buf, 31, callsign, 7);
_mav_put_char_array(buf, 38, name, 20);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_AIS_VESSEL_LEN);
#else
mavlink_ais_vessel_t packet;
packet.MMSI = MMSI;
packet.lat = lat;
packet.lon = lon;
packet.COG = COG;
packet.heading = heading;
packet.velocity = velocity;
packet.dimension_bow = dimension_bow;
packet.dimension_stern = dimension_stern;
packet.tslc = tslc;
packet.flags = flags;
packet.turn_rate = turn_rate;
packet.navigational_status = navigational_status;
packet.type = type;
packet.dimension_port = dimension_port;
packet.dimension_starboard = dimension_starboard;
mav_array_memcpy(packet.callsign, callsign, sizeof(char)*7);
mav_array_memcpy(packet.name, name, sizeof(char)*20);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_AIS_VESSEL_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_AIS_VESSEL;
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_AIS_VESSEL_MIN_LEN, MAVLINK_MSG_ID_AIS_VESSEL_LEN, MAVLINK_MSG_ID_AIS_VESSEL_CRC);
}
/**
* @brief Pack a ais_vessel message on a channel
* @param system_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 MMSI Mobile Marine Service Identifier, 9 decimal digits
* @param lat [degE7] Latitude
* @param lon [degE7] Longitude
* @param COG [cdeg] Course over ground
* @param heading [cdeg] True heading
* @param velocity [cm/s] Speed over ground
* @param turn_rate [cdeg/s] Turn rate
* @param navigational_status Navigational status
* @param type Type of vessels
* @param dimension_bow [m] Distance from lat/lon location to bow
* @param dimension_stern [m] Distance from lat/lon location to stern
* @param dimension_port [m] Distance from lat/lon location to port side
* @param dimension_starboard [m] Distance from lat/lon location to starboard side
* @param callsign The vessel callsign
* @param name The vessel name
* @param tslc [s] Time since last communication in seconds
* @param flags Bitmask to indicate various statuses including valid data fields
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_ais_vessel_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint32_t MMSI,int32_t lat,int32_t lon,uint16_t COG,uint16_t heading,uint16_t velocity,int8_t turn_rate,uint8_t navigational_status,uint8_t type,uint16_t dimension_bow,uint16_t dimension_stern,uint8_t dimension_port,uint8_t dimension_starboard,const char *callsign,const char *name,uint16_t tslc,uint16_t flags)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_AIS_VESSEL_LEN];
_mav_put_uint32_t(buf, 0, MMSI);
_mav_put_int32_t(buf, 4, lat);
_mav_put_int32_t(buf, 8, lon);
_mav_put_uint16_t(buf, 12, COG);
_mav_put_uint16_t(buf, 14, heading);
_mav_put_uint16_t(buf, 16, velocity);
_mav_put_uint16_t(buf, 18, dimension_bow);
_mav_put_uint16_t(buf, 20, dimension_stern);
_mav_put_uint16_t(buf, 22, tslc);
_mav_put_uint16_t(buf, 24, flags);
_mav_put_int8_t(buf, 26, turn_rate);
_mav_put_uint8_t(buf, 27, navigational_status);
_mav_put_uint8_t(buf, 28, type);
_mav_put_uint8_t(buf, 29, dimension_port);
_mav_put_uint8_t(buf, 30, dimension_starboard);
_mav_put_char_array(buf, 31, callsign, 7);
_mav_put_char_array(buf, 38, name, 20);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_AIS_VESSEL_LEN);
#else
mavlink_ais_vessel_t packet;
packet.MMSI = MMSI;
packet.lat = lat;
packet.lon = lon;
packet.COG = COG;
packet.heading = heading;
packet.velocity = velocity;
packet.dimension_bow = dimension_bow;
packet.dimension_stern = dimension_stern;
packet.tslc = tslc;
packet.flags = flags;
packet.turn_rate = turn_rate;
packet.navigational_status = navigational_status;
packet.type = type;
packet.dimension_port = dimension_port;
packet.dimension_starboard = dimension_starboard;
mav_array_memcpy(packet.callsign, callsign, sizeof(char)*7);
mav_array_memcpy(packet.name, name, sizeof(char)*20);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_AIS_VESSEL_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_AIS_VESSEL;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_AIS_VESSEL_MIN_LEN, MAVLINK_MSG_ID_AIS_VESSEL_LEN, MAVLINK_MSG_ID_AIS_VESSEL_CRC);
}
/**
* @brief Encode a ais_vessel 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 ais_vessel C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_ais_vessel_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_ais_vessel_t* ais_vessel)
{
return mavlink_msg_ais_vessel_pack(system_id, component_id, msg, ais_vessel->MMSI, ais_vessel->lat, ais_vessel->lon, ais_vessel->COG, ais_vessel->heading, ais_vessel->velocity, ais_vessel->turn_rate, ais_vessel->navigational_status, ais_vessel->type, ais_vessel->dimension_bow, ais_vessel->dimension_stern, ais_vessel->dimension_port, ais_vessel->dimension_starboard, ais_vessel->callsign, ais_vessel->name, ais_vessel->tslc, ais_vessel->flags);
}
/**
* @brief Encode a ais_vessel 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 ais_vessel C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_ais_vessel_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_ais_vessel_t* ais_vessel)
{
return mavlink_msg_ais_vessel_pack_chan(system_id, component_id, chan, msg, ais_vessel->MMSI, ais_vessel->lat, ais_vessel->lon, ais_vessel->COG, ais_vessel->heading, ais_vessel->velocity, ais_vessel->turn_rate, ais_vessel->navigational_status, ais_vessel->type, ais_vessel->dimension_bow, ais_vessel->dimension_stern, ais_vessel->dimension_port, ais_vessel->dimension_starboard, ais_vessel->callsign, ais_vessel->name, ais_vessel->tslc, ais_vessel->flags);
}
/**
* @brief Send a ais_vessel message
* @param chan MAVLink channel to send the message
*
* @param MMSI Mobile Marine Service Identifier, 9 decimal digits
* @param lat [degE7] Latitude
* @param lon [degE7] Longitude
* @param COG [cdeg] Course over ground
* @param heading [cdeg] True heading
* @param velocity [cm/s] Speed over ground
* @param turn_rate [cdeg/s] Turn rate
* @param navigational_status Navigational status
* @param type Type of vessels
* @param dimension_bow [m] Distance from lat/lon location to bow
* @param dimension_stern [m] Distance from lat/lon location to stern
* @param dimension_port [m] Distance from lat/lon location to port side
* @param dimension_starboard [m] Distance from lat/lon location to starboard side
* @param callsign The vessel callsign
* @param name The vessel name
* @param tslc [s] Time since last communication in seconds
* @param flags Bitmask to indicate various statuses including valid data fields
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_ais_vessel_send(mavlink_channel_t chan, uint32_t MMSI, int32_t lat, int32_t lon, uint16_t COG, uint16_t heading, uint16_t velocity, int8_t turn_rate, uint8_t navigational_status, uint8_t type, uint16_t dimension_bow, uint16_t dimension_stern, uint8_t dimension_port, uint8_t dimension_starboard, const char *callsign, const char *name, uint16_t tslc, uint16_t flags)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_AIS_VESSEL_LEN];
_mav_put_uint32_t(buf, 0, MMSI);
_mav_put_int32_t(buf, 4, lat);
_mav_put_int32_t(buf, 8, lon);
_mav_put_uint16_t(buf, 12, COG);
_mav_put_uint16_t(buf, 14, heading);
_mav_put_uint16_t(buf, 16, velocity);
_mav_put_uint16_t(buf, 18, dimension_bow);
_mav_put_uint16_t(buf, 20, dimension_stern);
_mav_put_uint16_t(buf, 22, tslc);
_mav_put_uint16_t(buf, 24, flags);
_mav_put_int8_t(buf, 26, turn_rate);
_mav_put_uint8_t(buf, 27, navigational_status);
_mav_put_uint8_t(buf, 28, type);
_mav_put_uint8_t(buf, 29, dimension_port);
_mav_put_uint8_t(buf, 30, dimension_starboard);
_mav_put_char_array(buf, 31, callsign, 7);
_mav_put_char_array(buf, 38, name, 20);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AIS_VESSEL, buf, MAVLINK_MSG_ID_AIS_VESSEL_MIN_LEN, MAVLINK_MSG_ID_AIS_VESSEL_LEN, MAVLINK_MSG_ID_AIS_VESSEL_CRC);
#else
mavlink_ais_vessel_t packet;
packet.MMSI = MMSI;
packet.lat = lat;
packet.lon = lon;
packet.COG = COG;
packet.heading = heading;
packet.velocity = velocity;
packet.dimension_bow = dimension_bow;
packet.dimension_stern = dimension_stern;
packet.tslc = tslc;
packet.flags = flags;
packet.turn_rate = turn_rate;
packet.navigational_status = navigational_status;
packet.type = type;
packet.dimension_port = dimension_port;
packet.dimension_starboard = dimension_starboard;
mav_array_memcpy(packet.callsign, callsign, sizeof(char)*7);
mav_array_memcpy(packet.name, name, sizeof(char)*20);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AIS_VESSEL, (const char *)&packet, MAVLINK_MSG_ID_AIS_VESSEL_MIN_LEN, MAVLINK_MSG_ID_AIS_VESSEL_LEN, MAVLINK_MSG_ID_AIS_VESSEL_CRC);
#endif
}
/**
* @brief Send a ais_vessel message
* @param chan MAVLink channel to send the message
* @param struct The MAVLink struct to serialize
*/
static inline void mavlink_msg_ais_vessel_send_struct(mavlink_channel_t chan, const mavlink_ais_vessel_t* ais_vessel)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mavlink_msg_ais_vessel_send(chan, ais_vessel->MMSI, ais_vessel->lat, ais_vessel->lon, ais_vessel->COG, ais_vessel->heading, ais_vessel->velocity, ais_vessel->turn_rate, ais_vessel->navigational_status, ais_vessel->type, ais_vessel->dimension_bow, ais_vessel->dimension_stern, ais_vessel->dimension_port, ais_vessel->dimension_starboard, ais_vessel->callsign, ais_vessel->name, ais_vessel->tslc, ais_vessel->flags);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AIS_VESSEL, (const char *)ais_vessel, MAVLINK_MSG_ID_AIS_VESSEL_MIN_LEN, MAVLINK_MSG_ID_AIS_VESSEL_LEN, MAVLINK_MSG_ID_AIS_VESSEL_CRC);
#endif
}
#if MAVLINK_MSG_ID_AIS_VESSEL_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_ais_vessel_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t MMSI, int32_t lat, int32_t lon, uint16_t COG, uint16_t heading, uint16_t velocity, int8_t turn_rate, uint8_t navigational_status, uint8_t type, uint16_t dimension_bow, uint16_t dimension_stern, uint8_t dimension_port, uint8_t dimension_starboard, const char *callsign, const char *name, uint16_t tslc, uint16_t flags)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
_mav_put_uint32_t(buf, 0, MMSI);
_mav_put_int32_t(buf, 4, lat);
_mav_put_int32_t(buf, 8, lon);
_mav_put_uint16_t(buf, 12, COG);
_mav_put_uint16_t(buf, 14, heading);
_mav_put_uint16_t(buf, 16, velocity);
_mav_put_uint16_t(buf, 18, dimension_bow);
_mav_put_uint16_t(buf, 20, dimension_stern);
_mav_put_uint16_t(buf, 22, tslc);
_mav_put_uint16_t(buf, 24, flags);
_mav_put_int8_t(buf, 26, turn_rate);
_mav_put_uint8_t(buf, 27, navigational_status);
_mav_put_uint8_t(buf, 28, type);
_mav_put_uint8_t(buf, 29, dimension_port);
_mav_put_uint8_t(buf, 30, dimension_starboard);
_mav_put_char_array(buf, 31, callsign, 7);
_mav_put_char_array(buf, 38, name, 20);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AIS_VESSEL, buf, MAVLINK_MSG_ID_AIS_VESSEL_MIN_LEN, MAVLINK_MSG_ID_AIS_VESSEL_LEN, MAVLINK_MSG_ID_AIS_VESSEL_CRC);
#else
mavlink_ais_vessel_t *packet = (mavlink_ais_vessel_t *)msgbuf;
packet->MMSI = MMSI;
packet->lat = lat;
packet->lon = lon;
packet->COG = COG;
packet->heading = heading;
packet->velocity = velocity;
packet->dimension_bow = dimension_bow;
packet->dimension_stern = dimension_stern;
packet->tslc = tslc;
packet->flags = flags;
packet->turn_rate = turn_rate;
packet->navigational_status = navigational_status;
packet->type = type;
packet->dimension_port = dimension_port;
packet->dimension_starboard = dimension_starboard;
mav_array_memcpy(packet->callsign, callsign, sizeof(char)*7);
mav_array_memcpy(packet->name, name, sizeof(char)*20);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AIS_VESSEL, (const char *)packet, MAVLINK_MSG_ID_AIS_VESSEL_MIN_LEN, MAVLINK_MSG_ID_AIS_VESSEL_LEN, MAVLINK_MSG_ID_AIS_VESSEL_CRC);
#endif
}
#endif
#endif
// MESSAGE AIS_VESSEL UNPACKING
/**
* @brief Get field MMSI from ais_vessel message
*
* @return Mobile Marine Service Identifier, 9 decimal digits
*/
static inline uint32_t mavlink_msg_ais_vessel_get_MMSI(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint32_t(msg, 0);
}
/**
* @brief Get field lat from ais_vessel message
*
* @return [degE7] Latitude
*/
static inline int32_t mavlink_msg_ais_vessel_get_lat(const mavlink_message_t* msg)
{
return _MAV_RETURN_int32_t(msg, 4);
}
/**
* @brief Get field lon from ais_vessel message
*
* @return [degE7] Longitude
*/
static inline int32_t mavlink_msg_ais_vessel_get_lon(const mavlink_message_t* msg)
{
return _MAV_RETURN_int32_t(msg, 8);
}
/**
* @brief Get field COG from ais_vessel message
*
* @return [cdeg] Course over ground
*/
static inline uint16_t mavlink_msg_ais_vessel_get_COG(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 12);
}
/**
* @brief Get field heading from ais_vessel message
*
* @return [cdeg] True heading
*/
static inline uint16_t mavlink_msg_ais_vessel_get_heading(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 14);
}
/**
* @brief Get field velocity from ais_vessel message
*
* @return [cm/s] Speed over ground
*/
static inline uint16_t mavlink_msg_ais_vessel_get_velocity(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 16);
}
/**
* @brief Get field turn_rate from ais_vessel message
*
* @return [cdeg/s] Turn rate
*/
static inline int8_t mavlink_msg_ais_vessel_get_turn_rate(const mavlink_message_t* msg)
{
return _MAV_RETURN_int8_t(msg, 26);
}
/**
* @brief Get field navigational_status from ais_vessel message
*
* @return Navigational status
*/
static inline uint8_t mavlink_msg_ais_vessel_get_navigational_status(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 27);
}
/**
* @brief Get field type from ais_vessel message
*
* @return Type of vessels
*/
static inline uint8_t mavlink_msg_ais_vessel_get_type(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 28);
}
/**
* @brief Get field dimension_bow from ais_vessel message
*
* @return [m] Distance from lat/lon location to bow
*/
static inline uint16_t mavlink_msg_ais_vessel_get_dimension_bow(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 18);
}
/**
* @brief Get field dimension_stern from ais_vessel message
*
* @return [m] Distance from lat/lon location to stern
*/
static inline uint16_t mavlink_msg_ais_vessel_get_dimension_stern(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 20);
}
/**
* @brief Get field dimension_port from ais_vessel message
*
* @return [m] Distance from lat/lon location to port side
*/
static inline uint8_t mavlink_msg_ais_vessel_get_dimension_port(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 29);
}
/**
* @brief Get field dimension_starboard from ais_vessel message
*
* @return [m] Distance from lat/lon location to starboard side
*/
static inline uint8_t mavlink_msg_ais_vessel_get_dimension_starboard(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 30);
}
/**
* @brief Get field callsign from ais_vessel message
*
* @return The vessel callsign
*/
static inline uint16_t mavlink_msg_ais_vessel_get_callsign(const mavlink_message_t* msg, char *callsign)
{
return _MAV_RETURN_char_array(msg, callsign, 7, 31);
}
/**
* @brief Get field name from ais_vessel message
*
* @return The vessel name
*/
static inline uint16_t mavlink_msg_ais_vessel_get_name(const mavlink_message_t* msg, char *name)
{
return _MAV_RETURN_char_array(msg, name, 20, 38);
}
/**
* @brief Get field tslc from ais_vessel message
*
* @return [s] Time since last communication in seconds
*/
static inline uint16_t mavlink_msg_ais_vessel_get_tslc(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 22);
}
/**
* @brief Get field flags from ais_vessel message
*
* @return Bitmask to indicate various statuses including valid data fields
*/
static inline uint16_t mavlink_msg_ais_vessel_get_flags(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 24);
}
/**
* @brief Decode a ais_vessel message into a struct
*
* @param msg The message to decode
* @param ais_vessel C-struct to decode the message contents into
*/
static inline void mavlink_msg_ais_vessel_decode(const mavlink_message_t* msg, mavlink_ais_vessel_t* ais_vessel)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
ais_vessel->MMSI = mavlink_msg_ais_vessel_get_MMSI(msg);
ais_vessel->lat = mavlink_msg_ais_vessel_get_lat(msg);
ais_vessel->lon = mavlink_msg_ais_vessel_get_lon(msg);
ais_vessel->COG = mavlink_msg_ais_vessel_get_COG(msg);
ais_vessel->heading = mavlink_msg_ais_vessel_get_heading(msg);
ais_vessel->velocity = mavlink_msg_ais_vessel_get_velocity(msg);
ais_vessel->dimension_bow = mavlink_msg_ais_vessel_get_dimension_bow(msg);
ais_vessel->dimension_stern = mavlink_msg_ais_vessel_get_dimension_stern(msg);
ais_vessel->tslc = mavlink_msg_ais_vessel_get_tslc(msg);
ais_vessel->flags = mavlink_msg_ais_vessel_get_flags(msg);
ais_vessel->turn_rate = mavlink_msg_ais_vessel_get_turn_rate(msg);
ais_vessel->navigational_status = mavlink_msg_ais_vessel_get_navigational_status(msg);
ais_vessel->type = mavlink_msg_ais_vessel_get_type(msg);
ais_vessel->dimension_port = mavlink_msg_ais_vessel_get_dimension_port(msg);
ais_vessel->dimension_starboard = mavlink_msg_ais_vessel_get_dimension_starboard(msg);
mavlink_msg_ais_vessel_get_callsign(msg, ais_vessel->callsign);
mavlink_msg_ais_vessel_get_name(msg, ais_vessel->name);
#else
uint8_t len = msg->len < MAVLINK_MSG_ID_AIS_VESSEL_LEN? msg->len : MAVLINK_MSG_ID_AIS_VESSEL_LEN;
memset(ais_vessel, 0, MAVLINK_MSG_ID_AIS_VESSEL_LEN);
memcpy(ais_vessel, _MAV_PAYLOAD(msg), len);
#endif
}

View file

@ -10,39 +10,43 @@ typedef struct __mavlink_att_pos_mocap_t {
float x; /*< [m] X position (NED)*/
float y; /*< [m] Y position (NED)*/
float z; /*< [m] Z position (NED)*/
float covariance[21]; /*< Row-major representation of a pose 6x6 cross-covariance matrix upper right triangle (states: x, y, z, roll, pitch, yaw; first six entries are the first ROW, next five entries are the second ROW, etc.). If unknown, assign NaN value to first element in the array.*/
} mavlink_att_pos_mocap_t;
#define MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN 36
#define MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN 120
#define MAVLINK_MSG_ID_ATT_POS_MOCAP_MIN_LEN 36
#define MAVLINK_MSG_ID_138_LEN 36
#define MAVLINK_MSG_ID_138_LEN 120
#define MAVLINK_MSG_ID_138_MIN_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_MSG_ATT_POS_MOCAP_FIELD_COVARIANCE_LEN 21
#if MAVLINK_COMMAND_24BIT
#define MAVLINK_MESSAGE_INFO_ATT_POS_MOCAP { \
138, \
"ATT_POS_MOCAP", \
5, \
6, \
{ { "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) }, \
{ "covariance", NULL, MAVLINK_TYPE_FLOAT, 21, 36, offsetof(mavlink_att_pos_mocap_t, covariance) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_ATT_POS_MOCAP { \
"ATT_POS_MOCAP", \
5, \
6, \
{ { "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) }, \
{ "covariance", NULL, MAVLINK_TYPE_FLOAT, 21, 36, offsetof(mavlink_att_pos_mocap_t, covariance) }, \
} \
}
#endif
@ -58,10 +62,11 @@ typedef struct __mavlink_att_pos_mocap_t {
* @param x [m] X position (NED)
* @param y [m] Y position (NED)
* @param z [m] Z position (NED)
* @param covariance Row-major representation of a pose 6x6 cross-covariance matrix upper right triangle (states: x, y, z, roll, pitch, yaw; first six entries are the first ROW, next five entries are the second ROW, etc.). If unknown, assign NaN value to first element in the array.
* @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)
uint64_t time_usec, const float *q, float x, float y, float z, const float *covariance)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN];
@ -70,6 +75,7 @@ static inline uint16_t mavlink_msg_att_pos_mocap_pack(uint8_t system_id, uint8_t
_mav_put_float(buf, 28, y);
_mav_put_float(buf, 32, z);
_mav_put_float_array(buf, 8, q, 4);
_mav_put_float_array(buf, 36, covariance, 21);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN);
#else
mavlink_att_pos_mocap_t packet;
@ -78,6 +84,7 @@ static inline uint16_t mavlink_msg_att_pos_mocap_pack(uint8_t system_id, uint8_t
packet.y = y;
packet.z = z;
mav_array_memcpy(packet.q, q, sizeof(float)*4);
mav_array_memcpy(packet.covariance, covariance, sizeof(float)*21);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN);
#endif
@ -96,11 +103,12 @@ static inline uint16_t mavlink_msg_att_pos_mocap_pack(uint8_t system_id, uint8_t
* @param x [m] X position (NED)
* @param y [m] Y position (NED)
* @param z [m] Z position (NED)
* @param covariance Row-major representation of a pose 6x6 cross-covariance matrix upper right triangle (states: x, y, z, roll, pitch, yaw; first six entries are the first ROW, next five entries are the second ROW, etc.). If unknown, assign NaN value to first element in the array.
* @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)
uint64_t time_usec,const float *q,float x,float y,float z,const float *covariance)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN];
@ -109,6 +117,7 @@ static inline uint16_t mavlink_msg_att_pos_mocap_pack_chan(uint8_t system_id, ui
_mav_put_float(buf, 28, y);
_mav_put_float(buf, 32, z);
_mav_put_float_array(buf, 8, q, 4);
_mav_put_float_array(buf, 36, covariance, 21);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN);
#else
mavlink_att_pos_mocap_t packet;
@ -117,6 +126,7 @@ static inline uint16_t mavlink_msg_att_pos_mocap_pack_chan(uint8_t system_id, ui
packet.y = y;
packet.z = z;
mav_array_memcpy(packet.q, q, sizeof(float)*4);
mav_array_memcpy(packet.covariance, covariance, sizeof(float)*21);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN);
#endif
@ -134,7 +144,7 @@ static inline uint16_t mavlink_msg_att_pos_mocap_pack_chan(uint8_t system_id, ui
*/
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);
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, att_pos_mocap->covariance);
}
/**
@ -148,7 +158,7 @@ static inline uint16_t mavlink_msg_att_pos_mocap_encode(uint8_t system_id, uint8
*/
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);
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, att_pos_mocap->covariance);
}
/**
@ -160,10 +170,11 @@ static inline uint16_t mavlink_msg_att_pos_mocap_encode_chan(uint8_t system_id,
* @param x [m] X position (NED)
* @param y [m] Y position (NED)
* @param z [m] Z position (NED)
* @param covariance Row-major representation of a pose 6x6 cross-covariance matrix upper right triangle (states: x, y, z, roll, pitch, yaw; first six entries are the first ROW, next five entries are the second ROW, etc.). If unknown, assign NaN value to first element in the array.
*/
#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)
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, const float *covariance)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN];
@ -172,6 +183,7 @@ static inline void mavlink_msg_att_pos_mocap_send(mavlink_channel_t chan, uint64
_mav_put_float(buf, 28, y);
_mav_put_float(buf, 32, z);
_mav_put_float_array(buf, 8, q, 4);
_mav_put_float_array(buf, 36, covariance, 21);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATT_POS_MOCAP, buf, MAVLINK_MSG_ID_ATT_POS_MOCAP_MIN_LEN, MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN, MAVLINK_MSG_ID_ATT_POS_MOCAP_CRC);
#else
mavlink_att_pos_mocap_t packet;
@ -180,6 +192,7 @@ static inline void mavlink_msg_att_pos_mocap_send(mavlink_channel_t chan, uint64
packet.y = y;
packet.z = z;
mav_array_memcpy(packet.q, q, sizeof(float)*4);
mav_array_memcpy(packet.covariance, covariance, sizeof(float)*21);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATT_POS_MOCAP, (const char *)&packet, MAVLINK_MSG_ID_ATT_POS_MOCAP_MIN_LEN, MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN, MAVLINK_MSG_ID_ATT_POS_MOCAP_CRC);
#endif
}
@ -192,7 +205,7 @@ static inline void mavlink_msg_att_pos_mocap_send(mavlink_channel_t chan, uint64
static inline void mavlink_msg_att_pos_mocap_send_struct(mavlink_channel_t chan, const mavlink_att_pos_mocap_t* att_pos_mocap)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mavlink_msg_att_pos_mocap_send(chan, att_pos_mocap->time_usec, att_pos_mocap->q, att_pos_mocap->x, att_pos_mocap->y, att_pos_mocap->z);
mavlink_msg_att_pos_mocap_send(chan, att_pos_mocap->time_usec, att_pos_mocap->q, att_pos_mocap->x, att_pos_mocap->y, att_pos_mocap->z, att_pos_mocap->covariance);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATT_POS_MOCAP, (const char *)att_pos_mocap, MAVLINK_MSG_ID_ATT_POS_MOCAP_MIN_LEN, MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN, MAVLINK_MSG_ID_ATT_POS_MOCAP_CRC);
#endif
@ -206,7 +219,7 @@ static inline void mavlink_msg_att_pos_mocap_send_struct(mavlink_channel_t chan,
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)
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, const float *covariance)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
@ -215,6 +228,7 @@ static inline void mavlink_msg_att_pos_mocap_send_buf(mavlink_message_t *msgbuf,
_mav_put_float(buf, 28, y);
_mav_put_float(buf, 32, z);
_mav_put_float_array(buf, 8, q, 4);
_mav_put_float_array(buf, 36, covariance, 21);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATT_POS_MOCAP, buf, MAVLINK_MSG_ID_ATT_POS_MOCAP_MIN_LEN, MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN, MAVLINK_MSG_ID_ATT_POS_MOCAP_CRC);
#else
mavlink_att_pos_mocap_t *packet = (mavlink_att_pos_mocap_t *)msgbuf;
@ -223,6 +237,7 @@ static inline void mavlink_msg_att_pos_mocap_send_buf(mavlink_message_t *msgbuf,
packet->y = y;
packet->z = z;
mav_array_memcpy(packet->q, q, sizeof(float)*4);
mav_array_memcpy(packet->covariance, covariance, sizeof(float)*21);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATT_POS_MOCAP, (const char *)packet, MAVLINK_MSG_ID_ATT_POS_MOCAP_MIN_LEN, MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN, MAVLINK_MSG_ID_ATT_POS_MOCAP_CRC);
#endif
}
@ -283,6 +298,16 @@ static inline float mavlink_msg_att_pos_mocap_get_z(const mavlink_message_t* msg
return _MAV_RETURN_float(msg, 32);
}
/**
* @brief Get field covariance from att_pos_mocap message
*
* @return Row-major representation of a pose 6x6 cross-covariance matrix upper right triangle (states: x, y, z, roll, pitch, yaw; first six entries are the first ROW, next five entries are the second ROW, etc.). If unknown, assign NaN value to first element in the array.
*/
static inline uint16_t mavlink_msg_att_pos_mocap_get_covariance(const mavlink_message_t* msg, float *covariance)
{
return _MAV_RETURN_float_array(msg, covariance, 21, 36);
}
/**
* @brief Decode a att_pos_mocap message into a struct
*
@ -297,6 +322,7 @@ static inline void mavlink_msg_att_pos_mocap_decode(const mavlink_message_t* msg
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);
mavlink_msg_att_pos_mocap_get_covariance(msg, att_pos_mocap->covariance);
#else
uint8_t len = msg->len < MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN? msg->len : MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN;
memset(att_pos_mocap, 0, MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN);

View file

@ -13,23 +13,24 @@ typedef struct __mavlink_attitude_quaternion_t {
float rollspeed; /*< [rad/s] Roll angular speed*/
float pitchspeed; /*< [rad/s] Pitch angular speed*/
float yawspeed; /*< [rad/s] Yaw angular speed*/
float repr_offset_q[4]; /*< Rotation offset by which the attitude quaternion and angular speed vector should be rotated for user display (quaternion with [w, x, y, z] order, zero-rotation is [1, 0, 0, 0], send [0, 0, 0, 0] if field not supported). This field is intended for systems in which the reference attitude may change during flight. For example, tailsitters VTOLs rotate their reference attitude by 90 degrees between hover mode and fixed wing mode, thus repr_offset_q is equal to [1, 0, 0, 0] in hover mode and equal to [0.7071, 0, 0.7071, 0] in fixed wing mode.*/
} mavlink_attitude_quaternion_t;
#define MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN 32
#define MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN 48
#define MAVLINK_MSG_ID_ATTITUDE_QUATERNION_MIN_LEN 32
#define MAVLINK_MSG_ID_31_LEN 32
#define MAVLINK_MSG_ID_31_LEN 48
#define MAVLINK_MSG_ID_31_MIN_LEN 32
#define MAVLINK_MSG_ID_ATTITUDE_QUATERNION_CRC 246
#define MAVLINK_MSG_ID_31_CRC 246
#define MAVLINK_MSG_ATTITUDE_QUATERNION_FIELD_REPR_OFFSET_Q_LEN 4
#if MAVLINK_COMMAND_24BIT
#define MAVLINK_MESSAGE_INFO_ATTITUDE_QUATERNION { \
31, \
"ATTITUDE_QUATERNION", \
8, \
9, \
{ { "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) }, \
@ -38,12 +39,13 @@ typedef struct __mavlink_attitude_quaternion_t {
{ "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) }, \
{ "repr_offset_q", NULL, MAVLINK_TYPE_FLOAT, 4, 32, offsetof(mavlink_attitude_quaternion_t, repr_offset_q) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_ATTITUDE_QUATERNION { \
"ATTITUDE_QUATERNION", \
8, \
9, \
{ { "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) }, \
@ -52,6 +54,7 @@ typedef struct __mavlink_attitude_quaternion_t {
{ "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) }, \
{ "repr_offset_q", NULL, MAVLINK_TYPE_FLOAT, 4, 32, offsetof(mavlink_attitude_quaternion_t, repr_offset_q) }, \
} \
}
#endif
@ -70,10 +73,11 @@ typedef struct __mavlink_attitude_quaternion_t {
* @param rollspeed [rad/s] Roll angular speed
* @param pitchspeed [rad/s] Pitch angular speed
* @param yawspeed [rad/s] Yaw angular speed
* @param repr_offset_q Rotation offset by which the attitude quaternion and angular speed vector should be rotated for user display (quaternion with [w, x, y, z] order, zero-rotation is [1, 0, 0, 0], send [0, 0, 0, 0] if field not supported). This field is intended for systems in which the reference attitude may change during flight. For example, tailsitters VTOLs rotate their reference attitude by 90 degrees between hover mode and fixed wing mode, thus repr_offset_q is equal to [1, 0, 0, 0] in hover mode and equal to [0.7071, 0, 0.7071, 0] in fixed wing mode.
* @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)
uint32_t time_boot_ms, float q1, float q2, float q3, float q4, float rollspeed, float pitchspeed, float yawspeed, const float *repr_offset_q)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN];
@ -85,7 +89,7 @@ static inline uint16_t mavlink_msg_attitude_quaternion_pack(uint8_t system_id, u
_mav_put_float(buf, 20, rollspeed);
_mav_put_float(buf, 24, pitchspeed);
_mav_put_float(buf, 28, yawspeed);
_mav_put_float_array(buf, 32, repr_offset_q, 4);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN);
#else
mavlink_attitude_quaternion_t packet;
@ -97,7 +101,7 @@ static inline uint16_t mavlink_msg_attitude_quaternion_pack(uint8_t system_id, u
packet.rollspeed = rollspeed;
packet.pitchspeed = pitchspeed;
packet.yawspeed = yawspeed;
mav_array_memcpy(packet.repr_offset_q, repr_offset_q, sizeof(float)*4);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN);
#endif
@ -119,11 +123,12 @@ static inline uint16_t mavlink_msg_attitude_quaternion_pack(uint8_t system_id, u
* @param rollspeed [rad/s] Roll angular speed
* @param pitchspeed [rad/s] Pitch angular speed
* @param yawspeed [rad/s] Yaw angular speed
* @param repr_offset_q Rotation offset by which the attitude quaternion and angular speed vector should be rotated for user display (quaternion with [w, x, y, z] order, zero-rotation is [1, 0, 0, 0], send [0, 0, 0, 0] if field not supported). This field is intended for systems in which the reference attitude may change during flight. For example, tailsitters VTOLs rotate their reference attitude by 90 degrees between hover mode and fixed wing mode, thus repr_offset_q is equal to [1, 0, 0, 0] in hover mode and equal to [0.7071, 0, 0.7071, 0] in fixed wing mode.
* @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)
uint32_t time_boot_ms,float q1,float q2,float q3,float q4,float rollspeed,float pitchspeed,float yawspeed,const float *repr_offset_q)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN];
@ -135,7 +140,7 @@ static inline uint16_t mavlink_msg_attitude_quaternion_pack_chan(uint8_t system_
_mav_put_float(buf, 20, rollspeed);
_mav_put_float(buf, 24, pitchspeed);
_mav_put_float(buf, 28, yawspeed);
_mav_put_float_array(buf, 32, repr_offset_q, 4);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN);
#else
mavlink_attitude_quaternion_t packet;
@ -147,7 +152,7 @@ static inline uint16_t mavlink_msg_attitude_quaternion_pack_chan(uint8_t system_
packet.rollspeed = rollspeed;
packet.pitchspeed = pitchspeed;
packet.yawspeed = yawspeed;
mav_array_memcpy(packet.repr_offset_q, repr_offset_q, sizeof(float)*4);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN);
#endif
@ -165,7 +170,7 @@ static inline uint16_t mavlink_msg_attitude_quaternion_pack_chan(uint8_t system_
*/
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);
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, attitude_quaternion->repr_offset_q);
}
/**
@ -179,7 +184,7 @@ static inline uint16_t mavlink_msg_attitude_quaternion_encode(uint8_t system_id,
*/
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);
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, attitude_quaternion->repr_offset_q);
}
/**
@ -194,10 +199,11 @@ static inline uint16_t mavlink_msg_attitude_quaternion_encode_chan(uint8_t syste
* @param rollspeed [rad/s] Roll angular speed
* @param pitchspeed [rad/s] Pitch angular speed
* @param yawspeed [rad/s] Yaw angular speed
* @param repr_offset_q Rotation offset by which the attitude quaternion and angular speed vector should be rotated for user display (quaternion with [w, x, y, z] order, zero-rotation is [1, 0, 0, 0], send [0, 0, 0, 0] if field not supported). This field is intended for systems in which the reference attitude may change during flight. For example, tailsitters VTOLs rotate their reference attitude by 90 degrees between hover mode and fixed wing mode, thus repr_offset_q is equal to [1, 0, 0, 0] in hover mode and equal to [0.7071, 0, 0.7071, 0] in fixed wing mode.
*/
#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)
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, const float *repr_offset_q)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN];
@ -209,7 +215,7 @@ static inline void mavlink_msg_attitude_quaternion_send(mavlink_channel_t chan,
_mav_put_float(buf, 20, rollspeed);
_mav_put_float(buf, 24, pitchspeed);
_mav_put_float(buf, 28, yawspeed);
_mav_put_float_array(buf, 32, repr_offset_q, 4);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION, buf, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_MIN_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_CRC);
#else
mavlink_attitude_quaternion_t packet;
@ -221,7 +227,7 @@ static inline void mavlink_msg_attitude_quaternion_send(mavlink_channel_t chan,
packet.rollspeed = rollspeed;
packet.pitchspeed = pitchspeed;
packet.yawspeed = yawspeed;
mav_array_memcpy(packet.repr_offset_q, repr_offset_q, sizeof(float)*4);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION, (const char *)&packet, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_MIN_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_CRC);
#endif
}
@ -234,7 +240,7 @@ static inline void mavlink_msg_attitude_quaternion_send(mavlink_channel_t chan,
static inline void mavlink_msg_attitude_quaternion_send_struct(mavlink_channel_t chan, const mavlink_attitude_quaternion_t* attitude_quaternion)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mavlink_msg_attitude_quaternion_send(chan, 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);
mavlink_msg_attitude_quaternion_send(chan, 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, attitude_quaternion->repr_offset_q);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION, (const char *)attitude_quaternion, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_MIN_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_CRC);
#endif
@ -248,7 +254,7 @@ static inline void mavlink_msg_attitude_quaternion_send_struct(mavlink_channel_t
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)
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, const float *repr_offset_q)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
@ -260,7 +266,7 @@ static inline void mavlink_msg_attitude_quaternion_send_buf(mavlink_message_t *m
_mav_put_float(buf, 20, rollspeed);
_mav_put_float(buf, 24, pitchspeed);
_mav_put_float(buf, 28, yawspeed);
_mav_put_float_array(buf, 32, repr_offset_q, 4);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION, buf, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_MIN_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_CRC);
#else
mavlink_attitude_quaternion_t *packet = (mavlink_attitude_quaternion_t *)msgbuf;
@ -272,7 +278,7 @@ static inline void mavlink_msg_attitude_quaternion_send_buf(mavlink_message_t *m
packet->rollspeed = rollspeed;
packet->pitchspeed = pitchspeed;
packet->yawspeed = yawspeed;
mav_array_memcpy(packet->repr_offset_q, repr_offset_q, sizeof(float)*4);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ATTITUDE_QUATERNION, (const char *)packet, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_MIN_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_CRC);
#endif
}
@ -363,6 +369,16 @@ static inline float mavlink_msg_attitude_quaternion_get_yawspeed(const mavlink_m
return _MAV_RETURN_float(msg, 28);
}
/**
* @brief Get field repr_offset_q from attitude_quaternion message
*
* @return Rotation offset by which the attitude quaternion and angular speed vector should be rotated for user display (quaternion with [w, x, y, z] order, zero-rotation is [1, 0, 0, 0], send [0, 0, 0, 0] if field not supported). This field is intended for systems in which the reference attitude may change during flight. For example, tailsitters VTOLs rotate their reference attitude by 90 degrees between hover mode and fixed wing mode, thus repr_offset_q is equal to [1, 0, 0, 0] in hover mode and equal to [0.7071, 0, 0.7071, 0] in fixed wing mode.
*/
static inline uint16_t mavlink_msg_attitude_quaternion_get_repr_offset_q(const mavlink_message_t* msg, float *repr_offset_q)
{
return _MAV_RETURN_float_array(msg, repr_offset_q, 4, 32);
}
/**
* @brief Decode a attitude_quaternion message into a struct
*
@ -380,6 +396,7 @@ static inline void mavlink_msg_attitude_quaternion_decode(const mavlink_message_
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);
mavlink_msg_attitude_quaternion_get_repr_offset_q(msg, attitude_quaternion->repr_offset_q);
#else
uint8_t len = msg->len < MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN? msg->len : MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN;
memset(attitude_quaternion, 0, MAVLINK_MSG_ID_ATTITUDE_QUATERNION_LEN);

View file

@ -11,7 +11,7 @@ typedef struct __mavlink_attitude_target_t {
float body_pitch_rate; /*< [rad/s] Body pitch rate*/
float body_yaw_rate; /*< [rad/s] Body yaw rate*/
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*/
uint8_t type_mask; /*< Bitmap to indicate which dimensions should be ignored by the vehicle.*/
} mavlink_attitude_target_t;
#define MAVLINK_MSG_ID_ATTITUDE_TARGET_LEN 37
@ -60,7 +60,7 @@ typedef struct __mavlink_attitude_target_t {
* @param msg The MAVLink message to compress the data into
*
* @param time_boot_ms [ms] Timestamp (time 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 type_mask Bitmap to indicate which dimensions should be ignored by the vehicle.
* @param q Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0)
* @param body_roll_rate [rad/s] Body roll rate
* @param body_pitch_rate [rad/s] Body pitch rate
@ -104,7 +104,7 @@ static inline uint16_t mavlink_msg_attitude_target_pack(uint8_t system_id, uint8
* @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 [ms] Timestamp (time 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 type_mask Bitmap to indicate which dimensions should be ignored by the vehicle.
* @param q Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0)
* @param body_roll_rate [rad/s] Body roll rate
* @param body_pitch_rate [rad/s] Body pitch rate
@ -174,7 +174,7 @@ static inline uint16_t mavlink_msg_attitude_target_encode_chan(uint8_t system_id
* @param chan MAVLink channel to send the message
*
* @param time_boot_ms [ms] Timestamp (time 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 type_mask Bitmap to indicate which dimensions should be ignored by the vehicle.
* @param q Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0)
* @param body_roll_rate [rad/s] Body roll rate
* @param body_pitch_rate [rad/s] Body pitch rate
@ -274,7 +274,7 @@ static inline uint32_t mavlink_msg_attitude_target_get_time_boot_ms(const mavlin
/**
* @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
* @return Bitmap to indicate which dimensions should be ignored by the vehicle.
*/
static inline uint8_t mavlink_msg_attitude_target_get_type_mask(const mavlink_message_t* msg)
{

View file

@ -0,0 +1,480 @@
#pragma once
// MESSAGE AUTOPILOT_STATE_FOR_GIMBAL_DEVICE PACKING
#define MAVLINK_MSG_ID_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE 286
typedef struct __mavlink_autopilot_state_for_gimbal_device_t {
uint64_t time_boot_us; /*< [us] Timestamp (time since system boot).*/
float q[4]; /*< Quaternion components of autopilot attitude: w, x, y, z (1 0 0 0 is the null-rotation, Hamilton convention).*/
uint32_t q_estimated_delay_us; /*< [us] Estimated delay of the attitude data.*/
float vx; /*< [m/s] X Speed in NED (North, East, Down).*/
float vy; /*< [m/s] Y Speed in NED (North, East, Down).*/
float vz; /*< [m/s] Z Speed in NED (North, East, Down).*/
uint32_t v_estimated_delay_us; /*< [us] Estimated delay of the speed data.*/
float feed_forward_angular_velocity_z; /*< [rad/s] Feed forward Z component of angular velocity, positive is yawing to the right, NaN to be ignored. This is to indicate if the autopilot is actively yawing.*/
uint16_t estimator_status; /*< Bitmap indicating which estimator outputs are valid.*/
uint8_t target_system; /*< System ID*/
uint8_t target_component; /*< Component ID*/
uint8_t landed_state; /*< The landed state. Is set to MAV_LANDED_STATE_UNDEFINED if landed state is unknown.*/
} mavlink_autopilot_state_for_gimbal_device_t;
#define MAVLINK_MSG_ID_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_LEN 53
#define MAVLINK_MSG_ID_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_MIN_LEN 53
#define MAVLINK_MSG_ID_286_LEN 53
#define MAVLINK_MSG_ID_286_MIN_LEN 53
#define MAVLINK_MSG_ID_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_CRC 210
#define MAVLINK_MSG_ID_286_CRC 210
#define MAVLINK_MSG_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_FIELD_Q_LEN 4
#if MAVLINK_COMMAND_24BIT
#define MAVLINK_MESSAGE_INFO_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE { \
286, \
"AUTOPILOT_STATE_FOR_GIMBAL_DEVICE", \
12, \
{ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 50, offsetof(mavlink_autopilot_state_for_gimbal_device_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 51, offsetof(mavlink_autopilot_state_for_gimbal_device_t, target_component) }, \
{ "time_boot_us", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_autopilot_state_for_gimbal_device_t, time_boot_us) }, \
{ "q", NULL, MAVLINK_TYPE_FLOAT, 4, 8, offsetof(mavlink_autopilot_state_for_gimbal_device_t, q) }, \
{ "q_estimated_delay_us", NULL, MAVLINK_TYPE_UINT32_T, 0, 24, offsetof(mavlink_autopilot_state_for_gimbal_device_t, q_estimated_delay_us) }, \
{ "vx", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_autopilot_state_for_gimbal_device_t, vx) }, \
{ "vy", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_autopilot_state_for_gimbal_device_t, vy) }, \
{ "vz", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_autopilot_state_for_gimbal_device_t, vz) }, \
{ "v_estimated_delay_us", NULL, MAVLINK_TYPE_UINT32_T, 0, 40, offsetof(mavlink_autopilot_state_for_gimbal_device_t, v_estimated_delay_us) }, \
{ "feed_forward_angular_velocity_z", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_autopilot_state_for_gimbal_device_t, feed_forward_angular_velocity_z) }, \
{ "estimator_status", NULL, MAVLINK_TYPE_UINT16_T, 0, 48, offsetof(mavlink_autopilot_state_for_gimbal_device_t, estimator_status) }, \
{ "landed_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 52, offsetof(mavlink_autopilot_state_for_gimbal_device_t, landed_state) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE { \
"AUTOPILOT_STATE_FOR_GIMBAL_DEVICE", \
12, \
{ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 50, offsetof(mavlink_autopilot_state_for_gimbal_device_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 51, offsetof(mavlink_autopilot_state_for_gimbal_device_t, target_component) }, \
{ "time_boot_us", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_autopilot_state_for_gimbal_device_t, time_boot_us) }, \
{ "q", NULL, MAVLINK_TYPE_FLOAT, 4, 8, offsetof(mavlink_autopilot_state_for_gimbal_device_t, q) }, \
{ "q_estimated_delay_us", NULL, MAVLINK_TYPE_UINT32_T, 0, 24, offsetof(mavlink_autopilot_state_for_gimbal_device_t, q_estimated_delay_us) }, \
{ "vx", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_autopilot_state_for_gimbal_device_t, vx) }, \
{ "vy", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_autopilot_state_for_gimbal_device_t, vy) }, \
{ "vz", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_autopilot_state_for_gimbal_device_t, vz) }, \
{ "v_estimated_delay_us", NULL, MAVLINK_TYPE_UINT32_T, 0, 40, offsetof(mavlink_autopilot_state_for_gimbal_device_t, v_estimated_delay_us) }, \
{ "feed_forward_angular_velocity_z", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_autopilot_state_for_gimbal_device_t, feed_forward_angular_velocity_z) }, \
{ "estimator_status", NULL, MAVLINK_TYPE_UINT16_T, 0, 48, offsetof(mavlink_autopilot_state_for_gimbal_device_t, estimator_status) }, \
{ "landed_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 52, offsetof(mavlink_autopilot_state_for_gimbal_device_t, landed_state) }, \
} \
}
#endif
/**
* @brief Pack a autopilot_state_for_gimbal_device message
* @param system_id ID of this 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 time_boot_us [us] Timestamp (time since system boot).
* @param q Quaternion components of autopilot attitude: w, x, y, z (1 0 0 0 is the null-rotation, Hamilton convention).
* @param q_estimated_delay_us [us] Estimated delay of the attitude data.
* @param vx [m/s] X Speed in NED (North, East, Down).
* @param vy [m/s] Y Speed in NED (North, East, Down).
* @param vz [m/s] Z Speed in NED (North, East, Down).
* @param v_estimated_delay_us [us] Estimated delay of the speed data.
* @param feed_forward_angular_velocity_z [rad/s] Feed forward Z component of angular velocity, positive is yawing to the right, NaN to be ignored. This is to indicate if the autopilot is actively yawing.
* @param estimator_status Bitmap indicating which estimator outputs are valid.
* @param landed_state The landed state. Is set to MAV_LANDED_STATE_UNDEFINED if landed state is unknown.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_autopilot_state_for_gimbal_device_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t target_system, uint8_t target_component, uint64_t time_boot_us, const float *q, uint32_t q_estimated_delay_us, float vx, float vy, float vz, uint32_t v_estimated_delay_us, float feed_forward_angular_velocity_z, uint16_t estimator_status, uint8_t landed_state)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_LEN];
_mav_put_uint64_t(buf, 0, time_boot_us);
_mav_put_uint32_t(buf, 24, q_estimated_delay_us);
_mav_put_float(buf, 28, vx);
_mav_put_float(buf, 32, vy);
_mav_put_float(buf, 36, vz);
_mav_put_uint32_t(buf, 40, v_estimated_delay_us);
_mav_put_float(buf, 44, feed_forward_angular_velocity_z);
_mav_put_uint16_t(buf, 48, estimator_status);
_mav_put_uint8_t(buf, 50, target_system);
_mav_put_uint8_t(buf, 51, target_component);
_mav_put_uint8_t(buf, 52, landed_state);
_mav_put_float_array(buf, 8, q, 4);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_LEN);
#else
mavlink_autopilot_state_for_gimbal_device_t packet;
packet.time_boot_us = time_boot_us;
packet.q_estimated_delay_us = q_estimated_delay_us;
packet.vx = vx;
packet.vy = vy;
packet.vz = vz;
packet.v_estimated_delay_us = v_estimated_delay_us;
packet.feed_forward_angular_velocity_z = feed_forward_angular_velocity_z;
packet.estimator_status = estimator_status;
packet.target_system = target_system;
packet.target_component = target_component;
packet.landed_state = landed_state;
mav_array_memcpy(packet.q, q, sizeof(float)*4);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE;
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_MIN_LEN, MAVLINK_MSG_ID_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_LEN, MAVLINK_MSG_ID_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_CRC);
}
/**
* @brief Pack a autopilot_state_for_gimbal_device message on a channel
* @param system_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 time_boot_us [us] Timestamp (time since system boot).
* @param q Quaternion components of autopilot attitude: w, x, y, z (1 0 0 0 is the null-rotation, Hamilton convention).
* @param q_estimated_delay_us [us] Estimated delay of the attitude data.
* @param vx [m/s] X Speed in NED (North, East, Down).
* @param vy [m/s] Y Speed in NED (North, East, Down).
* @param vz [m/s] Z Speed in NED (North, East, Down).
* @param v_estimated_delay_us [us] Estimated delay of the speed data.
* @param feed_forward_angular_velocity_z [rad/s] Feed forward Z component of angular velocity, positive is yawing to the right, NaN to be ignored. This is to indicate if the autopilot is actively yawing.
* @param estimator_status Bitmap indicating which estimator outputs are valid.
* @param landed_state The landed state. Is set to MAV_LANDED_STATE_UNDEFINED if landed state is unknown.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_autopilot_state_for_gimbal_device_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,uint64_t time_boot_us,const float *q,uint32_t q_estimated_delay_us,float vx,float vy,float vz,uint32_t v_estimated_delay_us,float feed_forward_angular_velocity_z,uint16_t estimator_status,uint8_t landed_state)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_LEN];
_mav_put_uint64_t(buf, 0, time_boot_us);
_mav_put_uint32_t(buf, 24, q_estimated_delay_us);
_mav_put_float(buf, 28, vx);
_mav_put_float(buf, 32, vy);
_mav_put_float(buf, 36, vz);
_mav_put_uint32_t(buf, 40, v_estimated_delay_us);
_mav_put_float(buf, 44, feed_forward_angular_velocity_z);
_mav_put_uint16_t(buf, 48, estimator_status);
_mav_put_uint8_t(buf, 50, target_system);
_mav_put_uint8_t(buf, 51, target_component);
_mav_put_uint8_t(buf, 52, landed_state);
_mav_put_float_array(buf, 8, q, 4);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_LEN);
#else
mavlink_autopilot_state_for_gimbal_device_t packet;
packet.time_boot_us = time_boot_us;
packet.q_estimated_delay_us = q_estimated_delay_us;
packet.vx = vx;
packet.vy = vy;
packet.vz = vz;
packet.v_estimated_delay_us = v_estimated_delay_us;
packet.feed_forward_angular_velocity_z = feed_forward_angular_velocity_z;
packet.estimator_status = estimator_status;
packet.target_system = target_system;
packet.target_component = target_component;
packet.landed_state = landed_state;
mav_array_memcpy(packet.q, q, sizeof(float)*4);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_MIN_LEN, MAVLINK_MSG_ID_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_LEN, MAVLINK_MSG_ID_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_CRC);
}
/**
* @brief Encode a autopilot_state_for_gimbal_device 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_state_for_gimbal_device C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_autopilot_state_for_gimbal_device_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_autopilot_state_for_gimbal_device_t* autopilot_state_for_gimbal_device)
{
return mavlink_msg_autopilot_state_for_gimbal_device_pack(system_id, component_id, msg, autopilot_state_for_gimbal_device->target_system, autopilot_state_for_gimbal_device->target_component, autopilot_state_for_gimbal_device->time_boot_us, autopilot_state_for_gimbal_device->q, autopilot_state_for_gimbal_device->q_estimated_delay_us, autopilot_state_for_gimbal_device->vx, autopilot_state_for_gimbal_device->vy, autopilot_state_for_gimbal_device->vz, autopilot_state_for_gimbal_device->v_estimated_delay_us, autopilot_state_for_gimbal_device->feed_forward_angular_velocity_z, autopilot_state_for_gimbal_device->estimator_status, autopilot_state_for_gimbal_device->landed_state);
}
/**
* @brief Encode a autopilot_state_for_gimbal_device 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_state_for_gimbal_device C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_autopilot_state_for_gimbal_device_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_autopilot_state_for_gimbal_device_t* autopilot_state_for_gimbal_device)
{
return mavlink_msg_autopilot_state_for_gimbal_device_pack_chan(system_id, component_id, chan, msg, autopilot_state_for_gimbal_device->target_system, autopilot_state_for_gimbal_device->target_component, autopilot_state_for_gimbal_device->time_boot_us, autopilot_state_for_gimbal_device->q, autopilot_state_for_gimbal_device->q_estimated_delay_us, autopilot_state_for_gimbal_device->vx, autopilot_state_for_gimbal_device->vy, autopilot_state_for_gimbal_device->vz, autopilot_state_for_gimbal_device->v_estimated_delay_us, autopilot_state_for_gimbal_device->feed_forward_angular_velocity_z, autopilot_state_for_gimbal_device->estimator_status, autopilot_state_for_gimbal_device->landed_state);
}
/**
* @brief Send a autopilot_state_for_gimbal_device message
* @param chan MAVLink channel to send the message
*
* @param target_system System ID
* @param target_component Component ID
* @param time_boot_us [us] Timestamp (time since system boot).
* @param q Quaternion components of autopilot attitude: w, x, y, z (1 0 0 0 is the null-rotation, Hamilton convention).
* @param q_estimated_delay_us [us] Estimated delay of the attitude data.
* @param vx [m/s] X Speed in NED (North, East, Down).
* @param vy [m/s] Y Speed in NED (North, East, Down).
* @param vz [m/s] Z Speed in NED (North, East, Down).
* @param v_estimated_delay_us [us] Estimated delay of the speed data.
* @param feed_forward_angular_velocity_z [rad/s] Feed forward Z component of angular velocity, positive is yawing to the right, NaN to be ignored. This is to indicate if the autopilot is actively yawing.
* @param estimator_status Bitmap indicating which estimator outputs are valid.
* @param landed_state The landed state. Is set to MAV_LANDED_STATE_UNDEFINED if landed state is unknown.
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_autopilot_state_for_gimbal_device_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint64_t time_boot_us, const float *q, uint32_t q_estimated_delay_us, float vx, float vy, float vz, uint32_t v_estimated_delay_us, float feed_forward_angular_velocity_z, uint16_t estimator_status, uint8_t landed_state)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_LEN];
_mav_put_uint64_t(buf, 0, time_boot_us);
_mav_put_uint32_t(buf, 24, q_estimated_delay_us);
_mav_put_float(buf, 28, vx);
_mav_put_float(buf, 32, vy);
_mav_put_float(buf, 36, vz);
_mav_put_uint32_t(buf, 40, v_estimated_delay_us);
_mav_put_float(buf, 44, feed_forward_angular_velocity_z);
_mav_put_uint16_t(buf, 48, estimator_status);
_mav_put_uint8_t(buf, 50, target_system);
_mav_put_uint8_t(buf, 51, target_component);
_mav_put_uint8_t(buf, 52, landed_state);
_mav_put_float_array(buf, 8, q, 4);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE, buf, MAVLINK_MSG_ID_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_MIN_LEN, MAVLINK_MSG_ID_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_LEN, MAVLINK_MSG_ID_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_CRC);
#else
mavlink_autopilot_state_for_gimbal_device_t packet;
packet.time_boot_us = time_boot_us;
packet.q_estimated_delay_us = q_estimated_delay_us;
packet.vx = vx;
packet.vy = vy;
packet.vz = vz;
packet.v_estimated_delay_us = v_estimated_delay_us;
packet.feed_forward_angular_velocity_z = feed_forward_angular_velocity_z;
packet.estimator_status = estimator_status;
packet.target_system = target_system;
packet.target_component = target_component;
packet.landed_state = landed_state;
mav_array_memcpy(packet.q, q, sizeof(float)*4);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE, (const char *)&packet, MAVLINK_MSG_ID_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_MIN_LEN, MAVLINK_MSG_ID_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_LEN, MAVLINK_MSG_ID_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_CRC);
#endif
}
/**
* @brief Send a autopilot_state_for_gimbal_device message
* @param chan MAVLink channel to send the message
* @param struct The MAVLink struct to serialize
*/
static inline void mavlink_msg_autopilot_state_for_gimbal_device_send_struct(mavlink_channel_t chan, const mavlink_autopilot_state_for_gimbal_device_t* autopilot_state_for_gimbal_device)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mavlink_msg_autopilot_state_for_gimbal_device_send(chan, autopilot_state_for_gimbal_device->target_system, autopilot_state_for_gimbal_device->target_component, autopilot_state_for_gimbal_device->time_boot_us, autopilot_state_for_gimbal_device->q, autopilot_state_for_gimbal_device->q_estimated_delay_us, autopilot_state_for_gimbal_device->vx, autopilot_state_for_gimbal_device->vy, autopilot_state_for_gimbal_device->vz, autopilot_state_for_gimbal_device->v_estimated_delay_us, autopilot_state_for_gimbal_device->feed_forward_angular_velocity_z, autopilot_state_for_gimbal_device->estimator_status, autopilot_state_for_gimbal_device->landed_state);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE, (const char *)autopilot_state_for_gimbal_device, MAVLINK_MSG_ID_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_MIN_LEN, MAVLINK_MSG_ID_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_LEN, MAVLINK_MSG_ID_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_CRC);
#endif
}
#if MAVLINK_MSG_ID_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_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_state_for_gimbal_device_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint64_t time_boot_us, const float *q, uint32_t q_estimated_delay_us, float vx, float vy, float vz, uint32_t v_estimated_delay_us, float feed_forward_angular_velocity_z, uint16_t estimator_status, uint8_t landed_state)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
_mav_put_uint64_t(buf, 0, time_boot_us);
_mav_put_uint32_t(buf, 24, q_estimated_delay_us);
_mav_put_float(buf, 28, vx);
_mav_put_float(buf, 32, vy);
_mav_put_float(buf, 36, vz);
_mav_put_uint32_t(buf, 40, v_estimated_delay_us);
_mav_put_float(buf, 44, feed_forward_angular_velocity_z);
_mav_put_uint16_t(buf, 48, estimator_status);
_mav_put_uint8_t(buf, 50, target_system);
_mav_put_uint8_t(buf, 51, target_component);
_mav_put_uint8_t(buf, 52, landed_state);
_mav_put_float_array(buf, 8, q, 4);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE, buf, MAVLINK_MSG_ID_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_MIN_LEN, MAVLINK_MSG_ID_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_LEN, MAVLINK_MSG_ID_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_CRC);
#else
mavlink_autopilot_state_for_gimbal_device_t *packet = (mavlink_autopilot_state_for_gimbal_device_t *)msgbuf;
packet->time_boot_us = time_boot_us;
packet->q_estimated_delay_us = q_estimated_delay_us;
packet->vx = vx;
packet->vy = vy;
packet->vz = vz;
packet->v_estimated_delay_us = v_estimated_delay_us;
packet->feed_forward_angular_velocity_z = feed_forward_angular_velocity_z;
packet->estimator_status = estimator_status;
packet->target_system = target_system;
packet->target_component = target_component;
packet->landed_state = landed_state;
mav_array_memcpy(packet->q, q, sizeof(float)*4);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE, (const char *)packet, MAVLINK_MSG_ID_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_MIN_LEN, MAVLINK_MSG_ID_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_LEN, MAVLINK_MSG_ID_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_CRC);
#endif
}
#endif
#endif
// MESSAGE AUTOPILOT_STATE_FOR_GIMBAL_DEVICE UNPACKING
/**
* @brief Get field target_system from autopilot_state_for_gimbal_device message
*
* @return System ID
*/
static inline uint8_t mavlink_msg_autopilot_state_for_gimbal_device_get_target_system(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 50);
}
/**
* @brief Get field target_component from autopilot_state_for_gimbal_device message
*
* @return Component ID
*/
static inline uint8_t mavlink_msg_autopilot_state_for_gimbal_device_get_target_component(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 51);
}
/**
* @brief Get field time_boot_us from autopilot_state_for_gimbal_device message
*
* @return [us] Timestamp (time since system boot).
*/
static inline uint64_t mavlink_msg_autopilot_state_for_gimbal_device_get_time_boot_us(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint64_t(msg, 0);
}
/**
* @brief Get field q from autopilot_state_for_gimbal_device message
*
* @return Quaternion components of autopilot attitude: w, x, y, z (1 0 0 0 is the null-rotation, Hamilton convention).
*/
static inline uint16_t mavlink_msg_autopilot_state_for_gimbal_device_get_q(const mavlink_message_t* msg, float *q)
{
return _MAV_RETURN_float_array(msg, q, 4, 8);
}
/**
* @brief Get field q_estimated_delay_us from autopilot_state_for_gimbal_device message
*
* @return [us] Estimated delay of the attitude data.
*/
static inline uint32_t mavlink_msg_autopilot_state_for_gimbal_device_get_q_estimated_delay_us(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint32_t(msg, 24);
}
/**
* @brief Get field vx from autopilot_state_for_gimbal_device message
*
* @return [m/s] X Speed in NED (North, East, Down).
*/
static inline float mavlink_msg_autopilot_state_for_gimbal_device_get_vx(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 28);
}
/**
* @brief Get field vy from autopilot_state_for_gimbal_device message
*
* @return [m/s] Y Speed in NED (North, East, Down).
*/
static inline float mavlink_msg_autopilot_state_for_gimbal_device_get_vy(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 32);
}
/**
* @brief Get field vz from autopilot_state_for_gimbal_device message
*
* @return [m/s] Z Speed in NED (North, East, Down).
*/
static inline float mavlink_msg_autopilot_state_for_gimbal_device_get_vz(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 36);
}
/**
* @brief Get field v_estimated_delay_us from autopilot_state_for_gimbal_device message
*
* @return [us] Estimated delay of the speed data.
*/
static inline uint32_t mavlink_msg_autopilot_state_for_gimbal_device_get_v_estimated_delay_us(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint32_t(msg, 40);
}
/**
* @brief Get field feed_forward_angular_velocity_z from autopilot_state_for_gimbal_device message
*
* @return [rad/s] Feed forward Z component of angular velocity, positive is yawing to the right, NaN to be ignored. This is to indicate if the autopilot is actively yawing.
*/
static inline float mavlink_msg_autopilot_state_for_gimbal_device_get_feed_forward_angular_velocity_z(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 44);
}
/**
* @brief Get field estimator_status from autopilot_state_for_gimbal_device message
*
* @return Bitmap indicating which estimator outputs are valid.
*/
static inline uint16_t mavlink_msg_autopilot_state_for_gimbal_device_get_estimator_status(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 48);
}
/**
* @brief Get field landed_state from autopilot_state_for_gimbal_device message
*
* @return The landed state. Is set to MAV_LANDED_STATE_UNDEFINED if landed state is unknown.
*/
static inline uint8_t mavlink_msg_autopilot_state_for_gimbal_device_get_landed_state(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 52);
}
/**
* @brief Decode a autopilot_state_for_gimbal_device message into a struct
*
* @param msg The message to decode
* @param autopilot_state_for_gimbal_device C-struct to decode the message contents into
*/
static inline void mavlink_msg_autopilot_state_for_gimbal_device_decode(const mavlink_message_t* msg, mavlink_autopilot_state_for_gimbal_device_t* autopilot_state_for_gimbal_device)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
autopilot_state_for_gimbal_device->time_boot_us = mavlink_msg_autopilot_state_for_gimbal_device_get_time_boot_us(msg);
mavlink_msg_autopilot_state_for_gimbal_device_get_q(msg, autopilot_state_for_gimbal_device->q);
autopilot_state_for_gimbal_device->q_estimated_delay_us = mavlink_msg_autopilot_state_for_gimbal_device_get_q_estimated_delay_us(msg);
autopilot_state_for_gimbal_device->vx = mavlink_msg_autopilot_state_for_gimbal_device_get_vx(msg);
autopilot_state_for_gimbal_device->vy = mavlink_msg_autopilot_state_for_gimbal_device_get_vy(msg);
autopilot_state_for_gimbal_device->vz = mavlink_msg_autopilot_state_for_gimbal_device_get_vz(msg);
autopilot_state_for_gimbal_device->v_estimated_delay_us = mavlink_msg_autopilot_state_for_gimbal_device_get_v_estimated_delay_us(msg);
autopilot_state_for_gimbal_device->feed_forward_angular_velocity_z = mavlink_msg_autopilot_state_for_gimbal_device_get_feed_forward_angular_velocity_z(msg);
autopilot_state_for_gimbal_device->estimator_status = mavlink_msg_autopilot_state_for_gimbal_device_get_estimator_status(msg);
autopilot_state_for_gimbal_device->target_system = mavlink_msg_autopilot_state_for_gimbal_device_get_target_system(msg);
autopilot_state_for_gimbal_device->target_component = mavlink_msg_autopilot_state_for_gimbal_device_get_target_component(msg);
autopilot_state_for_gimbal_device->landed_state = mavlink_msg_autopilot_state_for_gimbal_device_get_landed_state(msg);
#else
uint8_t len = msg->len < MAVLINK_MSG_ID_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_LEN? msg->len : MAVLINK_MSG_ID_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_LEN;
memset(autopilot_state_for_gimbal_device, 0, MAVLINK_MSG_ID_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE_LEN);
memcpy(autopilot_state_for_gimbal_device, _MAV_PAYLOAD(msg), len);
#endif
}

View file

@ -16,11 +16,12 @@ typedef struct __mavlink_autopilot_version_t {
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.*/
uint8_t uid2[18]; /*< UID if provided by hardware (supersedes the uid field. If this is non-zero, use this field, otherwise use uid)*/
} mavlink_autopilot_version_t;
#define MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN 60
#define MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN 78
#define MAVLINK_MSG_ID_AUTOPILOT_VERSION_MIN_LEN 60
#define MAVLINK_MSG_ID_148_LEN 60
#define MAVLINK_MSG_ID_148_LEN 78
#define MAVLINK_MSG_ID_148_MIN_LEN 60
#define MAVLINK_MSG_ID_AUTOPILOT_VERSION_CRC 178
@ -29,12 +30,13 @@ typedef struct __mavlink_autopilot_version_t {
#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_MSG_AUTOPILOT_VERSION_FIELD_UID2_LEN 18
#if MAVLINK_COMMAND_24BIT
#define MAVLINK_MESSAGE_INFO_AUTOPILOT_VERSION { \
148, \
"AUTOPILOT_VERSION", \
11, \
12, \
{ { "capabilities", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_autopilot_version_t, capabilities) }, \
{ "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) }, \
@ -46,12 +48,13 @@ typedef struct __mavlink_autopilot_version_t {
{ "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) }, \
{ "uid", NULL, MAVLINK_TYPE_UINT64_T, 0, 8, offsetof(mavlink_autopilot_version_t, uid) }, \
{ "uid2", NULL, MAVLINK_TYPE_UINT8_T, 18, 60, offsetof(mavlink_autopilot_version_t, uid2) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_AUTOPILOT_VERSION { \
"AUTOPILOT_VERSION", \
11, \
12, \
{ { "capabilities", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_autopilot_version_t, capabilities) }, \
{ "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) }, \
@ -63,6 +66,7 @@ typedef struct __mavlink_autopilot_version_t {
{ "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) }, \
{ "uid", NULL, MAVLINK_TYPE_UINT64_T, 0, 8, offsetof(mavlink_autopilot_version_t, uid) }, \
{ "uid2", NULL, MAVLINK_TYPE_UINT8_T, 18, 60, offsetof(mavlink_autopilot_version_t, uid2) }, \
} \
}
#endif
@ -84,10 +88,11 @@ typedef struct __mavlink_autopilot_version_t {
* @param vendor_id ID of the board vendor
* @param product_id ID of the product
* @param uid UID if provided by hardware (see uid2)
* @param uid2 UID if provided by hardware (supersedes the uid field. If this is non-zero, use this field, otherwise use uid)
* @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)
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, const uint8_t *uid2)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN];
@ -102,6 +107,7 @@ static inline uint16_t mavlink_msg_autopilot_version_pack(uint8_t system_id, uin
_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);
_mav_put_uint8_t_array(buf, 60, uid2, 18);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN);
#else
mavlink_autopilot_version_t packet;
@ -116,6 +122,7 @@ static inline uint16_t mavlink_msg_autopilot_version_pack(uint8_t system_id, uin
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);
mav_array_memcpy(packet.uid2, uid2, sizeof(uint8_t)*18);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN);
#endif
@ -140,11 +147,12 @@ static inline uint16_t mavlink_msg_autopilot_version_pack(uint8_t system_id, uin
* @param vendor_id ID of the board vendor
* @param product_id ID of the product
* @param uid UID if provided by hardware (see uid2)
* @param uid2 UID if provided by hardware (supersedes the uid field. If this is non-zero, use this field, otherwise use uid)
* @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)
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,const uint8_t *uid2)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN];
@ -159,6 +167,7 @@ static inline uint16_t mavlink_msg_autopilot_version_pack_chan(uint8_t system_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);
_mav_put_uint8_t_array(buf, 60, uid2, 18);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN);
#else
mavlink_autopilot_version_t packet;
@ -173,6 +182,7 @@ static inline uint16_t mavlink_msg_autopilot_version_pack_chan(uint8_t system_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);
mav_array_memcpy(packet.uid2, uid2, sizeof(uint8_t)*18);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN);
#endif
@ -190,7 +200,7 @@ static inline uint16_t mavlink_msg_autopilot_version_pack_chan(uint8_t system_id
*/
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);
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, autopilot_version->uid2);
}
/**
@ -204,7 +214,7 @@ static inline uint16_t mavlink_msg_autopilot_version_encode(uint8_t system_id, u
*/
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);
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, autopilot_version->uid2);
}
/**
@ -222,10 +232,11 @@ static inline uint16_t mavlink_msg_autopilot_version_encode_chan(uint8_t system_
* @param vendor_id ID of the board vendor
* @param product_id ID of the product
* @param uid UID if provided by hardware (see uid2)
* @param uid2 UID if provided by hardware (supersedes the uid field. If this is non-zero, use this field, otherwise use uid)
*/
#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)
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, const uint8_t *uid2)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN];
@ -240,6 +251,7 @@ static inline void mavlink_msg_autopilot_version_send(mavlink_channel_t chan, ui
_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);
_mav_put_uint8_t_array(buf, 60, uid2, 18);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTOPILOT_VERSION, buf, MAVLINK_MSG_ID_AUTOPILOT_VERSION_MIN_LEN, MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN, MAVLINK_MSG_ID_AUTOPILOT_VERSION_CRC);
#else
mavlink_autopilot_version_t packet;
@ -254,6 +266,7 @@ static inline void mavlink_msg_autopilot_version_send(mavlink_channel_t chan, ui
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);
mav_array_memcpy(packet.uid2, uid2, sizeof(uint8_t)*18);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTOPILOT_VERSION, (const char *)&packet, MAVLINK_MSG_ID_AUTOPILOT_VERSION_MIN_LEN, MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN, MAVLINK_MSG_ID_AUTOPILOT_VERSION_CRC);
#endif
}
@ -266,7 +279,7 @@ static inline void mavlink_msg_autopilot_version_send(mavlink_channel_t chan, ui
static inline void mavlink_msg_autopilot_version_send_struct(mavlink_channel_t chan, const mavlink_autopilot_version_t* autopilot_version)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mavlink_msg_autopilot_version_send(chan, 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);
mavlink_msg_autopilot_version_send(chan, 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, autopilot_version->uid2);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTOPILOT_VERSION, (const char *)autopilot_version, MAVLINK_MSG_ID_AUTOPILOT_VERSION_MIN_LEN, MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN, MAVLINK_MSG_ID_AUTOPILOT_VERSION_CRC);
#endif
@ -280,7 +293,7 @@ static inline void mavlink_msg_autopilot_version_send_struct(mavlink_channel_t c
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)
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, const uint8_t *uid2)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
@ -295,6 +308,7 @@ static inline void mavlink_msg_autopilot_version_send_buf(mavlink_message_t *msg
_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);
_mav_put_uint8_t_array(buf, 60, uid2, 18);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTOPILOT_VERSION, buf, MAVLINK_MSG_ID_AUTOPILOT_VERSION_MIN_LEN, MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN, MAVLINK_MSG_ID_AUTOPILOT_VERSION_CRC);
#else
mavlink_autopilot_version_t *packet = (mavlink_autopilot_version_t *)msgbuf;
@ -309,6 +323,7 @@ static inline void mavlink_msg_autopilot_version_send_buf(mavlink_message_t *msg
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);
mav_array_memcpy(packet->uid2, uid2, sizeof(uint8_t)*18);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_AUTOPILOT_VERSION, (const char *)packet, MAVLINK_MSG_ID_AUTOPILOT_VERSION_MIN_LEN, MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN, MAVLINK_MSG_ID_AUTOPILOT_VERSION_CRC);
#endif
}
@ -429,6 +444,16 @@ static inline uint64_t mavlink_msg_autopilot_version_get_uid(const mavlink_messa
return _MAV_RETURN_uint64_t(msg, 8);
}
/**
* @brief Get field uid2 from autopilot_version message
*
* @return UID if provided by hardware (supersedes the uid field. If this is non-zero, use this field, otherwise use uid)
*/
static inline uint16_t mavlink_msg_autopilot_version_get_uid2(const mavlink_message_t* msg, uint8_t *uid2)
{
return _MAV_RETURN_uint8_t_array(msg, uid2, 18, 60);
}
/**
* @brief Decode a autopilot_version message into a struct
*
@ -449,6 +474,7 @@ static inline void mavlink_msg_autopilot_version_decode(const mavlink_message_t*
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);
mavlink_msg_autopilot_version_get_uid2(msg, autopilot_version->uid2);
#else
uint8_t len = msg->len < MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN? msg->len : MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN;
memset(autopilot_version, 0, MAVLINK_MSG_ID_AUTOPILOT_VERSION_LEN);

View file

@ -3,7 +3,7 @@
#define MAVLINK_MSG_ID_BATTERY_STATUS 147
MAVPACKED(
typedef struct __mavlink_battery_status_t {
int32_t current_consumed; /*< [mAh] Consumed charge, -1: autopilot does not provide consumption estimate*/
int32_t energy_consumed; /*< [hJ] Consumed energy, -1: autopilot does not provide energy consumption estimate*/
@ -14,23 +14,29 @@ typedef struct __mavlink_battery_status_t {
uint8_t battery_function; /*< Function of the battery*/
uint8_t type; /*< Type (chemistry) of the battery*/
int8_t battery_remaining; /*< [%] Remaining battery energy. Values: [0-100], -1: autopilot does not estimate the remaining battery.*/
} mavlink_battery_status_t;
int32_t time_remaining; /*< [s] Remaining battery time, 0: autopilot does not provide remaining battery time estimate*/
uint8_t charge_state; /*< State for extent of discharge, provided by autopilot for warning or external reactions*/
uint16_t voltages_ext[4]; /*< [mV] Battery voltages for cells 11 to 14. Cells above the valid cell count for this battery should have a value of 0, where zero indicates not supported (note, this is different than for the voltages field and allows empty byte truncation). If the measured value is 0 then 1 should be sent instead.*/
uint8_t mode; /*< Battery mode. Default (0) is that battery mode reporting is not supported or battery is in normal-use mode.*/
uint32_t fault_bitmask; /*< Fault/health indications. These should be set when charge_state is MAV_BATTERY_CHARGE_STATE_FAILED or MAV_BATTERY_CHARGE_STATE_UNHEALTHY (if not, fault reporting is not supported).*/
}) mavlink_battery_status_t;
#define MAVLINK_MSG_ID_BATTERY_STATUS_LEN 36
#define MAVLINK_MSG_ID_BATTERY_STATUS_LEN 54
#define MAVLINK_MSG_ID_BATTERY_STATUS_MIN_LEN 36
#define MAVLINK_MSG_ID_147_LEN 36
#define MAVLINK_MSG_ID_147_LEN 54
#define MAVLINK_MSG_ID_147_MIN_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_MSG_BATTERY_STATUS_FIELD_VOLTAGES_EXT_LEN 4
#if MAVLINK_COMMAND_24BIT
#define MAVLINK_MESSAGE_INFO_BATTERY_STATUS { \
147, \
"BATTERY_STATUS", \
9, \
14, \
{ { "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) }, \
@ -40,12 +46,17 @@ typedef struct __mavlink_battery_status_t {
{ "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) }, \
{ "battery_remaining", NULL, MAVLINK_TYPE_INT8_T, 0, 35, offsetof(mavlink_battery_status_t, battery_remaining) }, \
{ "time_remaining", NULL, MAVLINK_TYPE_INT32_T, 0, 36, offsetof(mavlink_battery_status_t, time_remaining) }, \
{ "charge_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 40, offsetof(mavlink_battery_status_t, charge_state) }, \
{ "voltages_ext", NULL, MAVLINK_TYPE_UINT16_T, 4, 41, offsetof(mavlink_battery_status_t, voltages_ext) }, \
{ "mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 49, offsetof(mavlink_battery_status_t, mode) }, \
{ "fault_bitmask", NULL, MAVLINK_TYPE_UINT32_T, 0, 50, offsetof(mavlink_battery_status_t, fault_bitmask) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_BATTERY_STATUS { \
"BATTERY_STATUS", \
9, \
14, \
{ { "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) }, \
@ -55,6 +66,11 @@ typedef struct __mavlink_battery_status_t {
{ "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) }, \
{ "battery_remaining", NULL, MAVLINK_TYPE_INT8_T, 0, 35, offsetof(mavlink_battery_status_t, battery_remaining) }, \
{ "time_remaining", NULL, MAVLINK_TYPE_INT32_T, 0, 36, offsetof(mavlink_battery_status_t, time_remaining) }, \
{ "charge_state", NULL, MAVLINK_TYPE_UINT8_T, 0, 40, offsetof(mavlink_battery_status_t, charge_state) }, \
{ "voltages_ext", NULL, MAVLINK_TYPE_UINT16_T, 4, 41, offsetof(mavlink_battery_status_t, voltages_ext) }, \
{ "mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 49, offsetof(mavlink_battery_status_t, mode) }, \
{ "fault_bitmask", NULL, MAVLINK_TYPE_UINT32_T, 0, 50, offsetof(mavlink_battery_status_t, fault_bitmask) }, \
} \
}
#endif
@ -74,10 +90,15 @@ typedef struct __mavlink_battery_status_t {
* @param current_consumed [mAh] Consumed charge, -1: autopilot does not provide consumption estimate
* @param energy_consumed [hJ] Consumed energy, -1: autopilot does not provide energy consumption estimate
* @param battery_remaining [%] Remaining battery energy. Values: [0-100], -1: autopilot does not estimate the remaining battery.
* @param time_remaining [s] Remaining battery time, 0: autopilot does not provide remaining battery time estimate
* @param charge_state State for extent of discharge, provided by autopilot for warning or external reactions
* @param voltages_ext [mV] Battery voltages for cells 11 to 14. Cells above the valid cell count for this battery should have a value of 0, where zero indicates not supported (note, this is different than for the voltages field and allows empty byte truncation). If the measured value is 0 then 1 should be sent instead.
* @param mode Battery mode. Default (0) is that battery mode reporting is not supported or battery is in normal-use mode.
* @param fault_bitmask Fault/health indications. These should be set when charge_state is MAV_BATTERY_CHARGE_STATE_FAILED or MAV_BATTERY_CHARGE_STATE_UNHEALTHY (if not, fault reporting is not supported).
* @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)
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, int32_t time_remaining, uint8_t charge_state, const uint16_t *voltages_ext, uint8_t mode, uint32_t fault_bitmask)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_BATTERY_STATUS_LEN];
@ -89,7 +110,12 @@ static inline uint16_t mavlink_msg_battery_status_pack(uint8_t system_id, uint8_
_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_int32_t(buf, 36, time_remaining);
_mav_put_uint8_t(buf, 40, charge_state);
_mav_put_uint8_t(buf, 49, mode);
_mav_put_uint32_t(buf, 50, fault_bitmask);
_mav_put_uint16_t_array(buf, 10, voltages, 10);
_mav_put_uint16_t_array(buf, 41, voltages_ext, 4);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_BATTERY_STATUS_LEN);
#else
mavlink_battery_status_t packet;
@ -101,7 +127,12 @@ static inline uint16_t mavlink_msg_battery_status_pack(uint8_t system_id, uint8_
packet.battery_function = battery_function;
packet.type = type;
packet.battery_remaining = battery_remaining;
packet.time_remaining = time_remaining;
packet.charge_state = charge_state;
packet.mode = mode;
packet.fault_bitmask = fault_bitmask;
mav_array_memcpy(packet.voltages, voltages, sizeof(uint16_t)*10);
mav_array_memcpy(packet.voltages_ext, voltages_ext, sizeof(uint16_t)*4);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_BATTERY_STATUS_LEN);
#endif
@ -124,11 +155,16 @@ static inline uint16_t mavlink_msg_battery_status_pack(uint8_t system_id, uint8_
* @param current_consumed [mAh] Consumed charge, -1: autopilot does not provide consumption estimate
* @param energy_consumed [hJ] Consumed energy, -1: autopilot does not provide energy consumption estimate
* @param battery_remaining [%] Remaining battery energy. Values: [0-100], -1: autopilot does not estimate the remaining battery.
* @param time_remaining [s] Remaining battery time, 0: autopilot does not provide remaining battery time estimate
* @param charge_state State for extent of discharge, provided by autopilot for warning or external reactions
* @param voltages_ext [mV] Battery voltages for cells 11 to 14. Cells above the valid cell count for this battery should have a value of 0, where zero indicates not supported (note, this is different than for the voltages field and allows empty byte truncation). If the measured value is 0 then 1 should be sent instead.
* @param mode Battery mode. Default (0) is that battery mode reporting is not supported or battery is in normal-use mode.
* @param fault_bitmask Fault/health indications. These should be set when charge_state is MAV_BATTERY_CHARGE_STATE_FAILED or MAV_BATTERY_CHARGE_STATE_UNHEALTHY (if not, fault reporting is not supported).
* @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)
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,int32_t time_remaining,uint8_t charge_state,const uint16_t *voltages_ext,uint8_t mode,uint32_t fault_bitmask)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_BATTERY_STATUS_LEN];
@ -140,7 +176,12 @@ static inline uint16_t mavlink_msg_battery_status_pack_chan(uint8_t system_id, u
_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_int32_t(buf, 36, time_remaining);
_mav_put_uint8_t(buf, 40, charge_state);
_mav_put_uint8_t(buf, 49, mode);
_mav_put_uint32_t(buf, 50, fault_bitmask);
_mav_put_uint16_t_array(buf, 10, voltages, 10);
_mav_put_uint16_t_array(buf, 41, voltages_ext, 4);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_BATTERY_STATUS_LEN);
#else
mavlink_battery_status_t packet;
@ -152,7 +193,12 @@ static inline uint16_t mavlink_msg_battery_status_pack_chan(uint8_t system_id, u
packet.battery_function = battery_function;
packet.type = type;
packet.battery_remaining = battery_remaining;
packet.time_remaining = time_remaining;
packet.charge_state = charge_state;
packet.mode = mode;
packet.fault_bitmask = fault_bitmask;
mav_array_memcpy(packet.voltages, voltages, sizeof(uint16_t)*10);
mav_array_memcpy(packet.voltages_ext, voltages_ext, sizeof(uint16_t)*4);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_BATTERY_STATUS_LEN);
#endif
@ -170,7 +216,7 @@ static inline uint16_t mavlink_msg_battery_status_pack_chan(uint8_t system_id, u
*/
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);
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, battery_status->time_remaining, battery_status->charge_state, battery_status->voltages_ext, battery_status->mode, battery_status->fault_bitmask);
}
/**
@ -184,7 +230,7 @@ static inline uint16_t mavlink_msg_battery_status_encode(uint8_t system_id, uint
*/
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);
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, battery_status->time_remaining, battery_status->charge_state, battery_status->voltages_ext, battery_status->mode, battery_status->fault_bitmask);
}
/**
@ -200,10 +246,15 @@ static inline uint16_t mavlink_msg_battery_status_encode_chan(uint8_t system_id,
* @param current_consumed [mAh] Consumed charge, -1: autopilot does not provide consumption estimate
* @param energy_consumed [hJ] Consumed energy, -1: autopilot does not provide energy consumption estimate
* @param battery_remaining [%] Remaining battery energy. Values: [0-100], -1: autopilot does not estimate the remaining battery.
* @param time_remaining [s] Remaining battery time, 0: autopilot does not provide remaining battery time estimate
* @param charge_state State for extent of discharge, provided by autopilot for warning or external reactions
* @param voltages_ext [mV] Battery voltages for cells 11 to 14. Cells above the valid cell count for this battery should have a value of 0, where zero indicates not supported (note, this is different than for the voltages field and allows empty byte truncation). If the measured value is 0 then 1 should be sent instead.
* @param mode Battery mode. Default (0) is that battery mode reporting is not supported or battery is in normal-use mode.
* @param fault_bitmask Fault/health indications. These should be set when charge_state is MAV_BATTERY_CHARGE_STATE_FAILED or MAV_BATTERY_CHARGE_STATE_UNHEALTHY (if not, fault reporting is not supported).
*/
#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)
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, int32_t time_remaining, uint8_t charge_state, const uint16_t *voltages_ext, uint8_t mode, uint32_t fault_bitmask)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_BATTERY_STATUS_LEN];
@ -215,7 +266,12 @@ static inline void mavlink_msg_battery_status_send(mavlink_channel_t chan, uint8
_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_int32_t(buf, 36, time_remaining);
_mav_put_uint8_t(buf, 40, charge_state);
_mav_put_uint8_t(buf, 49, mode);
_mav_put_uint32_t(buf, 50, fault_bitmask);
_mav_put_uint16_t_array(buf, 10, voltages, 10);
_mav_put_uint16_t_array(buf, 41, voltages_ext, 4);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_BATTERY_STATUS, buf, MAVLINK_MSG_ID_BATTERY_STATUS_MIN_LEN, MAVLINK_MSG_ID_BATTERY_STATUS_LEN, MAVLINK_MSG_ID_BATTERY_STATUS_CRC);
#else
mavlink_battery_status_t packet;
@ -227,7 +283,12 @@ static inline void mavlink_msg_battery_status_send(mavlink_channel_t chan, uint8
packet.battery_function = battery_function;
packet.type = type;
packet.battery_remaining = battery_remaining;
packet.time_remaining = time_remaining;
packet.charge_state = charge_state;
packet.mode = mode;
packet.fault_bitmask = fault_bitmask;
mav_array_memcpy(packet.voltages, voltages, sizeof(uint16_t)*10);
mav_array_memcpy(packet.voltages_ext, voltages_ext, sizeof(uint16_t)*4);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_BATTERY_STATUS, (const char *)&packet, MAVLINK_MSG_ID_BATTERY_STATUS_MIN_LEN, MAVLINK_MSG_ID_BATTERY_STATUS_LEN, MAVLINK_MSG_ID_BATTERY_STATUS_CRC);
#endif
}
@ -240,7 +301,7 @@ static inline void mavlink_msg_battery_status_send(mavlink_channel_t chan, uint8
static inline void mavlink_msg_battery_status_send_struct(mavlink_channel_t chan, const mavlink_battery_status_t* battery_status)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mavlink_msg_battery_status_send(chan, 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);
mavlink_msg_battery_status_send(chan, 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, battery_status->time_remaining, battery_status->charge_state, battery_status->voltages_ext, battery_status->mode, battery_status->fault_bitmask);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_BATTERY_STATUS, (const char *)battery_status, MAVLINK_MSG_ID_BATTERY_STATUS_MIN_LEN, MAVLINK_MSG_ID_BATTERY_STATUS_LEN, MAVLINK_MSG_ID_BATTERY_STATUS_CRC);
#endif
@ -254,7 +315,7 @@ static inline void mavlink_msg_battery_status_send_struct(mavlink_channel_t chan
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)
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, int32_t time_remaining, uint8_t charge_state, const uint16_t *voltages_ext, uint8_t mode, uint32_t fault_bitmask)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
@ -266,7 +327,12 @@ static inline void mavlink_msg_battery_status_send_buf(mavlink_message_t *msgbuf
_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_int32_t(buf, 36, time_remaining);
_mav_put_uint8_t(buf, 40, charge_state);
_mav_put_uint8_t(buf, 49, mode);
_mav_put_uint32_t(buf, 50, fault_bitmask);
_mav_put_uint16_t_array(buf, 10, voltages, 10);
_mav_put_uint16_t_array(buf, 41, voltages_ext, 4);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_BATTERY_STATUS, buf, MAVLINK_MSG_ID_BATTERY_STATUS_MIN_LEN, MAVLINK_MSG_ID_BATTERY_STATUS_LEN, MAVLINK_MSG_ID_BATTERY_STATUS_CRC);
#else
mavlink_battery_status_t *packet = (mavlink_battery_status_t *)msgbuf;
@ -278,7 +344,12 @@ static inline void mavlink_msg_battery_status_send_buf(mavlink_message_t *msgbuf
packet->battery_function = battery_function;
packet->type = type;
packet->battery_remaining = battery_remaining;
packet->time_remaining = time_remaining;
packet->charge_state = charge_state;
packet->mode = mode;
packet->fault_bitmask = fault_bitmask;
mav_array_memcpy(packet->voltages, voltages, sizeof(uint16_t)*10);
mav_array_memcpy(packet->voltages_ext, voltages_ext, sizeof(uint16_t)*4);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_BATTERY_STATUS, (const char *)packet, MAVLINK_MSG_ID_BATTERY_STATUS_MIN_LEN, MAVLINK_MSG_ID_BATTERY_STATUS_LEN, MAVLINK_MSG_ID_BATTERY_STATUS_CRC);
#endif
}
@ -379,6 +450,56 @@ static inline int8_t mavlink_msg_battery_status_get_battery_remaining(const mavl
return _MAV_RETURN_int8_t(msg, 35);
}
/**
* @brief Get field time_remaining from battery_status message
*
* @return [s] Remaining battery time, 0: autopilot does not provide remaining battery time estimate
*/
static inline int32_t mavlink_msg_battery_status_get_time_remaining(const mavlink_message_t* msg)
{
return _MAV_RETURN_int32_t(msg, 36);
}
/**
* @brief Get field charge_state from battery_status message
*
* @return State for extent of discharge, provided by autopilot for warning or external reactions
*/
static inline uint8_t mavlink_msg_battery_status_get_charge_state(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 40);
}
/**
* @brief Get field voltages_ext from battery_status message
*
* @return [mV] Battery voltages for cells 11 to 14. Cells above the valid cell count for this battery should have a value of 0, where zero indicates not supported (note, this is different than for the voltages field and allows empty byte truncation). If the measured value is 0 then 1 should be sent instead.
*/
static inline uint16_t mavlink_msg_battery_status_get_voltages_ext(const mavlink_message_t* msg, uint16_t *voltages_ext)
{
return _MAV_RETURN_uint16_t_array(msg, voltages_ext, 4, 41);
}
/**
* @brief Get field mode from battery_status message
*
* @return Battery mode. Default (0) is that battery mode reporting is not supported or battery is in normal-use mode.
*/
static inline uint8_t mavlink_msg_battery_status_get_mode(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 49);
}
/**
* @brief Get field fault_bitmask from battery_status message
*
* @return Fault/health indications. These should be set when charge_state is MAV_BATTERY_CHARGE_STATE_FAILED or MAV_BATTERY_CHARGE_STATE_UNHEALTHY (if not, fault reporting is not supported).
*/
static inline uint32_t mavlink_msg_battery_status_get_fault_bitmask(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint32_t(msg, 50);
}
/**
* @brief Decode a battery_status message into a struct
*
@ -397,6 +518,11 @@ static inline void mavlink_msg_battery_status_decode(const mavlink_message_t* ms
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);
battery_status->time_remaining = mavlink_msg_battery_status_get_time_remaining(msg);
battery_status->charge_state = mavlink_msg_battery_status_get_charge_state(msg);
mavlink_msg_battery_status_get_voltages_ext(msg, battery_status->voltages_ext);
battery_status->mode = mavlink_msg_battery_status_get_mode(msg);
battery_status->fault_bitmask = mavlink_msg_battery_status_get_fault_bitmask(msg);
#else
uint8_t len = msg->len < MAVLINK_MSG_ID_BATTERY_STATUS_LEN? msg->len : MAVLINK_MSG_ID_BATTERY_STATUS_LEN;
memset(battery_status, 0, MAVLINK_MSG_ID_BATTERY_STATUS_LEN);

View file

@ -0,0 +1,263 @@
#pragma once
// MESSAGE BUTTON_CHANGE PACKING
#define MAVLINK_MSG_ID_BUTTON_CHANGE 257
typedef struct __mavlink_button_change_t {
uint32_t time_boot_ms; /*< [ms] Timestamp (time since system boot).*/
uint32_t last_change_ms; /*< [ms] Time of last change of button state.*/
uint8_t state; /*< Bitmap for state of buttons.*/
} mavlink_button_change_t;
#define MAVLINK_MSG_ID_BUTTON_CHANGE_LEN 9
#define MAVLINK_MSG_ID_BUTTON_CHANGE_MIN_LEN 9
#define MAVLINK_MSG_ID_257_LEN 9
#define MAVLINK_MSG_ID_257_MIN_LEN 9
#define MAVLINK_MSG_ID_BUTTON_CHANGE_CRC 131
#define MAVLINK_MSG_ID_257_CRC 131
#if MAVLINK_COMMAND_24BIT
#define MAVLINK_MESSAGE_INFO_BUTTON_CHANGE { \
257, \
"BUTTON_CHANGE", \
3, \
{ { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_button_change_t, time_boot_ms) }, \
{ "last_change_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_button_change_t, last_change_ms) }, \
{ "state", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_button_change_t, state) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_BUTTON_CHANGE { \
"BUTTON_CHANGE", \
3, \
{ { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_button_change_t, time_boot_ms) }, \
{ "last_change_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_button_change_t, last_change_ms) }, \
{ "state", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_button_change_t, state) }, \
} \
}
#endif
/**
* @brief Pack a button_change message
* @param system_id ID of this 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 [ms] Timestamp (time since system boot).
* @param last_change_ms [ms] Time of last change of button state.
* @param state Bitmap for state of buttons.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_button_change_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint32_t time_boot_ms, uint32_t last_change_ms, uint8_t state)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_BUTTON_CHANGE_LEN];
_mav_put_uint32_t(buf, 0, time_boot_ms);
_mav_put_uint32_t(buf, 4, last_change_ms);
_mav_put_uint8_t(buf, 8, state);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_BUTTON_CHANGE_LEN);
#else
mavlink_button_change_t packet;
packet.time_boot_ms = time_boot_ms;
packet.last_change_ms = last_change_ms;
packet.state = state;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_BUTTON_CHANGE_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_BUTTON_CHANGE;
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_BUTTON_CHANGE_MIN_LEN, MAVLINK_MSG_ID_BUTTON_CHANGE_LEN, MAVLINK_MSG_ID_BUTTON_CHANGE_CRC);
}
/**
* @brief Pack a button_change message on a channel
* @param system_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 [ms] Timestamp (time since system boot).
* @param last_change_ms [ms] Time of last change of button state.
* @param state Bitmap for state of buttons.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_button_change_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint32_t time_boot_ms,uint32_t last_change_ms,uint8_t state)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_BUTTON_CHANGE_LEN];
_mav_put_uint32_t(buf, 0, time_boot_ms);
_mav_put_uint32_t(buf, 4, last_change_ms);
_mav_put_uint8_t(buf, 8, state);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_BUTTON_CHANGE_LEN);
#else
mavlink_button_change_t packet;
packet.time_boot_ms = time_boot_ms;
packet.last_change_ms = last_change_ms;
packet.state = state;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_BUTTON_CHANGE_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_BUTTON_CHANGE;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_BUTTON_CHANGE_MIN_LEN, MAVLINK_MSG_ID_BUTTON_CHANGE_LEN, MAVLINK_MSG_ID_BUTTON_CHANGE_CRC);
}
/**
* @brief Encode a button_change 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 button_change C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_button_change_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_button_change_t* button_change)
{
return mavlink_msg_button_change_pack(system_id, component_id, msg, button_change->time_boot_ms, button_change->last_change_ms, button_change->state);
}
/**
* @brief Encode a button_change 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 button_change C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_button_change_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_button_change_t* button_change)
{
return mavlink_msg_button_change_pack_chan(system_id, component_id, chan, msg, button_change->time_boot_ms, button_change->last_change_ms, button_change->state);
}
/**
* @brief Send a button_change message
* @param chan MAVLink channel to send the message
*
* @param time_boot_ms [ms] Timestamp (time since system boot).
* @param last_change_ms [ms] Time of last change of button state.
* @param state Bitmap for state of buttons.
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_button_change_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint32_t last_change_ms, uint8_t state)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_BUTTON_CHANGE_LEN];
_mav_put_uint32_t(buf, 0, time_boot_ms);
_mav_put_uint32_t(buf, 4, last_change_ms);
_mav_put_uint8_t(buf, 8, state);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_BUTTON_CHANGE, buf, MAVLINK_MSG_ID_BUTTON_CHANGE_MIN_LEN, MAVLINK_MSG_ID_BUTTON_CHANGE_LEN, MAVLINK_MSG_ID_BUTTON_CHANGE_CRC);
#else
mavlink_button_change_t packet;
packet.time_boot_ms = time_boot_ms;
packet.last_change_ms = last_change_ms;
packet.state = state;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_BUTTON_CHANGE, (const char *)&packet, MAVLINK_MSG_ID_BUTTON_CHANGE_MIN_LEN, MAVLINK_MSG_ID_BUTTON_CHANGE_LEN, MAVLINK_MSG_ID_BUTTON_CHANGE_CRC);
#endif
}
/**
* @brief Send a button_change message
* @param chan MAVLink channel to send the message
* @param struct The MAVLink struct to serialize
*/
static inline void mavlink_msg_button_change_send_struct(mavlink_channel_t chan, const mavlink_button_change_t* button_change)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mavlink_msg_button_change_send(chan, button_change->time_boot_ms, button_change->last_change_ms, button_change->state);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_BUTTON_CHANGE, (const char *)button_change, MAVLINK_MSG_ID_BUTTON_CHANGE_MIN_LEN, MAVLINK_MSG_ID_BUTTON_CHANGE_LEN, MAVLINK_MSG_ID_BUTTON_CHANGE_CRC);
#endif
}
#if MAVLINK_MSG_ID_BUTTON_CHANGE_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_button_change_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, uint32_t last_change_ms, uint8_t state)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
_mav_put_uint32_t(buf, 0, time_boot_ms);
_mav_put_uint32_t(buf, 4, last_change_ms);
_mav_put_uint8_t(buf, 8, state);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_BUTTON_CHANGE, buf, MAVLINK_MSG_ID_BUTTON_CHANGE_MIN_LEN, MAVLINK_MSG_ID_BUTTON_CHANGE_LEN, MAVLINK_MSG_ID_BUTTON_CHANGE_CRC);
#else
mavlink_button_change_t *packet = (mavlink_button_change_t *)msgbuf;
packet->time_boot_ms = time_boot_ms;
packet->last_change_ms = last_change_ms;
packet->state = state;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_BUTTON_CHANGE, (const char *)packet, MAVLINK_MSG_ID_BUTTON_CHANGE_MIN_LEN, MAVLINK_MSG_ID_BUTTON_CHANGE_LEN, MAVLINK_MSG_ID_BUTTON_CHANGE_CRC);
#endif
}
#endif
#endif
// MESSAGE BUTTON_CHANGE UNPACKING
/**
* @brief Get field time_boot_ms from button_change message
*
* @return [ms] Timestamp (time since system boot).
*/
static inline uint32_t mavlink_msg_button_change_get_time_boot_ms(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint32_t(msg, 0);
}
/**
* @brief Get field last_change_ms from button_change message
*
* @return [ms] Time of last change of button state.
*/
static inline uint32_t mavlink_msg_button_change_get_last_change_ms(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint32_t(msg, 4);
}
/**
* @brief Get field state from button_change message
*
* @return Bitmap for state of buttons.
*/
static inline uint8_t mavlink_msg_button_change_get_state(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 8);
}
/**
* @brief Decode a button_change message into a struct
*
* @param msg The message to decode
* @param button_change C-struct to decode the message contents into
*/
static inline void mavlink_msg_button_change_decode(const mavlink_message_t* msg, mavlink_button_change_t* button_change)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
button_change->time_boot_ms = mavlink_msg_button_change_get_time_boot_ms(msg);
button_change->last_change_ms = mavlink_msg_button_change_get_last_change_ms(msg);
button_change->state = mavlink_msg_button_change_get_state(msg);
#else
uint8_t len = msg->len < MAVLINK_MSG_ID_BUTTON_CHANGE_LEN? msg->len : MAVLINK_MSG_ID_BUTTON_CHANGE_LEN;
memset(button_change, 0, MAVLINK_MSG_ID_BUTTON_CHANGE_LEN);
memcpy(button_change, _MAV_PAYLOAD(msg), len);
#endif
}

View file

@ -0,0 +1,363 @@
#pragma once
// MESSAGE CAMERA_CAPTURE_STATUS PACKING
#define MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS 262
MAVPACKED(
typedef struct __mavlink_camera_capture_status_t {
uint32_t time_boot_ms; /*< [ms] Timestamp (time since system boot).*/
float image_interval; /*< [s] Image capture interval*/
uint32_t recording_time_ms; /*< [ms] Time since recording started*/
float available_capacity; /*< [MiB] Available storage capacity.*/
uint8_t image_status; /*< Current status of image capturing (0: idle, 1: capture in progress, 2: interval set but idle, 3: interval set and capture in progress)*/
uint8_t video_status; /*< Current status of video capturing (0: idle, 1: capture in progress)*/
int32_t image_count; /*< Total number of images captured ('forever', or until reset using MAV_CMD_STORAGE_FORMAT).*/
}) mavlink_camera_capture_status_t;
#define MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS_LEN 22
#define MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS_MIN_LEN 18
#define MAVLINK_MSG_ID_262_LEN 22
#define MAVLINK_MSG_ID_262_MIN_LEN 18
#define MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS_CRC 12
#define MAVLINK_MSG_ID_262_CRC 12
#if MAVLINK_COMMAND_24BIT
#define MAVLINK_MESSAGE_INFO_CAMERA_CAPTURE_STATUS { \
262, \
"CAMERA_CAPTURE_STATUS", \
7, \
{ { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_camera_capture_status_t, time_boot_ms) }, \
{ "image_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 16, offsetof(mavlink_camera_capture_status_t, image_status) }, \
{ "video_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 17, offsetof(mavlink_camera_capture_status_t, video_status) }, \
{ "image_interval", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_camera_capture_status_t, image_interval) }, \
{ "recording_time_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_camera_capture_status_t, recording_time_ms) }, \
{ "available_capacity", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_camera_capture_status_t, available_capacity) }, \
{ "image_count", NULL, MAVLINK_TYPE_INT32_T, 0, 18, offsetof(mavlink_camera_capture_status_t, image_count) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_CAMERA_CAPTURE_STATUS { \
"CAMERA_CAPTURE_STATUS", \
7, \
{ { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_camera_capture_status_t, time_boot_ms) }, \
{ "image_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 16, offsetof(mavlink_camera_capture_status_t, image_status) }, \
{ "video_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 17, offsetof(mavlink_camera_capture_status_t, video_status) }, \
{ "image_interval", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_camera_capture_status_t, image_interval) }, \
{ "recording_time_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_camera_capture_status_t, recording_time_ms) }, \
{ "available_capacity", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_camera_capture_status_t, available_capacity) }, \
{ "image_count", NULL, MAVLINK_TYPE_INT32_T, 0, 18, offsetof(mavlink_camera_capture_status_t, image_count) }, \
} \
}
#endif
/**
* @brief Pack a camera_capture_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 time_boot_ms [ms] Timestamp (time since system boot).
* @param image_status Current status of image capturing (0: idle, 1: capture in progress, 2: interval set but idle, 3: interval set and capture in progress)
* @param video_status Current status of video capturing (0: idle, 1: capture in progress)
* @param image_interval [s] Image capture interval
* @param recording_time_ms [ms] Time since recording started
* @param available_capacity [MiB] Available storage capacity.
* @param image_count Total number of images captured ('forever', or until reset using MAV_CMD_STORAGE_FORMAT).
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_camera_capture_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint32_t time_boot_ms, uint8_t image_status, uint8_t video_status, float image_interval, uint32_t recording_time_ms, float available_capacity, int32_t image_count)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS_LEN];
_mav_put_uint32_t(buf, 0, time_boot_ms);
_mav_put_float(buf, 4, image_interval);
_mav_put_uint32_t(buf, 8, recording_time_ms);
_mav_put_float(buf, 12, available_capacity);
_mav_put_uint8_t(buf, 16, image_status);
_mav_put_uint8_t(buf, 17, video_status);
_mav_put_int32_t(buf, 18, image_count);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS_LEN);
#else
mavlink_camera_capture_status_t packet;
packet.time_boot_ms = time_boot_ms;
packet.image_interval = image_interval;
packet.recording_time_ms = recording_time_ms;
packet.available_capacity = available_capacity;
packet.image_status = image_status;
packet.video_status = video_status;
packet.image_count = image_count;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS;
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS_MIN_LEN, MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS_LEN, MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS_CRC);
}
/**
* @brief Pack a camera_capture_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 time_boot_ms [ms] Timestamp (time since system boot).
* @param image_status Current status of image capturing (0: idle, 1: capture in progress, 2: interval set but idle, 3: interval set and capture in progress)
* @param video_status Current status of video capturing (0: idle, 1: capture in progress)
* @param image_interval [s] Image capture interval
* @param recording_time_ms [ms] Time since recording started
* @param available_capacity [MiB] Available storage capacity.
* @param image_count Total number of images captured ('forever', or until reset using MAV_CMD_STORAGE_FORMAT).
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_camera_capture_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint32_t time_boot_ms,uint8_t image_status,uint8_t video_status,float image_interval,uint32_t recording_time_ms,float available_capacity,int32_t image_count)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS_LEN];
_mav_put_uint32_t(buf, 0, time_boot_ms);
_mav_put_float(buf, 4, image_interval);
_mav_put_uint32_t(buf, 8, recording_time_ms);
_mav_put_float(buf, 12, available_capacity);
_mav_put_uint8_t(buf, 16, image_status);
_mav_put_uint8_t(buf, 17, video_status);
_mav_put_int32_t(buf, 18, image_count);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS_LEN);
#else
mavlink_camera_capture_status_t packet;
packet.time_boot_ms = time_boot_ms;
packet.image_interval = image_interval;
packet.recording_time_ms = recording_time_ms;
packet.available_capacity = available_capacity;
packet.image_status = image_status;
packet.video_status = video_status;
packet.image_count = image_count;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS_MIN_LEN, MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS_LEN, MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS_CRC);
}
/**
* @brief Encode a camera_capture_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 camera_capture_status C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_camera_capture_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_camera_capture_status_t* camera_capture_status)
{
return mavlink_msg_camera_capture_status_pack(system_id, component_id, msg, camera_capture_status->time_boot_ms, camera_capture_status->image_status, camera_capture_status->video_status, camera_capture_status->image_interval, camera_capture_status->recording_time_ms, camera_capture_status->available_capacity, camera_capture_status->image_count);
}
/**
* @brief Encode a camera_capture_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 camera_capture_status C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_camera_capture_status_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_camera_capture_status_t* camera_capture_status)
{
return mavlink_msg_camera_capture_status_pack_chan(system_id, component_id, chan, msg, camera_capture_status->time_boot_ms, camera_capture_status->image_status, camera_capture_status->video_status, camera_capture_status->image_interval, camera_capture_status->recording_time_ms, camera_capture_status->available_capacity, camera_capture_status->image_count);
}
/**
* @brief Send a camera_capture_status message
* @param chan MAVLink channel to send the message
*
* @param time_boot_ms [ms] Timestamp (time since system boot).
* @param image_status Current status of image capturing (0: idle, 1: capture in progress, 2: interval set but idle, 3: interval set and capture in progress)
* @param video_status Current status of video capturing (0: idle, 1: capture in progress)
* @param image_interval [s] Image capture interval
* @param recording_time_ms [ms] Time since recording started
* @param available_capacity [MiB] Available storage capacity.
* @param image_count Total number of images captured ('forever', or until reset using MAV_CMD_STORAGE_FORMAT).
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_camera_capture_status_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t image_status, uint8_t video_status, float image_interval, uint32_t recording_time_ms, float available_capacity, int32_t image_count)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS_LEN];
_mav_put_uint32_t(buf, 0, time_boot_ms);
_mav_put_float(buf, 4, image_interval);
_mav_put_uint32_t(buf, 8, recording_time_ms);
_mav_put_float(buf, 12, available_capacity);
_mav_put_uint8_t(buf, 16, image_status);
_mav_put_uint8_t(buf, 17, video_status);
_mav_put_int32_t(buf, 18, image_count);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS, buf, MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS_MIN_LEN, MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS_LEN, MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS_CRC);
#else
mavlink_camera_capture_status_t packet;
packet.time_boot_ms = time_boot_ms;
packet.image_interval = image_interval;
packet.recording_time_ms = recording_time_ms;
packet.available_capacity = available_capacity;
packet.image_status = image_status;
packet.video_status = video_status;
packet.image_count = image_count;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS, (const char *)&packet, MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS_MIN_LEN, MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS_LEN, MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS_CRC);
#endif
}
/**
* @brief Send a camera_capture_status message
* @param chan MAVLink channel to send the message
* @param struct The MAVLink struct to serialize
*/
static inline void mavlink_msg_camera_capture_status_send_struct(mavlink_channel_t chan, const mavlink_camera_capture_status_t* camera_capture_status)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mavlink_msg_camera_capture_status_send(chan, camera_capture_status->time_boot_ms, camera_capture_status->image_status, camera_capture_status->video_status, camera_capture_status->image_interval, camera_capture_status->recording_time_ms, camera_capture_status->available_capacity, camera_capture_status->image_count);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS, (const char *)camera_capture_status, MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS_MIN_LEN, MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS_LEN, MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS_CRC);
#endif
}
#if MAVLINK_MSG_ID_CAMERA_CAPTURE_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_camera_capture_status_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t image_status, uint8_t video_status, float image_interval, uint32_t recording_time_ms, float available_capacity, int32_t image_count)
{
#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, image_interval);
_mav_put_uint32_t(buf, 8, recording_time_ms);
_mav_put_float(buf, 12, available_capacity);
_mav_put_uint8_t(buf, 16, image_status);
_mav_put_uint8_t(buf, 17, video_status);
_mav_put_int32_t(buf, 18, image_count);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS, buf, MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS_MIN_LEN, MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS_LEN, MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS_CRC);
#else
mavlink_camera_capture_status_t *packet = (mavlink_camera_capture_status_t *)msgbuf;
packet->time_boot_ms = time_boot_ms;
packet->image_interval = image_interval;
packet->recording_time_ms = recording_time_ms;
packet->available_capacity = available_capacity;
packet->image_status = image_status;
packet->video_status = video_status;
packet->image_count = image_count;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS, (const char *)packet, MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS_MIN_LEN, MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS_LEN, MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS_CRC);
#endif
}
#endif
#endif
// MESSAGE CAMERA_CAPTURE_STATUS UNPACKING
/**
* @brief Get field time_boot_ms from camera_capture_status message
*
* @return [ms] Timestamp (time since system boot).
*/
static inline uint32_t mavlink_msg_camera_capture_status_get_time_boot_ms(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint32_t(msg, 0);
}
/**
* @brief Get field image_status from camera_capture_status message
*
* @return Current status of image capturing (0: idle, 1: capture in progress, 2: interval set but idle, 3: interval set and capture in progress)
*/
static inline uint8_t mavlink_msg_camera_capture_status_get_image_status(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 16);
}
/**
* @brief Get field video_status from camera_capture_status message
*
* @return Current status of video capturing (0: idle, 1: capture in progress)
*/
static inline uint8_t mavlink_msg_camera_capture_status_get_video_status(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 17);
}
/**
* @brief Get field image_interval from camera_capture_status message
*
* @return [s] Image capture interval
*/
static inline float mavlink_msg_camera_capture_status_get_image_interval(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 4);
}
/**
* @brief Get field recording_time_ms from camera_capture_status message
*
* @return [ms] Time since recording started
*/
static inline uint32_t mavlink_msg_camera_capture_status_get_recording_time_ms(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint32_t(msg, 8);
}
/**
* @brief Get field available_capacity from camera_capture_status message
*
* @return [MiB] Available storage capacity.
*/
static inline float mavlink_msg_camera_capture_status_get_available_capacity(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 12);
}
/**
* @brief Get field image_count from camera_capture_status message
*
* @return Total number of images captured ('forever', or until reset using MAV_CMD_STORAGE_FORMAT).
*/
static inline int32_t mavlink_msg_camera_capture_status_get_image_count(const mavlink_message_t* msg)
{
return _MAV_RETURN_int32_t(msg, 18);
}
/**
* @brief Decode a camera_capture_status message into a struct
*
* @param msg The message to decode
* @param camera_capture_status C-struct to decode the message contents into
*/
static inline void mavlink_msg_camera_capture_status_decode(const mavlink_message_t* msg, mavlink_camera_capture_status_t* camera_capture_status)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
camera_capture_status->time_boot_ms = mavlink_msg_camera_capture_status_get_time_boot_ms(msg);
camera_capture_status->image_interval = mavlink_msg_camera_capture_status_get_image_interval(msg);
camera_capture_status->recording_time_ms = mavlink_msg_camera_capture_status_get_recording_time_ms(msg);
camera_capture_status->available_capacity = mavlink_msg_camera_capture_status_get_available_capacity(msg);
camera_capture_status->image_status = mavlink_msg_camera_capture_status_get_image_status(msg);
camera_capture_status->video_status = mavlink_msg_camera_capture_status_get_video_status(msg);
camera_capture_status->image_count = mavlink_msg_camera_capture_status_get_image_count(msg);
#else
uint8_t len = msg->len < MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS_LEN? msg->len : MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS_LEN;
memset(camera_capture_status, 0, MAVLINK_MSG_ID_CAMERA_CAPTURE_STATUS_LEN);
memcpy(camera_capture_status, _MAV_PAYLOAD(msg), len);
#endif
}

View file

@ -0,0 +1,430 @@
#pragma once
// MESSAGE CAMERA_FOV_STATUS PACKING
#define MAVLINK_MSG_ID_CAMERA_FOV_STATUS 271
typedef struct __mavlink_camera_fov_status_t {
uint32_t time_boot_ms; /*< [ms] Timestamp (time since system boot).*/
int32_t lat_camera; /*< [degE7] Latitude of camera (INT32_MAX if unknown).*/
int32_t lon_camera; /*< [degE7] Longitude of camera (INT32_MAX if unknown).*/
int32_t alt_camera; /*< [mm] Altitude (MSL) of camera (INT32_MAX if unknown).*/
int32_t lat_image; /*< [degE7] Latitude of center of image (INT32_MAX if unknown, INT32_MIN if at infinity, not intersecting with horizon).*/
int32_t lon_image; /*< [degE7] Longitude of center of image (INT32_MAX if unknown, INT32_MIN if at infinity, not intersecting with horizon).*/
int32_t alt_image; /*< [mm] Altitude (MSL) of center of image (INT32_MAX if unknown, INT32_MIN if at infinity, not intersecting with horizon).*/
float q[4]; /*< Quaternion of camera orientation (w, x, y, z order, zero-rotation is 1, 0, 0, 0)*/
float hfov; /*< [deg] Horizontal field of view (NaN if unknown).*/
float vfov; /*< [deg] Vertical field of view (NaN if unknown).*/
} mavlink_camera_fov_status_t;
#define MAVLINK_MSG_ID_CAMERA_FOV_STATUS_LEN 52
#define MAVLINK_MSG_ID_CAMERA_FOV_STATUS_MIN_LEN 52
#define MAVLINK_MSG_ID_271_LEN 52
#define MAVLINK_MSG_ID_271_MIN_LEN 52
#define MAVLINK_MSG_ID_CAMERA_FOV_STATUS_CRC 22
#define MAVLINK_MSG_ID_271_CRC 22
#define MAVLINK_MSG_CAMERA_FOV_STATUS_FIELD_Q_LEN 4
#if MAVLINK_COMMAND_24BIT
#define MAVLINK_MESSAGE_INFO_CAMERA_FOV_STATUS { \
271, \
"CAMERA_FOV_STATUS", \
10, \
{ { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_camera_fov_status_t, time_boot_ms) }, \
{ "lat_camera", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_camera_fov_status_t, lat_camera) }, \
{ "lon_camera", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_camera_fov_status_t, lon_camera) }, \
{ "alt_camera", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_camera_fov_status_t, alt_camera) }, \
{ "lat_image", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_camera_fov_status_t, lat_image) }, \
{ "lon_image", NULL, MAVLINK_TYPE_INT32_T, 0, 20, offsetof(mavlink_camera_fov_status_t, lon_image) }, \
{ "alt_image", NULL, MAVLINK_TYPE_INT32_T, 0, 24, offsetof(mavlink_camera_fov_status_t, alt_image) }, \
{ "q", NULL, MAVLINK_TYPE_FLOAT, 4, 28, offsetof(mavlink_camera_fov_status_t, q) }, \
{ "hfov", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_camera_fov_status_t, hfov) }, \
{ "vfov", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_camera_fov_status_t, vfov) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_CAMERA_FOV_STATUS { \
"CAMERA_FOV_STATUS", \
10, \
{ { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_camera_fov_status_t, time_boot_ms) }, \
{ "lat_camera", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_camera_fov_status_t, lat_camera) }, \
{ "lon_camera", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_camera_fov_status_t, lon_camera) }, \
{ "alt_camera", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_camera_fov_status_t, alt_camera) }, \
{ "lat_image", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_camera_fov_status_t, lat_image) }, \
{ "lon_image", NULL, MAVLINK_TYPE_INT32_T, 0, 20, offsetof(mavlink_camera_fov_status_t, lon_image) }, \
{ "alt_image", NULL, MAVLINK_TYPE_INT32_T, 0, 24, offsetof(mavlink_camera_fov_status_t, alt_image) }, \
{ "q", NULL, MAVLINK_TYPE_FLOAT, 4, 28, offsetof(mavlink_camera_fov_status_t, q) }, \
{ "hfov", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_camera_fov_status_t, hfov) }, \
{ "vfov", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_camera_fov_status_t, vfov) }, \
} \
}
#endif
/**
* @brief Pack a camera_fov_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 time_boot_ms [ms] Timestamp (time since system boot).
* @param lat_camera [degE7] Latitude of camera (INT32_MAX if unknown).
* @param lon_camera [degE7] Longitude of camera (INT32_MAX if unknown).
* @param alt_camera [mm] Altitude (MSL) of camera (INT32_MAX if unknown).
* @param lat_image [degE7] Latitude of center of image (INT32_MAX if unknown, INT32_MIN if at infinity, not intersecting with horizon).
* @param lon_image [degE7] Longitude of center of image (INT32_MAX if unknown, INT32_MIN if at infinity, not intersecting with horizon).
* @param alt_image [mm] Altitude (MSL) of center of image (INT32_MAX if unknown, INT32_MIN if at infinity, not intersecting with horizon).
* @param q Quaternion of camera orientation (w, x, y, z order, zero-rotation is 1, 0, 0, 0)
* @param hfov [deg] Horizontal field of view (NaN if unknown).
* @param vfov [deg] Vertical field of view (NaN if unknown).
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_camera_fov_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint32_t time_boot_ms, int32_t lat_camera, int32_t lon_camera, int32_t alt_camera, int32_t lat_image, int32_t lon_image, int32_t alt_image, const float *q, float hfov, float vfov)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_CAMERA_FOV_STATUS_LEN];
_mav_put_uint32_t(buf, 0, time_boot_ms);
_mav_put_int32_t(buf, 4, lat_camera);
_mav_put_int32_t(buf, 8, lon_camera);
_mav_put_int32_t(buf, 12, alt_camera);
_mav_put_int32_t(buf, 16, lat_image);
_mav_put_int32_t(buf, 20, lon_image);
_mav_put_int32_t(buf, 24, alt_image);
_mav_put_float(buf, 44, hfov);
_mav_put_float(buf, 48, vfov);
_mav_put_float_array(buf, 28, q, 4);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CAMERA_FOV_STATUS_LEN);
#else
mavlink_camera_fov_status_t packet;
packet.time_boot_ms = time_boot_ms;
packet.lat_camera = lat_camera;
packet.lon_camera = lon_camera;
packet.alt_camera = alt_camera;
packet.lat_image = lat_image;
packet.lon_image = lon_image;
packet.alt_image = alt_image;
packet.hfov = hfov;
packet.vfov = vfov;
mav_array_memcpy(packet.q, q, sizeof(float)*4);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CAMERA_FOV_STATUS_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_CAMERA_FOV_STATUS;
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_CAMERA_FOV_STATUS_MIN_LEN, MAVLINK_MSG_ID_CAMERA_FOV_STATUS_LEN, MAVLINK_MSG_ID_CAMERA_FOV_STATUS_CRC);
}
/**
* @brief Pack a camera_fov_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 time_boot_ms [ms] Timestamp (time since system boot).
* @param lat_camera [degE7] Latitude of camera (INT32_MAX if unknown).
* @param lon_camera [degE7] Longitude of camera (INT32_MAX if unknown).
* @param alt_camera [mm] Altitude (MSL) of camera (INT32_MAX if unknown).
* @param lat_image [degE7] Latitude of center of image (INT32_MAX if unknown, INT32_MIN if at infinity, not intersecting with horizon).
* @param lon_image [degE7] Longitude of center of image (INT32_MAX if unknown, INT32_MIN if at infinity, not intersecting with horizon).
* @param alt_image [mm] Altitude (MSL) of center of image (INT32_MAX if unknown, INT32_MIN if at infinity, not intersecting with horizon).
* @param q Quaternion of camera orientation (w, x, y, z order, zero-rotation is 1, 0, 0, 0)
* @param hfov [deg] Horizontal field of view (NaN if unknown).
* @param vfov [deg] Vertical field of view (NaN if unknown).
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_camera_fov_status_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_camera,int32_t lon_camera,int32_t alt_camera,int32_t lat_image,int32_t lon_image,int32_t alt_image,const float *q,float hfov,float vfov)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_CAMERA_FOV_STATUS_LEN];
_mav_put_uint32_t(buf, 0, time_boot_ms);
_mav_put_int32_t(buf, 4, lat_camera);
_mav_put_int32_t(buf, 8, lon_camera);
_mav_put_int32_t(buf, 12, alt_camera);
_mav_put_int32_t(buf, 16, lat_image);
_mav_put_int32_t(buf, 20, lon_image);
_mav_put_int32_t(buf, 24, alt_image);
_mav_put_float(buf, 44, hfov);
_mav_put_float(buf, 48, vfov);
_mav_put_float_array(buf, 28, q, 4);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CAMERA_FOV_STATUS_LEN);
#else
mavlink_camera_fov_status_t packet;
packet.time_boot_ms = time_boot_ms;
packet.lat_camera = lat_camera;
packet.lon_camera = lon_camera;
packet.alt_camera = alt_camera;
packet.lat_image = lat_image;
packet.lon_image = lon_image;
packet.alt_image = alt_image;
packet.hfov = hfov;
packet.vfov = vfov;
mav_array_memcpy(packet.q, q, sizeof(float)*4);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CAMERA_FOV_STATUS_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_CAMERA_FOV_STATUS;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_CAMERA_FOV_STATUS_MIN_LEN, MAVLINK_MSG_ID_CAMERA_FOV_STATUS_LEN, MAVLINK_MSG_ID_CAMERA_FOV_STATUS_CRC);
}
/**
* @brief Encode a camera_fov_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 camera_fov_status C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_camera_fov_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_camera_fov_status_t* camera_fov_status)
{
return mavlink_msg_camera_fov_status_pack(system_id, component_id, msg, camera_fov_status->time_boot_ms, camera_fov_status->lat_camera, camera_fov_status->lon_camera, camera_fov_status->alt_camera, camera_fov_status->lat_image, camera_fov_status->lon_image, camera_fov_status->alt_image, camera_fov_status->q, camera_fov_status->hfov, camera_fov_status->vfov);
}
/**
* @brief Encode a camera_fov_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 camera_fov_status C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_camera_fov_status_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_camera_fov_status_t* camera_fov_status)
{
return mavlink_msg_camera_fov_status_pack_chan(system_id, component_id, chan, msg, camera_fov_status->time_boot_ms, camera_fov_status->lat_camera, camera_fov_status->lon_camera, camera_fov_status->alt_camera, camera_fov_status->lat_image, camera_fov_status->lon_image, camera_fov_status->alt_image, camera_fov_status->q, camera_fov_status->hfov, camera_fov_status->vfov);
}
/**
* @brief Send a camera_fov_status message
* @param chan MAVLink channel to send the message
*
* @param time_boot_ms [ms] Timestamp (time since system boot).
* @param lat_camera [degE7] Latitude of camera (INT32_MAX if unknown).
* @param lon_camera [degE7] Longitude of camera (INT32_MAX if unknown).
* @param alt_camera [mm] Altitude (MSL) of camera (INT32_MAX if unknown).
* @param lat_image [degE7] Latitude of center of image (INT32_MAX if unknown, INT32_MIN if at infinity, not intersecting with horizon).
* @param lon_image [degE7] Longitude of center of image (INT32_MAX if unknown, INT32_MIN if at infinity, not intersecting with horizon).
* @param alt_image [mm] Altitude (MSL) of center of image (INT32_MAX if unknown, INT32_MIN if at infinity, not intersecting with horizon).
* @param q Quaternion of camera orientation (w, x, y, z order, zero-rotation is 1, 0, 0, 0)
* @param hfov [deg] Horizontal field of view (NaN if unknown).
* @param vfov [deg] Vertical field of view (NaN if unknown).
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_camera_fov_status_send(mavlink_channel_t chan, uint32_t time_boot_ms, int32_t lat_camera, int32_t lon_camera, int32_t alt_camera, int32_t lat_image, int32_t lon_image, int32_t alt_image, const float *q, float hfov, float vfov)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_CAMERA_FOV_STATUS_LEN];
_mav_put_uint32_t(buf, 0, time_boot_ms);
_mav_put_int32_t(buf, 4, lat_camera);
_mav_put_int32_t(buf, 8, lon_camera);
_mav_put_int32_t(buf, 12, alt_camera);
_mav_put_int32_t(buf, 16, lat_image);
_mav_put_int32_t(buf, 20, lon_image);
_mav_put_int32_t(buf, 24, alt_image);
_mav_put_float(buf, 44, hfov);
_mav_put_float(buf, 48, vfov);
_mav_put_float_array(buf, 28, q, 4);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_FOV_STATUS, buf, MAVLINK_MSG_ID_CAMERA_FOV_STATUS_MIN_LEN, MAVLINK_MSG_ID_CAMERA_FOV_STATUS_LEN, MAVLINK_MSG_ID_CAMERA_FOV_STATUS_CRC);
#else
mavlink_camera_fov_status_t packet;
packet.time_boot_ms = time_boot_ms;
packet.lat_camera = lat_camera;
packet.lon_camera = lon_camera;
packet.alt_camera = alt_camera;
packet.lat_image = lat_image;
packet.lon_image = lon_image;
packet.alt_image = alt_image;
packet.hfov = hfov;
packet.vfov = vfov;
mav_array_memcpy(packet.q, q, sizeof(float)*4);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_FOV_STATUS, (const char *)&packet, MAVLINK_MSG_ID_CAMERA_FOV_STATUS_MIN_LEN, MAVLINK_MSG_ID_CAMERA_FOV_STATUS_LEN, MAVLINK_MSG_ID_CAMERA_FOV_STATUS_CRC);
#endif
}
/**
* @brief Send a camera_fov_status message
* @param chan MAVLink channel to send the message
* @param struct The MAVLink struct to serialize
*/
static inline void mavlink_msg_camera_fov_status_send_struct(mavlink_channel_t chan, const mavlink_camera_fov_status_t* camera_fov_status)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mavlink_msg_camera_fov_status_send(chan, camera_fov_status->time_boot_ms, camera_fov_status->lat_camera, camera_fov_status->lon_camera, camera_fov_status->alt_camera, camera_fov_status->lat_image, camera_fov_status->lon_image, camera_fov_status->alt_image, camera_fov_status->q, camera_fov_status->hfov, camera_fov_status->vfov);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_FOV_STATUS, (const char *)camera_fov_status, MAVLINK_MSG_ID_CAMERA_FOV_STATUS_MIN_LEN, MAVLINK_MSG_ID_CAMERA_FOV_STATUS_LEN, MAVLINK_MSG_ID_CAMERA_FOV_STATUS_CRC);
#endif
}
#if MAVLINK_MSG_ID_CAMERA_FOV_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_camera_fov_status_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, int32_t lat_camera, int32_t lon_camera, int32_t alt_camera, int32_t lat_image, int32_t lon_image, int32_t alt_image, const float *q, float hfov, float vfov)
{
#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_camera);
_mav_put_int32_t(buf, 8, lon_camera);
_mav_put_int32_t(buf, 12, alt_camera);
_mav_put_int32_t(buf, 16, lat_image);
_mav_put_int32_t(buf, 20, lon_image);
_mav_put_int32_t(buf, 24, alt_image);
_mav_put_float(buf, 44, hfov);
_mav_put_float(buf, 48, vfov);
_mav_put_float_array(buf, 28, q, 4);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_FOV_STATUS, buf, MAVLINK_MSG_ID_CAMERA_FOV_STATUS_MIN_LEN, MAVLINK_MSG_ID_CAMERA_FOV_STATUS_LEN, MAVLINK_MSG_ID_CAMERA_FOV_STATUS_CRC);
#else
mavlink_camera_fov_status_t *packet = (mavlink_camera_fov_status_t *)msgbuf;
packet->time_boot_ms = time_boot_ms;
packet->lat_camera = lat_camera;
packet->lon_camera = lon_camera;
packet->alt_camera = alt_camera;
packet->lat_image = lat_image;
packet->lon_image = lon_image;
packet->alt_image = alt_image;
packet->hfov = hfov;
packet->vfov = vfov;
mav_array_memcpy(packet->q, q, sizeof(float)*4);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_FOV_STATUS, (const char *)packet, MAVLINK_MSG_ID_CAMERA_FOV_STATUS_MIN_LEN, MAVLINK_MSG_ID_CAMERA_FOV_STATUS_LEN, MAVLINK_MSG_ID_CAMERA_FOV_STATUS_CRC);
#endif
}
#endif
#endif
// MESSAGE CAMERA_FOV_STATUS UNPACKING
/**
* @brief Get field time_boot_ms from camera_fov_status message
*
* @return [ms] Timestamp (time since system boot).
*/
static inline uint32_t mavlink_msg_camera_fov_status_get_time_boot_ms(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint32_t(msg, 0);
}
/**
* @brief Get field lat_camera from camera_fov_status message
*
* @return [degE7] Latitude of camera (INT32_MAX if unknown).
*/
static inline int32_t mavlink_msg_camera_fov_status_get_lat_camera(const mavlink_message_t* msg)
{
return _MAV_RETURN_int32_t(msg, 4);
}
/**
* @brief Get field lon_camera from camera_fov_status message
*
* @return [degE7] Longitude of camera (INT32_MAX if unknown).
*/
static inline int32_t mavlink_msg_camera_fov_status_get_lon_camera(const mavlink_message_t* msg)
{
return _MAV_RETURN_int32_t(msg, 8);
}
/**
* @brief Get field alt_camera from camera_fov_status message
*
* @return [mm] Altitude (MSL) of camera (INT32_MAX if unknown).
*/
static inline int32_t mavlink_msg_camera_fov_status_get_alt_camera(const mavlink_message_t* msg)
{
return _MAV_RETURN_int32_t(msg, 12);
}
/**
* @brief Get field lat_image from camera_fov_status message
*
* @return [degE7] Latitude of center of image (INT32_MAX if unknown, INT32_MIN if at infinity, not intersecting with horizon).
*/
static inline int32_t mavlink_msg_camera_fov_status_get_lat_image(const mavlink_message_t* msg)
{
return _MAV_RETURN_int32_t(msg, 16);
}
/**
* @brief Get field lon_image from camera_fov_status message
*
* @return [degE7] Longitude of center of image (INT32_MAX if unknown, INT32_MIN if at infinity, not intersecting with horizon).
*/
static inline int32_t mavlink_msg_camera_fov_status_get_lon_image(const mavlink_message_t* msg)
{
return _MAV_RETURN_int32_t(msg, 20);
}
/**
* @brief Get field alt_image from camera_fov_status message
*
* @return [mm] Altitude (MSL) of center of image (INT32_MAX if unknown, INT32_MIN if at infinity, not intersecting with horizon).
*/
static inline int32_t mavlink_msg_camera_fov_status_get_alt_image(const mavlink_message_t* msg)
{
return _MAV_RETURN_int32_t(msg, 24);
}
/**
* @brief Get field q from camera_fov_status message
*
* @return Quaternion of camera orientation (w, x, y, z order, zero-rotation is 1, 0, 0, 0)
*/
static inline uint16_t mavlink_msg_camera_fov_status_get_q(const mavlink_message_t* msg, float *q)
{
return _MAV_RETURN_float_array(msg, q, 4, 28);
}
/**
* @brief Get field hfov from camera_fov_status message
*
* @return [deg] Horizontal field of view (NaN if unknown).
*/
static inline float mavlink_msg_camera_fov_status_get_hfov(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 44);
}
/**
* @brief Get field vfov from camera_fov_status message
*
* @return [deg] Vertical field of view (NaN if unknown).
*/
static inline float mavlink_msg_camera_fov_status_get_vfov(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 48);
}
/**
* @brief Decode a camera_fov_status message into a struct
*
* @param msg The message to decode
* @param camera_fov_status C-struct to decode the message contents into
*/
static inline void mavlink_msg_camera_fov_status_decode(const mavlink_message_t* msg, mavlink_camera_fov_status_t* camera_fov_status)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
camera_fov_status->time_boot_ms = mavlink_msg_camera_fov_status_get_time_boot_ms(msg);
camera_fov_status->lat_camera = mavlink_msg_camera_fov_status_get_lat_camera(msg);
camera_fov_status->lon_camera = mavlink_msg_camera_fov_status_get_lon_camera(msg);
camera_fov_status->alt_camera = mavlink_msg_camera_fov_status_get_alt_camera(msg);
camera_fov_status->lat_image = mavlink_msg_camera_fov_status_get_lat_image(msg);
camera_fov_status->lon_image = mavlink_msg_camera_fov_status_get_lon_image(msg);
camera_fov_status->alt_image = mavlink_msg_camera_fov_status_get_alt_image(msg);
mavlink_msg_camera_fov_status_get_q(msg, camera_fov_status->q);
camera_fov_status->hfov = mavlink_msg_camera_fov_status_get_hfov(msg);
camera_fov_status->vfov = mavlink_msg_camera_fov_status_get_vfov(msg);
#else
uint8_t len = msg->len < MAVLINK_MSG_ID_CAMERA_FOV_STATUS_LEN? msg->len : MAVLINK_MSG_ID_CAMERA_FOV_STATUS_LEN;
memset(camera_fov_status, 0, MAVLINK_MSG_ID_CAMERA_FOV_STATUS_LEN);
memcpy(camera_fov_status, _MAV_PAYLOAD(msg), len);
#endif
}

View file

@ -0,0 +1,456 @@
#pragma once
// MESSAGE CAMERA_IMAGE_CAPTURED PACKING
#define MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED 263
typedef struct __mavlink_camera_image_captured_t {
uint64_t time_utc; /*< [us] Timestamp (time since UNIX epoch) in UTC. 0 for unknown.*/
uint32_t time_boot_ms; /*< [ms] Timestamp (time since system boot).*/
int32_t lat; /*< [degE7] Latitude where image was taken*/
int32_t lon; /*< [degE7] Longitude where capture was taken*/
int32_t alt; /*< [mm] Altitude (MSL) where image was taken*/
int32_t relative_alt; /*< [mm] Altitude above ground*/
float q[4]; /*< Quaternion of camera orientation (w, x, y, z order, zero-rotation is 1, 0, 0, 0)*/
int32_t image_index; /*< Zero based index of this image (i.e. a new image will have index CAMERA_CAPTURE_STATUS.image count -1)*/
uint8_t camera_id; /*< Deprecated/unused. Component IDs are used to differentiate multiple cameras.*/
int8_t capture_result; /*< Boolean indicating success (1) or failure (0) while capturing this image.*/
char file_url[205]; /*< URL of image taken. Either local storage or http://foo.jpg if camera provides an HTTP interface.*/
} mavlink_camera_image_captured_t;
#define MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED_LEN 255
#define MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED_MIN_LEN 255
#define MAVLINK_MSG_ID_263_LEN 255
#define MAVLINK_MSG_ID_263_MIN_LEN 255
#define MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED_CRC 133
#define MAVLINK_MSG_ID_263_CRC 133
#define MAVLINK_MSG_CAMERA_IMAGE_CAPTURED_FIELD_Q_LEN 4
#define MAVLINK_MSG_CAMERA_IMAGE_CAPTURED_FIELD_FILE_URL_LEN 205
#if MAVLINK_COMMAND_24BIT
#define MAVLINK_MESSAGE_INFO_CAMERA_IMAGE_CAPTURED { \
263, \
"CAMERA_IMAGE_CAPTURED", \
11, \
{ { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_camera_image_captured_t, time_boot_ms) }, \
{ "time_utc", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_camera_image_captured_t, time_utc) }, \
{ "camera_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 48, offsetof(mavlink_camera_image_captured_t, camera_id) }, \
{ "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_camera_image_captured_t, lat) }, \
{ "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_camera_image_captured_t, lon) }, \
{ "alt", NULL, MAVLINK_TYPE_INT32_T, 0, 20, offsetof(mavlink_camera_image_captured_t, alt) }, \
{ "relative_alt", NULL, MAVLINK_TYPE_INT32_T, 0, 24, offsetof(mavlink_camera_image_captured_t, relative_alt) }, \
{ "q", NULL, MAVLINK_TYPE_FLOAT, 4, 28, offsetof(mavlink_camera_image_captured_t, q) }, \
{ "image_index", NULL, MAVLINK_TYPE_INT32_T, 0, 44, offsetof(mavlink_camera_image_captured_t, image_index) }, \
{ "capture_result", NULL, MAVLINK_TYPE_INT8_T, 0, 49, offsetof(mavlink_camera_image_captured_t, capture_result) }, \
{ "file_url", NULL, MAVLINK_TYPE_CHAR, 205, 50, offsetof(mavlink_camera_image_captured_t, file_url) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_CAMERA_IMAGE_CAPTURED { \
"CAMERA_IMAGE_CAPTURED", \
11, \
{ { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_camera_image_captured_t, time_boot_ms) }, \
{ "time_utc", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_camera_image_captured_t, time_utc) }, \
{ "camera_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 48, offsetof(mavlink_camera_image_captured_t, camera_id) }, \
{ "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_camera_image_captured_t, lat) }, \
{ "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_camera_image_captured_t, lon) }, \
{ "alt", NULL, MAVLINK_TYPE_INT32_T, 0, 20, offsetof(mavlink_camera_image_captured_t, alt) }, \
{ "relative_alt", NULL, MAVLINK_TYPE_INT32_T, 0, 24, offsetof(mavlink_camera_image_captured_t, relative_alt) }, \
{ "q", NULL, MAVLINK_TYPE_FLOAT, 4, 28, offsetof(mavlink_camera_image_captured_t, q) }, \
{ "image_index", NULL, MAVLINK_TYPE_INT32_T, 0, 44, offsetof(mavlink_camera_image_captured_t, image_index) }, \
{ "capture_result", NULL, MAVLINK_TYPE_INT8_T, 0, 49, offsetof(mavlink_camera_image_captured_t, capture_result) }, \
{ "file_url", NULL, MAVLINK_TYPE_CHAR, 205, 50, offsetof(mavlink_camera_image_captured_t, file_url) }, \
} \
}
#endif
/**
* @brief Pack a camera_image_captured message
* @param system_id ID of this 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 [ms] Timestamp (time since system boot).
* @param time_utc [us] Timestamp (time since UNIX epoch) in UTC. 0 for unknown.
* @param camera_id Deprecated/unused. Component IDs are used to differentiate multiple cameras.
* @param lat [degE7] Latitude where image was taken
* @param lon [degE7] Longitude where capture was taken
* @param alt [mm] Altitude (MSL) where image was taken
* @param relative_alt [mm] Altitude above ground
* @param q Quaternion of camera orientation (w, x, y, z order, zero-rotation is 1, 0, 0, 0)
* @param image_index Zero based index of this image (i.e. a new image will have index CAMERA_CAPTURE_STATUS.image count -1)
* @param capture_result Boolean indicating success (1) or failure (0) while capturing this image.
* @param file_url URL of image taken. Either local storage or http://foo.jpg if camera provides an HTTP interface.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_camera_image_captured_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint32_t time_boot_ms, uint64_t time_utc, uint8_t camera_id, int32_t lat, int32_t lon, int32_t alt, int32_t relative_alt, const float *q, int32_t image_index, int8_t capture_result, const char *file_url)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED_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_int32_t(buf, 44, image_index);
_mav_put_uint8_t(buf, 48, camera_id);
_mav_put_int8_t(buf, 49, capture_result);
_mav_put_float_array(buf, 28, q, 4);
_mav_put_char_array(buf, 50, file_url, 205);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED_LEN);
#else
mavlink_camera_image_captured_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.image_index = image_index;
packet.camera_id = camera_id;
packet.capture_result = capture_result;
mav_array_memcpy(packet.q, q, sizeof(float)*4);
mav_array_memcpy(packet.file_url, file_url, sizeof(char)*205);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED;
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED_MIN_LEN, MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED_LEN, MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED_CRC);
}
/**
* @brief Pack a camera_image_captured message on a channel
* @param system_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 [ms] Timestamp (time since system boot).
* @param time_utc [us] Timestamp (time since UNIX epoch) in UTC. 0 for unknown.
* @param camera_id Deprecated/unused. Component IDs are used to differentiate multiple cameras.
* @param lat [degE7] Latitude where image was taken
* @param lon [degE7] Longitude where capture was taken
* @param alt [mm] Altitude (MSL) where image was taken
* @param relative_alt [mm] Altitude above ground
* @param q Quaternion of camera orientation (w, x, y, z order, zero-rotation is 1, 0, 0, 0)
* @param image_index Zero based index of this image (i.e. a new image will have index CAMERA_CAPTURE_STATUS.image count -1)
* @param capture_result Boolean indicating success (1) or failure (0) while capturing this image.
* @param file_url URL of image taken. Either local storage or http://foo.jpg if camera provides an HTTP interface.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_camera_image_captured_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 camera_id,int32_t lat,int32_t lon,int32_t alt,int32_t relative_alt,const float *q,int32_t image_index,int8_t capture_result,const char *file_url)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED_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_int32_t(buf, 44, image_index);
_mav_put_uint8_t(buf, 48, camera_id);
_mav_put_int8_t(buf, 49, capture_result);
_mav_put_float_array(buf, 28, q, 4);
_mav_put_char_array(buf, 50, file_url, 205);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED_LEN);
#else
mavlink_camera_image_captured_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.image_index = image_index;
packet.camera_id = camera_id;
packet.capture_result = capture_result;
mav_array_memcpy(packet.q, q, sizeof(float)*4);
mav_array_memcpy(packet.file_url, file_url, sizeof(char)*205);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED_MIN_LEN, MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED_LEN, MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED_CRC);
}
/**
* @brief Encode a camera_image_captured 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_image_captured C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_camera_image_captured_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_camera_image_captured_t* camera_image_captured)
{
return mavlink_msg_camera_image_captured_pack(system_id, component_id, msg, camera_image_captured->time_boot_ms, camera_image_captured->time_utc, camera_image_captured->camera_id, camera_image_captured->lat, camera_image_captured->lon, camera_image_captured->alt, camera_image_captured->relative_alt, camera_image_captured->q, camera_image_captured->image_index, camera_image_captured->capture_result, camera_image_captured->file_url);
}
/**
* @brief Encode a camera_image_captured 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_image_captured C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_camera_image_captured_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_camera_image_captured_t* camera_image_captured)
{
return mavlink_msg_camera_image_captured_pack_chan(system_id, component_id, chan, msg, camera_image_captured->time_boot_ms, camera_image_captured->time_utc, camera_image_captured->camera_id, camera_image_captured->lat, camera_image_captured->lon, camera_image_captured->alt, camera_image_captured->relative_alt, camera_image_captured->q, camera_image_captured->image_index, camera_image_captured->capture_result, camera_image_captured->file_url);
}
/**
* @brief Send a camera_image_captured message
* @param chan MAVLink channel to send the message
*
* @param time_boot_ms [ms] Timestamp (time since system boot).
* @param time_utc [us] Timestamp (time since UNIX epoch) in UTC. 0 for unknown.
* @param camera_id Deprecated/unused. Component IDs are used to differentiate multiple cameras.
* @param lat [degE7] Latitude where image was taken
* @param lon [degE7] Longitude where capture was taken
* @param alt [mm] Altitude (MSL) where image was taken
* @param relative_alt [mm] Altitude above ground
* @param q Quaternion of camera orientation (w, x, y, z order, zero-rotation is 1, 0, 0, 0)
* @param image_index Zero based index of this image (i.e. a new image will have index CAMERA_CAPTURE_STATUS.image count -1)
* @param capture_result Boolean indicating success (1) or failure (0) while capturing this image.
* @param file_url URL of image taken. Either local storage or http://foo.jpg if camera provides an HTTP interface.
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_camera_image_captured_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint64_t time_utc, uint8_t camera_id, int32_t lat, int32_t lon, int32_t alt, int32_t relative_alt, const float *q, int32_t image_index, int8_t capture_result, const char *file_url)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED_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_int32_t(buf, 44, image_index);
_mav_put_uint8_t(buf, 48, camera_id);
_mav_put_int8_t(buf, 49, capture_result);
_mav_put_float_array(buf, 28, q, 4);
_mav_put_char_array(buf, 50, file_url, 205);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED, buf, MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED_MIN_LEN, MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED_LEN, MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED_CRC);
#else
mavlink_camera_image_captured_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.image_index = image_index;
packet.camera_id = camera_id;
packet.capture_result = capture_result;
mav_array_memcpy(packet.q, q, sizeof(float)*4);
mav_array_memcpy(packet.file_url, file_url, sizeof(char)*205);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED, (const char *)&packet, MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED_MIN_LEN, MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED_LEN, MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED_CRC);
#endif
}
/**
* @brief Send a camera_image_captured message
* @param chan MAVLink channel to send the message
* @param struct The MAVLink struct to serialize
*/
static inline void mavlink_msg_camera_image_captured_send_struct(mavlink_channel_t chan, const mavlink_camera_image_captured_t* camera_image_captured)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mavlink_msg_camera_image_captured_send(chan, camera_image_captured->time_boot_ms, camera_image_captured->time_utc, camera_image_captured->camera_id, camera_image_captured->lat, camera_image_captured->lon, camera_image_captured->alt, camera_image_captured->relative_alt, camera_image_captured->q, camera_image_captured->image_index, camera_image_captured->capture_result, camera_image_captured->file_url);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED, (const char *)camera_image_captured, MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED_MIN_LEN, MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED_LEN, MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED_CRC);
#endif
}
#if MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED_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_image_captured_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, uint64_t time_utc, uint8_t camera_id, int32_t lat, int32_t lon, int32_t alt, int32_t relative_alt, const float *q, int32_t image_index, int8_t capture_result, const char *file_url)
{
#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_int32_t(buf, 44, image_index);
_mav_put_uint8_t(buf, 48, camera_id);
_mav_put_int8_t(buf, 49, capture_result);
_mav_put_float_array(buf, 28, q, 4);
_mav_put_char_array(buf, 50, file_url, 205);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED, buf, MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED_MIN_LEN, MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED_LEN, MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED_CRC);
#else
mavlink_camera_image_captured_t *packet = (mavlink_camera_image_captured_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->image_index = image_index;
packet->camera_id = camera_id;
packet->capture_result = capture_result;
mav_array_memcpy(packet->q, q, sizeof(float)*4);
mav_array_memcpy(packet->file_url, file_url, sizeof(char)*205);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED, (const char *)packet, MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED_MIN_LEN, MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED_LEN, MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED_CRC);
#endif
}
#endif
#endif
// MESSAGE CAMERA_IMAGE_CAPTURED UNPACKING
/**
* @brief Get field time_boot_ms from camera_image_captured message
*
* @return [ms] Timestamp (time since system boot).
*/
static inline uint32_t mavlink_msg_camera_image_captured_get_time_boot_ms(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint32_t(msg, 8);
}
/**
* @brief Get field time_utc from camera_image_captured message
*
* @return [us] Timestamp (time since UNIX epoch) in UTC. 0 for unknown.
*/
static inline uint64_t mavlink_msg_camera_image_captured_get_time_utc(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint64_t(msg, 0);
}
/**
* @brief Get field camera_id from camera_image_captured message
*
* @return Deprecated/unused. Component IDs are used to differentiate multiple cameras.
*/
static inline uint8_t mavlink_msg_camera_image_captured_get_camera_id(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 48);
}
/**
* @brief Get field lat from camera_image_captured message
*
* @return [degE7] Latitude where image was taken
*/
static inline int32_t mavlink_msg_camera_image_captured_get_lat(const mavlink_message_t* msg)
{
return _MAV_RETURN_int32_t(msg, 12);
}
/**
* @brief Get field lon from camera_image_captured message
*
* @return [degE7] Longitude where capture was taken
*/
static inline int32_t mavlink_msg_camera_image_captured_get_lon(const mavlink_message_t* msg)
{
return _MAV_RETURN_int32_t(msg, 16);
}
/**
* @brief Get field alt from camera_image_captured message
*
* @return [mm] Altitude (MSL) where image was taken
*/
static inline int32_t mavlink_msg_camera_image_captured_get_alt(const mavlink_message_t* msg)
{
return _MAV_RETURN_int32_t(msg, 20);
}
/**
* @brief Get field relative_alt from camera_image_captured message
*
* @return [mm] Altitude above ground
*/
static inline int32_t mavlink_msg_camera_image_captured_get_relative_alt(const mavlink_message_t* msg)
{
return _MAV_RETURN_int32_t(msg, 24);
}
/**
* @brief Get field q from camera_image_captured message
*
* @return Quaternion of camera orientation (w, x, y, z order, zero-rotation is 1, 0, 0, 0)
*/
static inline uint16_t mavlink_msg_camera_image_captured_get_q(const mavlink_message_t* msg, float *q)
{
return _MAV_RETURN_float_array(msg, q, 4, 28);
}
/**
* @brief Get field image_index from camera_image_captured message
*
* @return Zero based index of this image (i.e. a new image will have index CAMERA_CAPTURE_STATUS.image count -1)
*/
static inline int32_t mavlink_msg_camera_image_captured_get_image_index(const mavlink_message_t* msg)
{
return _MAV_RETURN_int32_t(msg, 44);
}
/**
* @brief Get field capture_result from camera_image_captured message
*
* @return Boolean indicating success (1) or failure (0) while capturing this image.
*/
static inline int8_t mavlink_msg_camera_image_captured_get_capture_result(const mavlink_message_t* msg)
{
return _MAV_RETURN_int8_t(msg, 49);
}
/**
* @brief Get field file_url from camera_image_captured message
*
* @return URL of image taken. Either local storage or http://foo.jpg if camera provides an HTTP interface.
*/
static inline uint16_t mavlink_msg_camera_image_captured_get_file_url(const mavlink_message_t* msg, char *file_url)
{
return _MAV_RETURN_char_array(msg, file_url, 205, 50);
}
/**
* @brief Decode a camera_image_captured message into a struct
*
* @param msg The message to decode
* @param camera_image_captured C-struct to decode the message contents into
*/
static inline void mavlink_msg_camera_image_captured_decode(const mavlink_message_t* msg, mavlink_camera_image_captured_t* camera_image_captured)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
camera_image_captured->time_utc = mavlink_msg_camera_image_captured_get_time_utc(msg);
camera_image_captured->time_boot_ms = mavlink_msg_camera_image_captured_get_time_boot_ms(msg);
camera_image_captured->lat = mavlink_msg_camera_image_captured_get_lat(msg);
camera_image_captured->lon = mavlink_msg_camera_image_captured_get_lon(msg);
camera_image_captured->alt = mavlink_msg_camera_image_captured_get_alt(msg);
camera_image_captured->relative_alt = mavlink_msg_camera_image_captured_get_relative_alt(msg);
mavlink_msg_camera_image_captured_get_q(msg, camera_image_captured->q);
camera_image_captured->image_index = mavlink_msg_camera_image_captured_get_image_index(msg);
camera_image_captured->camera_id = mavlink_msg_camera_image_captured_get_camera_id(msg);
camera_image_captured->capture_result = mavlink_msg_camera_image_captured_get_capture_result(msg);
mavlink_msg_camera_image_captured_get_file_url(msg, camera_image_captured->file_url);
#else
uint8_t len = msg->len < MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED_LEN? msg->len : MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED_LEN;
memset(camera_image_captured, 0, MAVLINK_MSG_ID_CAMERA_IMAGE_CAPTURED_LEN);
memcpy(camera_image_captured, _MAV_PAYLOAD(msg), len);
#endif
}

View file

@ -0,0 +1,507 @@
#pragma once
// MESSAGE CAMERA_INFORMATION PACKING
#define MAVLINK_MSG_ID_CAMERA_INFORMATION 259
typedef struct __mavlink_camera_information_t {
uint32_t time_boot_ms; /*< [ms] Timestamp (time since system boot).*/
uint32_t firmware_version; /*< Version of the camera firmware, encoded as: (Dev & 0xff) << 24 | (Patch & 0xff) << 16 | (Minor & 0xff) << 8 | (Major & 0xff)*/
float focal_length; /*< [mm] Focal length*/
float sensor_size_h; /*< [mm] Image sensor size horizontal*/
float sensor_size_v; /*< [mm] Image sensor size vertical*/
uint32_t flags; /*< Bitmap of camera capability flags.*/
uint16_t resolution_h; /*< [pix] Horizontal image resolution*/
uint16_t resolution_v; /*< [pix] Vertical image resolution*/
uint16_t cam_definition_version; /*< Camera definition version (iteration)*/
uint8_t vendor_name[32]; /*< Name of the camera vendor*/
uint8_t model_name[32]; /*< Name of the camera model*/
uint8_t lens_id; /*< Reserved for a lens ID*/
char cam_definition_uri[140]; /*< Camera definition URI (if any, otherwise only basic functions will be available). HTTP- (http://) and MAVLink FTP- (mavlinkftp://) formatted URIs are allowed (and both must be supported by any GCS that implements the Camera Protocol).*/
} mavlink_camera_information_t;
#define MAVLINK_MSG_ID_CAMERA_INFORMATION_LEN 235
#define MAVLINK_MSG_ID_CAMERA_INFORMATION_MIN_LEN 235
#define MAVLINK_MSG_ID_259_LEN 235
#define MAVLINK_MSG_ID_259_MIN_LEN 235
#define MAVLINK_MSG_ID_CAMERA_INFORMATION_CRC 92
#define MAVLINK_MSG_ID_259_CRC 92
#define MAVLINK_MSG_CAMERA_INFORMATION_FIELD_VENDOR_NAME_LEN 32
#define MAVLINK_MSG_CAMERA_INFORMATION_FIELD_MODEL_NAME_LEN 32
#define MAVLINK_MSG_CAMERA_INFORMATION_FIELD_CAM_DEFINITION_URI_LEN 140
#if MAVLINK_COMMAND_24BIT
#define MAVLINK_MESSAGE_INFO_CAMERA_INFORMATION { \
259, \
"CAMERA_INFORMATION", \
13, \
{ { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_camera_information_t, time_boot_ms) }, \
{ "vendor_name", NULL, MAVLINK_TYPE_UINT8_T, 32, 30, offsetof(mavlink_camera_information_t, vendor_name) }, \
{ "model_name", NULL, MAVLINK_TYPE_UINT8_T, 32, 62, offsetof(mavlink_camera_information_t, model_name) }, \
{ "firmware_version", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_camera_information_t, firmware_version) }, \
{ "focal_length", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_camera_information_t, focal_length) }, \
{ "sensor_size_h", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_camera_information_t, sensor_size_h) }, \
{ "sensor_size_v", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_camera_information_t, sensor_size_v) }, \
{ "resolution_h", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_camera_information_t, resolution_h) }, \
{ "resolution_v", NULL, MAVLINK_TYPE_UINT16_T, 0, 26, offsetof(mavlink_camera_information_t, resolution_v) }, \
{ "lens_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 94, offsetof(mavlink_camera_information_t, lens_id) }, \
{ "flags", NULL, MAVLINK_TYPE_UINT32_T, 0, 20, offsetof(mavlink_camera_information_t, flags) }, \
{ "cam_definition_version", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_camera_information_t, cam_definition_version) }, \
{ "cam_definition_uri", NULL, MAVLINK_TYPE_CHAR, 140, 95, offsetof(mavlink_camera_information_t, cam_definition_uri) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_CAMERA_INFORMATION { \
"CAMERA_INFORMATION", \
13, \
{ { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_camera_information_t, time_boot_ms) }, \
{ "vendor_name", NULL, MAVLINK_TYPE_UINT8_T, 32, 30, offsetof(mavlink_camera_information_t, vendor_name) }, \
{ "model_name", NULL, MAVLINK_TYPE_UINT8_T, 32, 62, offsetof(mavlink_camera_information_t, model_name) }, \
{ "firmware_version", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_camera_information_t, firmware_version) }, \
{ "focal_length", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_camera_information_t, focal_length) }, \
{ "sensor_size_h", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_camera_information_t, sensor_size_h) }, \
{ "sensor_size_v", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_camera_information_t, sensor_size_v) }, \
{ "resolution_h", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_camera_information_t, resolution_h) }, \
{ "resolution_v", NULL, MAVLINK_TYPE_UINT16_T, 0, 26, offsetof(mavlink_camera_information_t, resolution_v) }, \
{ "lens_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 94, offsetof(mavlink_camera_information_t, lens_id) }, \
{ "flags", NULL, MAVLINK_TYPE_UINT32_T, 0, 20, offsetof(mavlink_camera_information_t, flags) }, \
{ "cam_definition_version", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_camera_information_t, cam_definition_version) }, \
{ "cam_definition_uri", NULL, MAVLINK_TYPE_CHAR, 140, 95, offsetof(mavlink_camera_information_t, cam_definition_uri) }, \
} \
}
#endif
/**
* @brief Pack a camera_information message
* @param system_id ID of this 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 [ms] Timestamp (time since system boot).
* @param vendor_name Name of the camera vendor
* @param model_name Name of the camera model
* @param firmware_version Version of the camera firmware, encoded as: (Dev & 0xff) << 24 | (Patch & 0xff) << 16 | (Minor & 0xff) << 8 | (Major & 0xff)
* @param focal_length [mm] Focal length
* @param sensor_size_h [mm] Image sensor size horizontal
* @param sensor_size_v [mm] Image sensor size vertical
* @param resolution_h [pix] Horizontal image resolution
* @param resolution_v [pix] Vertical image resolution
* @param lens_id Reserved for a lens ID
* @param flags Bitmap of camera capability flags.
* @param cam_definition_version Camera definition version (iteration)
* @param cam_definition_uri Camera definition URI (if any, otherwise only basic functions will be available). HTTP- (http://) and MAVLink FTP- (mavlinkftp://) formatted URIs are allowed (and both must be supported by any GCS that implements the Camera Protocol).
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_camera_information_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint32_t time_boot_ms, const uint8_t *vendor_name, const uint8_t *model_name, uint32_t firmware_version, float focal_length, float sensor_size_h, float sensor_size_v, uint16_t resolution_h, uint16_t resolution_v, uint8_t lens_id, uint32_t flags, uint16_t cam_definition_version, const char *cam_definition_uri)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_CAMERA_INFORMATION_LEN];
_mav_put_uint32_t(buf, 0, time_boot_ms);
_mav_put_uint32_t(buf, 4, firmware_version);
_mav_put_float(buf, 8, focal_length);
_mav_put_float(buf, 12, sensor_size_h);
_mav_put_float(buf, 16, sensor_size_v);
_mav_put_uint32_t(buf, 20, flags);
_mav_put_uint16_t(buf, 24, resolution_h);
_mav_put_uint16_t(buf, 26, resolution_v);
_mav_put_uint16_t(buf, 28, cam_definition_version);
_mav_put_uint8_t(buf, 94, lens_id);
_mav_put_uint8_t_array(buf, 30, vendor_name, 32);
_mav_put_uint8_t_array(buf, 62, model_name, 32);
_mav_put_char_array(buf, 95, cam_definition_uri, 140);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CAMERA_INFORMATION_LEN);
#else
mavlink_camera_information_t packet;
packet.time_boot_ms = time_boot_ms;
packet.firmware_version = firmware_version;
packet.focal_length = focal_length;
packet.sensor_size_h = sensor_size_h;
packet.sensor_size_v = sensor_size_v;
packet.flags = flags;
packet.resolution_h = resolution_h;
packet.resolution_v = resolution_v;
packet.cam_definition_version = cam_definition_version;
packet.lens_id = lens_id;
mav_array_memcpy(packet.vendor_name, vendor_name, sizeof(uint8_t)*32);
mav_array_memcpy(packet.model_name, model_name, sizeof(uint8_t)*32);
mav_array_memcpy(packet.cam_definition_uri, cam_definition_uri, sizeof(char)*140);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CAMERA_INFORMATION_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_CAMERA_INFORMATION;
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_CAMERA_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_CAMERA_INFORMATION_LEN, MAVLINK_MSG_ID_CAMERA_INFORMATION_CRC);
}
/**
* @brief Pack a camera_information message on a channel
* @param system_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 [ms] Timestamp (time since system boot).
* @param vendor_name Name of the camera vendor
* @param model_name Name of the camera model
* @param firmware_version Version of the camera firmware, encoded as: (Dev & 0xff) << 24 | (Patch & 0xff) << 16 | (Minor & 0xff) << 8 | (Major & 0xff)
* @param focal_length [mm] Focal length
* @param sensor_size_h [mm] Image sensor size horizontal
* @param sensor_size_v [mm] Image sensor size vertical
* @param resolution_h [pix] Horizontal image resolution
* @param resolution_v [pix] Vertical image resolution
* @param lens_id Reserved for a lens ID
* @param flags Bitmap of camera capability flags.
* @param cam_definition_version Camera definition version (iteration)
* @param cam_definition_uri Camera definition URI (if any, otherwise only basic functions will be available). HTTP- (http://) and MAVLink FTP- (mavlinkftp://) formatted URIs are allowed (and both must be supported by any GCS that implements the Camera Protocol).
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_camera_information_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint32_t time_boot_ms,const uint8_t *vendor_name,const uint8_t *model_name,uint32_t firmware_version,float focal_length,float sensor_size_h,float sensor_size_v,uint16_t resolution_h,uint16_t resolution_v,uint8_t lens_id,uint32_t flags,uint16_t cam_definition_version,const char *cam_definition_uri)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_CAMERA_INFORMATION_LEN];
_mav_put_uint32_t(buf, 0, time_boot_ms);
_mav_put_uint32_t(buf, 4, firmware_version);
_mav_put_float(buf, 8, focal_length);
_mav_put_float(buf, 12, sensor_size_h);
_mav_put_float(buf, 16, sensor_size_v);
_mav_put_uint32_t(buf, 20, flags);
_mav_put_uint16_t(buf, 24, resolution_h);
_mav_put_uint16_t(buf, 26, resolution_v);
_mav_put_uint16_t(buf, 28, cam_definition_version);
_mav_put_uint8_t(buf, 94, lens_id);
_mav_put_uint8_t_array(buf, 30, vendor_name, 32);
_mav_put_uint8_t_array(buf, 62, model_name, 32);
_mav_put_char_array(buf, 95, cam_definition_uri, 140);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CAMERA_INFORMATION_LEN);
#else
mavlink_camera_information_t packet;
packet.time_boot_ms = time_boot_ms;
packet.firmware_version = firmware_version;
packet.focal_length = focal_length;
packet.sensor_size_h = sensor_size_h;
packet.sensor_size_v = sensor_size_v;
packet.flags = flags;
packet.resolution_h = resolution_h;
packet.resolution_v = resolution_v;
packet.cam_definition_version = cam_definition_version;
packet.lens_id = lens_id;
mav_array_memcpy(packet.vendor_name, vendor_name, sizeof(uint8_t)*32);
mav_array_memcpy(packet.model_name, model_name, sizeof(uint8_t)*32);
mav_array_memcpy(packet.cam_definition_uri, cam_definition_uri, sizeof(char)*140);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CAMERA_INFORMATION_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_CAMERA_INFORMATION;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_CAMERA_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_CAMERA_INFORMATION_LEN, MAVLINK_MSG_ID_CAMERA_INFORMATION_CRC);
}
/**
* @brief Encode a camera_information 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_information C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_camera_information_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_camera_information_t* camera_information)
{
return mavlink_msg_camera_information_pack(system_id, component_id, msg, camera_information->time_boot_ms, camera_information->vendor_name, camera_information->model_name, camera_information->firmware_version, camera_information->focal_length, camera_information->sensor_size_h, camera_information->sensor_size_v, camera_information->resolution_h, camera_information->resolution_v, camera_information->lens_id, camera_information->flags, camera_information->cam_definition_version, camera_information->cam_definition_uri);
}
/**
* @brief Encode a camera_information 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_information C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_camera_information_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_camera_information_t* camera_information)
{
return mavlink_msg_camera_information_pack_chan(system_id, component_id, chan, msg, camera_information->time_boot_ms, camera_information->vendor_name, camera_information->model_name, camera_information->firmware_version, camera_information->focal_length, camera_information->sensor_size_h, camera_information->sensor_size_v, camera_information->resolution_h, camera_information->resolution_v, camera_information->lens_id, camera_information->flags, camera_information->cam_definition_version, camera_information->cam_definition_uri);
}
/**
* @brief Send a camera_information message
* @param chan MAVLink channel to send the message
*
* @param time_boot_ms [ms] Timestamp (time since system boot).
* @param vendor_name Name of the camera vendor
* @param model_name Name of the camera model
* @param firmware_version Version of the camera firmware, encoded as: (Dev & 0xff) << 24 | (Patch & 0xff) << 16 | (Minor & 0xff) << 8 | (Major & 0xff)
* @param focal_length [mm] Focal length
* @param sensor_size_h [mm] Image sensor size horizontal
* @param sensor_size_v [mm] Image sensor size vertical
* @param resolution_h [pix] Horizontal image resolution
* @param resolution_v [pix] Vertical image resolution
* @param lens_id Reserved for a lens ID
* @param flags Bitmap of camera capability flags.
* @param cam_definition_version Camera definition version (iteration)
* @param cam_definition_uri Camera definition URI (if any, otherwise only basic functions will be available). HTTP- (http://) and MAVLink FTP- (mavlinkftp://) formatted URIs are allowed (and both must be supported by any GCS that implements the Camera Protocol).
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_camera_information_send(mavlink_channel_t chan, uint32_t time_boot_ms, const uint8_t *vendor_name, const uint8_t *model_name, uint32_t firmware_version, float focal_length, float sensor_size_h, float sensor_size_v, uint16_t resolution_h, uint16_t resolution_v, uint8_t lens_id, uint32_t flags, uint16_t cam_definition_version, const char *cam_definition_uri)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_CAMERA_INFORMATION_LEN];
_mav_put_uint32_t(buf, 0, time_boot_ms);
_mav_put_uint32_t(buf, 4, firmware_version);
_mav_put_float(buf, 8, focal_length);
_mav_put_float(buf, 12, sensor_size_h);
_mav_put_float(buf, 16, sensor_size_v);
_mav_put_uint32_t(buf, 20, flags);
_mav_put_uint16_t(buf, 24, resolution_h);
_mav_put_uint16_t(buf, 26, resolution_v);
_mav_put_uint16_t(buf, 28, cam_definition_version);
_mav_put_uint8_t(buf, 94, lens_id);
_mav_put_uint8_t_array(buf, 30, vendor_name, 32);
_mav_put_uint8_t_array(buf, 62, model_name, 32);
_mav_put_char_array(buf, 95, cam_definition_uri, 140);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_INFORMATION, buf, MAVLINK_MSG_ID_CAMERA_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_CAMERA_INFORMATION_LEN, MAVLINK_MSG_ID_CAMERA_INFORMATION_CRC);
#else
mavlink_camera_information_t packet;
packet.time_boot_ms = time_boot_ms;
packet.firmware_version = firmware_version;
packet.focal_length = focal_length;
packet.sensor_size_h = sensor_size_h;
packet.sensor_size_v = sensor_size_v;
packet.flags = flags;
packet.resolution_h = resolution_h;
packet.resolution_v = resolution_v;
packet.cam_definition_version = cam_definition_version;
packet.lens_id = lens_id;
mav_array_memcpy(packet.vendor_name, vendor_name, sizeof(uint8_t)*32);
mav_array_memcpy(packet.model_name, model_name, sizeof(uint8_t)*32);
mav_array_memcpy(packet.cam_definition_uri, cam_definition_uri, sizeof(char)*140);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_INFORMATION, (const char *)&packet, MAVLINK_MSG_ID_CAMERA_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_CAMERA_INFORMATION_LEN, MAVLINK_MSG_ID_CAMERA_INFORMATION_CRC);
#endif
}
/**
* @brief Send a camera_information message
* @param chan MAVLink channel to send the message
* @param struct The MAVLink struct to serialize
*/
static inline void mavlink_msg_camera_information_send_struct(mavlink_channel_t chan, const mavlink_camera_information_t* camera_information)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mavlink_msg_camera_information_send(chan, camera_information->time_boot_ms, camera_information->vendor_name, camera_information->model_name, camera_information->firmware_version, camera_information->focal_length, camera_information->sensor_size_h, camera_information->sensor_size_v, camera_information->resolution_h, camera_information->resolution_v, camera_information->lens_id, camera_information->flags, camera_information->cam_definition_version, camera_information->cam_definition_uri);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_INFORMATION, (const char *)camera_information, MAVLINK_MSG_ID_CAMERA_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_CAMERA_INFORMATION_LEN, MAVLINK_MSG_ID_CAMERA_INFORMATION_CRC);
#endif
}
#if MAVLINK_MSG_ID_CAMERA_INFORMATION_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_information_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, const uint8_t *vendor_name, const uint8_t *model_name, uint32_t firmware_version, float focal_length, float sensor_size_h, float sensor_size_v, uint16_t resolution_h, uint16_t resolution_v, uint8_t lens_id, uint32_t flags, uint16_t cam_definition_version, const char *cam_definition_uri)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
_mav_put_uint32_t(buf, 0, time_boot_ms);
_mav_put_uint32_t(buf, 4, firmware_version);
_mav_put_float(buf, 8, focal_length);
_mav_put_float(buf, 12, sensor_size_h);
_mav_put_float(buf, 16, sensor_size_v);
_mav_put_uint32_t(buf, 20, flags);
_mav_put_uint16_t(buf, 24, resolution_h);
_mav_put_uint16_t(buf, 26, resolution_v);
_mav_put_uint16_t(buf, 28, cam_definition_version);
_mav_put_uint8_t(buf, 94, lens_id);
_mav_put_uint8_t_array(buf, 30, vendor_name, 32);
_mav_put_uint8_t_array(buf, 62, model_name, 32);
_mav_put_char_array(buf, 95, cam_definition_uri, 140);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_INFORMATION, buf, MAVLINK_MSG_ID_CAMERA_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_CAMERA_INFORMATION_LEN, MAVLINK_MSG_ID_CAMERA_INFORMATION_CRC);
#else
mavlink_camera_information_t *packet = (mavlink_camera_information_t *)msgbuf;
packet->time_boot_ms = time_boot_ms;
packet->firmware_version = firmware_version;
packet->focal_length = focal_length;
packet->sensor_size_h = sensor_size_h;
packet->sensor_size_v = sensor_size_v;
packet->flags = flags;
packet->resolution_h = resolution_h;
packet->resolution_v = resolution_v;
packet->cam_definition_version = cam_definition_version;
packet->lens_id = lens_id;
mav_array_memcpy(packet->vendor_name, vendor_name, sizeof(uint8_t)*32);
mav_array_memcpy(packet->model_name, model_name, sizeof(uint8_t)*32);
mav_array_memcpy(packet->cam_definition_uri, cam_definition_uri, sizeof(char)*140);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_INFORMATION, (const char *)packet, MAVLINK_MSG_ID_CAMERA_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_CAMERA_INFORMATION_LEN, MAVLINK_MSG_ID_CAMERA_INFORMATION_CRC);
#endif
}
#endif
#endif
// MESSAGE CAMERA_INFORMATION UNPACKING
/**
* @brief Get field time_boot_ms from camera_information message
*
* @return [ms] Timestamp (time since system boot).
*/
static inline uint32_t mavlink_msg_camera_information_get_time_boot_ms(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint32_t(msg, 0);
}
/**
* @brief Get field vendor_name from camera_information message
*
* @return Name of the camera vendor
*/
static inline uint16_t mavlink_msg_camera_information_get_vendor_name(const mavlink_message_t* msg, uint8_t *vendor_name)
{
return _MAV_RETURN_uint8_t_array(msg, vendor_name, 32, 30);
}
/**
* @brief Get field model_name from camera_information message
*
* @return Name of the camera model
*/
static inline uint16_t mavlink_msg_camera_information_get_model_name(const mavlink_message_t* msg, uint8_t *model_name)
{
return _MAV_RETURN_uint8_t_array(msg, model_name, 32, 62);
}
/**
* @brief Get field firmware_version from camera_information message
*
* @return Version of the camera firmware, encoded as: (Dev & 0xff) << 24 | (Patch & 0xff) << 16 | (Minor & 0xff) << 8 | (Major & 0xff)
*/
static inline uint32_t mavlink_msg_camera_information_get_firmware_version(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint32_t(msg, 4);
}
/**
* @brief Get field focal_length from camera_information message
*
* @return [mm] Focal length
*/
static inline float mavlink_msg_camera_information_get_focal_length(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 8);
}
/**
* @brief Get field sensor_size_h from camera_information message
*
* @return [mm] Image sensor size horizontal
*/
static inline float mavlink_msg_camera_information_get_sensor_size_h(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 12);
}
/**
* @brief Get field sensor_size_v from camera_information message
*
* @return [mm] Image sensor size vertical
*/
static inline float mavlink_msg_camera_information_get_sensor_size_v(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 16);
}
/**
* @brief Get field resolution_h from camera_information message
*
* @return [pix] Horizontal image resolution
*/
static inline uint16_t mavlink_msg_camera_information_get_resolution_h(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 24);
}
/**
* @brief Get field resolution_v from camera_information message
*
* @return [pix] Vertical image resolution
*/
static inline uint16_t mavlink_msg_camera_information_get_resolution_v(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 26);
}
/**
* @brief Get field lens_id from camera_information message
*
* @return Reserved for a lens ID
*/
static inline uint8_t mavlink_msg_camera_information_get_lens_id(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 94);
}
/**
* @brief Get field flags from camera_information message
*
* @return Bitmap of camera capability flags.
*/
static inline uint32_t mavlink_msg_camera_information_get_flags(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint32_t(msg, 20);
}
/**
* @brief Get field cam_definition_version from camera_information message
*
* @return Camera definition version (iteration)
*/
static inline uint16_t mavlink_msg_camera_information_get_cam_definition_version(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 28);
}
/**
* @brief Get field cam_definition_uri from camera_information message
*
* @return Camera definition URI (if any, otherwise only basic functions will be available). HTTP- (http://) and MAVLink FTP- (mavlinkftp://) formatted URIs are allowed (and both must be supported by any GCS that implements the Camera Protocol).
*/
static inline uint16_t mavlink_msg_camera_information_get_cam_definition_uri(const mavlink_message_t* msg, char *cam_definition_uri)
{
return _MAV_RETURN_char_array(msg, cam_definition_uri, 140, 95);
}
/**
* @brief Decode a camera_information message into a struct
*
* @param msg The message to decode
* @param camera_information C-struct to decode the message contents into
*/
static inline void mavlink_msg_camera_information_decode(const mavlink_message_t* msg, mavlink_camera_information_t* camera_information)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
camera_information->time_boot_ms = mavlink_msg_camera_information_get_time_boot_ms(msg);
camera_information->firmware_version = mavlink_msg_camera_information_get_firmware_version(msg);
camera_information->focal_length = mavlink_msg_camera_information_get_focal_length(msg);
camera_information->sensor_size_h = mavlink_msg_camera_information_get_sensor_size_h(msg);
camera_information->sensor_size_v = mavlink_msg_camera_information_get_sensor_size_v(msg);
camera_information->flags = mavlink_msg_camera_information_get_flags(msg);
camera_information->resolution_h = mavlink_msg_camera_information_get_resolution_h(msg);
camera_information->resolution_v = mavlink_msg_camera_information_get_resolution_v(msg);
camera_information->cam_definition_version = mavlink_msg_camera_information_get_cam_definition_version(msg);
mavlink_msg_camera_information_get_vendor_name(msg, camera_information->vendor_name);
mavlink_msg_camera_information_get_model_name(msg, camera_information->model_name);
camera_information->lens_id = mavlink_msg_camera_information_get_lens_id(msg);
mavlink_msg_camera_information_get_cam_definition_uri(msg, camera_information->cam_definition_uri);
#else
uint8_t len = msg->len < MAVLINK_MSG_ID_CAMERA_INFORMATION_LEN? msg->len : MAVLINK_MSG_ID_CAMERA_INFORMATION_LEN;
memset(camera_information, 0, MAVLINK_MSG_ID_CAMERA_INFORMATION_LEN);
memcpy(camera_information, _MAV_PAYLOAD(msg), len);
#endif
}

View file

@ -0,0 +1,288 @@
#pragma once
// MESSAGE CAMERA_SETTINGS PACKING
#define MAVLINK_MSG_ID_CAMERA_SETTINGS 260
MAVPACKED(
typedef struct __mavlink_camera_settings_t {
uint32_t time_boot_ms; /*< [ms] Timestamp (time since system boot).*/
uint8_t mode_id; /*< Camera mode*/
float zoomLevel; /*< Current zoom level (0.0 to 100.0, NaN if not known)*/
float focusLevel; /*< Current focus level (0.0 to 100.0, NaN if not known)*/
}) mavlink_camera_settings_t;
#define MAVLINK_MSG_ID_CAMERA_SETTINGS_LEN 13
#define MAVLINK_MSG_ID_CAMERA_SETTINGS_MIN_LEN 5
#define MAVLINK_MSG_ID_260_LEN 13
#define MAVLINK_MSG_ID_260_MIN_LEN 5
#define MAVLINK_MSG_ID_CAMERA_SETTINGS_CRC 146
#define MAVLINK_MSG_ID_260_CRC 146
#if MAVLINK_COMMAND_24BIT
#define MAVLINK_MESSAGE_INFO_CAMERA_SETTINGS { \
260, \
"CAMERA_SETTINGS", \
4, \
{ { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_camera_settings_t, time_boot_ms) }, \
{ "mode_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_camera_settings_t, mode_id) }, \
{ "zoomLevel", NULL, MAVLINK_TYPE_FLOAT, 0, 5, offsetof(mavlink_camera_settings_t, zoomLevel) }, \
{ "focusLevel", NULL, MAVLINK_TYPE_FLOAT, 0, 9, offsetof(mavlink_camera_settings_t, focusLevel) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_CAMERA_SETTINGS { \
"CAMERA_SETTINGS", \
4, \
{ { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_camera_settings_t, time_boot_ms) }, \
{ "mode_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_camera_settings_t, mode_id) }, \
{ "zoomLevel", NULL, MAVLINK_TYPE_FLOAT, 0, 5, offsetof(mavlink_camera_settings_t, zoomLevel) }, \
{ "focusLevel", NULL, MAVLINK_TYPE_FLOAT, 0, 9, offsetof(mavlink_camera_settings_t, focusLevel) }, \
} \
}
#endif
/**
* @brief Pack a camera_settings message
* @param system_id ID of this 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 [ms] Timestamp (time since system boot).
* @param mode_id Camera mode
* @param zoomLevel Current zoom level (0.0 to 100.0, NaN if not known)
* @param focusLevel Current focus level (0.0 to 100.0, NaN if not known)
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_camera_settings_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint32_t time_boot_ms, uint8_t mode_id, float zoomLevel, float focusLevel)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_CAMERA_SETTINGS_LEN];
_mav_put_uint32_t(buf, 0, time_boot_ms);
_mav_put_uint8_t(buf, 4, mode_id);
_mav_put_float(buf, 5, zoomLevel);
_mav_put_float(buf, 9, focusLevel);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CAMERA_SETTINGS_LEN);
#else
mavlink_camera_settings_t packet;
packet.time_boot_ms = time_boot_ms;
packet.mode_id = mode_id;
packet.zoomLevel = zoomLevel;
packet.focusLevel = focusLevel;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CAMERA_SETTINGS_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_CAMERA_SETTINGS;
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_CAMERA_SETTINGS_MIN_LEN, MAVLINK_MSG_ID_CAMERA_SETTINGS_LEN, MAVLINK_MSG_ID_CAMERA_SETTINGS_CRC);
}
/**
* @brief Pack a camera_settings message on a channel
* @param system_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 [ms] Timestamp (time since system boot).
* @param mode_id Camera mode
* @param zoomLevel Current zoom level (0.0 to 100.0, NaN if not known)
* @param focusLevel Current focus level (0.0 to 100.0, NaN if not known)
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_camera_settings_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint32_t time_boot_ms,uint8_t mode_id,float zoomLevel,float focusLevel)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_CAMERA_SETTINGS_LEN];
_mav_put_uint32_t(buf, 0, time_boot_ms);
_mav_put_uint8_t(buf, 4, mode_id);
_mav_put_float(buf, 5, zoomLevel);
_mav_put_float(buf, 9, focusLevel);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CAMERA_SETTINGS_LEN);
#else
mavlink_camera_settings_t packet;
packet.time_boot_ms = time_boot_ms;
packet.mode_id = mode_id;
packet.zoomLevel = zoomLevel;
packet.focusLevel = focusLevel;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CAMERA_SETTINGS_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_CAMERA_SETTINGS;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_CAMERA_SETTINGS_MIN_LEN, MAVLINK_MSG_ID_CAMERA_SETTINGS_LEN, MAVLINK_MSG_ID_CAMERA_SETTINGS_CRC);
}
/**
* @brief Encode a camera_settings 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_settings C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_camera_settings_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_camera_settings_t* camera_settings)
{
return mavlink_msg_camera_settings_pack(system_id, component_id, msg, camera_settings->time_boot_ms, camera_settings->mode_id, camera_settings->zoomLevel, camera_settings->focusLevel);
}
/**
* @brief Encode a camera_settings 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_settings C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_camera_settings_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_camera_settings_t* camera_settings)
{
return mavlink_msg_camera_settings_pack_chan(system_id, component_id, chan, msg, camera_settings->time_boot_ms, camera_settings->mode_id, camera_settings->zoomLevel, camera_settings->focusLevel);
}
/**
* @brief Send a camera_settings message
* @param chan MAVLink channel to send the message
*
* @param time_boot_ms [ms] Timestamp (time since system boot).
* @param mode_id Camera mode
* @param zoomLevel Current zoom level (0.0 to 100.0, NaN if not known)
* @param focusLevel Current focus level (0.0 to 100.0, NaN if not known)
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_camera_settings_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t mode_id, float zoomLevel, float focusLevel)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_CAMERA_SETTINGS_LEN];
_mav_put_uint32_t(buf, 0, time_boot_ms);
_mav_put_uint8_t(buf, 4, mode_id);
_mav_put_float(buf, 5, zoomLevel);
_mav_put_float(buf, 9, focusLevel);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_SETTINGS, buf, MAVLINK_MSG_ID_CAMERA_SETTINGS_MIN_LEN, MAVLINK_MSG_ID_CAMERA_SETTINGS_LEN, MAVLINK_MSG_ID_CAMERA_SETTINGS_CRC);
#else
mavlink_camera_settings_t packet;
packet.time_boot_ms = time_boot_ms;
packet.mode_id = mode_id;
packet.zoomLevel = zoomLevel;
packet.focusLevel = focusLevel;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_SETTINGS, (const char *)&packet, MAVLINK_MSG_ID_CAMERA_SETTINGS_MIN_LEN, MAVLINK_MSG_ID_CAMERA_SETTINGS_LEN, MAVLINK_MSG_ID_CAMERA_SETTINGS_CRC);
#endif
}
/**
* @brief Send a camera_settings message
* @param chan MAVLink channel to send the message
* @param struct The MAVLink struct to serialize
*/
static inline void mavlink_msg_camera_settings_send_struct(mavlink_channel_t chan, const mavlink_camera_settings_t* camera_settings)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mavlink_msg_camera_settings_send(chan, camera_settings->time_boot_ms, camera_settings->mode_id, camera_settings->zoomLevel, camera_settings->focusLevel);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_SETTINGS, (const char *)camera_settings, MAVLINK_MSG_ID_CAMERA_SETTINGS_MIN_LEN, MAVLINK_MSG_ID_CAMERA_SETTINGS_LEN, MAVLINK_MSG_ID_CAMERA_SETTINGS_CRC);
#endif
}
#if MAVLINK_MSG_ID_CAMERA_SETTINGS_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_settings_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, uint8_t mode_id, float zoomLevel, float focusLevel)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
_mav_put_uint32_t(buf, 0, time_boot_ms);
_mav_put_uint8_t(buf, 4, mode_id);
_mav_put_float(buf, 5, zoomLevel);
_mav_put_float(buf, 9, focusLevel);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_SETTINGS, buf, MAVLINK_MSG_ID_CAMERA_SETTINGS_MIN_LEN, MAVLINK_MSG_ID_CAMERA_SETTINGS_LEN, MAVLINK_MSG_ID_CAMERA_SETTINGS_CRC);
#else
mavlink_camera_settings_t *packet = (mavlink_camera_settings_t *)msgbuf;
packet->time_boot_ms = time_boot_ms;
packet->mode_id = mode_id;
packet->zoomLevel = zoomLevel;
packet->focusLevel = focusLevel;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_SETTINGS, (const char *)packet, MAVLINK_MSG_ID_CAMERA_SETTINGS_MIN_LEN, MAVLINK_MSG_ID_CAMERA_SETTINGS_LEN, MAVLINK_MSG_ID_CAMERA_SETTINGS_CRC);
#endif
}
#endif
#endif
// MESSAGE CAMERA_SETTINGS UNPACKING
/**
* @brief Get field time_boot_ms from camera_settings message
*
* @return [ms] Timestamp (time since system boot).
*/
static inline uint32_t mavlink_msg_camera_settings_get_time_boot_ms(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint32_t(msg, 0);
}
/**
* @brief Get field mode_id from camera_settings message
*
* @return Camera mode
*/
static inline uint8_t mavlink_msg_camera_settings_get_mode_id(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 4);
}
/**
* @brief Get field zoomLevel from camera_settings message
*
* @return Current zoom level (0.0 to 100.0, NaN if not known)
*/
static inline float mavlink_msg_camera_settings_get_zoomLevel(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 5);
}
/**
* @brief Get field focusLevel from camera_settings message
*
* @return Current focus level (0.0 to 100.0, NaN if not known)
*/
static inline float mavlink_msg_camera_settings_get_focusLevel(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 9);
}
/**
* @brief Decode a camera_settings message into a struct
*
* @param msg The message to decode
* @param camera_settings C-struct to decode the message contents into
*/
static inline void mavlink_msg_camera_settings_decode(const mavlink_message_t* msg, mavlink_camera_settings_t* camera_settings)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
camera_settings->time_boot_ms = mavlink_msg_camera_settings_get_time_boot_ms(msg);
camera_settings->mode_id = mavlink_msg_camera_settings_get_mode_id(msg);
camera_settings->zoomLevel = mavlink_msg_camera_settings_get_zoomLevel(msg);
camera_settings->focusLevel = mavlink_msg_camera_settings_get_focusLevel(msg);
#else
uint8_t len = msg->len < MAVLINK_MSG_ID_CAMERA_SETTINGS_LEN? msg->len : MAVLINK_MSG_ID_CAMERA_SETTINGS_LEN;
memset(camera_settings, 0, MAVLINK_MSG_ID_CAMERA_SETTINGS_LEN);
memcpy(camera_settings, _MAV_PAYLOAD(msg), len);
#endif
}

View file

@ -0,0 +1,513 @@
#pragma once
// MESSAGE CAMERA_TRACKING_GEO_STATUS PACKING
#define MAVLINK_MSG_ID_CAMERA_TRACKING_GEO_STATUS 276
typedef struct __mavlink_camera_tracking_geo_status_t {
int32_t lat; /*< [degE7] Latitude of tracked object*/
int32_t lon; /*< [degE7] Longitude of tracked object*/
float alt; /*< [m] Altitude of tracked object(AMSL, WGS84)*/
float h_acc; /*< [m] Horizontal accuracy. NAN if unknown*/
float v_acc; /*< [m] Vertical accuracy. NAN if unknown*/
float vel_n; /*< [m/s] North velocity of tracked object. NAN if unknown*/
float vel_e; /*< [m/s] East velocity of tracked object. NAN if unknown*/
float vel_d; /*< [m/s] Down velocity of tracked object. NAN if unknown*/
float vel_acc; /*< [m/s] Velocity accuracy. NAN if unknown*/
float dist; /*< [m] Distance between camera and tracked object. NAN if unknown*/
float hdg; /*< [rad] Heading in radians, in NED. NAN if unknown*/
float hdg_acc; /*< [rad] Accuracy of heading, in NED. NAN if unknown*/
uint8_t tracking_status; /*< Current tracking status*/
} mavlink_camera_tracking_geo_status_t;
#define MAVLINK_MSG_ID_CAMERA_TRACKING_GEO_STATUS_LEN 49
#define MAVLINK_MSG_ID_CAMERA_TRACKING_GEO_STATUS_MIN_LEN 49
#define MAVLINK_MSG_ID_276_LEN 49
#define MAVLINK_MSG_ID_276_MIN_LEN 49
#define MAVLINK_MSG_ID_CAMERA_TRACKING_GEO_STATUS_CRC 18
#define MAVLINK_MSG_ID_276_CRC 18
#if MAVLINK_COMMAND_24BIT
#define MAVLINK_MESSAGE_INFO_CAMERA_TRACKING_GEO_STATUS { \
276, \
"CAMERA_TRACKING_GEO_STATUS", \
13, \
{ { "tracking_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 48, offsetof(mavlink_camera_tracking_geo_status_t, tracking_status) }, \
{ "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_camera_tracking_geo_status_t, lat) }, \
{ "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_camera_tracking_geo_status_t, lon) }, \
{ "alt", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_camera_tracking_geo_status_t, alt) }, \
{ "h_acc", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_camera_tracking_geo_status_t, h_acc) }, \
{ "v_acc", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_camera_tracking_geo_status_t, v_acc) }, \
{ "vel_n", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_camera_tracking_geo_status_t, vel_n) }, \
{ "vel_e", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_camera_tracking_geo_status_t, vel_e) }, \
{ "vel_d", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_camera_tracking_geo_status_t, vel_d) }, \
{ "vel_acc", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_camera_tracking_geo_status_t, vel_acc) }, \
{ "dist", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_camera_tracking_geo_status_t, dist) }, \
{ "hdg", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_camera_tracking_geo_status_t, hdg) }, \
{ "hdg_acc", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_camera_tracking_geo_status_t, hdg_acc) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_CAMERA_TRACKING_GEO_STATUS { \
"CAMERA_TRACKING_GEO_STATUS", \
13, \
{ { "tracking_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 48, offsetof(mavlink_camera_tracking_geo_status_t, tracking_status) }, \
{ "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_camera_tracking_geo_status_t, lat) }, \
{ "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_camera_tracking_geo_status_t, lon) }, \
{ "alt", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_camera_tracking_geo_status_t, alt) }, \
{ "h_acc", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_camera_tracking_geo_status_t, h_acc) }, \
{ "v_acc", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_camera_tracking_geo_status_t, v_acc) }, \
{ "vel_n", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_camera_tracking_geo_status_t, vel_n) }, \
{ "vel_e", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_camera_tracking_geo_status_t, vel_e) }, \
{ "vel_d", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_camera_tracking_geo_status_t, vel_d) }, \
{ "vel_acc", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_camera_tracking_geo_status_t, vel_acc) }, \
{ "dist", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_camera_tracking_geo_status_t, dist) }, \
{ "hdg", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_camera_tracking_geo_status_t, hdg) }, \
{ "hdg_acc", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_camera_tracking_geo_status_t, hdg_acc) }, \
} \
}
#endif
/**
* @brief Pack a camera_tracking_geo_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 tracking_status Current tracking status
* @param lat [degE7] Latitude of tracked object
* @param lon [degE7] Longitude of tracked object
* @param alt [m] Altitude of tracked object(AMSL, WGS84)
* @param h_acc [m] Horizontal accuracy. NAN if unknown
* @param v_acc [m] Vertical accuracy. NAN if unknown
* @param vel_n [m/s] North velocity of tracked object. NAN if unknown
* @param vel_e [m/s] East velocity of tracked object. NAN if unknown
* @param vel_d [m/s] Down velocity of tracked object. NAN if unknown
* @param vel_acc [m/s] Velocity accuracy. NAN if unknown
* @param dist [m] Distance between camera and tracked object. NAN if unknown
* @param hdg [rad] Heading in radians, in NED. NAN if unknown
* @param hdg_acc [rad] Accuracy of heading, in NED. NAN if unknown
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_camera_tracking_geo_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t tracking_status, int32_t lat, int32_t lon, float alt, float h_acc, float v_acc, float vel_n, float vel_e, float vel_d, float vel_acc, float dist, float hdg, float hdg_acc)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_CAMERA_TRACKING_GEO_STATUS_LEN];
_mav_put_int32_t(buf, 0, lat);
_mav_put_int32_t(buf, 4, lon);
_mav_put_float(buf, 8, alt);
_mav_put_float(buf, 12, h_acc);
_mav_put_float(buf, 16, v_acc);
_mav_put_float(buf, 20, vel_n);
_mav_put_float(buf, 24, vel_e);
_mav_put_float(buf, 28, vel_d);
_mav_put_float(buf, 32, vel_acc);
_mav_put_float(buf, 36, dist);
_mav_put_float(buf, 40, hdg);
_mav_put_float(buf, 44, hdg_acc);
_mav_put_uint8_t(buf, 48, tracking_status);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CAMERA_TRACKING_GEO_STATUS_LEN);
#else
mavlink_camera_tracking_geo_status_t packet;
packet.lat = lat;
packet.lon = lon;
packet.alt = alt;
packet.h_acc = h_acc;
packet.v_acc = v_acc;
packet.vel_n = vel_n;
packet.vel_e = vel_e;
packet.vel_d = vel_d;
packet.vel_acc = vel_acc;
packet.dist = dist;
packet.hdg = hdg;
packet.hdg_acc = hdg_acc;
packet.tracking_status = tracking_status;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CAMERA_TRACKING_GEO_STATUS_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_CAMERA_TRACKING_GEO_STATUS;
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_CAMERA_TRACKING_GEO_STATUS_MIN_LEN, MAVLINK_MSG_ID_CAMERA_TRACKING_GEO_STATUS_LEN, MAVLINK_MSG_ID_CAMERA_TRACKING_GEO_STATUS_CRC);
}
/**
* @brief Pack a camera_tracking_geo_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 tracking_status Current tracking status
* @param lat [degE7] Latitude of tracked object
* @param lon [degE7] Longitude of tracked object
* @param alt [m] Altitude of tracked object(AMSL, WGS84)
* @param h_acc [m] Horizontal accuracy. NAN if unknown
* @param v_acc [m] Vertical accuracy. NAN if unknown
* @param vel_n [m/s] North velocity of tracked object. NAN if unknown
* @param vel_e [m/s] East velocity of tracked object. NAN if unknown
* @param vel_d [m/s] Down velocity of tracked object. NAN if unknown
* @param vel_acc [m/s] Velocity accuracy. NAN if unknown
* @param dist [m] Distance between camera and tracked object. NAN if unknown
* @param hdg [rad] Heading in radians, in NED. NAN if unknown
* @param hdg_acc [rad] Accuracy of heading, in NED. NAN if unknown
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_camera_tracking_geo_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint8_t tracking_status,int32_t lat,int32_t lon,float alt,float h_acc,float v_acc,float vel_n,float vel_e,float vel_d,float vel_acc,float dist,float hdg,float hdg_acc)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_CAMERA_TRACKING_GEO_STATUS_LEN];
_mav_put_int32_t(buf, 0, lat);
_mav_put_int32_t(buf, 4, lon);
_mav_put_float(buf, 8, alt);
_mav_put_float(buf, 12, h_acc);
_mav_put_float(buf, 16, v_acc);
_mav_put_float(buf, 20, vel_n);
_mav_put_float(buf, 24, vel_e);
_mav_put_float(buf, 28, vel_d);
_mav_put_float(buf, 32, vel_acc);
_mav_put_float(buf, 36, dist);
_mav_put_float(buf, 40, hdg);
_mav_put_float(buf, 44, hdg_acc);
_mav_put_uint8_t(buf, 48, tracking_status);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CAMERA_TRACKING_GEO_STATUS_LEN);
#else
mavlink_camera_tracking_geo_status_t packet;
packet.lat = lat;
packet.lon = lon;
packet.alt = alt;
packet.h_acc = h_acc;
packet.v_acc = v_acc;
packet.vel_n = vel_n;
packet.vel_e = vel_e;
packet.vel_d = vel_d;
packet.vel_acc = vel_acc;
packet.dist = dist;
packet.hdg = hdg;
packet.hdg_acc = hdg_acc;
packet.tracking_status = tracking_status;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CAMERA_TRACKING_GEO_STATUS_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_CAMERA_TRACKING_GEO_STATUS;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_CAMERA_TRACKING_GEO_STATUS_MIN_LEN, MAVLINK_MSG_ID_CAMERA_TRACKING_GEO_STATUS_LEN, MAVLINK_MSG_ID_CAMERA_TRACKING_GEO_STATUS_CRC);
}
/**
* @brief Encode a camera_tracking_geo_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 camera_tracking_geo_status C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_camera_tracking_geo_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_camera_tracking_geo_status_t* camera_tracking_geo_status)
{
return mavlink_msg_camera_tracking_geo_status_pack(system_id, component_id, msg, camera_tracking_geo_status->tracking_status, camera_tracking_geo_status->lat, camera_tracking_geo_status->lon, camera_tracking_geo_status->alt, camera_tracking_geo_status->h_acc, camera_tracking_geo_status->v_acc, camera_tracking_geo_status->vel_n, camera_tracking_geo_status->vel_e, camera_tracking_geo_status->vel_d, camera_tracking_geo_status->vel_acc, camera_tracking_geo_status->dist, camera_tracking_geo_status->hdg, camera_tracking_geo_status->hdg_acc);
}
/**
* @brief Encode a camera_tracking_geo_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 camera_tracking_geo_status C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_camera_tracking_geo_status_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_camera_tracking_geo_status_t* camera_tracking_geo_status)
{
return mavlink_msg_camera_tracking_geo_status_pack_chan(system_id, component_id, chan, msg, camera_tracking_geo_status->tracking_status, camera_tracking_geo_status->lat, camera_tracking_geo_status->lon, camera_tracking_geo_status->alt, camera_tracking_geo_status->h_acc, camera_tracking_geo_status->v_acc, camera_tracking_geo_status->vel_n, camera_tracking_geo_status->vel_e, camera_tracking_geo_status->vel_d, camera_tracking_geo_status->vel_acc, camera_tracking_geo_status->dist, camera_tracking_geo_status->hdg, camera_tracking_geo_status->hdg_acc);
}
/**
* @brief Send a camera_tracking_geo_status message
* @param chan MAVLink channel to send the message
*
* @param tracking_status Current tracking status
* @param lat [degE7] Latitude of tracked object
* @param lon [degE7] Longitude of tracked object
* @param alt [m] Altitude of tracked object(AMSL, WGS84)
* @param h_acc [m] Horizontal accuracy. NAN if unknown
* @param v_acc [m] Vertical accuracy. NAN if unknown
* @param vel_n [m/s] North velocity of tracked object. NAN if unknown
* @param vel_e [m/s] East velocity of tracked object. NAN if unknown
* @param vel_d [m/s] Down velocity of tracked object. NAN if unknown
* @param vel_acc [m/s] Velocity accuracy. NAN if unknown
* @param dist [m] Distance between camera and tracked object. NAN if unknown
* @param hdg [rad] Heading in radians, in NED. NAN if unknown
* @param hdg_acc [rad] Accuracy of heading, in NED. NAN if unknown
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_camera_tracking_geo_status_send(mavlink_channel_t chan, uint8_t tracking_status, int32_t lat, int32_t lon, float alt, float h_acc, float v_acc, float vel_n, float vel_e, float vel_d, float vel_acc, float dist, float hdg, float hdg_acc)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_CAMERA_TRACKING_GEO_STATUS_LEN];
_mav_put_int32_t(buf, 0, lat);
_mav_put_int32_t(buf, 4, lon);
_mav_put_float(buf, 8, alt);
_mav_put_float(buf, 12, h_acc);
_mav_put_float(buf, 16, v_acc);
_mav_put_float(buf, 20, vel_n);
_mav_put_float(buf, 24, vel_e);
_mav_put_float(buf, 28, vel_d);
_mav_put_float(buf, 32, vel_acc);
_mav_put_float(buf, 36, dist);
_mav_put_float(buf, 40, hdg);
_mav_put_float(buf, 44, hdg_acc);
_mav_put_uint8_t(buf, 48, tracking_status);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_TRACKING_GEO_STATUS, buf, MAVLINK_MSG_ID_CAMERA_TRACKING_GEO_STATUS_MIN_LEN, MAVLINK_MSG_ID_CAMERA_TRACKING_GEO_STATUS_LEN, MAVLINK_MSG_ID_CAMERA_TRACKING_GEO_STATUS_CRC);
#else
mavlink_camera_tracking_geo_status_t packet;
packet.lat = lat;
packet.lon = lon;
packet.alt = alt;
packet.h_acc = h_acc;
packet.v_acc = v_acc;
packet.vel_n = vel_n;
packet.vel_e = vel_e;
packet.vel_d = vel_d;
packet.vel_acc = vel_acc;
packet.dist = dist;
packet.hdg = hdg;
packet.hdg_acc = hdg_acc;
packet.tracking_status = tracking_status;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_TRACKING_GEO_STATUS, (const char *)&packet, MAVLINK_MSG_ID_CAMERA_TRACKING_GEO_STATUS_MIN_LEN, MAVLINK_MSG_ID_CAMERA_TRACKING_GEO_STATUS_LEN, MAVLINK_MSG_ID_CAMERA_TRACKING_GEO_STATUS_CRC);
#endif
}
/**
* @brief Send a camera_tracking_geo_status message
* @param chan MAVLink channel to send the message
* @param struct The MAVLink struct to serialize
*/
static inline void mavlink_msg_camera_tracking_geo_status_send_struct(mavlink_channel_t chan, const mavlink_camera_tracking_geo_status_t* camera_tracking_geo_status)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mavlink_msg_camera_tracking_geo_status_send(chan, camera_tracking_geo_status->tracking_status, camera_tracking_geo_status->lat, camera_tracking_geo_status->lon, camera_tracking_geo_status->alt, camera_tracking_geo_status->h_acc, camera_tracking_geo_status->v_acc, camera_tracking_geo_status->vel_n, camera_tracking_geo_status->vel_e, camera_tracking_geo_status->vel_d, camera_tracking_geo_status->vel_acc, camera_tracking_geo_status->dist, camera_tracking_geo_status->hdg, camera_tracking_geo_status->hdg_acc);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_TRACKING_GEO_STATUS, (const char *)camera_tracking_geo_status, MAVLINK_MSG_ID_CAMERA_TRACKING_GEO_STATUS_MIN_LEN, MAVLINK_MSG_ID_CAMERA_TRACKING_GEO_STATUS_LEN, MAVLINK_MSG_ID_CAMERA_TRACKING_GEO_STATUS_CRC);
#endif
}
#if MAVLINK_MSG_ID_CAMERA_TRACKING_GEO_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_camera_tracking_geo_status_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t tracking_status, int32_t lat, int32_t lon, float alt, float h_acc, float v_acc, float vel_n, float vel_e, float vel_d, float vel_acc, float dist, float hdg, float hdg_acc)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
_mav_put_int32_t(buf, 0, lat);
_mav_put_int32_t(buf, 4, lon);
_mav_put_float(buf, 8, alt);
_mav_put_float(buf, 12, h_acc);
_mav_put_float(buf, 16, v_acc);
_mav_put_float(buf, 20, vel_n);
_mav_put_float(buf, 24, vel_e);
_mav_put_float(buf, 28, vel_d);
_mav_put_float(buf, 32, vel_acc);
_mav_put_float(buf, 36, dist);
_mav_put_float(buf, 40, hdg);
_mav_put_float(buf, 44, hdg_acc);
_mav_put_uint8_t(buf, 48, tracking_status);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_TRACKING_GEO_STATUS, buf, MAVLINK_MSG_ID_CAMERA_TRACKING_GEO_STATUS_MIN_LEN, MAVLINK_MSG_ID_CAMERA_TRACKING_GEO_STATUS_LEN, MAVLINK_MSG_ID_CAMERA_TRACKING_GEO_STATUS_CRC);
#else
mavlink_camera_tracking_geo_status_t *packet = (mavlink_camera_tracking_geo_status_t *)msgbuf;
packet->lat = lat;
packet->lon = lon;
packet->alt = alt;
packet->h_acc = h_acc;
packet->v_acc = v_acc;
packet->vel_n = vel_n;
packet->vel_e = vel_e;
packet->vel_d = vel_d;
packet->vel_acc = vel_acc;
packet->dist = dist;
packet->hdg = hdg;
packet->hdg_acc = hdg_acc;
packet->tracking_status = tracking_status;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_TRACKING_GEO_STATUS, (const char *)packet, MAVLINK_MSG_ID_CAMERA_TRACKING_GEO_STATUS_MIN_LEN, MAVLINK_MSG_ID_CAMERA_TRACKING_GEO_STATUS_LEN, MAVLINK_MSG_ID_CAMERA_TRACKING_GEO_STATUS_CRC);
#endif
}
#endif
#endif
// MESSAGE CAMERA_TRACKING_GEO_STATUS UNPACKING
/**
* @brief Get field tracking_status from camera_tracking_geo_status message
*
* @return Current tracking status
*/
static inline uint8_t mavlink_msg_camera_tracking_geo_status_get_tracking_status(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 48);
}
/**
* @brief Get field lat from camera_tracking_geo_status message
*
* @return [degE7] Latitude of tracked object
*/
static inline int32_t mavlink_msg_camera_tracking_geo_status_get_lat(const mavlink_message_t* msg)
{
return _MAV_RETURN_int32_t(msg, 0);
}
/**
* @brief Get field lon from camera_tracking_geo_status message
*
* @return [degE7] Longitude of tracked object
*/
static inline int32_t mavlink_msg_camera_tracking_geo_status_get_lon(const mavlink_message_t* msg)
{
return _MAV_RETURN_int32_t(msg, 4);
}
/**
* @brief Get field alt from camera_tracking_geo_status message
*
* @return [m] Altitude of tracked object(AMSL, WGS84)
*/
static inline float mavlink_msg_camera_tracking_geo_status_get_alt(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 8);
}
/**
* @brief Get field h_acc from camera_tracking_geo_status message
*
* @return [m] Horizontal accuracy. NAN if unknown
*/
static inline float mavlink_msg_camera_tracking_geo_status_get_h_acc(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 12);
}
/**
* @brief Get field v_acc from camera_tracking_geo_status message
*
* @return [m] Vertical accuracy. NAN if unknown
*/
static inline float mavlink_msg_camera_tracking_geo_status_get_v_acc(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 16);
}
/**
* @brief Get field vel_n from camera_tracking_geo_status message
*
* @return [m/s] North velocity of tracked object. NAN if unknown
*/
static inline float mavlink_msg_camera_tracking_geo_status_get_vel_n(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 20);
}
/**
* @brief Get field vel_e from camera_tracking_geo_status message
*
* @return [m/s] East velocity of tracked object. NAN if unknown
*/
static inline float mavlink_msg_camera_tracking_geo_status_get_vel_e(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 24);
}
/**
* @brief Get field vel_d from camera_tracking_geo_status message
*
* @return [m/s] Down velocity of tracked object. NAN if unknown
*/
static inline float mavlink_msg_camera_tracking_geo_status_get_vel_d(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 28);
}
/**
* @brief Get field vel_acc from camera_tracking_geo_status message
*
* @return [m/s] Velocity accuracy. NAN if unknown
*/
static inline float mavlink_msg_camera_tracking_geo_status_get_vel_acc(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 32);
}
/**
* @brief Get field dist from camera_tracking_geo_status message
*
* @return [m] Distance between camera and tracked object. NAN if unknown
*/
static inline float mavlink_msg_camera_tracking_geo_status_get_dist(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 36);
}
/**
* @brief Get field hdg from camera_tracking_geo_status message
*
* @return [rad] Heading in radians, in NED. NAN if unknown
*/
static inline float mavlink_msg_camera_tracking_geo_status_get_hdg(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 40);
}
/**
* @brief Get field hdg_acc from camera_tracking_geo_status message
*
* @return [rad] Accuracy of heading, in NED. NAN if unknown
*/
static inline float mavlink_msg_camera_tracking_geo_status_get_hdg_acc(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 44);
}
/**
* @brief Decode a camera_tracking_geo_status message into a struct
*
* @param msg The message to decode
* @param camera_tracking_geo_status C-struct to decode the message contents into
*/
static inline void mavlink_msg_camera_tracking_geo_status_decode(const mavlink_message_t* msg, mavlink_camera_tracking_geo_status_t* camera_tracking_geo_status)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
camera_tracking_geo_status->lat = mavlink_msg_camera_tracking_geo_status_get_lat(msg);
camera_tracking_geo_status->lon = mavlink_msg_camera_tracking_geo_status_get_lon(msg);
camera_tracking_geo_status->alt = mavlink_msg_camera_tracking_geo_status_get_alt(msg);
camera_tracking_geo_status->h_acc = mavlink_msg_camera_tracking_geo_status_get_h_acc(msg);
camera_tracking_geo_status->v_acc = mavlink_msg_camera_tracking_geo_status_get_v_acc(msg);
camera_tracking_geo_status->vel_n = mavlink_msg_camera_tracking_geo_status_get_vel_n(msg);
camera_tracking_geo_status->vel_e = mavlink_msg_camera_tracking_geo_status_get_vel_e(msg);
camera_tracking_geo_status->vel_d = mavlink_msg_camera_tracking_geo_status_get_vel_d(msg);
camera_tracking_geo_status->vel_acc = mavlink_msg_camera_tracking_geo_status_get_vel_acc(msg);
camera_tracking_geo_status->dist = mavlink_msg_camera_tracking_geo_status_get_dist(msg);
camera_tracking_geo_status->hdg = mavlink_msg_camera_tracking_geo_status_get_hdg(msg);
camera_tracking_geo_status->hdg_acc = mavlink_msg_camera_tracking_geo_status_get_hdg_acc(msg);
camera_tracking_geo_status->tracking_status = mavlink_msg_camera_tracking_geo_status_get_tracking_status(msg);
#else
uint8_t len = msg->len < MAVLINK_MSG_ID_CAMERA_TRACKING_GEO_STATUS_LEN? msg->len : MAVLINK_MSG_ID_CAMERA_TRACKING_GEO_STATUS_LEN;
memset(camera_tracking_geo_status, 0, MAVLINK_MSG_ID_CAMERA_TRACKING_GEO_STATUS_LEN);
memcpy(camera_tracking_geo_status, _MAV_PAYLOAD(msg), len);
#endif
}

View file

@ -0,0 +1,438 @@
#pragma once
// MESSAGE CAMERA_TRACKING_IMAGE_STATUS PACKING
#define MAVLINK_MSG_ID_CAMERA_TRACKING_IMAGE_STATUS 275
typedef struct __mavlink_camera_tracking_image_status_t {
float point_x; /*< Current tracked point x value if CAMERA_TRACKING_MODE_POINT (normalized 0..1, 0 is left, 1 is right), NAN if unknown*/
float point_y; /*< Current tracked point y value if CAMERA_TRACKING_MODE_POINT (normalized 0..1, 0 is top, 1 is bottom), NAN if unknown*/
float radius; /*< Current tracked radius if CAMERA_TRACKING_MODE_POINT (normalized 0..1, 0 is image left, 1 is image right), NAN if unknown*/
float rec_top_x; /*< Current tracked rectangle top x value if CAMERA_TRACKING_MODE_RECTANGLE (normalized 0..1, 0 is left, 1 is right), NAN if unknown*/
float rec_top_y; /*< Current tracked rectangle top y value if CAMERA_TRACKING_MODE_RECTANGLE (normalized 0..1, 0 is top, 1 is bottom), NAN if unknown*/
float rec_bottom_x; /*< Current tracked rectangle bottom x value if CAMERA_TRACKING_MODE_RECTANGLE (normalized 0..1, 0 is left, 1 is right), NAN if unknown*/
float rec_bottom_y; /*< Current tracked rectangle bottom y value if CAMERA_TRACKING_MODE_RECTANGLE (normalized 0..1, 0 is top, 1 is bottom), NAN if unknown*/
uint8_t tracking_status; /*< Current tracking status*/
uint8_t tracking_mode; /*< Current tracking mode*/
uint8_t target_data; /*< Defines location of target data*/
} mavlink_camera_tracking_image_status_t;
#define MAVLINK_MSG_ID_CAMERA_TRACKING_IMAGE_STATUS_LEN 31
#define MAVLINK_MSG_ID_CAMERA_TRACKING_IMAGE_STATUS_MIN_LEN 31
#define MAVLINK_MSG_ID_275_LEN 31
#define MAVLINK_MSG_ID_275_MIN_LEN 31
#define MAVLINK_MSG_ID_CAMERA_TRACKING_IMAGE_STATUS_CRC 126
#define MAVLINK_MSG_ID_275_CRC 126
#if MAVLINK_COMMAND_24BIT
#define MAVLINK_MESSAGE_INFO_CAMERA_TRACKING_IMAGE_STATUS { \
275, \
"CAMERA_TRACKING_IMAGE_STATUS", \
10, \
{ { "tracking_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 28, offsetof(mavlink_camera_tracking_image_status_t, tracking_status) }, \
{ "tracking_mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 29, offsetof(mavlink_camera_tracking_image_status_t, tracking_mode) }, \
{ "target_data", NULL, MAVLINK_TYPE_UINT8_T, 0, 30, offsetof(mavlink_camera_tracking_image_status_t, target_data) }, \
{ "point_x", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_camera_tracking_image_status_t, point_x) }, \
{ "point_y", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_camera_tracking_image_status_t, point_y) }, \
{ "radius", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_camera_tracking_image_status_t, radius) }, \
{ "rec_top_x", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_camera_tracking_image_status_t, rec_top_x) }, \
{ "rec_top_y", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_camera_tracking_image_status_t, rec_top_y) }, \
{ "rec_bottom_x", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_camera_tracking_image_status_t, rec_bottom_x) }, \
{ "rec_bottom_y", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_camera_tracking_image_status_t, rec_bottom_y) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_CAMERA_TRACKING_IMAGE_STATUS { \
"CAMERA_TRACKING_IMAGE_STATUS", \
10, \
{ { "tracking_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 28, offsetof(mavlink_camera_tracking_image_status_t, tracking_status) }, \
{ "tracking_mode", NULL, MAVLINK_TYPE_UINT8_T, 0, 29, offsetof(mavlink_camera_tracking_image_status_t, tracking_mode) }, \
{ "target_data", NULL, MAVLINK_TYPE_UINT8_T, 0, 30, offsetof(mavlink_camera_tracking_image_status_t, target_data) }, \
{ "point_x", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_camera_tracking_image_status_t, point_x) }, \
{ "point_y", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_camera_tracking_image_status_t, point_y) }, \
{ "radius", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_camera_tracking_image_status_t, radius) }, \
{ "rec_top_x", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_camera_tracking_image_status_t, rec_top_x) }, \
{ "rec_top_y", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_camera_tracking_image_status_t, rec_top_y) }, \
{ "rec_bottom_x", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_camera_tracking_image_status_t, rec_bottom_x) }, \
{ "rec_bottom_y", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_camera_tracking_image_status_t, rec_bottom_y) }, \
} \
}
#endif
/**
* @brief Pack a camera_tracking_image_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 tracking_status Current tracking status
* @param tracking_mode Current tracking mode
* @param target_data Defines location of target data
* @param point_x Current tracked point x value if CAMERA_TRACKING_MODE_POINT (normalized 0..1, 0 is left, 1 is right), NAN if unknown
* @param point_y Current tracked point y value if CAMERA_TRACKING_MODE_POINT (normalized 0..1, 0 is top, 1 is bottom), NAN if unknown
* @param radius Current tracked radius if CAMERA_TRACKING_MODE_POINT (normalized 0..1, 0 is image left, 1 is image right), NAN if unknown
* @param rec_top_x Current tracked rectangle top x value if CAMERA_TRACKING_MODE_RECTANGLE (normalized 0..1, 0 is left, 1 is right), NAN if unknown
* @param rec_top_y Current tracked rectangle top y value if CAMERA_TRACKING_MODE_RECTANGLE (normalized 0..1, 0 is top, 1 is bottom), NAN if unknown
* @param rec_bottom_x Current tracked rectangle bottom x value if CAMERA_TRACKING_MODE_RECTANGLE (normalized 0..1, 0 is left, 1 is right), NAN if unknown
* @param rec_bottom_y Current tracked rectangle bottom y value if CAMERA_TRACKING_MODE_RECTANGLE (normalized 0..1, 0 is top, 1 is bottom), NAN if unknown
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_camera_tracking_image_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t tracking_status, uint8_t tracking_mode, uint8_t target_data, float point_x, float point_y, float radius, float rec_top_x, float rec_top_y, float rec_bottom_x, float rec_bottom_y)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_CAMERA_TRACKING_IMAGE_STATUS_LEN];
_mav_put_float(buf, 0, point_x);
_mav_put_float(buf, 4, point_y);
_mav_put_float(buf, 8, radius);
_mav_put_float(buf, 12, rec_top_x);
_mav_put_float(buf, 16, rec_top_y);
_mav_put_float(buf, 20, rec_bottom_x);
_mav_put_float(buf, 24, rec_bottom_y);
_mav_put_uint8_t(buf, 28, tracking_status);
_mav_put_uint8_t(buf, 29, tracking_mode);
_mav_put_uint8_t(buf, 30, target_data);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CAMERA_TRACKING_IMAGE_STATUS_LEN);
#else
mavlink_camera_tracking_image_status_t packet;
packet.point_x = point_x;
packet.point_y = point_y;
packet.radius = radius;
packet.rec_top_x = rec_top_x;
packet.rec_top_y = rec_top_y;
packet.rec_bottom_x = rec_bottom_x;
packet.rec_bottom_y = rec_bottom_y;
packet.tracking_status = tracking_status;
packet.tracking_mode = tracking_mode;
packet.target_data = target_data;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CAMERA_TRACKING_IMAGE_STATUS_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_CAMERA_TRACKING_IMAGE_STATUS;
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_CAMERA_TRACKING_IMAGE_STATUS_MIN_LEN, MAVLINK_MSG_ID_CAMERA_TRACKING_IMAGE_STATUS_LEN, MAVLINK_MSG_ID_CAMERA_TRACKING_IMAGE_STATUS_CRC);
}
/**
* @brief Pack a camera_tracking_image_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 tracking_status Current tracking status
* @param tracking_mode Current tracking mode
* @param target_data Defines location of target data
* @param point_x Current tracked point x value if CAMERA_TRACKING_MODE_POINT (normalized 0..1, 0 is left, 1 is right), NAN if unknown
* @param point_y Current tracked point y value if CAMERA_TRACKING_MODE_POINT (normalized 0..1, 0 is top, 1 is bottom), NAN if unknown
* @param radius Current tracked radius if CAMERA_TRACKING_MODE_POINT (normalized 0..1, 0 is image left, 1 is image right), NAN if unknown
* @param rec_top_x Current tracked rectangle top x value if CAMERA_TRACKING_MODE_RECTANGLE (normalized 0..1, 0 is left, 1 is right), NAN if unknown
* @param rec_top_y Current tracked rectangle top y value if CAMERA_TRACKING_MODE_RECTANGLE (normalized 0..1, 0 is top, 1 is bottom), NAN if unknown
* @param rec_bottom_x Current tracked rectangle bottom x value if CAMERA_TRACKING_MODE_RECTANGLE (normalized 0..1, 0 is left, 1 is right), NAN if unknown
* @param rec_bottom_y Current tracked rectangle bottom y value if CAMERA_TRACKING_MODE_RECTANGLE (normalized 0..1, 0 is top, 1 is bottom), NAN if unknown
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_camera_tracking_image_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint8_t tracking_status,uint8_t tracking_mode,uint8_t target_data,float point_x,float point_y,float radius,float rec_top_x,float rec_top_y,float rec_bottom_x,float rec_bottom_y)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_CAMERA_TRACKING_IMAGE_STATUS_LEN];
_mav_put_float(buf, 0, point_x);
_mav_put_float(buf, 4, point_y);
_mav_put_float(buf, 8, radius);
_mav_put_float(buf, 12, rec_top_x);
_mav_put_float(buf, 16, rec_top_y);
_mav_put_float(buf, 20, rec_bottom_x);
_mav_put_float(buf, 24, rec_bottom_y);
_mav_put_uint8_t(buf, 28, tracking_status);
_mav_put_uint8_t(buf, 29, tracking_mode);
_mav_put_uint8_t(buf, 30, target_data);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CAMERA_TRACKING_IMAGE_STATUS_LEN);
#else
mavlink_camera_tracking_image_status_t packet;
packet.point_x = point_x;
packet.point_y = point_y;
packet.radius = radius;
packet.rec_top_x = rec_top_x;
packet.rec_top_y = rec_top_y;
packet.rec_bottom_x = rec_bottom_x;
packet.rec_bottom_y = rec_bottom_y;
packet.tracking_status = tracking_status;
packet.tracking_mode = tracking_mode;
packet.target_data = target_data;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CAMERA_TRACKING_IMAGE_STATUS_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_CAMERA_TRACKING_IMAGE_STATUS;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_CAMERA_TRACKING_IMAGE_STATUS_MIN_LEN, MAVLINK_MSG_ID_CAMERA_TRACKING_IMAGE_STATUS_LEN, MAVLINK_MSG_ID_CAMERA_TRACKING_IMAGE_STATUS_CRC);
}
/**
* @brief Encode a camera_tracking_image_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 camera_tracking_image_status C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_camera_tracking_image_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_camera_tracking_image_status_t* camera_tracking_image_status)
{
return mavlink_msg_camera_tracking_image_status_pack(system_id, component_id, msg, camera_tracking_image_status->tracking_status, camera_tracking_image_status->tracking_mode, camera_tracking_image_status->target_data, camera_tracking_image_status->point_x, camera_tracking_image_status->point_y, camera_tracking_image_status->radius, camera_tracking_image_status->rec_top_x, camera_tracking_image_status->rec_top_y, camera_tracking_image_status->rec_bottom_x, camera_tracking_image_status->rec_bottom_y);
}
/**
* @brief Encode a camera_tracking_image_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 camera_tracking_image_status C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_camera_tracking_image_status_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_camera_tracking_image_status_t* camera_tracking_image_status)
{
return mavlink_msg_camera_tracking_image_status_pack_chan(system_id, component_id, chan, msg, camera_tracking_image_status->tracking_status, camera_tracking_image_status->tracking_mode, camera_tracking_image_status->target_data, camera_tracking_image_status->point_x, camera_tracking_image_status->point_y, camera_tracking_image_status->radius, camera_tracking_image_status->rec_top_x, camera_tracking_image_status->rec_top_y, camera_tracking_image_status->rec_bottom_x, camera_tracking_image_status->rec_bottom_y);
}
/**
* @brief Send a camera_tracking_image_status message
* @param chan MAVLink channel to send the message
*
* @param tracking_status Current tracking status
* @param tracking_mode Current tracking mode
* @param target_data Defines location of target data
* @param point_x Current tracked point x value if CAMERA_TRACKING_MODE_POINT (normalized 0..1, 0 is left, 1 is right), NAN if unknown
* @param point_y Current tracked point y value if CAMERA_TRACKING_MODE_POINT (normalized 0..1, 0 is top, 1 is bottom), NAN if unknown
* @param radius Current tracked radius if CAMERA_TRACKING_MODE_POINT (normalized 0..1, 0 is image left, 1 is image right), NAN if unknown
* @param rec_top_x Current tracked rectangle top x value if CAMERA_TRACKING_MODE_RECTANGLE (normalized 0..1, 0 is left, 1 is right), NAN if unknown
* @param rec_top_y Current tracked rectangle top y value if CAMERA_TRACKING_MODE_RECTANGLE (normalized 0..1, 0 is top, 1 is bottom), NAN if unknown
* @param rec_bottom_x Current tracked rectangle bottom x value if CAMERA_TRACKING_MODE_RECTANGLE (normalized 0..1, 0 is left, 1 is right), NAN if unknown
* @param rec_bottom_y Current tracked rectangle bottom y value if CAMERA_TRACKING_MODE_RECTANGLE (normalized 0..1, 0 is top, 1 is bottom), NAN if unknown
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_camera_tracking_image_status_send(mavlink_channel_t chan, uint8_t tracking_status, uint8_t tracking_mode, uint8_t target_data, float point_x, float point_y, float radius, float rec_top_x, float rec_top_y, float rec_bottom_x, float rec_bottom_y)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_CAMERA_TRACKING_IMAGE_STATUS_LEN];
_mav_put_float(buf, 0, point_x);
_mav_put_float(buf, 4, point_y);
_mav_put_float(buf, 8, radius);
_mav_put_float(buf, 12, rec_top_x);
_mav_put_float(buf, 16, rec_top_y);
_mav_put_float(buf, 20, rec_bottom_x);
_mav_put_float(buf, 24, rec_bottom_y);
_mav_put_uint8_t(buf, 28, tracking_status);
_mav_put_uint8_t(buf, 29, tracking_mode);
_mav_put_uint8_t(buf, 30, target_data);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_TRACKING_IMAGE_STATUS, buf, MAVLINK_MSG_ID_CAMERA_TRACKING_IMAGE_STATUS_MIN_LEN, MAVLINK_MSG_ID_CAMERA_TRACKING_IMAGE_STATUS_LEN, MAVLINK_MSG_ID_CAMERA_TRACKING_IMAGE_STATUS_CRC);
#else
mavlink_camera_tracking_image_status_t packet;
packet.point_x = point_x;
packet.point_y = point_y;
packet.radius = radius;
packet.rec_top_x = rec_top_x;
packet.rec_top_y = rec_top_y;
packet.rec_bottom_x = rec_bottom_x;
packet.rec_bottom_y = rec_bottom_y;
packet.tracking_status = tracking_status;
packet.tracking_mode = tracking_mode;
packet.target_data = target_data;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_TRACKING_IMAGE_STATUS, (const char *)&packet, MAVLINK_MSG_ID_CAMERA_TRACKING_IMAGE_STATUS_MIN_LEN, MAVLINK_MSG_ID_CAMERA_TRACKING_IMAGE_STATUS_LEN, MAVLINK_MSG_ID_CAMERA_TRACKING_IMAGE_STATUS_CRC);
#endif
}
/**
* @brief Send a camera_tracking_image_status message
* @param chan MAVLink channel to send the message
* @param struct The MAVLink struct to serialize
*/
static inline void mavlink_msg_camera_tracking_image_status_send_struct(mavlink_channel_t chan, const mavlink_camera_tracking_image_status_t* camera_tracking_image_status)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mavlink_msg_camera_tracking_image_status_send(chan, camera_tracking_image_status->tracking_status, camera_tracking_image_status->tracking_mode, camera_tracking_image_status->target_data, camera_tracking_image_status->point_x, camera_tracking_image_status->point_y, camera_tracking_image_status->radius, camera_tracking_image_status->rec_top_x, camera_tracking_image_status->rec_top_y, camera_tracking_image_status->rec_bottom_x, camera_tracking_image_status->rec_bottom_y);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_TRACKING_IMAGE_STATUS, (const char *)camera_tracking_image_status, MAVLINK_MSG_ID_CAMERA_TRACKING_IMAGE_STATUS_MIN_LEN, MAVLINK_MSG_ID_CAMERA_TRACKING_IMAGE_STATUS_LEN, MAVLINK_MSG_ID_CAMERA_TRACKING_IMAGE_STATUS_CRC);
#endif
}
#if MAVLINK_MSG_ID_CAMERA_TRACKING_IMAGE_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_camera_tracking_image_status_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t tracking_status, uint8_t tracking_mode, uint8_t target_data, float point_x, float point_y, float radius, float rec_top_x, float rec_top_y, float rec_bottom_x, float rec_bottom_y)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
_mav_put_float(buf, 0, point_x);
_mav_put_float(buf, 4, point_y);
_mav_put_float(buf, 8, radius);
_mav_put_float(buf, 12, rec_top_x);
_mav_put_float(buf, 16, rec_top_y);
_mav_put_float(buf, 20, rec_bottom_x);
_mav_put_float(buf, 24, rec_bottom_y);
_mav_put_uint8_t(buf, 28, tracking_status);
_mav_put_uint8_t(buf, 29, tracking_mode);
_mav_put_uint8_t(buf, 30, target_data);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_TRACKING_IMAGE_STATUS, buf, MAVLINK_MSG_ID_CAMERA_TRACKING_IMAGE_STATUS_MIN_LEN, MAVLINK_MSG_ID_CAMERA_TRACKING_IMAGE_STATUS_LEN, MAVLINK_MSG_ID_CAMERA_TRACKING_IMAGE_STATUS_CRC);
#else
mavlink_camera_tracking_image_status_t *packet = (mavlink_camera_tracking_image_status_t *)msgbuf;
packet->point_x = point_x;
packet->point_y = point_y;
packet->radius = radius;
packet->rec_top_x = rec_top_x;
packet->rec_top_y = rec_top_y;
packet->rec_bottom_x = rec_bottom_x;
packet->rec_bottom_y = rec_bottom_y;
packet->tracking_status = tracking_status;
packet->tracking_mode = tracking_mode;
packet->target_data = target_data;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CAMERA_TRACKING_IMAGE_STATUS, (const char *)packet, MAVLINK_MSG_ID_CAMERA_TRACKING_IMAGE_STATUS_MIN_LEN, MAVLINK_MSG_ID_CAMERA_TRACKING_IMAGE_STATUS_LEN, MAVLINK_MSG_ID_CAMERA_TRACKING_IMAGE_STATUS_CRC);
#endif
}
#endif
#endif
// MESSAGE CAMERA_TRACKING_IMAGE_STATUS UNPACKING
/**
* @brief Get field tracking_status from camera_tracking_image_status message
*
* @return Current tracking status
*/
static inline uint8_t mavlink_msg_camera_tracking_image_status_get_tracking_status(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 28);
}
/**
* @brief Get field tracking_mode from camera_tracking_image_status message
*
* @return Current tracking mode
*/
static inline uint8_t mavlink_msg_camera_tracking_image_status_get_tracking_mode(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 29);
}
/**
* @brief Get field target_data from camera_tracking_image_status message
*
* @return Defines location of target data
*/
static inline uint8_t mavlink_msg_camera_tracking_image_status_get_target_data(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 30);
}
/**
* @brief Get field point_x from camera_tracking_image_status message
*
* @return Current tracked point x value if CAMERA_TRACKING_MODE_POINT (normalized 0..1, 0 is left, 1 is right), NAN if unknown
*/
static inline float mavlink_msg_camera_tracking_image_status_get_point_x(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 0);
}
/**
* @brief Get field point_y from camera_tracking_image_status message
*
* @return Current tracked point y value if CAMERA_TRACKING_MODE_POINT (normalized 0..1, 0 is top, 1 is bottom), NAN if unknown
*/
static inline float mavlink_msg_camera_tracking_image_status_get_point_y(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 4);
}
/**
* @brief Get field radius from camera_tracking_image_status message
*
* @return Current tracked radius if CAMERA_TRACKING_MODE_POINT (normalized 0..1, 0 is image left, 1 is image right), NAN if unknown
*/
static inline float mavlink_msg_camera_tracking_image_status_get_radius(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 8);
}
/**
* @brief Get field rec_top_x from camera_tracking_image_status message
*
* @return Current tracked rectangle top x value if CAMERA_TRACKING_MODE_RECTANGLE (normalized 0..1, 0 is left, 1 is right), NAN if unknown
*/
static inline float mavlink_msg_camera_tracking_image_status_get_rec_top_x(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 12);
}
/**
* @brief Get field rec_top_y from camera_tracking_image_status message
*
* @return Current tracked rectangle top y value if CAMERA_TRACKING_MODE_RECTANGLE (normalized 0..1, 0 is top, 1 is bottom), NAN if unknown
*/
static inline float mavlink_msg_camera_tracking_image_status_get_rec_top_y(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 16);
}
/**
* @brief Get field rec_bottom_x from camera_tracking_image_status message
*
* @return Current tracked rectangle bottom x value if CAMERA_TRACKING_MODE_RECTANGLE (normalized 0..1, 0 is left, 1 is right), NAN if unknown
*/
static inline float mavlink_msg_camera_tracking_image_status_get_rec_bottom_x(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 20);
}
/**
* @brief Get field rec_bottom_y from camera_tracking_image_status message
*
* @return Current tracked rectangle bottom y value if CAMERA_TRACKING_MODE_RECTANGLE (normalized 0..1, 0 is top, 1 is bottom), NAN if unknown
*/
static inline float mavlink_msg_camera_tracking_image_status_get_rec_bottom_y(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 24);
}
/**
* @brief Decode a camera_tracking_image_status message into a struct
*
* @param msg The message to decode
* @param camera_tracking_image_status C-struct to decode the message contents into
*/
static inline void mavlink_msg_camera_tracking_image_status_decode(const mavlink_message_t* msg, mavlink_camera_tracking_image_status_t* camera_tracking_image_status)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
camera_tracking_image_status->point_x = mavlink_msg_camera_tracking_image_status_get_point_x(msg);
camera_tracking_image_status->point_y = mavlink_msg_camera_tracking_image_status_get_point_y(msg);
camera_tracking_image_status->radius = mavlink_msg_camera_tracking_image_status_get_radius(msg);
camera_tracking_image_status->rec_top_x = mavlink_msg_camera_tracking_image_status_get_rec_top_x(msg);
camera_tracking_image_status->rec_top_y = mavlink_msg_camera_tracking_image_status_get_rec_top_y(msg);
camera_tracking_image_status->rec_bottom_x = mavlink_msg_camera_tracking_image_status_get_rec_bottom_x(msg);
camera_tracking_image_status->rec_bottom_y = mavlink_msg_camera_tracking_image_status_get_rec_bottom_y(msg);
camera_tracking_image_status->tracking_status = mavlink_msg_camera_tracking_image_status_get_tracking_status(msg);
camera_tracking_image_status->tracking_mode = mavlink_msg_camera_tracking_image_status_get_tracking_mode(msg);
camera_tracking_image_status->target_data = mavlink_msg_camera_tracking_image_status_get_target_data(msg);
#else
uint8_t len = msg->len < MAVLINK_MSG_ID_CAMERA_TRACKING_IMAGE_STATUS_LEN? msg->len : MAVLINK_MSG_ID_CAMERA_TRACKING_IMAGE_STATUS_LEN;
memset(camera_tracking_image_status, 0, MAVLINK_MSG_ID_CAMERA_TRACKING_IMAGE_STATUS_LEN);
memcpy(camera_tracking_image_status, _MAV_PAYLOAD(msg), len);
#endif
}

View file

@ -0,0 +1,383 @@
#pragma once
// MESSAGE CELLULAR_CONFIG PACKING
#define MAVLINK_MSG_ID_CELLULAR_CONFIG 336
typedef struct __mavlink_cellular_config_t {
uint8_t enable_lte; /*< Enable/disable LTE. 0: setting unchanged, 1: disabled, 2: enabled. Current setting when sent back as a response.*/
uint8_t enable_pin; /*< Enable/disable PIN on the SIM card. 0: setting unchanged, 1: disabled, 2: enabled. Current setting when sent back as a response.*/
char pin[16]; /*< PIN sent to the SIM card. Blank when PIN is disabled. Empty when message is sent back as a response.*/
char new_pin[16]; /*< New PIN when changing the PIN. Blank to leave it unchanged. Empty when message is sent back as a response.*/
char apn[32]; /*< Name of the cellular APN. Blank to leave it unchanged. Current APN when sent back as a response.*/
char puk[16]; /*< Required PUK code in case the user failed to authenticate 3 times with the PIN. Empty when message is sent back as a response.*/
uint8_t roaming; /*< Enable/disable roaming. 0: setting unchanged, 1: disabled, 2: enabled. Current setting when sent back as a response.*/
uint8_t response; /*< Message acceptance response (sent back to GS).*/
} mavlink_cellular_config_t;
#define MAVLINK_MSG_ID_CELLULAR_CONFIG_LEN 84
#define MAVLINK_MSG_ID_CELLULAR_CONFIG_MIN_LEN 84
#define MAVLINK_MSG_ID_336_LEN 84
#define MAVLINK_MSG_ID_336_MIN_LEN 84
#define MAVLINK_MSG_ID_CELLULAR_CONFIG_CRC 245
#define MAVLINK_MSG_ID_336_CRC 245
#define MAVLINK_MSG_CELLULAR_CONFIG_FIELD_PIN_LEN 16
#define MAVLINK_MSG_CELLULAR_CONFIG_FIELD_NEW_PIN_LEN 16
#define MAVLINK_MSG_CELLULAR_CONFIG_FIELD_APN_LEN 32
#define MAVLINK_MSG_CELLULAR_CONFIG_FIELD_PUK_LEN 16
#if MAVLINK_COMMAND_24BIT
#define MAVLINK_MESSAGE_INFO_CELLULAR_CONFIG { \
336, \
"CELLULAR_CONFIG", \
8, \
{ { "enable_lte", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_cellular_config_t, enable_lte) }, \
{ "enable_pin", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_cellular_config_t, enable_pin) }, \
{ "pin", NULL, MAVLINK_TYPE_CHAR, 16, 2, offsetof(mavlink_cellular_config_t, pin) }, \
{ "new_pin", NULL, MAVLINK_TYPE_CHAR, 16, 18, offsetof(mavlink_cellular_config_t, new_pin) }, \
{ "apn", NULL, MAVLINK_TYPE_CHAR, 32, 34, offsetof(mavlink_cellular_config_t, apn) }, \
{ "puk", NULL, MAVLINK_TYPE_CHAR, 16, 66, offsetof(mavlink_cellular_config_t, puk) }, \
{ "roaming", NULL, MAVLINK_TYPE_UINT8_T, 0, 82, offsetof(mavlink_cellular_config_t, roaming) }, \
{ "response", NULL, MAVLINK_TYPE_UINT8_T, 0, 83, offsetof(mavlink_cellular_config_t, response) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_CELLULAR_CONFIG { \
"CELLULAR_CONFIG", \
8, \
{ { "enable_lte", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_cellular_config_t, enable_lte) }, \
{ "enable_pin", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_cellular_config_t, enable_pin) }, \
{ "pin", NULL, MAVLINK_TYPE_CHAR, 16, 2, offsetof(mavlink_cellular_config_t, pin) }, \
{ "new_pin", NULL, MAVLINK_TYPE_CHAR, 16, 18, offsetof(mavlink_cellular_config_t, new_pin) }, \
{ "apn", NULL, MAVLINK_TYPE_CHAR, 32, 34, offsetof(mavlink_cellular_config_t, apn) }, \
{ "puk", NULL, MAVLINK_TYPE_CHAR, 16, 66, offsetof(mavlink_cellular_config_t, puk) }, \
{ "roaming", NULL, MAVLINK_TYPE_UINT8_T, 0, 82, offsetof(mavlink_cellular_config_t, roaming) }, \
{ "response", NULL, MAVLINK_TYPE_UINT8_T, 0, 83, offsetof(mavlink_cellular_config_t, response) }, \
} \
}
#endif
/**
* @brief Pack a cellular_config message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param enable_lte Enable/disable LTE. 0: setting unchanged, 1: disabled, 2: enabled. Current setting when sent back as a response.
* @param enable_pin Enable/disable PIN on the SIM card. 0: setting unchanged, 1: disabled, 2: enabled. Current setting when sent back as a response.
* @param pin PIN sent to the SIM card. Blank when PIN is disabled. Empty when message is sent back as a response.
* @param new_pin New PIN when changing the PIN. Blank to leave it unchanged. Empty when message is sent back as a response.
* @param apn Name of the cellular APN. Blank to leave it unchanged. Current APN when sent back as a response.
* @param puk Required PUK code in case the user failed to authenticate 3 times with the PIN. Empty when message is sent back as a response.
* @param roaming Enable/disable roaming. 0: setting unchanged, 1: disabled, 2: enabled. Current setting when sent back as a response.
* @param response Message acceptance response (sent back to GS).
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_cellular_config_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t enable_lte, uint8_t enable_pin, const char *pin, const char *new_pin, const char *apn, const char *puk, uint8_t roaming, uint8_t response)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_CELLULAR_CONFIG_LEN];
_mav_put_uint8_t(buf, 0, enable_lte);
_mav_put_uint8_t(buf, 1, enable_pin);
_mav_put_uint8_t(buf, 82, roaming);
_mav_put_uint8_t(buf, 83, response);
_mav_put_char_array(buf, 2, pin, 16);
_mav_put_char_array(buf, 18, new_pin, 16);
_mav_put_char_array(buf, 34, apn, 32);
_mav_put_char_array(buf, 66, puk, 16);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CELLULAR_CONFIG_LEN);
#else
mavlink_cellular_config_t packet;
packet.enable_lte = enable_lte;
packet.enable_pin = enable_pin;
packet.roaming = roaming;
packet.response = response;
mav_array_memcpy(packet.pin, pin, sizeof(char)*16);
mav_array_memcpy(packet.new_pin, new_pin, sizeof(char)*16);
mav_array_memcpy(packet.apn, apn, sizeof(char)*32);
mav_array_memcpy(packet.puk, puk, sizeof(char)*16);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CELLULAR_CONFIG_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_CELLULAR_CONFIG;
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_CELLULAR_CONFIG_MIN_LEN, MAVLINK_MSG_ID_CELLULAR_CONFIG_LEN, MAVLINK_MSG_ID_CELLULAR_CONFIG_CRC);
}
/**
* @brief Pack a cellular_config message on a channel
* @param system_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 enable_lte Enable/disable LTE. 0: setting unchanged, 1: disabled, 2: enabled. Current setting when sent back as a response.
* @param enable_pin Enable/disable PIN on the SIM card. 0: setting unchanged, 1: disabled, 2: enabled. Current setting when sent back as a response.
* @param pin PIN sent to the SIM card. Blank when PIN is disabled. Empty when message is sent back as a response.
* @param new_pin New PIN when changing the PIN. Blank to leave it unchanged. Empty when message is sent back as a response.
* @param apn Name of the cellular APN. Blank to leave it unchanged. Current APN when sent back as a response.
* @param puk Required PUK code in case the user failed to authenticate 3 times with the PIN. Empty when message is sent back as a response.
* @param roaming Enable/disable roaming. 0: setting unchanged, 1: disabled, 2: enabled. Current setting when sent back as a response.
* @param response Message acceptance response (sent back to GS).
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_cellular_config_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint8_t enable_lte,uint8_t enable_pin,const char *pin,const char *new_pin,const char *apn,const char *puk,uint8_t roaming,uint8_t response)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_CELLULAR_CONFIG_LEN];
_mav_put_uint8_t(buf, 0, enable_lte);
_mav_put_uint8_t(buf, 1, enable_pin);
_mav_put_uint8_t(buf, 82, roaming);
_mav_put_uint8_t(buf, 83, response);
_mav_put_char_array(buf, 2, pin, 16);
_mav_put_char_array(buf, 18, new_pin, 16);
_mav_put_char_array(buf, 34, apn, 32);
_mav_put_char_array(buf, 66, puk, 16);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CELLULAR_CONFIG_LEN);
#else
mavlink_cellular_config_t packet;
packet.enable_lte = enable_lte;
packet.enable_pin = enable_pin;
packet.roaming = roaming;
packet.response = response;
mav_array_memcpy(packet.pin, pin, sizeof(char)*16);
mav_array_memcpy(packet.new_pin, new_pin, sizeof(char)*16);
mav_array_memcpy(packet.apn, apn, sizeof(char)*32);
mav_array_memcpy(packet.puk, puk, sizeof(char)*16);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CELLULAR_CONFIG_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_CELLULAR_CONFIG;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_CELLULAR_CONFIG_MIN_LEN, MAVLINK_MSG_ID_CELLULAR_CONFIG_LEN, MAVLINK_MSG_ID_CELLULAR_CONFIG_CRC);
}
/**
* @brief Encode a cellular_config 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 cellular_config C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_cellular_config_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_cellular_config_t* cellular_config)
{
return mavlink_msg_cellular_config_pack(system_id, component_id, msg, cellular_config->enable_lte, cellular_config->enable_pin, cellular_config->pin, cellular_config->new_pin, cellular_config->apn, cellular_config->puk, cellular_config->roaming, cellular_config->response);
}
/**
* @brief Encode a cellular_config 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 cellular_config C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_cellular_config_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_cellular_config_t* cellular_config)
{
return mavlink_msg_cellular_config_pack_chan(system_id, component_id, chan, msg, cellular_config->enable_lte, cellular_config->enable_pin, cellular_config->pin, cellular_config->new_pin, cellular_config->apn, cellular_config->puk, cellular_config->roaming, cellular_config->response);
}
/**
* @brief Send a cellular_config message
* @param chan MAVLink channel to send the message
*
* @param enable_lte Enable/disable LTE. 0: setting unchanged, 1: disabled, 2: enabled. Current setting when sent back as a response.
* @param enable_pin Enable/disable PIN on the SIM card. 0: setting unchanged, 1: disabled, 2: enabled. Current setting when sent back as a response.
* @param pin PIN sent to the SIM card. Blank when PIN is disabled. Empty when message is sent back as a response.
* @param new_pin New PIN when changing the PIN. Blank to leave it unchanged. Empty when message is sent back as a response.
* @param apn Name of the cellular APN. Blank to leave it unchanged. Current APN when sent back as a response.
* @param puk Required PUK code in case the user failed to authenticate 3 times with the PIN. Empty when message is sent back as a response.
* @param roaming Enable/disable roaming. 0: setting unchanged, 1: disabled, 2: enabled. Current setting when sent back as a response.
* @param response Message acceptance response (sent back to GS).
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_cellular_config_send(mavlink_channel_t chan, uint8_t enable_lte, uint8_t enable_pin, const char *pin, const char *new_pin, const char *apn, const char *puk, uint8_t roaming, uint8_t response)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_CELLULAR_CONFIG_LEN];
_mav_put_uint8_t(buf, 0, enable_lte);
_mav_put_uint8_t(buf, 1, enable_pin);
_mav_put_uint8_t(buf, 82, roaming);
_mav_put_uint8_t(buf, 83, response);
_mav_put_char_array(buf, 2, pin, 16);
_mav_put_char_array(buf, 18, new_pin, 16);
_mav_put_char_array(buf, 34, apn, 32);
_mav_put_char_array(buf, 66, puk, 16);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CELLULAR_CONFIG, buf, MAVLINK_MSG_ID_CELLULAR_CONFIG_MIN_LEN, MAVLINK_MSG_ID_CELLULAR_CONFIG_LEN, MAVLINK_MSG_ID_CELLULAR_CONFIG_CRC);
#else
mavlink_cellular_config_t packet;
packet.enable_lte = enable_lte;
packet.enable_pin = enable_pin;
packet.roaming = roaming;
packet.response = response;
mav_array_memcpy(packet.pin, pin, sizeof(char)*16);
mav_array_memcpy(packet.new_pin, new_pin, sizeof(char)*16);
mav_array_memcpy(packet.apn, apn, sizeof(char)*32);
mav_array_memcpy(packet.puk, puk, sizeof(char)*16);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CELLULAR_CONFIG, (const char *)&packet, MAVLINK_MSG_ID_CELLULAR_CONFIG_MIN_LEN, MAVLINK_MSG_ID_CELLULAR_CONFIG_LEN, MAVLINK_MSG_ID_CELLULAR_CONFIG_CRC);
#endif
}
/**
* @brief Send a cellular_config message
* @param chan MAVLink channel to send the message
* @param struct The MAVLink struct to serialize
*/
static inline void mavlink_msg_cellular_config_send_struct(mavlink_channel_t chan, const mavlink_cellular_config_t* cellular_config)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mavlink_msg_cellular_config_send(chan, cellular_config->enable_lte, cellular_config->enable_pin, cellular_config->pin, cellular_config->new_pin, cellular_config->apn, cellular_config->puk, cellular_config->roaming, cellular_config->response);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CELLULAR_CONFIG, (const char *)cellular_config, MAVLINK_MSG_ID_CELLULAR_CONFIG_MIN_LEN, MAVLINK_MSG_ID_CELLULAR_CONFIG_LEN, MAVLINK_MSG_ID_CELLULAR_CONFIG_CRC);
#endif
}
#if MAVLINK_MSG_ID_CELLULAR_CONFIG_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_cellular_config_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t enable_lte, uint8_t enable_pin, const char *pin, const char *new_pin, const char *apn, const char *puk, uint8_t roaming, uint8_t response)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
_mav_put_uint8_t(buf, 0, enable_lte);
_mav_put_uint8_t(buf, 1, enable_pin);
_mav_put_uint8_t(buf, 82, roaming);
_mav_put_uint8_t(buf, 83, response);
_mav_put_char_array(buf, 2, pin, 16);
_mav_put_char_array(buf, 18, new_pin, 16);
_mav_put_char_array(buf, 34, apn, 32);
_mav_put_char_array(buf, 66, puk, 16);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CELLULAR_CONFIG, buf, MAVLINK_MSG_ID_CELLULAR_CONFIG_MIN_LEN, MAVLINK_MSG_ID_CELLULAR_CONFIG_LEN, MAVLINK_MSG_ID_CELLULAR_CONFIG_CRC);
#else
mavlink_cellular_config_t *packet = (mavlink_cellular_config_t *)msgbuf;
packet->enable_lte = enable_lte;
packet->enable_pin = enable_pin;
packet->roaming = roaming;
packet->response = response;
mav_array_memcpy(packet->pin, pin, sizeof(char)*16);
mav_array_memcpy(packet->new_pin, new_pin, sizeof(char)*16);
mav_array_memcpy(packet->apn, apn, sizeof(char)*32);
mav_array_memcpy(packet->puk, puk, sizeof(char)*16);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CELLULAR_CONFIG, (const char *)packet, MAVLINK_MSG_ID_CELLULAR_CONFIG_MIN_LEN, MAVLINK_MSG_ID_CELLULAR_CONFIG_LEN, MAVLINK_MSG_ID_CELLULAR_CONFIG_CRC);
#endif
}
#endif
#endif
// MESSAGE CELLULAR_CONFIG UNPACKING
/**
* @brief Get field enable_lte from cellular_config message
*
* @return Enable/disable LTE. 0: setting unchanged, 1: disabled, 2: enabled. Current setting when sent back as a response.
*/
static inline uint8_t mavlink_msg_cellular_config_get_enable_lte(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 0);
}
/**
* @brief Get field enable_pin from cellular_config message
*
* @return Enable/disable PIN on the SIM card. 0: setting unchanged, 1: disabled, 2: enabled. Current setting when sent back as a response.
*/
static inline uint8_t mavlink_msg_cellular_config_get_enable_pin(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 1);
}
/**
* @brief Get field pin from cellular_config message
*
* @return PIN sent to the SIM card. Blank when PIN is disabled. Empty when message is sent back as a response.
*/
static inline uint16_t mavlink_msg_cellular_config_get_pin(const mavlink_message_t* msg, char *pin)
{
return _MAV_RETURN_char_array(msg, pin, 16, 2);
}
/**
* @brief Get field new_pin from cellular_config message
*
* @return New PIN when changing the PIN. Blank to leave it unchanged. Empty when message is sent back as a response.
*/
static inline uint16_t mavlink_msg_cellular_config_get_new_pin(const mavlink_message_t* msg, char *new_pin)
{
return _MAV_RETURN_char_array(msg, new_pin, 16, 18);
}
/**
* @brief Get field apn from cellular_config message
*
* @return Name of the cellular APN. Blank to leave it unchanged. Current APN when sent back as a response.
*/
static inline uint16_t mavlink_msg_cellular_config_get_apn(const mavlink_message_t* msg, char *apn)
{
return _MAV_RETURN_char_array(msg, apn, 32, 34);
}
/**
* @brief Get field puk from cellular_config message
*
* @return Required PUK code in case the user failed to authenticate 3 times with the PIN. Empty when message is sent back as a response.
*/
static inline uint16_t mavlink_msg_cellular_config_get_puk(const mavlink_message_t* msg, char *puk)
{
return _MAV_RETURN_char_array(msg, puk, 16, 66);
}
/**
* @brief Get field roaming from cellular_config message
*
* @return Enable/disable roaming. 0: setting unchanged, 1: disabled, 2: enabled. Current setting when sent back as a response.
*/
static inline uint8_t mavlink_msg_cellular_config_get_roaming(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 82);
}
/**
* @brief Get field response from cellular_config message
*
* @return Message acceptance response (sent back to GS).
*/
static inline uint8_t mavlink_msg_cellular_config_get_response(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 83);
}
/**
* @brief Decode a cellular_config message into a struct
*
* @param msg The message to decode
* @param cellular_config C-struct to decode the message contents into
*/
static inline void mavlink_msg_cellular_config_decode(const mavlink_message_t* msg, mavlink_cellular_config_t* cellular_config)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
cellular_config->enable_lte = mavlink_msg_cellular_config_get_enable_lte(msg);
cellular_config->enable_pin = mavlink_msg_cellular_config_get_enable_pin(msg);
mavlink_msg_cellular_config_get_pin(msg, cellular_config->pin);
mavlink_msg_cellular_config_get_new_pin(msg, cellular_config->new_pin);
mavlink_msg_cellular_config_get_apn(msg, cellular_config->apn);
mavlink_msg_cellular_config_get_puk(msg, cellular_config->puk);
cellular_config->roaming = mavlink_msg_cellular_config_get_roaming(msg);
cellular_config->response = mavlink_msg_cellular_config_get_response(msg);
#else
uint8_t len = msg->len < MAVLINK_MSG_ID_CELLULAR_CONFIG_LEN? msg->len : MAVLINK_MSG_ID_CELLULAR_CONFIG_LEN;
memset(cellular_config, 0, MAVLINK_MSG_ID_CELLULAR_CONFIG_LEN);
memcpy(cellular_config, _MAV_PAYLOAD(msg), len);
#endif
}

View file

@ -0,0 +1,363 @@
#pragma once
// MESSAGE CELLULAR_STATUS PACKING
#define MAVLINK_MSG_ID_CELLULAR_STATUS 334
typedef struct __mavlink_cellular_status_t {
uint16_t mcc; /*< Mobile country code. If unknown, set to UINT16_MAX*/
uint16_t mnc; /*< Mobile network code. If unknown, set to UINT16_MAX*/
uint16_t lac; /*< Location area code. If unknown, set to 0*/
uint8_t status; /*< Cellular modem status*/
uint8_t failure_reason; /*< Failure reason when status in in CELLUAR_STATUS_FAILED*/
uint8_t type; /*< Cellular network radio type: gsm, cdma, lte...*/
uint8_t quality; /*< Signal quality in percent. If unknown, set to UINT8_MAX*/
} mavlink_cellular_status_t;
#define MAVLINK_MSG_ID_CELLULAR_STATUS_LEN 10
#define MAVLINK_MSG_ID_CELLULAR_STATUS_MIN_LEN 10
#define MAVLINK_MSG_ID_334_LEN 10
#define MAVLINK_MSG_ID_334_MIN_LEN 10
#define MAVLINK_MSG_ID_CELLULAR_STATUS_CRC 72
#define MAVLINK_MSG_ID_334_CRC 72
#if MAVLINK_COMMAND_24BIT
#define MAVLINK_MESSAGE_INFO_CELLULAR_STATUS { \
334, \
"CELLULAR_STATUS", \
7, \
{ { "status", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_cellular_status_t, status) }, \
{ "failure_reason", NULL, MAVLINK_TYPE_UINT8_T, 0, 7, offsetof(mavlink_cellular_status_t, failure_reason) }, \
{ "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_cellular_status_t, type) }, \
{ "quality", NULL, MAVLINK_TYPE_UINT8_T, 0, 9, offsetof(mavlink_cellular_status_t, quality) }, \
{ "mcc", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_cellular_status_t, mcc) }, \
{ "mnc", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_cellular_status_t, mnc) }, \
{ "lac", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_cellular_status_t, lac) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_CELLULAR_STATUS { \
"CELLULAR_STATUS", \
7, \
{ { "status", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_cellular_status_t, status) }, \
{ "failure_reason", NULL, MAVLINK_TYPE_UINT8_T, 0, 7, offsetof(mavlink_cellular_status_t, failure_reason) }, \
{ "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_cellular_status_t, type) }, \
{ "quality", NULL, MAVLINK_TYPE_UINT8_T, 0, 9, offsetof(mavlink_cellular_status_t, quality) }, \
{ "mcc", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_cellular_status_t, mcc) }, \
{ "mnc", NULL, MAVLINK_TYPE_UINT16_T, 0, 2, offsetof(mavlink_cellular_status_t, mnc) }, \
{ "lac", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_cellular_status_t, lac) }, \
} \
}
#endif
/**
* @brief Pack a cellular_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 status Cellular modem status
* @param failure_reason Failure reason when status in in CELLUAR_STATUS_FAILED
* @param type Cellular network radio type: gsm, cdma, lte...
* @param quality Signal quality in percent. If unknown, set to UINT8_MAX
* @param mcc Mobile country code. If unknown, set to UINT16_MAX
* @param mnc Mobile network code. If unknown, set to UINT16_MAX
* @param lac Location area code. If unknown, set to 0
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_cellular_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t status, uint8_t failure_reason, uint8_t type, uint8_t quality, uint16_t mcc, uint16_t mnc, uint16_t lac)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_CELLULAR_STATUS_LEN];
_mav_put_uint16_t(buf, 0, mcc);
_mav_put_uint16_t(buf, 2, mnc);
_mav_put_uint16_t(buf, 4, lac);
_mav_put_uint8_t(buf, 6, status);
_mav_put_uint8_t(buf, 7, failure_reason);
_mav_put_uint8_t(buf, 8, type);
_mav_put_uint8_t(buf, 9, quality);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CELLULAR_STATUS_LEN);
#else
mavlink_cellular_status_t packet;
packet.mcc = mcc;
packet.mnc = mnc;
packet.lac = lac;
packet.status = status;
packet.failure_reason = failure_reason;
packet.type = type;
packet.quality = quality;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CELLULAR_STATUS_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_CELLULAR_STATUS;
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_CELLULAR_STATUS_MIN_LEN, MAVLINK_MSG_ID_CELLULAR_STATUS_LEN, MAVLINK_MSG_ID_CELLULAR_STATUS_CRC);
}
/**
* @brief Pack a cellular_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 status Cellular modem status
* @param failure_reason Failure reason when status in in CELLUAR_STATUS_FAILED
* @param type Cellular network radio type: gsm, cdma, lte...
* @param quality Signal quality in percent. If unknown, set to UINT8_MAX
* @param mcc Mobile country code. If unknown, set to UINT16_MAX
* @param mnc Mobile network code. If unknown, set to UINT16_MAX
* @param lac Location area code. If unknown, set to 0
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_cellular_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint8_t status,uint8_t failure_reason,uint8_t type,uint8_t quality,uint16_t mcc,uint16_t mnc,uint16_t lac)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_CELLULAR_STATUS_LEN];
_mav_put_uint16_t(buf, 0, mcc);
_mav_put_uint16_t(buf, 2, mnc);
_mav_put_uint16_t(buf, 4, lac);
_mav_put_uint8_t(buf, 6, status);
_mav_put_uint8_t(buf, 7, failure_reason);
_mav_put_uint8_t(buf, 8, type);
_mav_put_uint8_t(buf, 9, quality);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_CELLULAR_STATUS_LEN);
#else
mavlink_cellular_status_t packet;
packet.mcc = mcc;
packet.mnc = mnc;
packet.lac = lac;
packet.status = status;
packet.failure_reason = failure_reason;
packet.type = type;
packet.quality = quality;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_CELLULAR_STATUS_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_CELLULAR_STATUS;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_CELLULAR_STATUS_MIN_LEN, MAVLINK_MSG_ID_CELLULAR_STATUS_LEN, MAVLINK_MSG_ID_CELLULAR_STATUS_CRC);
}
/**
* @brief Encode a cellular_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 cellular_status C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_cellular_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_cellular_status_t* cellular_status)
{
return mavlink_msg_cellular_status_pack(system_id, component_id, msg, cellular_status->status, cellular_status->failure_reason, cellular_status->type, cellular_status->quality, cellular_status->mcc, cellular_status->mnc, cellular_status->lac);
}
/**
* @brief Encode a cellular_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 cellular_status C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_cellular_status_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_cellular_status_t* cellular_status)
{
return mavlink_msg_cellular_status_pack_chan(system_id, component_id, chan, msg, cellular_status->status, cellular_status->failure_reason, cellular_status->type, cellular_status->quality, cellular_status->mcc, cellular_status->mnc, cellular_status->lac);
}
/**
* @brief Send a cellular_status message
* @param chan MAVLink channel to send the message
*
* @param status Cellular modem status
* @param failure_reason Failure reason when status in in CELLUAR_STATUS_FAILED
* @param type Cellular network radio type: gsm, cdma, lte...
* @param quality Signal quality in percent. If unknown, set to UINT8_MAX
* @param mcc Mobile country code. If unknown, set to UINT16_MAX
* @param mnc Mobile network code. If unknown, set to UINT16_MAX
* @param lac Location area code. If unknown, set to 0
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_cellular_status_send(mavlink_channel_t chan, uint8_t status, uint8_t failure_reason, uint8_t type, uint8_t quality, uint16_t mcc, uint16_t mnc, uint16_t lac)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_CELLULAR_STATUS_LEN];
_mav_put_uint16_t(buf, 0, mcc);
_mav_put_uint16_t(buf, 2, mnc);
_mav_put_uint16_t(buf, 4, lac);
_mav_put_uint8_t(buf, 6, status);
_mav_put_uint8_t(buf, 7, failure_reason);
_mav_put_uint8_t(buf, 8, type);
_mav_put_uint8_t(buf, 9, quality);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CELLULAR_STATUS, buf, MAVLINK_MSG_ID_CELLULAR_STATUS_MIN_LEN, MAVLINK_MSG_ID_CELLULAR_STATUS_LEN, MAVLINK_MSG_ID_CELLULAR_STATUS_CRC);
#else
mavlink_cellular_status_t packet;
packet.mcc = mcc;
packet.mnc = mnc;
packet.lac = lac;
packet.status = status;
packet.failure_reason = failure_reason;
packet.type = type;
packet.quality = quality;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CELLULAR_STATUS, (const char *)&packet, MAVLINK_MSG_ID_CELLULAR_STATUS_MIN_LEN, MAVLINK_MSG_ID_CELLULAR_STATUS_LEN, MAVLINK_MSG_ID_CELLULAR_STATUS_CRC);
#endif
}
/**
* @brief Send a cellular_status message
* @param chan MAVLink channel to send the message
* @param struct The MAVLink struct to serialize
*/
static inline void mavlink_msg_cellular_status_send_struct(mavlink_channel_t chan, const mavlink_cellular_status_t* cellular_status)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mavlink_msg_cellular_status_send(chan, cellular_status->status, cellular_status->failure_reason, cellular_status->type, cellular_status->quality, cellular_status->mcc, cellular_status->mnc, cellular_status->lac);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CELLULAR_STATUS, (const char *)cellular_status, MAVLINK_MSG_ID_CELLULAR_STATUS_MIN_LEN, MAVLINK_MSG_ID_CELLULAR_STATUS_LEN, MAVLINK_MSG_ID_CELLULAR_STATUS_CRC);
#endif
}
#if MAVLINK_MSG_ID_CELLULAR_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_cellular_status_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t status, uint8_t failure_reason, uint8_t type, uint8_t quality, uint16_t mcc, uint16_t mnc, uint16_t lac)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
_mav_put_uint16_t(buf, 0, mcc);
_mav_put_uint16_t(buf, 2, mnc);
_mav_put_uint16_t(buf, 4, lac);
_mav_put_uint8_t(buf, 6, status);
_mav_put_uint8_t(buf, 7, failure_reason);
_mav_put_uint8_t(buf, 8, type);
_mav_put_uint8_t(buf, 9, quality);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CELLULAR_STATUS, buf, MAVLINK_MSG_ID_CELLULAR_STATUS_MIN_LEN, MAVLINK_MSG_ID_CELLULAR_STATUS_LEN, MAVLINK_MSG_ID_CELLULAR_STATUS_CRC);
#else
mavlink_cellular_status_t *packet = (mavlink_cellular_status_t *)msgbuf;
packet->mcc = mcc;
packet->mnc = mnc;
packet->lac = lac;
packet->status = status;
packet->failure_reason = failure_reason;
packet->type = type;
packet->quality = quality;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_CELLULAR_STATUS, (const char *)packet, MAVLINK_MSG_ID_CELLULAR_STATUS_MIN_LEN, MAVLINK_MSG_ID_CELLULAR_STATUS_LEN, MAVLINK_MSG_ID_CELLULAR_STATUS_CRC);
#endif
}
#endif
#endif
// MESSAGE CELLULAR_STATUS UNPACKING
/**
* @brief Get field status from cellular_status message
*
* @return Cellular modem status
*/
static inline uint8_t mavlink_msg_cellular_status_get_status(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 6);
}
/**
* @brief Get field failure_reason from cellular_status message
*
* @return Failure reason when status in in CELLUAR_STATUS_FAILED
*/
static inline uint8_t mavlink_msg_cellular_status_get_failure_reason(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 7);
}
/**
* @brief Get field type from cellular_status message
*
* @return Cellular network radio type: gsm, cdma, lte...
*/
static inline uint8_t mavlink_msg_cellular_status_get_type(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 8);
}
/**
* @brief Get field quality from cellular_status message
*
* @return Signal quality in percent. If unknown, set to UINT8_MAX
*/
static inline uint8_t mavlink_msg_cellular_status_get_quality(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 9);
}
/**
* @brief Get field mcc from cellular_status message
*
* @return Mobile country code. If unknown, set to UINT16_MAX
*/
static inline uint16_t mavlink_msg_cellular_status_get_mcc(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 0);
}
/**
* @brief Get field mnc from cellular_status message
*
* @return Mobile network code. If unknown, set to UINT16_MAX
*/
static inline uint16_t mavlink_msg_cellular_status_get_mnc(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 2);
}
/**
* @brief Get field lac from cellular_status message
*
* @return Location area code. If unknown, set to 0
*/
static inline uint16_t mavlink_msg_cellular_status_get_lac(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 4);
}
/**
* @brief Decode a cellular_status message into a struct
*
* @param msg The message to decode
* @param cellular_status C-struct to decode the message contents into
*/
static inline void mavlink_msg_cellular_status_decode(const mavlink_message_t* msg, mavlink_cellular_status_t* cellular_status)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
cellular_status->mcc = mavlink_msg_cellular_status_get_mcc(msg);
cellular_status->mnc = mavlink_msg_cellular_status_get_mnc(msg);
cellular_status->lac = mavlink_msg_cellular_status_get_lac(msg);
cellular_status->status = mavlink_msg_cellular_status_get_status(msg);
cellular_status->failure_reason = mavlink_msg_cellular_status_get_failure_reason(msg);
cellular_status->type = mavlink_msg_cellular_status_get_type(msg);
cellular_status->quality = mavlink_msg_cellular_status_get_quality(msg);
#else
uint8_t len = msg->len < MAVLINK_MSG_ID_CELLULAR_STATUS_LEN? msg->len : MAVLINK_MSG_ID_CELLULAR_STATUS_LEN;
memset(cellular_status, 0, MAVLINK_MSG_ID_CELLULAR_STATUS_LEN);
memcpy(cellular_status, _MAV_PAYLOAD(msg), len);
#endif
}

View file

@ -7,11 +7,15 @@
typedef struct __mavlink_command_ack_t {
uint16_t command; /*< Command ID (of acknowledged command).*/
uint8_t result; /*< Result of command.*/
uint8_t progress; /*< WIP: Also used as result_param1, it can be set with an enum containing the errors reasons of why the command was denied, or the progress percentage when result is MAV_RESULT_IN_PROGRESS (255 if the progress is unknown).*/
int32_t result_param2; /*< WIP: Additional parameter of the result, example: which parameter of MAV_CMD_NAV_WAYPOINT caused it to be denied.*/
uint8_t target_system; /*< WIP: System ID of the target recipient. This is the ID of the system that sent the command for which this COMMAND_ACK is an acknowledgement.*/
uint8_t target_component; /*< WIP: Component ID of the target recipient. This is the ID of the system that sent the command for which this COMMAND_ACK is an acknowledgement.*/
} mavlink_command_ack_t;
#define MAVLINK_MSG_ID_COMMAND_ACK_LEN 3
#define MAVLINK_MSG_ID_COMMAND_ACK_LEN 10
#define MAVLINK_MSG_ID_COMMAND_ACK_MIN_LEN 3
#define MAVLINK_MSG_ID_77_LEN 3
#define MAVLINK_MSG_ID_77_LEN 10
#define MAVLINK_MSG_ID_77_MIN_LEN 3
#define MAVLINK_MSG_ID_COMMAND_ACK_CRC 143
@ -23,17 +27,25 @@ typedef struct __mavlink_command_ack_t {
#define MAVLINK_MESSAGE_INFO_COMMAND_ACK { \
77, \
"COMMAND_ACK", \
2, \
6, \
{ { "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) }, \
{ "progress", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_command_ack_t, progress) }, \
{ "result_param2", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_command_ack_t, result_param2) }, \
{ "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_command_ack_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 9, offsetof(mavlink_command_ack_t, target_component) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_COMMAND_ACK { \
"COMMAND_ACK", \
2, \
6, \
{ { "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) }, \
{ "progress", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_command_ack_t, progress) }, \
{ "result_param2", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_command_ack_t, result_param2) }, \
{ "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_command_ack_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 9, offsetof(mavlink_command_ack_t, target_component) }, \
} \
}
#endif
@ -46,21 +58,33 @@ typedef struct __mavlink_command_ack_t {
*
* @param command Command ID (of acknowledged command).
* @param result Result of command.
* @param progress WIP: Also used as result_param1, it can be set with an enum containing the errors reasons of why the command was denied, or the progress percentage when result is MAV_RESULT_IN_PROGRESS (255 if the progress is unknown).
* @param result_param2 WIP: Additional parameter of the result, example: which parameter of MAV_CMD_NAV_WAYPOINT caused it to be denied.
* @param target_system WIP: System ID of the target recipient. This is the ID of the system that sent the command for which this COMMAND_ACK is an acknowledgement.
* @param target_component WIP: Component ID of the target recipient. This is the ID of the system that sent the command for which this COMMAND_ACK is an acknowledgement.
* @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)
uint16_t command, uint8_t result, uint8_t progress, int32_t result_param2, uint8_t target_system, uint8_t target_component)
{
#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);
_mav_put_uint8_t(buf, 3, progress);
_mav_put_int32_t(buf, 4, result_param2);
_mav_put_uint8_t(buf, 8, target_system);
_mav_put_uint8_t(buf, 9, target_component);
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;
packet.progress = progress;
packet.result_param2 = result_param2;
packet.target_system = target_system;
packet.target_component = target_component;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_COMMAND_ACK_LEN);
#endif
@ -77,22 +101,34 @@ static inline uint16_t mavlink_msg_command_ack_pack(uint8_t system_id, uint8_t c
* @param msg The MAVLink message to compress the data into
* @param command Command ID (of acknowledged command).
* @param result Result of command.
* @param progress WIP: Also used as result_param1, it can be set with an enum containing the errors reasons of why the command was denied, or the progress percentage when result is MAV_RESULT_IN_PROGRESS (255 if the progress is unknown).
* @param result_param2 WIP: Additional parameter of the result, example: which parameter of MAV_CMD_NAV_WAYPOINT caused it to be denied.
* @param target_system WIP: System ID of the target recipient. This is the ID of the system that sent the command for which this COMMAND_ACK is an acknowledgement.
* @param target_component WIP: Component ID of the target recipient. This is the ID of the system that sent the command for which this COMMAND_ACK is an acknowledgement.
* @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)
uint16_t command,uint8_t result,uint8_t progress,int32_t result_param2,uint8_t target_system,uint8_t target_component)
{
#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);
_mav_put_uint8_t(buf, 3, progress);
_mav_put_int32_t(buf, 4, result_param2);
_mav_put_uint8_t(buf, 8, target_system);
_mav_put_uint8_t(buf, 9, target_component);
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;
packet.progress = progress;
packet.result_param2 = result_param2;
packet.target_system = target_system;
packet.target_component = target_component;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_COMMAND_ACK_LEN);
#endif
@ -111,7 +147,7 @@ static inline uint16_t mavlink_msg_command_ack_pack_chan(uint8_t system_id, uint
*/
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);
return mavlink_msg_command_ack_pack(system_id, component_id, msg, command_ack->command, command_ack->result, command_ack->progress, command_ack->result_param2, command_ack->target_system, command_ack->target_component);
}
/**
@ -125,7 +161,7 @@ static inline uint16_t mavlink_msg_command_ack_encode(uint8_t system_id, uint8_t
*/
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);
return mavlink_msg_command_ack_pack_chan(system_id, component_id, chan, msg, command_ack->command, command_ack->result, command_ack->progress, command_ack->result_param2, command_ack->target_system, command_ack->target_component);
}
/**
@ -134,21 +170,33 @@ static inline uint16_t mavlink_msg_command_ack_encode_chan(uint8_t system_id, ui
*
* @param command Command ID (of acknowledged command).
* @param result Result of command.
* @param progress WIP: Also used as result_param1, it can be set with an enum containing the errors reasons of why the command was denied, or the progress percentage when result is MAV_RESULT_IN_PROGRESS (255 if the progress is unknown).
* @param result_param2 WIP: Additional parameter of the result, example: which parameter of MAV_CMD_NAV_WAYPOINT caused it to be denied.
* @param target_system WIP: System ID of the target recipient. This is the ID of the system that sent the command for which this COMMAND_ACK is an acknowledgement.
* @param target_component WIP: Component ID of the target recipient. This is the ID of the system that sent the command for which this COMMAND_ACK is an acknowledgement.
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_command_ack_send(mavlink_channel_t chan, uint16_t command, uint8_t result)
static inline void mavlink_msg_command_ack_send(mavlink_channel_t chan, uint16_t command, uint8_t result, uint8_t progress, int32_t result_param2, uint8_t target_system, uint8_t target_component)
{
#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);
_mav_put_uint8_t(buf, 3, progress);
_mav_put_int32_t(buf, 4, result_param2);
_mav_put_uint8_t(buf, 8, target_system);
_mav_put_uint8_t(buf, 9, target_component);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_ACK, buf, MAVLINK_MSG_ID_COMMAND_ACK_MIN_LEN, MAVLINK_MSG_ID_COMMAND_ACK_LEN, MAVLINK_MSG_ID_COMMAND_ACK_CRC);
#else
mavlink_command_ack_t packet;
packet.command = command;
packet.result = result;
packet.progress = progress;
packet.result_param2 = result_param2;
packet.target_system = target_system;
packet.target_component = target_component;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_ACK, (const char *)&packet, MAVLINK_MSG_ID_COMMAND_ACK_MIN_LEN, MAVLINK_MSG_ID_COMMAND_ACK_LEN, MAVLINK_MSG_ID_COMMAND_ACK_CRC);
#endif
@ -162,7 +210,7 @@ static inline void mavlink_msg_command_ack_send(mavlink_channel_t chan, uint16_t
static inline void mavlink_msg_command_ack_send_struct(mavlink_channel_t chan, const mavlink_command_ack_t* command_ack)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mavlink_msg_command_ack_send(chan, command_ack->command, command_ack->result);
mavlink_msg_command_ack_send(chan, command_ack->command, command_ack->result, command_ack->progress, command_ack->result_param2, command_ack->target_system, command_ack->target_component);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_ACK, (const char *)command_ack, MAVLINK_MSG_ID_COMMAND_ACK_MIN_LEN, MAVLINK_MSG_ID_COMMAND_ACK_LEN, MAVLINK_MSG_ID_COMMAND_ACK_CRC);
#endif
@ -176,18 +224,26 @@ static inline void mavlink_msg_command_ack_send_struct(mavlink_channel_t chan, c
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)
static inline void mavlink_msg_command_ack_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint16_t command, uint8_t result, uint8_t progress, int32_t result_param2, uint8_t target_system, uint8_t target_component)
{
#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);
_mav_put_uint8_t(buf, 3, progress);
_mav_put_int32_t(buf, 4, result_param2);
_mav_put_uint8_t(buf, 8, target_system);
_mav_put_uint8_t(buf, 9, target_component);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_ACK, buf, MAVLINK_MSG_ID_COMMAND_ACK_MIN_LEN, MAVLINK_MSG_ID_COMMAND_ACK_LEN, MAVLINK_MSG_ID_COMMAND_ACK_CRC);
#else
mavlink_command_ack_t *packet = (mavlink_command_ack_t *)msgbuf;
packet->command = command;
packet->result = result;
packet->progress = progress;
packet->result_param2 = result_param2;
packet->target_system = target_system;
packet->target_component = target_component;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMMAND_ACK, (const char *)packet, MAVLINK_MSG_ID_COMMAND_ACK_MIN_LEN, MAVLINK_MSG_ID_COMMAND_ACK_LEN, MAVLINK_MSG_ID_COMMAND_ACK_CRC);
#endif
@ -219,6 +275,46 @@ static inline uint8_t mavlink_msg_command_ack_get_result(const mavlink_message_t
return _MAV_RETURN_uint8_t(msg, 2);
}
/**
* @brief Get field progress from command_ack message
*
* @return WIP: Also used as result_param1, it can be set with an enum containing the errors reasons of why the command was denied, or the progress percentage when result is MAV_RESULT_IN_PROGRESS (255 if the progress is unknown).
*/
static inline uint8_t mavlink_msg_command_ack_get_progress(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 3);
}
/**
* @brief Get field result_param2 from command_ack message
*
* @return WIP: Additional parameter of the result, example: which parameter of MAV_CMD_NAV_WAYPOINT caused it to be denied.
*/
static inline int32_t mavlink_msg_command_ack_get_result_param2(const mavlink_message_t* msg)
{
return _MAV_RETURN_int32_t(msg, 4);
}
/**
* @brief Get field target_system from command_ack message
*
* @return WIP: System ID of the target recipient. This is the ID of the system that sent the command for which this COMMAND_ACK is an acknowledgement.
*/
static inline uint8_t mavlink_msg_command_ack_get_target_system(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 8);
}
/**
* @brief Get field target_component from command_ack message
*
* @return WIP: Component ID of the target recipient. This is the ID of the system that sent the command for which this COMMAND_ACK is an acknowledgement.
*/
static inline uint8_t mavlink_msg_command_ack_get_target_component(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 9);
}
/**
* @brief Decode a command_ack message into a struct
*
@ -230,6 +326,10 @@ static inline void mavlink_msg_command_ack_decode(const mavlink_message_t* msg,
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
command_ack->command = mavlink_msg_command_ack_get_command(msg);
command_ack->result = mavlink_msg_command_ack_get_result(msg);
command_ack->progress = mavlink_msg_command_ack_get_progress(msg);
command_ack->result_param2 = mavlink_msg_command_ack_get_result_param2(msg);
command_ack->target_system = mavlink_msg_command_ack_get_target_system(msg);
command_ack->target_component = mavlink_msg_command_ack_get_target_component(msg);
#else
uint8_t len = msg->len < MAVLINK_MSG_ID_COMMAND_ACK_LEN? msg->len : MAVLINK_MSG_ID_COMMAND_ACK_LEN;
memset(command_ack, 0, MAVLINK_MSG_ID_COMMAND_ACK_LEN);

View file

@ -16,8 +16,8 @@ typedef struct __mavlink_command_int_t {
uint8_t target_system; /*< System ID*/
uint8_t target_component; /*< Component ID*/
uint8_t frame; /*< The coordinate system of the COMMAND.*/
uint8_t current; /*< false:0, true:1*/
uint8_t autocontinue; /*< autocontinue to next wp*/
uint8_t current; /*< Not used.*/
uint8_t autocontinue; /*< Not used (set 0).*/
} mavlink_command_int_t;
#define MAVLINK_MSG_ID_COMMAND_INT_LEN 35
@ -81,8 +81,8 @@ typedef struct __mavlink_command_int_t {
* @param target_component Component ID
* @param frame The coordinate system of the COMMAND.
* @param command The scheduled action for the mission item.
* @param current false:0, true:1
* @param autocontinue autocontinue to next wp
* @param current Not used.
* @param autocontinue Not used (set 0).
* @param param1 PARAM1, see MAV_CMD enum
* @param param2 PARAM2, see MAV_CMD enum
* @param param3 PARAM3, see MAV_CMD enum
@ -145,8 +145,8 @@ static inline uint16_t mavlink_msg_command_int_pack(uint8_t system_id, uint8_t c
* @param target_component Component ID
* @param frame The coordinate system of the COMMAND.
* @param command The scheduled action for the mission item.
* @param current false:0, true:1
* @param autocontinue autocontinue to next wp
* @param current Not used.
* @param autocontinue Not used (set 0).
* @param param1 PARAM1, see MAV_CMD enum
* @param param2 PARAM2, see MAV_CMD enum
* @param param3 PARAM3, see MAV_CMD enum
@ -235,8 +235,8 @@ static inline uint16_t mavlink_msg_command_int_encode_chan(uint8_t system_id, ui
* @param target_component Component ID
* @param frame The coordinate system of the COMMAND.
* @param command The scheduled action for the mission item.
* @param current false:0, true:1
* @param autocontinue autocontinue to next wp
* @param current Not used.
* @param autocontinue Not used (set 0).
* @param param1 PARAM1, see MAV_CMD enum
* @param param2 PARAM2, see MAV_CMD enum
* @param param3 PARAM3, see MAV_CMD enum
@ -396,7 +396,7 @@ static inline uint16_t mavlink_msg_command_int_get_command(const mavlink_message
/**
* @brief Get field current from command_int message
*
* @return false:0, true:1
* @return Not used.
*/
static inline uint8_t mavlink_msg_command_int_get_current(const mavlink_message_t* msg)
{
@ -406,7 +406,7 @@ static inline uint8_t mavlink_msg_command_int_get_current(const mavlink_message_
/**
* @brief Get field autocontinue from command_int message
*
* @return autocontinue to next wp
* @return Not used (set 0).
*/
static inline uint8_t mavlink_msg_command_int_get_autocontinue(const mavlink_message_t* msg)
{

View file

@ -0,0 +1,331 @@
#pragma once
// MESSAGE COMPONENT_INFORMATION PACKING
#define MAVLINK_MSG_ID_COMPONENT_INFORMATION 395
typedef struct __mavlink_component_information_t {
uint32_t time_boot_ms; /*< [ms] Timestamp (time since system boot).*/
uint32_t metadata_type; /*< The type of metadata being requested.*/
uint32_t metadata_uid; /*< Unique uid for this metadata which a gcs can use for created cached metadata and understanding whether it's cache it up to date or whether it needs to download new data.*/
uint32_t translation_uid; /*< Unique uid for the translation file associated with the metadata.*/
char metadata_uri[70]; /*< Component definition URI. If prefix mavlinkftp:// file is downloaded from vehicle over mavlink ftp protocol. If prefix http[s]:// file is downloaded over internet. Files are json format. They can end in .gz to indicate file is in gzip format.*/
char translation_uri[70]; /*< The translations for strings within the metadata file. If null the either do not exist or may be included in the metadata file itself. The translations specified here supercede any which may be in the metadata file itself. The uri format is the same as component_metadata_uri . Files are in Json Translation spec format. Empty string indicates no tranlsation file.*/
} mavlink_component_information_t;
#define MAVLINK_MSG_ID_COMPONENT_INFORMATION_LEN 156
#define MAVLINK_MSG_ID_COMPONENT_INFORMATION_MIN_LEN 156
#define MAVLINK_MSG_ID_395_LEN 156
#define MAVLINK_MSG_ID_395_MIN_LEN 156
#define MAVLINK_MSG_ID_COMPONENT_INFORMATION_CRC 163
#define MAVLINK_MSG_ID_395_CRC 163
#define MAVLINK_MSG_COMPONENT_INFORMATION_FIELD_METADATA_URI_LEN 70
#define MAVLINK_MSG_COMPONENT_INFORMATION_FIELD_TRANSLATION_URI_LEN 70
#if MAVLINK_COMMAND_24BIT
#define MAVLINK_MESSAGE_INFO_COMPONENT_INFORMATION { \
395, \
"COMPONENT_INFORMATION", \
6, \
{ { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_component_information_t, time_boot_ms) }, \
{ "metadata_type", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_component_information_t, metadata_type) }, \
{ "metadata_uid", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_component_information_t, metadata_uid) }, \
{ "metadata_uri", NULL, MAVLINK_TYPE_CHAR, 70, 16, offsetof(mavlink_component_information_t, metadata_uri) }, \
{ "translation_uid", NULL, MAVLINK_TYPE_UINT32_T, 0, 12, offsetof(mavlink_component_information_t, translation_uid) }, \
{ "translation_uri", NULL, MAVLINK_TYPE_CHAR, 70, 86, offsetof(mavlink_component_information_t, translation_uri) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_COMPONENT_INFORMATION { \
"COMPONENT_INFORMATION", \
6, \
{ { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_component_information_t, time_boot_ms) }, \
{ "metadata_type", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_component_information_t, metadata_type) }, \
{ "metadata_uid", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_component_information_t, metadata_uid) }, \
{ "metadata_uri", NULL, MAVLINK_TYPE_CHAR, 70, 16, offsetof(mavlink_component_information_t, metadata_uri) }, \
{ "translation_uid", NULL, MAVLINK_TYPE_UINT32_T, 0, 12, offsetof(mavlink_component_information_t, translation_uid) }, \
{ "translation_uri", NULL, MAVLINK_TYPE_CHAR, 70, 86, offsetof(mavlink_component_information_t, translation_uri) }, \
} \
}
#endif
/**
* @brief Pack a component_information message
* @param system_id ID of this 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 [ms] Timestamp (time since system boot).
* @param metadata_type The type of metadata being requested.
* @param metadata_uid Unique uid for this metadata which a gcs can use for created cached metadata and understanding whether it's cache it up to date or whether it needs to download new data.
* @param metadata_uri Component definition URI. If prefix mavlinkftp:// file is downloaded from vehicle over mavlink ftp protocol. If prefix http[s]:// file is downloaded over internet. Files are json format. They can end in .gz to indicate file is in gzip format.
* @param translation_uid Unique uid for the translation file associated with the metadata.
* @param translation_uri The translations for strings within the metadata file. If null the either do not exist or may be included in the metadata file itself. The translations specified here supercede any which may be in the metadata file itself. The uri format is the same as component_metadata_uri . Files are in Json Translation spec format. Empty string indicates no tranlsation file.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_component_information_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint32_t time_boot_ms, uint32_t metadata_type, uint32_t metadata_uid, const char *metadata_uri, uint32_t translation_uid, const char *translation_uri)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_COMPONENT_INFORMATION_LEN];
_mav_put_uint32_t(buf, 0, time_boot_ms);
_mav_put_uint32_t(buf, 4, metadata_type);
_mav_put_uint32_t(buf, 8, metadata_uid);
_mav_put_uint32_t(buf, 12, translation_uid);
_mav_put_char_array(buf, 16, metadata_uri, 70);
_mav_put_char_array(buf, 86, translation_uri, 70);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_COMPONENT_INFORMATION_LEN);
#else
mavlink_component_information_t packet;
packet.time_boot_ms = time_boot_ms;
packet.metadata_type = metadata_type;
packet.metadata_uid = metadata_uid;
packet.translation_uid = translation_uid;
mav_array_memcpy(packet.metadata_uri, metadata_uri, sizeof(char)*70);
mav_array_memcpy(packet.translation_uri, translation_uri, sizeof(char)*70);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_COMPONENT_INFORMATION_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_COMPONENT_INFORMATION;
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_COMPONENT_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_COMPONENT_INFORMATION_LEN, MAVLINK_MSG_ID_COMPONENT_INFORMATION_CRC);
}
/**
* @brief Pack a component_information message on a channel
* @param system_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 [ms] Timestamp (time since system boot).
* @param metadata_type The type of metadata being requested.
* @param metadata_uid Unique uid for this metadata which a gcs can use for created cached metadata and understanding whether it's cache it up to date or whether it needs to download new data.
* @param metadata_uri Component definition URI. If prefix mavlinkftp:// file is downloaded from vehicle over mavlink ftp protocol. If prefix http[s]:// file is downloaded over internet. Files are json format. They can end in .gz to indicate file is in gzip format.
* @param translation_uid Unique uid for the translation file associated with the metadata.
* @param translation_uri The translations for strings within the metadata file. If null the either do not exist or may be included in the metadata file itself. The translations specified here supercede any which may be in the metadata file itself. The uri format is the same as component_metadata_uri . Files are in Json Translation spec format. Empty string indicates no tranlsation file.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_component_information_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint32_t time_boot_ms,uint32_t metadata_type,uint32_t metadata_uid,const char *metadata_uri,uint32_t translation_uid,const char *translation_uri)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_COMPONENT_INFORMATION_LEN];
_mav_put_uint32_t(buf, 0, time_boot_ms);
_mav_put_uint32_t(buf, 4, metadata_type);
_mav_put_uint32_t(buf, 8, metadata_uid);
_mav_put_uint32_t(buf, 12, translation_uid);
_mav_put_char_array(buf, 16, metadata_uri, 70);
_mav_put_char_array(buf, 86, translation_uri, 70);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_COMPONENT_INFORMATION_LEN);
#else
mavlink_component_information_t packet;
packet.time_boot_ms = time_boot_ms;
packet.metadata_type = metadata_type;
packet.metadata_uid = metadata_uid;
packet.translation_uid = translation_uid;
mav_array_memcpy(packet.metadata_uri, metadata_uri, sizeof(char)*70);
mav_array_memcpy(packet.translation_uri, translation_uri, sizeof(char)*70);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_COMPONENT_INFORMATION_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_COMPONENT_INFORMATION;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_COMPONENT_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_COMPONENT_INFORMATION_LEN, MAVLINK_MSG_ID_COMPONENT_INFORMATION_CRC);
}
/**
* @brief Encode a component_information 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 component_information C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_component_information_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_component_information_t* component_information)
{
return mavlink_msg_component_information_pack(system_id, component_id, msg, component_information->time_boot_ms, component_information->metadata_type, component_information->metadata_uid, component_information->metadata_uri, component_information->translation_uid, component_information->translation_uri);
}
/**
* @brief Encode a component_information 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 component_information C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_component_information_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_component_information_t* component_information)
{
return mavlink_msg_component_information_pack_chan(system_id, component_id, chan, msg, component_information->time_boot_ms, component_information->metadata_type, component_information->metadata_uid, component_information->metadata_uri, component_information->translation_uid, component_information->translation_uri);
}
/**
* @brief Send a component_information message
* @param chan MAVLink channel to send the message
*
* @param time_boot_ms [ms] Timestamp (time since system boot).
* @param metadata_type The type of metadata being requested.
* @param metadata_uid Unique uid for this metadata which a gcs can use for created cached metadata and understanding whether it's cache it up to date or whether it needs to download new data.
* @param metadata_uri Component definition URI. If prefix mavlinkftp:// file is downloaded from vehicle over mavlink ftp protocol. If prefix http[s]:// file is downloaded over internet. Files are json format. They can end in .gz to indicate file is in gzip format.
* @param translation_uid Unique uid for the translation file associated with the metadata.
* @param translation_uri The translations for strings within the metadata file. If null the either do not exist or may be included in the metadata file itself. The translations specified here supercede any which may be in the metadata file itself. The uri format is the same as component_metadata_uri . Files are in Json Translation spec format. Empty string indicates no tranlsation file.
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_component_information_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint32_t metadata_type, uint32_t metadata_uid, const char *metadata_uri, uint32_t translation_uid, const char *translation_uri)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_COMPONENT_INFORMATION_LEN];
_mav_put_uint32_t(buf, 0, time_boot_ms);
_mav_put_uint32_t(buf, 4, metadata_type);
_mav_put_uint32_t(buf, 8, metadata_uid);
_mav_put_uint32_t(buf, 12, translation_uid);
_mav_put_char_array(buf, 16, metadata_uri, 70);
_mav_put_char_array(buf, 86, translation_uri, 70);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMPONENT_INFORMATION, buf, MAVLINK_MSG_ID_COMPONENT_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_COMPONENT_INFORMATION_LEN, MAVLINK_MSG_ID_COMPONENT_INFORMATION_CRC);
#else
mavlink_component_information_t packet;
packet.time_boot_ms = time_boot_ms;
packet.metadata_type = metadata_type;
packet.metadata_uid = metadata_uid;
packet.translation_uid = translation_uid;
mav_array_memcpy(packet.metadata_uri, metadata_uri, sizeof(char)*70);
mav_array_memcpy(packet.translation_uri, translation_uri, sizeof(char)*70);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMPONENT_INFORMATION, (const char *)&packet, MAVLINK_MSG_ID_COMPONENT_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_COMPONENT_INFORMATION_LEN, MAVLINK_MSG_ID_COMPONENT_INFORMATION_CRC);
#endif
}
/**
* @brief Send a component_information message
* @param chan MAVLink channel to send the message
* @param struct The MAVLink struct to serialize
*/
static inline void mavlink_msg_component_information_send_struct(mavlink_channel_t chan, const mavlink_component_information_t* component_information)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mavlink_msg_component_information_send(chan, component_information->time_boot_ms, component_information->metadata_type, component_information->metadata_uid, component_information->metadata_uri, component_information->translation_uid, component_information->translation_uri);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMPONENT_INFORMATION, (const char *)component_information, MAVLINK_MSG_ID_COMPONENT_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_COMPONENT_INFORMATION_LEN, MAVLINK_MSG_ID_COMPONENT_INFORMATION_CRC);
#endif
}
#if MAVLINK_MSG_ID_COMPONENT_INFORMATION_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_component_information_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, uint32_t metadata_type, uint32_t metadata_uid, const char *metadata_uri, uint32_t translation_uid, const char *translation_uri)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
_mav_put_uint32_t(buf, 0, time_boot_ms);
_mav_put_uint32_t(buf, 4, metadata_type);
_mav_put_uint32_t(buf, 8, metadata_uid);
_mav_put_uint32_t(buf, 12, translation_uid);
_mav_put_char_array(buf, 16, metadata_uri, 70);
_mav_put_char_array(buf, 86, translation_uri, 70);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMPONENT_INFORMATION, buf, MAVLINK_MSG_ID_COMPONENT_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_COMPONENT_INFORMATION_LEN, MAVLINK_MSG_ID_COMPONENT_INFORMATION_CRC);
#else
mavlink_component_information_t *packet = (mavlink_component_information_t *)msgbuf;
packet->time_boot_ms = time_boot_ms;
packet->metadata_type = metadata_type;
packet->metadata_uid = metadata_uid;
packet->translation_uid = translation_uid;
mav_array_memcpy(packet->metadata_uri, metadata_uri, sizeof(char)*70);
mav_array_memcpy(packet->translation_uri, translation_uri, sizeof(char)*70);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_COMPONENT_INFORMATION, (const char *)packet, MAVLINK_MSG_ID_COMPONENT_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_COMPONENT_INFORMATION_LEN, MAVLINK_MSG_ID_COMPONENT_INFORMATION_CRC);
#endif
}
#endif
#endif
// MESSAGE COMPONENT_INFORMATION UNPACKING
/**
* @brief Get field time_boot_ms from component_information message
*
* @return [ms] Timestamp (time since system boot).
*/
static inline uint32_t mavlink_msg_component_information_get_time_boot_ms(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint32_t(msg, 0);
}
/**
* @brief Get field metadata_type from component_information message
*
* @return The type of metadata being requested.
*/
static inline uint32_t mavlink_msg_component_information_get_metadata_type(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint32_t(msg, 4);
}
/**
* @brief Get field metadata_uid from component_information message
*
* @return Unique uid for this metadata which a gcs can use for created cached metadata and understanding whether it's cache it up to date or whether it needs to download new data.
*/
static inline uint32_t mavlink_msg_component_information_get_metadata_uid(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint32_t(msg, 8);
}
/**
* @brief Get field metadata_uri from component_information message
*
* @return Component definition URI. If prefix mavlinkftp:// file is downloaded from vehicle over mavlink ftp protocol. If prefix http[s]:// file is downloaded over internet. Files are json format. They can end in .gz to indicate file is in gzip format.
*/
static inline uint16_t mavlink_msg_component_information_get_metadata_uri(const mavlink_message_t* msg, char *metadata_uri)
{
return _MAV_RETURN_char_array(msg, metadata_uri, 70, 16);
}
/**
* @brief Get field translation_uid from component_information message
*
* @return Unique uid for the translation file associated with the metadata.
*/
static inline uint32_t mavlink_msg_component_information_get_translation_uid(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint32_t(msg, 12);
}
/**
* @brief Get field translation_uri from component_information message
*
* @return The translations for strings within the metadata file. If null the either do not exist or may be included in the metadata file itself. The translations specified here supercede any which may be in the metadata file itself. The uri format is the same as component_metadata_uri . Files are in Json Translation spec format. Empty string indicates no tranlsation file.
*/
static inline uint16_t mavlink_msg_component_information_get_translation_uri(const mavlink_message_t* msg, char *translation_uri)
{
return _MAV_RETURN_char_array(msg, translation_uri, 70, 86);
}
/**
* @brief Decode a component_information message into a struct
*
* @param msg The message to decode
* @param component_information C-struct to decode the message contents into
*/
static inline void mavlink_msg_component_information_decode(const mavlink_message_t* msg, mavlink_component_information_t* component_information)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
component_information->time_boot_ms = mavlink_msg_component_information_get_time_boot_ms(msg);
component_information->metadata_type = mavlink_msg_component_information_get_metadata_type(msg);
component_information->metadata_uid = mavlink_msg_component_information_get_metadata_uid(msg);
component_information->translation_uid = mavlink_msg_component_information_get_translation_uid(msg);
mavlink_msg_component_information_get_metadata_uri(msg, component_information->metadata_uri);
mavlink_msg_component_information_get_translation_uri(msg, component_information->translation_uri);
#else
uint8_t len = msg->len < MAVLINK_MSG_ID_COMPONENT_INFORMATION_LEN? msg->len : MAVLINK_MSG_ID_COMPONENT_INFORMATION_LEN;
memset(component_information, 0, MAVLINK_MSG_ID_COMPONENT_INFORMATION_LEN);
memcpy(component_information, _MAV_PAYLOAD(msg), len);
#endif
}

View file

@ -0,0 +1,281 @@
#pragma once
// MESSAGE DEBUG_FLOAT_ARRAY PACKING
#define MAVLINK_MSG_ID_DEBUG_FLOAT_ARRAY 350
typedef struct __mavlink_debug_float_array_t {
uint64_t time_usec; /*< [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.*/
uint16_t array_id; /*< Unique ID used to discriminate between arrays*/
char name[10]; /*< Name, for human-friendly display in a Ground Control Station*/
float data[58]; /*< data*/
} mavlink_debug_float_array_t;
#define MAVLINK_MSG_ID_DEBUG_FLOAT_ARRAY_LEN 252
#define MAVLINK_MSG_ID_DEBUG_FLOAT_ARRAY_MIN_LEN 20
#define MAVLINK_MSG_ID_350_LEN 252
#define MAVLINK_MSG_ID_350_MIN_LEN 20
#define MAVLINK_MSG_ID_DEBUG_FLOAT_ARRAY_CRC 232
#define MAVLINK_MSG_ID_350_CRC 232
#define MAVLINK_MSG_DEBUG_FLOAT_ARRAY_FIELD_NAME_LEN 10
#define MAVLINK_MSG_DEBUG_FLOAT_ARRAY_FIELD_DATA_LEN 58
#if MAVLINK_COMMAND_24BIT
#define MAVLINK_MESSAGE_INFO_DEBUG_FLOAT_ARRAY { \
350, \
"DEBUG_FLOAT_ARRAY", \
4, \
{ { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_debug_float_array_t, time_usec) }, \
{ "name", NULL, MAVLINK_TYPE_CHAR, 10, 10, offsetof(mavlink_debug_float_array_t, name) }, \
{ "array_id", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_debug_float_array_t, array_id) }, \
{ "data", NULL, MAVLINK_TYPE_FLOAT, 58, 20, offsetof(mavlink_debug_float_array_t, data) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_DEBUG_FLOAT_ARRAY { \
"DEBUG_FLOAT_ARRAY", \
4, \
{ { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_debug_float_array_t, time_usec) }, \
{ "name", NULL, MAVLINK_TYPE_CHAR, 10, 10, offsetof(mavlink_debug_float_array_t, name) }, \
{ "array_id", NULL, MAVLINK_TYPE_UINT16_T, 0, 8, offsetof(mavlink_debug_float_array_t, array_id) }, \
{ "data", NULL, MAVLINK_TYPE_FLOAT, 58, 20, offsetof(mavlink_debug_float_array_t, data) }, \
} \
}
#endif
/**
* @brief Pack a debug_float_array message
* @param system_id ID of this 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 [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
* @param name Name, for human-friendly display in a Ground Control Station
* @param array_id Unique ID used to discriminate between arrays
* @param data data
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_debug_float_array_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint64_t time_usec, const char *name, uint16_t array_id, const float *data)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_DEBUG_FLOAT_ARRAY_LEN];
_mav_put_uint64_t(buf, 0, time_usec);
_mav_put_uint16_t(buf, 8, array_id);
_mav_put_char_array(buf, 10, name, 10);
_mav_put_float_array(buf, 20, data, 58);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DEBUG_FLOAT_ARRAY_LEN);
#else
mavlink_debug_float_array_t packet;
packet.time_usec = time_usec;
packet.array_id = array_id;
mav_array_memcpy(packet.name, name, sizeof(char)*10);
mav_array_memcpy(packet.data, data, sizeof(float)*58);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DEBUG_FLOAT_ARRAY_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_DEBUG_FLOAT_ARRAY;
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_DEBUG_FLOAT_ARRAY_MIN_LEN, MAVLINK_MSG_ID_DEBUG_FLOAT_ARRAY_LEN, MAVLINK_MSG_ID_DEBUG_FLOAT_ARRAY_CRC);
}
/**
* @brief Pack a debug_float_array message on a channel
* @param system_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 [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
* @param name Name, for human-friendly display in a Ground Control Station
* @param array_id Unique ID used to discriminate between arrays
* @param data data
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_debug_float_array_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint64_t time_usec,const char *name,uint16_t array_id,const float *data)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_DEBUG_FLOAT_ARRAY_LEN];
_mav_put_uint64_t(buf, 0, time_usec);
_mav_put_uint16_t(buf, 8, array_id);
_mav_put_char_array(buf, 10, name, 10);
_mav_put_float_array(buf, 20, data, 58);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DEBUG_FLOAT_ARRAY_LEN);
#else
mavlink_debug_float_array_t packet;
packet.time_usec = time_usec;
packet.array_id = array_id;
mav_array_memcpy(packet.name, name, sizeof(char)*10);
mav_array_memcpy(packet.data, data, sizeof(float)*58);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DEBUG_FLOAT_ARRAY_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_DEBUG_FLOAT_ARRAY;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_DEBUG_FLOAT_ARRAY_MIN_LEN, MAVLINK_MSG_ID_DEBUG_FLOAT_ARRAY_LEN, MAVLINK_MSG_ID_DEBUG_FLOAT_ARRAY_CRC);
}
/**
* @brief Encode a debug_float_array 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_float_array C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_debug_float_array_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_debug_float_array_t* debug_float_array)
{
return mavlink_msg_debug_float_array_pack(system_id, component_id, msg, debug_float_array->time_usec, debug_float_array->name, debug_float_array->array_id, debug_float_array->data);
}
/**
* @brief Encode a debug_float_array 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_float_array C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_debug_float_array_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_debug_float_array_t* debug_float_array)
{
return mavlink_msg_debug_float_array_pack_chan(system_id, component_id, chan, msg, debug_float_array->time_usec, debug_float_array->name, debug_float_array->array_id, debug_float_array->data);
}
/**
* @brief Send a debug_float_array message
* @param chan MAVLink channel to send the message
*
* @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
* @param name Name, for human-friendly display in a Ground Control Station
* @param array_id Unique ID used to discriminate between arrays
* @param data data
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_debug_float_array_send(mavlink_channel_t chan, uint64_t time_usec, const char *name, uint16_t array_id, const float *data)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_DEBUG_FLOAT_ARRAY_LEN];
_mav_put_uint64_t(buf, 0, time_usec);
_mav_put_uint16_t(buf, 8, array_id);
_mav_put_char_array(buf, 10, name, 10);
_mav_put_float_array(buf, 20, data, 58);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG_FLOAT_ARRAY, buf, MAVLINK_MSG_ID_DEBUG_FLOAT_ARRAY_MIN_LEN, MAVLINK_MSG_ID_DEBUG_FLOAT_ARRAY_LEN, MAVLINK_MSG_ID_DEBUG_FLOAT_ARRAY_CRC);
#else
mavlink_debug_float_array_t packet;
packet.time_usec = time_usec;
packet.array_id = array_id;
mav_array_memcpy(packet.name, name, sizeof(char)*10);
mav_array_memcpy(packet.data, data, sizeof(float)*58);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG_FLOAT_ARRAY, (const char *)&packet, MAVLINK_MSG_ID_DEBUG_FLOAT_ARRAY_MIN_LEN, MAVLINK_MSG_ID_DEBUG_FLOAT_ARRAY_LEN, MAVLINK_MSG_ID_DEBUG_FLOAT_ARRAY_CRC);
#endif
}
/**
* @brief Send a debug_float_array message
* @param chan MAVLink channel to send the message
* @param struct The MAVLink struct to serialize
*/
static inline void mavlink_msg_debug_float_array_send_struct(mavlink_channel_t chan, const mavlink_debug_float_array_t* debug_float_array)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mavlink_msg_debug_float_array_send(chan, debug_float_array->time_usec, debug_float_array->name, debug_float_array->array_id, debug_float_array->data);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG_FLOAT_ARRAY, (const char *)debug_float_array, MAVLINK_MSG_ID_DEBUG_FLOAT_ARRAY_MIN_LEN, MAVLINK_MSG_ID_DEBUG_FLOAT_ARRAY_LEN, MAVLINK_MSG_ID_DEBUG_FLOAT_ARRAY_CRC);
#endif
}
#if MAVLINK_MSG_ID_DEBUG_FLOAT_ARRAY_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_float_array_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, const char *name, uint16_t array_id, const float *data)
{
#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, array_id);
_mav_put_char_array(buf, 10, name, 10);
_mav_put_float_array(buf, 20, data, 58);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG_FLOAT_ARRAY, buf, MAVLINK_MSG_ID_DEBUG_FLOAT_ARRAY_MIN_LEN, MAVLINK_MSG_ID_DEBUG_FLOAT_ARRAY_LEN, MAVLINK_MSG_ID_DEBUG_FLOAT_ARRAY_CRC);
#else
mavlink_debug_float_array_t *packet = (mavlink_debug_float_array_t *)msgbuf;
packet->time_usec = time_usec;
packet->array_id = array_id;
mav_array_memcpy(packet->name, name, sizeof(char)*10);
mav_array_memcpy(packet->data, data, sizeof(float)*58);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DEBUG_FLOAT_ARRAY, (const char *)packet, MAVLINK_MSG_ID_DEBUG_FLOAT_ARRAY_MIN_LEN, MAVLINK_MSG_ID_DEBUG_FLOAT_ARRAY_LEN, MAVLINK_MSG_ID_DEBUG_FLOAT_ARRAY_CRC);
#endif
}
#endif
#endif
// MESSAGE DEBUG_FLOAT_ARRAY UNPACKING
/**
* @brief Get field time_usec from debug_float_array message
*
* @return [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
*/
static inline uint64_t mavlink_msg_debug_float_array_get_time_usec(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint64_t(msg, 0);
}
/**
* @brief Get field name from debug_float_array message
*
* @return Name, for human-friendly display in a Ground Control Station
*/
static inline uint16_t mavlink_msg_debug_float_array_get_name(const mavlink_message_t* msg, char *name)
{
return _MAV_RETURN_char_array(msg, name, 10, 10);
}
/**
* @brief Get field array_id from debug_float_array message
*
* @return Unique ID used to discriminate between arrays
*/
static inline uint16_t mavlink_msg_debug_float_array_get_array_id(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 8);
}
/**
* @brief Get field data from debug_float_array message
*
* @return data
*/
static inline uint16_t mavlink_msg_debug_float_array_get_data(const mavlink_message_t* msg, float *data)
{
return _MAV_RETURN_float_array(msg, data, 58, 20);
}
/**
* @brief Decode a debug_float_array message into a struct
*
* @param msg The message to decode
* @param debug_float_array C-struct to decode the message contents into
*/
static inline void mavlink_msg_debug_float_array_decode(const mavlink_message_t* msg, mavlink_debug_float_array_t* debug_float_array)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
debug_float_array->time_usec = mavlink_msg_debug_float_array_get_time_usec(msg);
debug_float_array->array_id = mavlink_msg_debug_float_array_get_array_id(msg);
mavlink_msg_debug_float_array_get_name(msg, debug_float_array->name);
mavlink_msg_debug_float_array_get_data(msg, debug_float_array->data);
#else
uint8_t len = msg->len < MAVLINK_MSG_ID_DEBUG_FLOAT_ARRAY_LEN? msg->len : MAVLINK_MSG_ID_DEBUG_FLOAT_ARRAY_LEN;
memset(debug_float_array, 0, MAVLINK_MSG_ID_DEBUG_FLOAT_ARRAY_LEN);
memcpy(debug_float_array, _MAV_PAYLOAD(msg), len);
#endif
}

View file

@ -3,7 +3,7 @@
#define MAVLINK_MSG_ID_DISTANCE_SENSOR 132
MAVPACKED(
typedef struct __mavlink_distance_sensor_t {
uint32_t time_boot_ms; /*< [ms] Timestamp (time since system boot).*/
uint16_t min_distance; /*< [cm] Minimum distance the sensor can measure*/
@ -13,23 +13,27 @@ typedef struct __mavlink_distance_sensor_t {
uint8_t id; /*< Onboard ID of the sensor*/
uint8_t orientation; /*< Direction the sensor faces. downward-facing: ROTATION_PITCH_270, upward-facing: ROTATION_PITCH_90, backward-facing: ROTATION_PITCH_180, forward-facing: ROTATION_NONE, left-facing: ROTATION_YAW_90, right-facing: ROTATION_YAW_270*/
uint8_t covariance; /*< [cm^2] Measurement variance. Max standard deviation is 6cm. 255 if unknown.*/
} mavlink_distance_sensor_t;
float horizontal_fov; /*< [rad] Horizontal Field of View (angle) where the distance measurement is valid and the field of view is known. Otherwise this is set to 0.*/
float vertical_fov; /*< [rad] Vertical Field of View (angle) where the distance measurement is valid and the field of view is known. Otherwise this is set to 0.*/
float quaternion[4]; /*< Quaternion of the sensor orientation in vehicle body frame (w, x, y, z order, zero-rotation is 1, 0, 0, 0). Zero-rotation is along the vehicle body x-axis. This field is required if the orientation is set to MAV_SENSOR_ROTATION_CUSTOM. Set it to 0 if invalid."*/
uint8_t signal_quality; /*< [%] Signal quality of the sensor. Specific to each sensor type, representing the relation of the signal strength with the target reflectivity, distance, size or aspect, but normalised as a percentage. 0 = unknown/unset signal quality, 1 = invalid signal, 100 = perfect signal.*/
}) mavlink_distance_sensor_t;
#define MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN 14
#define MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN 39
#define MAVLINK_MSG_ID_DISTANCE_SENSOR_MIN_LEN 14
#define MAVLINK_MSG_ID_132_LEN 14
#define MAVLINK_MSG_ID_132_LEN 39
#define MAVLINK_MSG_ID_132_MIN_LEN 14
#define MAVLINK_MSG_ID_DISTANCE_SENSOR_CRC 85
#define MAVLINK_MSG_ID_132_CRC 85
#define MAVLINK_MSG_DISTANCE_SENSOR_FIELD_QUATERNION_LEN 4
#if MAVLINK_COMMAND_24BIT
#define MAVLINK_MESSAGE_INFO_DISTANCE_SENSOR { \
132, \
"DISTANCE_SENSOR", \
8, \
12, \
{ { "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) }, \
@ -38,12 +42,16 @@ typedef struct __mavlink_distance_sensor_t {
{ "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) }, \
{ "horizontal_fov", NULL, MAVLINK_TYPE_FLOAT, 0, 14, offsetof(mavlink_distance_sensor_t, horizontal_fov) }, \
{ "vertical_fov", NULL, MAVLINK_TYPE_FLOAT, 0, 18, offsetof(mavlink_distance_sensor_t, vertical_fov) }, \
{ "quaternion", NULL, MAVLINK_TYPE_FLOAT, 4, 22, offsetof(mavlink_distance_sensor_t, quaternion) }, \
{ "signal_quality", NULL, MAVLINK_TYPE_UINT8_T, 0, 38, offsetof(mavlink_distance_sensor_t, signal_quality) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_DISTANCE_SENSOR { \
"DISTANCE_SENSOR", \
8, \
12, \
{ { "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) }, \
@ -52,6 +60,10 @@ typedef struct __mavlink_distance_sensor_t {
{ "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) }, \
{ "horizontal_fov", NULL, MAVLINK_TYPE_FLOAT, 0, 14, offsetof(mavlink_distance_sensor_t, horizontal_fov) }, \
{ "vertical_fov", NULL, MAVLINK_TYPE_FLOAT, 0, 18, offsetof(mavlink_distance_sensor_t, vertical_fov) }, \
{ "quaternion", NULL, MAVLINK_TYPE_FLOAT, 4, 22, offsetof(mavlink_distance_sensor_t, quaternion) }, \
{ "signal_quality", NULL, MAVLINK_TYPE_UINT8_T, 0, 38, offsetof(mavlink_distance_sensor_t, signal_quality) }, \
} \
}
#endif
@ -70,10 +82,14 @@ typedef struct __mavlink_distance_sensor_t {
* @param id Onboard ID of the sensor
* @param orientation Direction the sensor faces. downward-facing: ROTATION_PITCH_270, upward-facing: ROTATION_PITCH_90, backward-facing: ROTATION_PITCH_180, forward-facing: ROTATION_NONE, left-facing: ROTATION_YAW_90, right-facing: ROTATION_YAW_270
* @param covariance [cm^2] Measurement variance. Max standard deviation is 6cm. 255 if unknown.
* @param horizontal_fov [rad] Horizontal Field of View (angle) where the distance measurement is valid and the field of view is known. Otherwise this is set to 0.
* @param vertical_fov [rad] Vertical Field of View (angle) where the distance measurement is valid and the field of view is known. Otherwise this is set to 0.
* @param quaternion Quaternion of the sensor orientation in vehicle body frame (w, x, y, z order, zero-rotation is 1, 0, 0, 0). Zero-rotation is along the vehicle body x-axis. This field is required if the orientation is set to MAV_SENSOR_ROTATION_CUSTOM. Set it to 0 if invalid."
* @param signal_quality [%] Signal quality of the sensor. Specific to each sensor type, representing the relation of the signal strength with the target reflectivity, distance, size or aspect, but normalised as a percentage. 0 = unknown/unset signal quality, 1 = invalid signal, 100 = perfect signal.
* @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)
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, float horizontal_fov, float vertical_fov, const float *quaternion, uint8_t signal_quality)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN];
@ -85,7 +101,10 @@ static inline uint16_t mavlink_msg_distance_sensor_pack(uint8_t system_id, uint8
_mav_put_uint8_t(buf, 11, id);
_mav_put_uint8_t(buf, 12, orientation);
_mav_put_uint8_t(buf, 13, covariance);
_mav_put_float(buf, 14, horizontal_fov);
_mav_put_float(buf, 18, vertical_fov);
_mav_put_uint8_t(buf, 38, signal_quality);
_mav_put_float_array(buf, 22, quaternion, 4);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN);
#else
mavlink_distance_sensor_t packet;
@ -97,7 +116,10 @@ static inline uint16_t mavlink_msg_distance_sensor_pack(uint8_t system_id, uint8
packet.id = id;
packet.orientation = orientation;
packet.covariance = covariance;
packet.horizontal_fov = horizontal_fov;
packet.vertical_fov = vertical_fov;
packet.signal_quality = signal_quality;
mav_array_memcpy(packet.quaternion, quaternion, sizeof(float)*4);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN);
#endif
@ -119,11 +141,15 @@ static inline uint16_t mavlink_msg_distance_sensor_pack(uint8_t system_id, uint8
* @param id Onboard ID of the sensor
* @param orientation Direction the sensor faces. downward-facing: ROTATION_PITCH_270, upward-facing: ROTATION_PITCH_90, backward-facing: ROTATION_PITCH_180, forward-facing: ROTATION_NONE, left-facing: ROTATION_YAW_90, right-facing: ROTATION_YAW_270
* @param covariance [cm^2] Measurement variance. Max standard deviation is 6cm. 255 if unknown.
* @param horizontal_fov [rad] Horizontal Field of View (angle) where the distance measurement is valid and the field of view is known. Otherwise this is set to 0.
* @param vertical_fov [rad] Vertical Field of View (angle) where the distance measurement is valid and the field of view is known. Otherwise this is set to 0.
* @param quaternion Quaternion of the sensor orientation in vehicle body frame (w, x, y, z order, zero-rotation is 1, 0, 0, 0). Zero-rotation is along the vehicle body x-axis. This field is required if the orientation is set to MAV_SENSOR_ROTATION_CUSTOM. Set it to 0 if invalid."
* @param signal_quality [%] Signal quality of the sensor. Specific to each sensor type, representing the relation of the signal strength with the target reflectivity, distance, size or aspect, but normalised as a percentage. 0 = unknown/unset signal quality, 1 = invalid signal, 100 = perfect signal.
* @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)
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,float horizontal_fov,float vertical_fov,const float *quaternion,uint8_t signal_quality)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN];
@ -135,7 +161,10 @@ static inline uint16_t mavlink_msg_distance_sensor_pack_chan(uint8_t system_id,
_mav_put_uint8_t(buf, 11, id);
_mav_put_uint8_t(buf, 12, orientation);
_mav_put_uint8_t(buf, 13, covariance);
_mav_put_float(buf, 14, horizontal_fov);
_mav_put_float(buf, 18, vertical_fov);
_mav_put_uint8_t(buf, 38, signal_quality);
_mav_put_float_array(buf, 22, quaternion, 4);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN);
#else
mavlink_distance_sensor_t packet;
@ -147,7 +176,10 @@ static inline uint16_t mavlink_msg_distance_sensor_pack_chan(uint8_t system_id,
packet.id = id;
packet.orientation = orientation;
packet.covariance = covariance;
packet.horizontal_fov = horizontal_fov;
packet.vertical_fov = vertical_fov;
packet.signal_quality = signal_quality;
mav_array_memcpy(packet.quaternion, quaternion, sizeof(float)*4);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN);
#endif
@ -165,7 +197,7 @@ static inline uint16_t mavlink_msg_distance_sensor_pack_chan(uint8_t system_id,
*/
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);
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, distance_sensor->horizontal_fov, distance_sensor->vertical_fov, distance_sensor->quaternion, distance_sensor->signal_quality);
}
/**
@ -179,7 +211,7 @@ static inline uint16_t mavlink_msg_distance_sensor_encode(uint8_t system_id, uin
*/
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);
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, distance_sensor->horizontal_fov, distance_sensor->vertical_fov, distance_sensor->quaternion, distance_sensor->signal_quality);
}
/**
@ -194,10 +226,14 @@ static inline uint16_t mavlink_msg_distance_sensor_encode_chan(uint8_t system_id
* @param id Onboard ID of the sensor
* @param orientation Direction the sensor faces. downward-facing: ROTATION_PITCH_270, upward-facing: ROTATION_PITCH_90, backward-facing: ROTATION_PITCH_180, forward-facing: ROTATION_NONE, left-facing: ROTATION_YAW_90, right-facing: ROTATION_YAW_270
* @param covariance [cm^2] Measurement variance. Max standard deviation is 6cm. 255 if unknown.
* @param horizontal_fov [rad] Horizontal Field of View (angle) where the distance measurement is valid and the field of view is known. Otherwise this is set to 0.
* @param vertical_fov [rad] Vertical Field of View (angle) where the distance measurement is valid and the field of view is known. Otherwise this is set to 0.
* @param quaternion Quaternion of the sensor orientation in vehicle body frame (w, x, y, z order, zero-rotation is 1, 0, 0, 0). Zero-rotation is along the vehicle body x-axis. This field is required if the orientation is set to MAV_SENSOR_ROTATION_CUSTOM. Set it to 0 if invalid."
* @param signal_quality [%] Signal quality of the sensor. Specific to each sensor type, representing the relation of the signal strength with the target reflectivity, distance, size or aspect, but normalised as a percentage. 0 = unknown/unset signal quality, 1 = invalid signal, 100 = perfect signal.
*/
#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)
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, float horizontal_fov, float vertical_fov, const float *quaternion, uint8_t signal_quality)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN];
@ -209,7 +245,10 @@ static inline void mavlink_msg_distance_sensor_send(mavlink_channel_t chan, uint
_mav_put_uint8_t(buf, 11, id);
_mav_put_uint8_t(buf, 12, orientation);
_mav_put_uint8_t(buf, 13, covariance);
_mav_put_float(buf, 14, horizontal_fov);
_mav_put_float(buf, 18, vertical_fov);
_mav_put_uint8_t(buf, 38, signal_quality);
_mav_put_float_array(buf, 22, quaternion, 4);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DISTANCE_SENSOR, buf, MAVLINK_MSG_ID_DISTANCE_SENSOR_MIN_LEN, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN, MAVLINK_MSG_ID_DISTANCE_SENSOR_CRC);
#else
mavlink_distance_sensor_t packet;
@ -221,7 +260,10 @@ static inline void mavlink_msg_distance_sensor_send(mavlink_channel_t chan, uint
packet.id = id;
packet.orientation = orientation;
packet.covariance = covariance;
packet.horizontal_fov = horizontal_fov;
packet.vertical_fov = vertical_fov;
packet.signal_quality = signal_quality;
mav_array_memcpy(packet.quaternion, quaternion, sizeof(float)*4);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DISTANCE_SENSOR, (const char *)&packet, MAVLINK_MSG_ID_DISTANCE_SENSOR_MIN_LEN, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN, MAVLINK_MSG_ID_DISTANCE_SENSOR_CRC);
#endif
}
@ -234,7 +276,7 @@ static inline void mavlink_msg_distance_sensor_send(mavlink_channel_t chan, uint
static inline void mavlink_msg_distance_sensor_send_struct(mavlink_channel_t chan, const mavlink_distance_sensor_t* distance_sensor)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mavlink_msg_distance_sensor_send(chan, 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);
mavlink_msg_distance_sensor_send(chan, 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, distance_sensor->horizontal_fov, distance_sensor->vertical_fov, distance_sensor->quaternion, distance_sensor->signal_quality);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DISTANCE_SENSOR, (const char *)distance_sensor, MAVLINK_MSG_ID_DISTANCE_SENSOR_MIN_LEN, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN, MAVLINK_MSG_ID_DISTANCE_SENSOR_CRC);
#endif
@ -248,7 +290,7 @@ static inline void mavlink_msg_distance_sensor_send_struct(mavlink_channel_t cha
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)
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, float horizontal_fov, float vertical_fov, const float *quaternion, uint8_t signal_quality)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
@ -260,7 +302,10 @@ static inline void mavlink_msg_distance_sensor_send_buf(mavlink_message_t *msgbu
_mav_put_uint8_t(buf, 11, id);
_mav_put_uint8_t(buf, 12, orientation);
_mav_put_uint8_t(buf, 13, covariance);
_mav_put_float(buf, 14, horizontal_fov);
_mav_put_float(buf, 18, vertical_fov);
_mav_put_uint8_t(buf, 38, signal_quality);
_mav_put_float_array(buf, 22, quaternion, 4);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DISTANCE_SENSOR, buf, MAVLINK_MSG_ID_DISTANCE_SENSOR_MIN_LEN, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN, MAVLINK_MSG_ID_DISTANCE_SENSOR_CRC);
#else
mavlink_distance_sensor_t *packet = (mavlink_distance_sensor_t *)msgbuf;
@ -272,7 +317,10 @@ static inline void mavlink_msg_distance_sensor_send_buf(mavlink_message_t *msgbu
packet->id = id;
packet->orientation = orientation;
packet->covariance = covariance;
packet->horizontal_fov = horizontal_fov;
packet->vertical_fov = vertical_fov;
packet->signal_quality = signal_quality;
mav_array_memcpy(packet->quaternion, quaternion, sizeof(float)*4);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_DISTANCE_SENSOR, (const char *)packet, MAVLINK_MSG_ID_DISTANCE_SENSOR_MIN_LEN, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN, MAVLINK_MSG_ID_DISTANCE_SENSOR_CRC);
#endif
}
@ -363,6 +411,46 @@ static inline uint8_t mavlink_msg_distance_sensor_get_covariance(const mavlink_m
return _MAV_RETURN_uint8_t(msg, 13);
}
/**
* @brief Get field horizontal_fov from distance_sensor message
*
* @return [rad] Horizontal Field of View (angle) where the distance measurement is valid and the field of view is known. Otherwise this is set to 0.
*/
static inline float mavlink_msg_distance_sensor_get_horizontal_fov(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 14);
}
/**
* @brief Get field vertical_fov from distance_sensor message
*
* @return [rad] Vertical Field of View (angle) where the distance measurement is valid and the field of view is known. Otherwise this is set to 0.
*/
static inline float mavlink_msg_distance_sensor_get_vertical_fov(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 18);
}
/**
* @brief Get field quaternion from distance_sensor message
*
* @return Quaternion of the sensor orientation in vehicle body frame (w, x, y, z order, zero-rotation is 1, 0, 0, 0). Zero-rotation is along the vehicle body x-axis. This field is required if the orientation is set to MAV_SENSOR_ROTATION_CUSTOM. Set it to 0 if invalid."
*/
static inline uint16_t mavlink_msg_distance_sensor_get_quaternion(const mavlink_message_t* msg, float *quaternion)
{
return _MAV_RETURN_float_array(msg, quaternion, 4, 22);
}
/**
* @brief Get field signal_quality from distance_sensor message
*
* @return [%] Signal quality of the sensor. Specific to each sensor type, representing the relation of the signal strength with the target reflectivity, distance, size or aspect, but normalised as a percentage. 0 = unknown/unset signal quality, 1 = invalid signal, 100 = perfect signal.
*/
static inline uint8_t mavlink_msg_distance_sensor_get_signal_quality(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 38);
}
/**
* @brief Decode a distance_sensor message into a struct
*
@ -380,6 +468,10 @@ static inline void mavlink_msg_distance_sensor_decode(const mavlink_message_t* m
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);
distance_sensor->horizontal_fov = mavlink_msg_distance_sensor_get_horizontal_fov(msg);
distance_sensor->vertical_fov = mavlink_msg_distance_sensor_get_vertical_fov(msg);
mavlink_msg_distance_sensor_get_quaternion(msg, distance_sensor->quaternion);
distance_sensor->signal_quality = mavlink_msg_distance_sensor_get_signal_quality(msg);
#else
uint8_t len = msg->len < MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN? msg->len : MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN;
memset(distance_sensor, 0, MAVLINK_MSG_ID_DISTANCE_SENSOR_LEN);

View file

@ -0,0 +1,613 @@
#pragma once
// MESSAGE EFI_STATUS PACKING
#define MAVLINK_MSG_ID_EFI_STATUS 225
typedef struct __mavlink_efi_status_t {
float ecu_index; /*< ECU index*/
float rpm; /*< RPM*/
float fuel_consumed; /*< [cm^3] Fuel consumed*/
float fuel_flow; /*< [cm^3/min] Fuel flow rate*/
float engine_load; /*< [%] Engine load*/
float throttle_position; /*< [%] Throttle position*/
float spark_dwell_time; /*< [ms] Spark dwell time*/
float barometric_pressure; /*< [kPa] Barometric pressure*/
float intake_manifold_pressure; /*< [kPa] Intake manifold pressure(*/
float intake_manifold_temperature; /*< [degC] Intake manifold temperature*/
float cylinder_head_temperature; /*< [degC] Cylinder head temperature*/
float ignition_timing; /*< [deg] Ignition timing (Crank angle degrees)*/
float injection_time; /*< [ms] Injection time*/
float exhaust_gas_temperature; /*< [degC] Exhaust gas temperature*/
float throttle_out; /*< [%] Output throttle*/
float pt_compensation; /*< Pressure/temperature compensation*/
uint8_t health; /*< EFI health status*/
} mavlink_efi_status_t;
#define MAVLINK_MSG_ID_EFI_STATUS_LEN 65
#define MAVLINK_MSG_ID_EFI_STATUS_MIN_LEN 65
#define MAVLINK_MSG_ID_225_LEN 65
#define MAVLINK_MSG_ID_225_MIN_LEN 65
#define MAVLINK_MSG_ID_EFI_STATUS_CRC 208
#define MAVLINK_MSG_ID_225_CRC 208
#if MAVLINK_COMMAND_24BIT
#define MAVLINK_MESSAGE_INFO_EFI_STATUS { \
225, \
"EFI_STATUS", \
17, \
{ { "health", NULL, MAVLINK_TYPE_UINT8_T, 0, 64, offsetof(mavlink_efi_status_t, health) }, \
{ "ecu_index", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_efi_status_t, ecu_index) }, \
{ "rpm", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_efi_status_t, rpm) }, \
{ "fuel_consumed", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_efi_status_t, fuel_consumed) }, \
{ "fuel_flow", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_efi_status_t, fuel_flow) }, \
{ "engine_load", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_efi_status_t, engine_load) }, \
{ "throttle_position", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_efi_status_t, throttle_position) }, \
{ "spark_dwell_time", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_efi_status_t, spark_dwell_time) }, \
{ "barometric_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_efi_status_t, barometric_pressure) }, \
{ "intake_manifold_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_efi_status_t, intake_manifold_pressure) }, \
{ "intake_manifold_temperature", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_efi_status_t, intake_manifold_temperature) }, \
{ "cylinder_head_temperature", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_efi_status_t, cylinder_head_temperature) }, \
{ "ignition_timing", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_efi_status_t, ignition_timing) }, \
{ "injection_time", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_efi_status_t, injection_time) }, \
{ "exhaust_gas_temperature", NULL, MAVLINK_TYPE_FLOAT, 0, 52, offsetof(mavlink_efi_status_t, exhaust_gas_temperature) }, \
{ "throttle_out", NULL, MAVLINK_TYPE_FLOAT, 0, 56, offsetof(mavlink_efi_status_t, throttle_out) }, \
{ "pt_compensation", NULL, MAVLINK_TYPE_FLOAT, 0, 60, offsetof(mavlink_efi_status_t, pt_compensation) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_EFI_STATUS { \
"EFI_STATUS", \
17, \
{ { "health", NULL, MAVLINK_TYPE_UINT8_T, 0, 64, offsetof(mavlink_efi_status_t, health) }, \
{ "ecu_index", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_efi_status_t, ecu_index) }, \
{ "rpm", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_efi_status_t, rpm) }, \
{ "fuel_consumed", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_efi_status_t, fuel_consumed) }, \
{ "fuel_flow", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_efi_status_t, fuel_flow) }, \
{ "engine_load", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_efi_status_t, engine_load) }, \
{ "throttle_position", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_efi_status_t, throttle_position) }, \
{ "spark_dwell_time", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_efi_status_t, spark_dwell_time) }, \
{ "barometric_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_efi_status_t, barometric_pressure) }, \
{ "intake_manifold_pressure", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_efi_status_t, intake_manifold_pressure) }, \
{ "intake_manifold_temperature", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_efi_status_t, intake_manifold_temperature) }, \
{ "cylinder_head_temperature", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_efi_status_t, cylinder_head_temperature) }, \
{ "ignition_timing", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_efi_status_t, ignition_timing) }, \
{ "injection_time", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_efi_status_t, injection_time) }, \
{ "exhaust_gas_temperature", NULL, MAVLINK_TYPE_FLOAT, 0, 52, offsetof(mavlink_efi_status_t, exhaust_gas_temperature) }, \
{ "throttle_out", NULL, MAVLINK_TYPE_FLOAT, 0, 56, offsetof(mavlink_efi_status_t, throttle_out) }, \
{ "pt_compensation", NULL, MAVLINK_TYPE_FLOAT, 0, 60, offsetof(mavlink_efi_status_t, pt_compensation) }, \
} \
}
#endif
/**
* @brief Pack a efi_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 health EFI health status
* @param ecu_index ECU index
* @param rpm RPM
* @param fuel_consumed [cm^3] Fuel consumed
* @param fuel_flow [cm^3/min] Fuel flow rate
* @param engine_load [%] Engine load
* @param throttle_position [%] Throttle position
* @param spark_dwell_time [ms] Spark dwell time
* @param barometric_pressure [kPa] Barometric pressure
* @param intake_manifold_pressure [kPa] Intake manifold pressure(
* @param intake_manifold_temperature [degC] Intake manifold temperature
* @param cylinder_head_temperature [degC] Cylinder head temperature
* @param ignition_timing [deg] Ignition timing (Crank angle degrees)
* @param injection_time [ms] Injection time
* @param exhaust_gas_temperature [degC] Exhaust gas temperature
* @param throttle_out [%] Output throttle
* @param pt_compensation Pressure/temperature compensation
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_efi_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t health, float ecu_index, float rpm, float fuel_consumed, float fuel_flow, float engine_load, float throttle_position, float spark_dwell_time, float barometric_pressure, float intake_manifold_pressure, float intake_manifold_temperature, float cylinder_head_temperature, float ignition_timing, float injection_time, float exhaust_gas_temperature, float throttle_out, float pt_compensation)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_EFI_STATUS_LEN];
_mav_put_float(buf, 0, ecu_index);
_mav_put_float(buf, 4, rpm);
_mav_put_float(buf, 8, fuel_consumed);
_mav_put_float(buf, 12, fuel_flow);
_mav_put_float(buf, 16, engine_load);
_mav_put_float(buf, 20, throttle_position);
_mav_put_float(buf, 24, spark_dwell_time);
_mav_put_float(buf, 28, barometric_pressure);
_mav_put_float(buf, 32, intake_manifold_pressure);
_mav_put_float(buf, 36, intake_manifold_temperature);
_mav_put_float(buf, 40, cylinder_head_temperature);
_mav_put_float(buf, 44, ignition_timing);
_mav_put_float(buf, 48, injection_time);
_mav_put_float(buf, 52, exhaust_gas_temperature);
_mav_put_float(buf, 56, throttle_out);
_mav_put_float(buf, 60, pt_compensation);
_mav_put_uint8_t(buf, 64, health);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_EFI_STATUS_LEN);
#else
mavlink_efi_status_t packet;
packet.ecu_index = ecu_index;
packet.rpm = rpm;
packet.fuel_consumed = fuel_consumed;
packet.fuel_flow = fuel_flow;
packet.engine_load = engine_load;
packet.throttle_position = throttle_position;
packet.spark_dwell_time = spark_dwell_time;
packet.barometric_pressure = barometric_pressure;
packet.intake_manifold_pressure = intake_manifold_pressure;
packet.intake_manifold_temperature = intake_manifold_temperature;
packet.cylinder_head_temperature = cylinder_head_temperature;
packet.ignition_timing = ignition_timing;
packet.injection_time = injection_time;
packet.exhaust_gas_temperature = exhaust_gas_temperature;
packet.throttle_out = throttle_out;
packet.pt_compensation = pt_compensation;
packet.health = health;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_EFI_STATUS_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_EFI_STATUS;
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_EFI_STATUS_MIN_LEN, MAVLINK_MSG_ID_EFI_STATUS_LEN, MAVLINK_MSG_ID_EFI_STATUS_CRC);
}
/**
* @brief Pack a efi_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 health EFI health status
* @param ecu_index ECU index
* @param rpm RPM
* @param fuel_consumed [cm^3] Fuel consumed
* @param fuel_flow [cm^3/min] Fuel flow rate
* @param engine_load [%] Engine load
* @param throttle_position [%] Throttle position
* @param spark_dwell_time [ms] Spark dwell time
* @param barometric_pressure [kPa] Barometric pressure
* @param intake_manifold_pressure [kPa] Intake manifold pressure(
* @param intake_manifold_temperature [degC] Intake manifold temperature
* @param cylinder_head_temperature [degC] Cylinder head temperature
* @param ignition_timing [deg] Ignition timing (Crank angle degrees)
* @param injection_time [ms] Injection time
* @param exhaust_gas_temperature [degC] Exhaust gas temperature
* @param throttle_out [%] Output throttle
* @param pt_compensation Pressure/temperature compensation
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_efi_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint8_t health,float ecu_index,float rpm,float fuel_consumed,float fuel_flow,float engine_load,float throttle_position,float spark_dwell_time,float barometric_pressure,float intake_manifold_pressure,float intake_manifold_temperature,float cylinder_head_temperature,float ignition_timing,float injection_time,float exhaust_gas_temperature,float throttle_out,float pt_compensation)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_EFI_STATUS_LEN];
_mav_put_float(buf, 0, ecu_index);
_mav_put_float(buf, 4, rpm);
_mav_put_float(buf, 8, fuel_consumed);
_mav_put_float(buf, 12, fuel_flow);
_mav_put_float(buf, 16, engine_load);
_mav_put_float(buf, 20, throttle_position);
_mav_put_float(buf, 24, spark_dwell_time);
_mav_put_float(buf, 28, barometric_pressure);
_mav_put_float(buf, 32, intake_manifold_pressure);
_mav_put_float(buf, 36, intake_manifold_temperature);
_mav_put_float(buf, 40, cylinder_head_temperature);
_mav_put_float(buf, 44, ignition_timing);
_mav_put_float(buf, 48, injection_time);
_mav_put_float(buf, 52, exhaust_gas_temperature);
_mav_put_float(buf, 56, throttle_out);
_mav_put_float(buf, 60, pt_compensation);
_mav_put_uint8_t(buf, 64, health);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_EFI_STATUS_LEN);
#else
mavlink_efi_status_t packet;
packet.ecu_index = ecu_index;
packet.rpm = rpm;
packet.fuel_consumed = fuel_consumed;
packet.fuel_flow = fuel_flow;
packet.engine_load = engine_load;
packet.throttle_position = throttle_position;
packet.spark_dwell_time = spark_dwell_time;
packet.barometric_pressure = barometric_pressure;
packet.intake_manifold_pressure = intake_manifold_pressure;
packet.intake_manifold_temperature = intake_manifold_temperature;
packet.cylinder_head_temperature = cylinder_head_temperature;
packet.ignition_timing = ignition_timing;
packet.injection_time = injection_time;
packet.exhaust_gas_temperature = exhaust_gas_temperature;
packet.throttle_out = throttle_out;
packet.pt_compensation = pt_compensation;
packet.health = health;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_EFI_STATUS_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_EFI_STATUS;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_EFI_STATUS_MIN_LEN, MAVLINK_MSG_ID_EFI_STATUS_LEN, MAVLINK_MSG_ID_EFI_STATUS_CRC);
}
/**
* @brief Encode a efi_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 efi_status C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_efi_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_efi_status_t* efi_status)
{
return mavlink_msg_efi_status_pack(system_id, component_id, msg, efi_status->health, efi_status->ecu_index, efi_status->rpm, efi_status->fuel_consumed, efi_status->fuel_flow, efi_status->engine_load, efi_status->throttle_position, efi_status->spark_dwell_time, efi_status->barometric_pressure, efi_status->intake_manifold_pressure, efi_status->intake_manifold_temperature, efi_status->cylinder_head_temperature, efi_status->ignition_timing, efi_status->injection_time, efi_status->exhaust_gas_temperature, efi_status->throttle_out, efi_status->pt_compensation);
}
/**
* @brief Encode a efi_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 efi_status C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_efi_status_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_efi_status_t* efi_status)
{
return mavlink_msg_efi_status_pack_chan(system_id, component_id, chan, msg, efi_status->health, efi_status->ecu_index, efi_status->rpm, efi_status->fuel_consumed, efi_status->fuel_flow, efi_status->engine_load, efi_status->throttle_position, efi_status->spark_dwell_time, efi_status->barometric_pressure, efi_status->intake_manifold_pressure, efi_status->intake_manifold_temperature, efi_status->cylinder_head_temperature, efi_status->ignition_timing, efi_status->injection_time, efi_status->exhaust_gas_temperature, efi_status->throttle_out, efi_status->pt_compensation);
}
/**
* @brief Send a efi_status message
* @param chan MAVLink channel to send the message
*
* @param health EFI health status
* @param ecu_index ECU index
* @param rpm RPM
* @param fuel_consumed [cm^3] Fuel consumed
* @param fuel_flow [cm^3/min] Fuel flow rate
* @param engine_load [%] Engine load
* @param throttle_position [%] Throttle position
* @param spark_dwell_time [ms] Spark dwell time
* @param barometric_pressure [kPa] Barometric pressure
* @param intake_manifold_pressure [kPa] Intake manifold pressure(
* @param intake_manifold_temperature [degC] Intake manifold temperature
* @param cylinder_head_temperature [degC] Cylinder head temperature
* @param ignition_timing [deg] Ignition timing (Crank angle degrees)
* @param injection_time [ms] Injection time
* @param exhaust_gas_temperature [degC] Exhaust gas temperature
* @param throttle_out [%] Output throttle
* @param pt_compensation Pressure/temperature compensation
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_efi_status_send(mavlink_channel_t chan, uint8_t health, float ecu_index, float rpm, float fuel_consumed, float fuel_flow, float engine_load, float throttle_position, float spark_dwell_time, float barometric_pressure, float intake_manifold_pressure, float intake_manifold_temperature, float cylinder_head_temperature, float ignition_timing, float injection_time, float exhaust_gas_temperature, float throttle_out, float pt_compensation)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_EFI_STATUS_LEN];
_mav_put_float(buf, 0, ecu_index);
_mav_put_float(buf, 4, rpm);
_mav_put_float(buf, 8, fuel_consumed);
_mav_put_float(buf, 12, fuel_flow);
_mav_put_float(buf, 16, engine_load);
_mav_put_float(buf, 20, throttle_position);
_mav_put_float(buf, 24, spark_dwell_time);
_mav_put_float(buf, 28, barometric_pressure);
_mav_put_float(buf, 32, intake_manifold_pressure);
_mav_put_float(buf, 36, intake_manifold_temperature);
_mav_put_float(buf, 40, cylinder_head_temperature);
_mav_put_float(buf, 44, ignition_timing);
_mav_put_float(buf, 48, injection_time);
_mav_put_float(buf, 52, exhaust_gas_temperature);
_mav_put_float(buf, 56, throttle_out);
_mav_put_float(buf, 60, pt_compensation);
_mav_put_uint8_t(buf, 64, health);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_EFI_STATUS, buf, MAVLINK_MSG_ID_EFI_STATUS_MIN_LEN, MAVLINK_MSG_ID_EFI_STATUS_LEN, MAVLINK_MSG_ID_EFI_STATUS_CRC);
#else
mavlink_efi_status_t packet;
packet.ecu_index = ecu_index;
packet.rpm = rpm;
packet.fuel_consumed = fuel_consumed;
packet.fuel_flow = fuel_flow;
packet.engine_load = engine_load;
packet.throttle_position = throttle_position;
packet.spark_dwell_time = spark_dwell_time;
packet.barometric_pressure = barometric_pressure;
packet.intake_manifold_pressure = intake_manifold_pressure;
packet.intake_manifold_temperature = intake_manifold_temperature;
packet.cylinder_head_temperature = cylinder_head_temperature;
packet.ignition_timing = ignition_timing;
packet.injection_time = injection_time;
packet.exhaust_gas_temperature = exhaust_gas_temperature;
packet.throttle_out = throttle_out;
packet.pt_compensation = pt_compensation;
packet.health = health;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_EFI_STATUS, (const char *)&packet, MAVLINK_MSG_ID_EFI_STATUS_MIN_LEN, MAVLINK_MSG_ID_EFI_STATUS_LEN, MAVLINK_MSG_ID_EFI_STATUS_CRC);
#endif
}
/**
* @brief Send a efi_status message
* @param chan MAVLink channel to send the message
* @param struct The MAVLink struct to serialize
*/
static inline void mavlink_msg_efi_status_send_struct(mavlink_channel_t chan, const mavlink_efi_status_t* efi_status)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mavlink_msg_efi_status_send(chan, efi_status->health, efi_status->ecu_index, efi_status->rpm, efi_status->fuel_consumed, efi_status->fuel_flow, efi_status->engine_load, efi_status->throttle_position, efi_status->spark_dwell_time, efi_status->barometric_pressure, efi_status->intake_manifold_pressure, efi_status->intake_manifold_temperature, efi_status->cylinder_head_temperature, efi_status->ignition_timing, efi_status->injection_time, efi_status->exhaust_gas_temperature, efi_status->throttle_out, efi_status->pt_compensation);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_EFI_STATUS, (const char *)efi_status, MAVLINK_MSG_ID_EFI_STATUS_MIN_LEN, MAVLINK_MSG_ID_EFI_STATUS_LEN, MAVLINK_MSG_ID_EFI_STATUS_CRC);
#endif
}
#if MAVLINK_MSG_ID_EFI_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_efi_status_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t health, float ecu_index, float rpm, float fuel_consumed, float fuel_flow, float engine_load, float throttle_position, float spark_dwell_time, float barometric_pressure, float intake_manifold_pressure, float intake_manifold_temperature, float cylinder_head_temperature, float ignition_timing, float injection_time, float exhaust_gas_temperature, float throttle_out, float pt_compensation)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
_mav_put_float(buf, 0, ecu_index);
_mav_put_float(buf, 4, rpm);
_mav_put_float(buf, 8, fuel_consumed);
_mav_put_float(buf, 12, fuel_flow);
_mav_put_float(buf, 16, engine_load);
_mav_put_float(buf, 20, throttle_position);
_mav_put_float(buf, 24, spark_dwell_time);
_mav_put_float(buf, 28, barometric_pressure);
_mav_put_float(buf, 32, intake_manifold_pressure);
_mav_put_float(buf, 36, intake_manifold_temperature);
_mav_put_float(buf, 40, cylinder_head_temperature);
_mav_put_float(buf, 44, ignition_timing);
_mav_put_float(buf, 48, injection_time);
_mav_put_float(buf, 52, exhaust_gas_temperature);
_mav_put_float(buf, 56, throttle_out);
_mav_put_float(buf, 60, pt_compensation);
_mav_put_uint8_t(buf, 64, health);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_EFI_STATUS, buf, MAVLINK_MSG_ID_EFI_STATUS_MIN_LEN, MAVLINK_MSG_ID_EFI_STATUS_LEN, MAVLINK_MSG_ID_EFI_STATUS_CRC);
#else
mavlink_efi_status_t *packet = (mavlink_efi_status_t *)msgbuf;
packet->ecu_index = ecu_index;
packet->rpm = rpm;
packet->fuel_consumed = fuel_consumed;
packet->fuel_flow = fuel_flow;
packet->engine_load = engine_load;
packet->throttle_position = throttle_position;
packet->spark_dwell_time = spark_dwell_time;
packet->barometric_pressure = barometric_pressure;
packet->intake_manifold_pressure = intake_manifold_pressure;
packet->intake_manifold_temperature = intake_manifold_temperature;
packet->cylinder_head_temperature = cylinder_head_temperature;
packet->ignition_timing = ignition_timing;
packet->injection_time = injection_time;
packet->exhaust_gas_temperature = exhaust_gas_temperature;
packet->throttle_out = throttle_out;
packet->pt_compensation = pt_compensation;
packet->health = health;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_EFI_STATUS, (const char *)packet, MAVLINK_MSG_ID_EFI_STATUS_MIN_LEN, MAVLINK_MSG_ID_EFI_STATUS_LEN, MAVLINK_MSG_ID_EFI_STATUS_CRC);
#endif
}
#endif
#endif
// MESSAGE EFI_STATUS UNPACKING
/**
* @brief Get field health from efi_status message
*
* @return EFI health status
*/
static inline uint8_t mavlink_msg_efi_status_get_health(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 64);
}
/**
* @brief Get field ecu_index from efi_status message
*
* @return ECU index
*/
static inline float mavlink_msg_efi_status_get_ecu_index(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 0);
}
/**
* @brief Get field rpm from efi_status message
*
* @return RPM
*/
static inline float mavlink_msg_efi_status_get_rpm(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 4);
}
/**
* @brief Get field fuel_consumed from efi_status message
*
* @return [cm^3] Fuel consumed
*/
static inline float mavlink_msg_efi_status_get_fuel_consumed(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 8);
}
/**
* @brief Get field fuel_flow from efi_status message
*
* @return [cm^3/min] Fuel flow rate
*/
static inline float mavlink_msg_efi_status_get_fuel_flow(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 12);
}
/**
* @brief Get field engine_load from efi_status message
*
* @return [%] Engine load
*/
static inline float mavlink_msg_efi_status_get_engine_load(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 16);
}
/**
* @brief Get field throttle_position from efi_status message
*
* @return [%] Throttle position
*/
static inline float mavlink_msg_efi_status_get_throttle_position(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 20);
}
/**
* @brief Get field spark_dwell_time from efi_status message
*
* @return [ms] Spark dwell time
*/
static inline float mavlink_msg_efi_status_get_spark_dwell_time(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 24);
}
/**
* @brief Get field barometric_pressure from efi_status message
*
* @return [kPa] Barometric pressure
*/
static inline float mavlink_msg_efi_status_get_barometric_pressure(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 28);
}
/**
* @brief Get field intake_manifold_pressure from efi_status message
*
* @return [kPa] Intake manifold pressure(
*/
static inline float mavlink_msg_efi_status_get_intake_manifold_pressure(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 32);
}
/**
* @brief Get field intake_manifold_temperature from efi_status message
*
* @return [degC] Intake manifold temperature
*/
static inline float mavlink_msg_efi_status_get_intake_manifold_temperature(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 36);
}
/**
* @brief Get field cylinder_head_temperature from efi_status message
*
* @return [degC] Cylinder head temperature
*/
static inline float mavlink_msg_efi_status_get_cylinder_head_temperature(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 40);
}
/**
* @brief Get field ignition_timing from efi_status message
*
* @return [deg] Ignition timing (Crank angle degrees)
*/
static inline float mavlink_msg_efi_status_get_ignition_timing(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 44);
}
/**
* @brief Get field injection_time from efi_status message
*
* @return [ms] Injection time
*/
static inline float mavlink_msg_efi_status_get_injection_time(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 48);
}
/**
* @brief Get field exhaust_gas_temperature from efi_status message
*
* @return [degC] Exhaust gas temperature
*/
static inline float mavlink_msg_efi_status_get_exhaust_gas_temperature(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 52);
}
/**
* @brief Get field throttle_out from efi_status message
*
* @return [%] Output throttle
*/
static inline float mavlink_msg_efi_status_get_throttle_out(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 56);
}
/**
* @brief Get field pt_compensation from efi_status message
*
* @return Pressure/temperature compensation
*/
static inline float mavlink_msg_efi_status_get_pt_compensation(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 60);
}
/**
* @brief Decode a efi_status message into a struct
*
* @param msg The message to decode
* @param efi_status C-struct to decode the message contents into
*/
static inline void mavlink_msg_efi_status_decode(const mavlink_message_t* msg, mavlink_efi_status_t* efi_status)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
efi_status->ecu_index = mavlink_msg_efi_status_get_ecu_index(msg);
efi_status->rpm = mavlink_msg_efi_status_get_rpm(msg);
efi_status->fuel_consumed = mavlink_msg_efi_status_get_fuel_consumed(msg);
efi_status->fuel_flow = mavlink_msg_efi_status_get_fuel_flow(msg);
efi_status->engine_load = mavlink_msg_efi_status_get_engine_load(msg);
efi_status->throttle_position = mavlink_msg_efi_status_get_throttle_position(msg);
efi_status->spark_dwell_time = mavlink_msg_efi_status_get_spark_dwell_time(msg);
efi_status->barometric_pressure = mavlink_msg_efi_status_get_barometric_pressure(msg);
efi_status->intake_manifold_pressure = mavlink_msg_efi_status_get_intake_manifold_pressure(msg);
efi_status->intake_manifold_temperature = mavlink_msg_efi_status_get_intake_manifold_temperature(msg);
efi_status->cylinder_head_temperature = mavlink_msg_efi_status_get_cylinder_head_temperature(msg);
efi_status->ignition_timing = mavlink_msg_efi_status_get_ignition_timing(msg);
efi_status->injection_time = mavlink_msg_efi_status_get_injection_time(msg);
efi_status->exhaust_gas_temperature = mavlink_msg_efi_status_get_exhaust_gas_temperature(msg);
efi_status->throttle_out = mavlink_msg_efi_status_get_throttle_out(msg);
efi_status->pt_compensation = mavlink_msg_efi_status_get_pt_compensation(msg);
efi_status->health = mavlink_msg_efi_status_get_health(msg);
#else
uint8_t len = msg->len < MAVLINK_MSG_ID_EFI_STATUS_LEN? msg->len : MAVLINK_MSG_ID_EFI_STATUS_LEN;
memset(efi_status, 0, MAVLINK_MSG_ID_EFI_STATUS_LEN);
memcpy(efi_status, _MAV_PAYLOAD(msg), len);
#endif
}

View file

@ -0,0 +1,407 @@
#pragma once
// MESSAGE ESC_INFO PACKING
#define MAVLINK_MSG_ID_ESC_INFO 290
typedef struct __mavlink_esc_info_t {
uint64_t time_usec; /*< [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude the number.*/
uint32_t error_count[4]; /*< Number of reported errors by each ESC since boot.*/
uint16_t counter; /*< Counter of data packets received.*/
uint16_t failure_flags[4]; /*< Bitmap of ESC failure flags.*/
uint8_t index; /*< Index of the first ESC in this message. minValue = 0, maxValue = 60, increment = 4.*/
uint8_t count; /*< Total number of ESCs in all messages of this type. Message fields with an index higher than this should be ignored because they contain invalid data.*/
uint8_t connection_type; /*< Connection type protocol for all ESC.*/
uint8_t info; /*< Information regarding online/offline status of each ESC.*/
uint8_t temperature[4]; /*< [degC] Temperature measured by each ESC. UINT8_MAX if data not supplied by ESC.*/
} mavlink_esc_info_t;
#define MAVLINK_MSG_ID_ESC_INFO_LEN 42
#define MAVLINK_MSG_ID_ESC_INFO_MIN_LEN 42
#define MAVLINK_MSG_ID_290_LEN 42
#define MAVLINK_MSG_ID_290_MIN_LEN 42
#define MAVLINK_MSG_ID_ESC_INFO_CRC 221
#define MAVLINK_MSG_ID_290_CRC 221
#define MAVLINK_MSG_ESC_INFO_FIELD_ERROR_COUNT_LEN 4
#define MAVLINK_MSG_ESC_INFO_FIELD_FAILURE_FLAGS_LEN 4
#define MAVLINK_MSG_ESC_INFO_FIELD_TEMPERATURE_LEN 4
#if MAVLINK_COMMAND_24BIT
#define MAVLINK_MESSAGE_INFO_ESC_INFO { \
290, \
"ESC_INFO", \
9, \
{ { "index", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_esc_info_t, index) }, \
{ "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_esc_info_t, time_usec) }, \
{ "counter", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_esc_info_t, counter) }, \
{ "count", NULL, MAVLINK_TYPE_UINT8_T, 0, 35, offsetof(mavlink_esc_info_t, count) }, \
{ "connection_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 36, offsetof(mavlink_esc_info_t, connection_type) }, \
{ "info", NULL, MAVLINK_TYPE_UINT8_T, 0, 37, offsetof(mavlink_esc_info_t, info) }, \
{ "failure_flags", NULL, MAVLINK_TYPE_UINT16_T, 4, 26, offsetof(mavlink_esc_info_t, failure_flags) }, \
{ "error_count", NULL, MAVLINK_TYPE_UINT32_T, 4, 8, offsetof(mavlink_esc_info_t, error_count) }, \
{ "temperature", NULL, MAVLINK_TYPE_UINT8_T, 4, 38, offsetof(mavlink_esc_info_t, temperature) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_ESC_INFO { \
"ESC_INFO", \
9, \
{ { "index", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_esc_info_t, index) }, \
{ "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_esc_info_t, time_usec) }, \
{ "counter", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_esc_info_t, counter) }, \
{ "count", NULL, MAVLINK_TYPE_UINT8_T, 0, 35, offsetof(mavlink_esc_info_t, count) }, \
{ "connection_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 36, offsetof(mavlink_esc_info_t, connection_type) }, \
{ "info", NULL, MAVLINK_TYPE_UINT8_T, 0, 37, offsetof(mavlink_esc_info_t, info) }, \
{ "failure_flags", NULL, MAVLINK_TYPE_UINT16_T, 4, 26, offsetof(mavlink_esc_info_t, failure_flags) }, \
{ "error_count", NULL, MAVLINK_TYPE_UINT32_T, 4, 8, offsetof(mavlink_esc_info_t, error_count) }, \
{ "temperature", NULL, MAVLINK_TYPE_UINT8_T, 4, 38, offsetof(mavlink_esc_info_t, temperature) }, \
} \
}
#endif
/**
* @brief Pack a esc_info message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param index Index of the first ESC in this message. minValue = 0, maxValue = 60, increment = 4.
* @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude the number.
* @param counter Counter of data packets received.
* @param count Total number of ESCs in all messages of this type. Message fields with an index higher than this should be ignored because they contain invalid data.
* @param connection_type Connection type protocol for all ESC.
* @param info Information regarding online/offline status of each ESC.
* @param failure_flags Bitmap of ESC failure flags.
* @param error_count Number of reported errors by each ESC since boot.
* @param temperature [degC] Temperature measured by each ESC. UINT8_MAX if data not supplied by ESC.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_esc_info_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t index, uint64_t time_usec, uint16_t counter, uint8_t count, uint8_t connection_type, uint8_t info, const uint16_t *failure_flags, const uint32_t *error_count, const uint8_t *temperature)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_ESC_INFO_LEN];
_mav_put_uint64_t(buf, 0, time_usec);
_mav_put_uint16_t(buf, 24, counter);
_mav_put_uint8_t(buf, 34, index);
_mav_put_uint8_t(buf, 35, count);
_mav_put_uint8_t(buf, 36, connection_type);
_mav_put_uint8_t(buf, 37, info);
_mav_put_uint32_t_array(buf, 8, error_count, 4);
_mav_put_uint16_t_array(buf, 26, failure_flags, 4);
_mav_put_uint8_t_array(buf, 38, temperature, 4);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ESC_INFO_LEN);
#else
mavlink_esc_info_t packet;
packet.time_usec = time_usec;
packet.counter = counter;
packet.index = index;
packet.count = count;
packet.connection_type = connection_type;
packet.info = info;
mav_array_memcpy(packet.error_count, error_count, sizeof(uint32_t)*4);
mav_array_memcpy(packet.failure_flags, failure_flags, sizeof(uint16_t)*4);
mav_array_memcpy(packet.temperature, temperature, sizeof(uint8_t)*4);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ESC_INFO_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_ESC_INFO;
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ESC_INFO_MIN_LEN, MAVLINK_MSG_ID_ESC_INFO_LEN, MAVLINK_MSG_ID_ESC_INFO_CRC);
}
/**
* @brief Pack a esc_info message on a channel
* @param system_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 index Index of the first ESC in this message. minValue = 0, maxValue = 60, increment = 4.
* @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude the number.
* @param counter Counter of data packets received.
* @param count Total number of ESCs in all messages of this type. Message fields with an index higher than this should be ignored because they contain invalid data.
* @param connection_type Connection type protocol for all ESC.
* @param info Information regarding online/offline status of each ESC.
* @param failure_flags Bitmap of ESC failure flags.
* @param error_count Number of reported errors by each ESC since boot.
* @param temperature [degC] Temperature measured by each ESC. UINT8_MAX if data not supplied by ESC.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_esc_info_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint8_t index,uint64_t time_usec,uint16_t counter,uint8_t count,uint8_t connection_type,uint8_t info,const uint16_t *failure_flags,const uint32_t *error_count,const uint8_t *temperature)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_ESC_INFO_LEN];
_mav_put_uint64_t(buf, 0, time_usec);
_mav_put_uint16_t(buf, 24, counter);
_mav_put_uint8_t(buf, 34, index);
_mav_put_uint8_t(buf, 35, count);
_mav_put_uint8_t(buf, 36, connection_type);
_mav_put_uint8_t(buf, 37, info);
_mav_put_uint32_t_array(buf, 8, error_count, 4);
_mav_put_uint16_t_array(buf, 26, failure_flags, 4);
_mav_put_uint8_t_array(buf, 38, temperature, 4);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ESC_INFO_LEN);
#else
mavlink_esc_info_t packet;
packet.time_usec = time_usec;
packet.counter = counter;
packet.index = index;
packet.count = count;
packet.connection_type = connection_type;
packet.info = info;
mav_array_memcpy(packet.error_count, error_count, sizeof(uint32_t)*4);
mav_array_memcpy(packet.failure_flags, failure_flags, sizeof(uint16_t)*4);
mav_array_memcpy(packet.temperature, temperature, sizeof(uint8_t)*4);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ESC_INFO_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_ESC_INFO;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ESC_INFO_MIN_LEN, MAVLINK_MSG_ID_ESC_INFO_LEN, MAVLINK_MSG_ID_ESC_INFO_CRC);
}
/**
* @brief Encode a esc_info 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 esc_info C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_esc_info_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_esc_info_t* esc_info)
{
return mavlink_msg_esc_info_pack(system_id, component_id, msg, esc_info->index, esc_info->time_usec, esc_info->counter, esc_info->count, esc_info->connection_type, esc_info->info, esc_info->failure_flags, esc_info->error_count, esc_info->temperature);
}
/**
* @brief Encode a esc_info 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 esc_info C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_esc_info_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_esc_info_t* esc_info)
{
return mavlink_msg_esc_info_pack_chan(system_id, component_id, chan, msg, esc_info->index, esc_info->time_usec, esc_info->counter, esc_info->count, esc_info->connection_type, esc_info->info, esc_info->failure_flags, esc_info->error_count, esc_info->temperature);
}
/**
* @brief Send a esc_info message
* @param chan MAVLink channel to send the message
*
* @param index Index of the first ESC in this message. minValue = 0, maxValue = 60, increment = 4.
* @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude the number.
* @param counter Counter of data packets received.
* @param count Total number of ESCs in all messages of this type. Message fields with an index higher than this should be ignored because they contain invalid data.
* @param connection_type Connection type protocol for all ESC.
* @param info Information regarding online/offline status of each ESC.
* @param failure_flags Bitmap of ESC failure flags.
* @param error_count Number of reported errors by each ESC since boot.
* @param temperature [degC] Temperature measured by each ESC. UINT8_MAX if data not supplied by ESC.
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_esc_info_send(mavlink_channel_t chan, uint8_t index, uint64_t time_usec, uint16_t counter, uint8_t count, uint8_t connection_type, uint8_t info, const uint16_t *failure_flags, const uint32_t *error_count, const uint8_t *temperature)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_ESC_INFO_LEN];
_mav_put_uint64_t(buf, 0, time_usec);
_mav_put_uint16_t(buf, 24, counter);
_mav_put_uint8_t(buf, 34, index);
_mav_put_uint8_t(buf, 35, count);
_mav_put_uint8_t(buf, 36, connection_type);
_mav_put_uint8_t(buf, 37, info);
_mav_put_uint32_t_array(buf, 8, error_count, 4);
_mav_put_uint16_t_array(buf, 26, failure_flags, 4);
_mav_put_uint8_t_array(buf, 38, temperature, 4);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ESC_INFO, buf, MAVLINK_MSG_ID_ESC_INFO_MIN_LEN, MAVLINK_MSG_ID_ESC_INFO_LEN, MAVLINK_MSG_ID_ESC_INFO_CRC);
#else
mavlink_esc_info_t packet;
packet.time_usec = time_usec;
packet.counter = counter;
packet.index = index;
packet.count = count;
packet.connection_type = connection_type;
packet.info = info;
mav_array_memcpy(packet.error_count, error_count, sizeof(uint32_t)*4);
mav_array_memcpy(packet.failure_flags, failure_flags, sizeof(uint16_t)*4);
mav_array_memcpy(packet.temperature, temperature, sizeof(uint8_t)*4);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ESC_INFO, (const char *)&packet, MAVLINK_MSG_ID_ESC_INFO_MIN_LEN, MAVLINK_MSG_ID_ESC_INFO_LEN, MAVLINK_MSG_ID_ESC_INFO_CRC);
#endif
}
/**
* @brief Send a esc_info message
* @param chan MAVLink channel to send the message
* @param struct The MAVLink struct to serialize
*/
static inline void mavlink_msg_esc_info_send_struct(mavlink_channel_t chan, const mavlink_esc_info_t* esc_info)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mavlink_msg_esc_info_send(chan, esc_info->index, esc_info->time_usec, esc_info->counter, esc_info->count, esc_info->connection_type, esc_info->info, esc_info->failure_flags, esc_info->error_count, esc_info->temperature);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ESC_INFO, (const char *)esc_info, MAVLINK_MSG_ID_ESC_INFO_MIN_LEN, MAVLINK_MSG_ID_ESC_INFO_LEN, MAVLINK_MSG_ID_ESC_INFO_CRC);
#endif
}
#if MAVLINK_MSG_ID_ESC_INFO_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_esc_info_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t index, uint64_t time_usec, uint16_t counter, uint8_t count, uint8_t connection_type, uint8_t info, const uint16_t *failure_flags, const uint32_t *error_count, const uint8_t *temperature)
{
#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, 24, counter);
_mav_put_uint8_t(buf, 34, index);
_mav_put_uint8_t(buf, 35, count);
_mav_put_uint8_t(buf, 36, connection_type);
_mav_put_uint8_t(buf, 37, info);
_mav_put_uint32_t_array(buf, 8, error_count, 4);
_mav_put_uint16_t_array(buf, 26, failure_flags, 4);
_mav_put_uint8_t_array(buf, 38, temperature, 4);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ESC_INFO, buf, MAVLINK_MSG_ID_ESC_INFO_MIN_LEN, MAVLINK_MSG_ID_ESC_INFO_LEN, MAVLINK_MSG_ID_ESC_INFO_CRC);
#else
mavlink_esc_info_t *packet = (mavlink_esc_info_t *)msgbuf;
packet->time_usec = time_usec;
packet->counter = counter;
packet->index = index;
packet->count = count;
packet->connection_type = connection_type;
packet->info = info;
mav_array_memcpy(packet->error_count, error_count, sizeof(uint32_t)*4);
mav_array_memcpy(packet->failure_flags, failure_flags, sizeof(uint16_t)*4);
mav_array_memcpy(packet->temperature, temperature, sizeof(uint8_t)*4);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ESC_INFO, (const char *)packet, MAVLINK_MSG_ID_ESC_INFO_MIN_LEN, MAVLINK_MSG_ID_ESC_INFO_LEN, MAVLINK_MSG_ID_ESC_INFO_CRC);
#endif
}
#endif
#endif
// MESSAGE ESC_INFO UNPACKING
/**
* @brief Get field index from esc_info message
*
* @return Index of the first ESC in this message. minValue = 0, maxValue = 60, increment = 4.
*/
static inline uint8_t mavlink_msg_esc_info_get_index(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 34);
}
/**
* @brief Get field time_usec from esc_info message
*
* @return [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude the number.
*/
static inline uint64_t mavlink_msg_esc_info_get_time_usec(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint64_t(msg, 0);
}
/**
* @brief Get field counter from esc_info message
*
* @return Counter of data packets received.
*/
static inline uint16_t mavlink_msg_esc_info_get_counter(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 24);
}
/**
* @brief Get field count from esc_info message
*
* @return Total number of ESCs in all messages of this type. Message fields with an index higher than this should be ignored because they contain invalid data.
*/
static inline uint8_t mavlink_msg_esc_info_get_count(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 35);
}
/**
* @brief Get field connection_type from esc_info message
*
* @return Connection type protocol for all ESC.
*/
static inline uint8_t mavlink_msg_esc_info_get_connection_type(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 36);
}
/**
* @brief Get field info from esc_info message
*
* @return Information regarding online/offline status of each ESC.
*/
static inline uint8_t mavlink_msg_esc_info_get_info(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 37);
}
/**
* @brief Get field failure_flags from esc_info message
*
* @return Bitmap of ESC failure flags.
*/
static inline uint16_t mavlink_msg_esc_info_get_failure_flags(const mavlink_message_t* msg, uint16_t *failure_flags)
{
return _MAV_RETURN_uint16_t_array(msg, failure_flags, 4, 26);
}
/**
* @brief Get field error_count from esc_info message
*
* @return Number of reported errors by each ESC since boot.
*/
static inline uint16_t mavlink_msg_esc_info_get_error_count(const mavlink_message_t* msg, uint32_t *error_count)
{
return _MAV_RETURN_uint32_t_array(msg, error_count, 4, 8);
}
/**
* @brief Get field temperature from esc_info message
*
* @return [degC] Temperature measured by each ESC. UINT8_MAX if data not supplied by ESC.
*/
static inline uint16_t mavlink_msg_esc_info_get_temperature(const mavlink_message_t* msg, uint8_t *temperature)
{
return _MAV_RETURN_uint8_t_array(msg, temperature, 4, 38);
}
/**
* @brief Decode a esc_info message into a struct
*
* @param msg The message to decode
* @param esc_info C-struct to decode the message contents into
*/
static inline void mavlink_msg_esc_info_decode(const mavlink_message_t* msg, mavlink_esc_info_t* esc_info)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
esc_info->time_usec = mavlink_msg_esc_info_get_time_usec(msg);
mavlink_msg_esc_info_get_error_count(msg, esc_info->error_count);
esc_info->counter = mavlink_msg_esc_info_get_counter(msg);
mavlink_msg_esc_info_get_failure_flags(msg, esc_info->failure_flags);
esc_info->index = mavlink_msg_esc_info_get_index(msg);
esc_info->count = mavlink_msg_esc_info_get_count(msg);
esc_info->connection_type = mavlink_msg_esc_info_get_connection_type(msg);
esc_info->info = mavlink_msg_esc_info_get_info(msg);
mavlink_msg_esc_info_get_temperature(msg, esc_info->temperature);
#else
uint8_t len = msg->len < MAVLINK_MSG_ID_ESC_INFO_LEN? msg->len : MAVLINK_MSG_ID_ESC_INFO_LEN;
memset(esc_info, 0, MAVLINK_MSG_ID_ESC_INFO_LEN);
memcpy(esc_info, _MAV_PAYLOAD(msg), len);
#endif
}

View file

@ -0,0 +1,307 @@
#pragma once
// MESSAGE ESC_STATUS PACKING
#define MAVLINK_MSG_ID_ESC_STATUS 291
typedef struct __mavlink_esc_status_t {
uint64_t time_usec; /*< [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude the number.*/
int32_t rpm[4]; /*< [rpm] Reported motor RPM from each ESC (negative for reverse rotation).*/
float voltage[4]; /*< [V] Voltage measured from each ESC.*/
float current[4]; /*< [A] Current measured from each ESC.*/
uint8_t index; /*< Index of the first ESC in this message. minValue = 0, maxValue = 60, increment = 4.*/
} mavlink_esc_status_t;
#define MAVLINK_MSG_ID_ESC_STATUS_LEN 57
#define MAVLINK_MSG_ID_ESC_STATUS_MIN_LEN 57
#define MAVLINK_MSG_ID_291_LEN 57
#define MAVLINK_MSG_ID_291_MIN_LEN 57
#define MAVLINK_MSG_ID_ESC_STATUS_CRC 10
#define MAVLINK_MSG_ID_291_CRC 10
#define MAVLINK_MSG_ESC_STATUS_FIELD_RPM_LEN 4
#define MAVLINK_MSG_ESC_STATUS_FIELD_VOLTAGE_LEN 4
#define MAVLINK_MSG_ESC_STATUS_FIELD_CURRENT_LEN 4
#if MAVLINK_COMMAND_24BIT
#define MAVLINK_MESSAGE_INFO_ESC_STATUS { \
291, \
"ESC_STATUS", \
5, \
{ { "index", NULL, MAVLINK_TYPE_UINT8_T, 0, 56, offsetof(mavlink_esc_status_t, index) }, \
{ "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_esc_status_t, time_usec) }, \
{ "rpm", NULL, MAVLINK_TYPE_INT32_T, 4, 8, offsetof(mavlink_esc_status_t, rpm) }, \
{ "voltage", NULL, MAVLINK_TYPE_FLOAT, 4, 24, offsetof(mavlink_esc_status_t, voltage) }, \
{ "current", NULL, MAVLINK_TYPE_FLOAT, 4, 40, offsetof(mavlink_esc_status_t, current) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_ESC_STATUS { \
"ESC_STATUS", \
5, \
{ { "index", NULL, MAVLINK_TYPE_UINT8_T, 0, 56, offsetof(mavlink_esc_status_t, index) }, \
{ "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_esc_status_t, time_usec) }, \
{ "rpm", NULL, MAVLINK_TYPE_INT32_T, 4, 8, offsetof(mavlink_esc_status_t, rpm) }, \
{ "voltage", NULL, MAVLINK_TYPE_FLOAT, 4, 24, offsetof(mavlink_esc_status_t, voltage) }, \
{ "current", NULL, MAVLINK_TYPE_FLOAT, 4, 40, offsetof(mavlink_esc_status_t, current) }, \
} \
}
#endif
/**
* @brief Pack a esc_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 index Index of the first ESC in this message. minValue = 0, maxValue = 60, increment = 4.
* @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude the number.
* @param rpm [rpm] Reported motor RPM from each ESC (negative for reverse rotation).
* @param voltage [V] Voltage measured from each ESC.
* @param current [A] Current measured from each ESC.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_esc_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t index, uint64_t time_usec, const int32_t *rpm, const float *voltage, const float *current)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_ESC_STATUS_LEN];
_mav_put_uint64_t(buf, 0, time_usec);
_mav_put_uint8_t(buf, 56, index);
_mav_put_int32_t_array(buf, 8, rpm, 4);
_mav_put_float_array(buf, 24, voltage, 4);
_mav_put_float_array(buf, 40, current, 4);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ESC_STATUS_LEN);
#else
mavlink_esc_status_t packet;
packet.time_usec = time_usec;
packet.index = index;
mav_array_memcpy(packet.rpm, rpm, sizeof(int32_t)*4);
mav_array_memcpy(packet.voltage, voltage, sizeof(float)*4);
mav_array_memcpy(packet.current, current, sizeof(float)*4);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ESC_STATUS_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_ESC_STATUS;
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ESC_STATUS_MIN_LEN, MAVLINK_MSG_ID_ESC_STATUS_LEN, MAVLINK_MSG_ID_ESC_STATUS_CRC);
}
/**
* @brief Pack a esc_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 index Index of the first ESC in this message. minValue = 0, maxValue = 60, increment = 4.
* @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude the number.
* @param rpm [rpm] Reported motor RPM from each ESC (negative for reverse rotation).
* @param voltage [V] Voltage measured from each ESC.
* @param current [A] Current measured from each ESC.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_esc_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint8_t index,uint64_t time_usec,const int32_t *rpm,const float *voltage,const float *current)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_ESC_STATUS_LEN];
_mav_put_uint64_t(buf, 0, time_usec);
_mav_put_uint8_t(buf, 56, index);
_mav_put_int32_t_array(buf, 8, rpm, 4);
_mav_put_float_array(buf, 24, voltage, 4);
_mav_put_float_array(buf, 40, current, 4);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ESC_STATUS_LEN);
#else
mavlink_esc_status_t packet;
packet.time_usec = time_usec;
packet.index = index;
mav_array_memcpy(packet.rpm, rpm, sizeof(int32_t)*4);
mav_array_memcpy(packet.voltage, voltage, sizeof(float)*4);
mav_array_memcpy(packet.current, current, sizeof(float)*4);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ESC_STATUS_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_ESC_STATUS;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ESC_STATUS_MIN_LEN, MAVLINK_MSG_ID_ESC_STATUS_LEN, MAVLINK_MSG_ID_ESC_STATUS_CRC);
}
/**
* @brief Encode a esc_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 esc_status C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_esc_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_esc_status_t* esc_status)
{
return mavlink_msg_esc_status_pack(system_id, component_id, msg, esc_status->index, esc_status->time_usec, esc_status->rpm, esc_status->voltage, esc_status->current);
}
/**
* @brief Encode a esc_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 esc_status C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_esc_status_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_esc_status_t* esc_status)
{
return mavlink_msg_esc_status_pack_chan(system_id, component_id, chan, msg, esc_status->index, esc_status->time_usec, esc_status->rpm, esc_status->voltage, esc_status->current);
}
/**
* @brief Send a esc_status message
* @param chan MAVLink channel to send the message
*
* @param index Index of the first ESC in this message. minValue = 0, maxValue = 60, increment = 4.
* @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude the number.
* @param rpm [rpm] Reported motor RPM from each ESC (negative for reverse rotation).
* @param voltage [V] Voltage measured from each ESC.
* @param current [A] Current measured from each ESC.
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_esc_status_send(mavlink_channel_t chan, uint8_t index, uint64_t time_usec, const int32_t *rpm, const float *voltage, const float *current)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_ESC_STATUS_LEN];
_mav_put_uint64_t(buf, 0, time_usec);
_mav_put_uint8_t(buf, 56, index);
_mav_put_int32_t_array(buf, 8, rpm, 4);
_mav_put_float_array(buf, 24, voltage, 4);
_mav_put_float_array(buf, 40, current, 4);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ESC_STATUS, buf, MAVLINK_MSG_ID_ESC_STATUS_MIN_LEN, MAVLINK_MSG_ID_ESC_STATUS_LEN, MAVLINK_MSG_ID_ESC_STATUS_CRC);
#else
mavlink_esc_status_t packet;
packet.time_usec = time_usec;
packet.index = index;
mav_array_memcpy(packet.rpm, rpm, sizeof(int32_t)*4);
mav_array_memcpy(packet.voltage, voltage, sizeof(float)*4);
mav_array_memcpy(packet.current, current, sizeof(float)*4);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ESC_STATUS, (const char *)&packet, MAVLINK_MSG_ID_ESC_STATUS_MIN_LEN, MAVLINK_MSG_ID_ESC_STATUS_LEN, MAVLINK_MSG_ID_ESC_STATUS_CRC);
#endif
}
/**
* @brief Send a esc_status message
* @param chan MAVLink channel to send the message
* @param struct The MAVLink struct to serialize
*/
static inline void mavlink_msg_esc_status_send_struct(mavlink_channel_t chan, const mavlink_esc_status_t* esc_status)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mavlink_msg_esc_status_send(chan, esc_status->index, esc_status->time_usec, esc_status->rpm, esc_status->voltage, esc_status->current);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ESC_STATUS, (const char *)esc_status, MAVLINK_MSG_ID_ESC_STATUS_MIN_LEN, MAVLINK_MSG_ID_ESC_STATUS_LEN, MAVLINK_MSG_ID_ESC_STATUS_CRC);
#endif
}
#if MAVLINK_MSG_ID_ESC_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_esc_status_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t index, uint64_t time_usec, const int32_t *rpm, const float *voltage, const float *current)
{
#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, 56, index);
_mav_put_int32_t_array(buf, 8, rpm, 4);
_mav_put_float_array(buf, 24, voltage, 4);
_mav_put_float_array(buf, 40, current, 4);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ESC_STATUS, buf, MAVLINK_MSG_ID_ESC_STATUS_MIN_LEN, MAVLINK_MSG_ID_ESC_STATUS_LEN, MAVLINK_MSG_ID_ESC_STATUS_CRC);
#else
mavlink_esc_status_t *packet = (mavlink_esc_status_t *)msgbuf;
packet->time_usec = time_usec;
packet->index = index;
mav_array_memcpy(packet->rpm, rpm, sizeof(int32_t)*4);
mav_array_memcpy(packet->voltage, voltage, sizeof(float)*4);
mav_array_memcpy(packet->current, current, sizeof(float)*4);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ESC_STATUS, (const char *)packet, MAVLINK_MSG_ID_ESC_STATUS_MIN_LEN, MAVLINK_MSG_ID_ESC_STATUS_LEN, MAVLINK_MSG_ID_ESC_STATUS_CRC);
#endif
}
#endif
#endif
// MESSAGE ESC_STATUS UNPACKING
/**
* @brief Get field index from esc_status message
*
* @return Index of the first ESC in this message. minValue = 0, maxValue = 60, increment = 4.
*/
static inline uint8_t mavlink_msg_esc_status_get_index(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 56);
}
/**
* @brief Get field time_usec from esc_status message
*
* @return [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude the number.
*/
static inline uint64_t mavlink_msg_esc_status_get_time_usec(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint64_t(msg, 0);
}
/**
* @brief Get field rpm from esc_status message
*
* @return [rpm] Reported motor RPM from each ESC (negative for reverse rotation).
*/
static inline uint16_t mavlink_msg_esc_status_get_rpm(const mavlink_message_t* msg, int32_t *rpm)
{
return _MAV_RETURN_int32_t_array(msg, rpm, 4, 8);
}
/**
* @brief Get field voltage from esc_status message
*
* @return [V] Voltage measured from each ESC.
*/
static inline uint16_t mavlink_msg_esc_status_get_voltage(const mavlink_message_t* msg, float *voltage)
{
return _MAV_RETURN_float_array(msg, voltage, 4, 24);
}
/**
* @brief Get field current from esc_status message
*
* @return [A] Current measured from each ESC.
*/
static inline uint16_t mavlink_msg_esc_status_get_current(const mavlink_message_t* msg, float *current)
{
return _MAV_RETURN_float_array(msg, current, 4, 40);
}
/**
* @brief Decode a esc_status message into a struct
*
* @param msg The message to decode
* @param esc_status C-struct to decode the message contents into
*/
static inline void mavlink_msg_esc_status_decode(const mavlink_message_t* msg, mavlink_esc_status_t* esc_status)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
esc_status->time_usec = mavlink_msg_esc_status_get_time_usec(msg);
mavlink_msg_esc_status_get_rpm(msg, esc_status->rpm);
mavlink_msg_esc_status_get_voltage(msg, esc_status->voltage);
mavlink_msg_esc_status_get_current(msg, esc_status->current);
esc_status->index = mavlink_msg_esc_status_get_index(msg);
#else
uint8_t len = msg->len < MAVLINK_MSG_ID_ESC_STATUS_LEN? msg->len : MAVLINK_MSG_ID_ESC_STATUS_LEN;
memset(esc_status, 0, MAVLINK_MSG_ID_ESC_STATUS_LEN);
memcpy(esc_status, _MAV_PAYLOAD(msg), len);
#endif
}

View file

@ -9,11 +9,12 @@ typedef struct __mavlink_fence_status_t {
uint16_t breach_count; /*< Number of fence breaches.*/
uint8_t breach_status; /*< Breach status (0 if currently inside fence, 1 if outside).*/
uint8_t breach_type; /*< Last breach type.*/
uint8_t breach_mitigation; /*< Active action to prevent fence breach*/
} mavlink_fence_status_t;
#define MAVLINK_MSG_ID_FENCE_STATUS_LEN 8
#define MAVLINK_MSG_ID_FENCE_STATUS_LEN 9
#define MAVLINK_MSG_ID_FENCE_STATUS_MIN_LEN 8
#define MAVLINK_MSG_ID_162_LEN 8
#define MAVLINK_MSG_ID_162_LEN 9
#define MAVLINK_MSG_ID_162_MIN_LEN 8
#define MAVLINK_MSG_ID_FENCE_STATUS_CRC 189
@ -25,21 +26,23 @@ typedef struct __mavlink_fence_status_t {
#define MAVLINK_MESSAGE_INFO_FENCE_STATUS { \
162, \
"FENCE_STATUS", \
4, \
5, \
{ { "breach_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_fence_status_t, breach_status) }, \
{ "breach_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_fence_status_t, breach_count) }, \
{ "breach_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 7, offsetof(mavlink_fence_status_t, breach_type) }, \
{ "breach_time", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_fence_status_t, breach_time) }, \
{ "breach_mitigation", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_fence_status_t, breach_mitigation) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_FENCE_STATUS { \
"FENCE_STATUS", \
4, \
5, \
{ { "breach_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_fence_status_t, breach_status) }, \
{ "breach_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 4, offsetof(mavlink_fence_status_t, breach_count) }, \
{ "breach_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 7, offsetof(mavlink_fence_status_t, breach_type) }, \
{ "breach_time", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_fence_status_t, breach_time) }, \
{ "breach_mitigation", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_fence_status_t, breach_mitigation) }, \
} \
}
#endif
@ -54,10 +57,11 @@ typedef struct __mavlink_fence_status_t {
* @param breach_count Number of fence breaches.
* @param breach_type Last breach type.
* @param breach_time [ms] Time (since boot) of last breach.
* @param breach_mitigation Active action to prevent fence breach
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_fence_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t breach_status, uint16_t breach_count, uint8_t breach_type, uint32_t breach_time)
uint8_t breach_status, uint16_t breach_count, uint8_t breach_type, uint32_t breach_time, uint8_t breach_mitigation)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_FENCE_STATUS_LEN];
@ -65,6 +69,7 @@ static inline uint16_t mavlink_msg_fence_status_pack(uint8_t system_id, uint8_t
_mav_put_uint16_t(buf, 4, breach_count);
_mav_put_uint8_t(buf, 6, breach_status);
_mav_put_uint8_t(buf, 7, breach_type);
_mav_put_uint8_t(buf, 8, breach_mitigation);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_FENCE_STATUS_LEN);
#else
@ -73,6 +78,7 @@ static inline uint16_t mavlink_msg_fence_status_pack(uint8_t system_id, uint8_t
packet.breach_count = breach_count;
packet.breach_status = breach_status;
packet.breach_type = breach_type;
packet.breach_mitigation = breach_mitigation;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_FENCE_STATUS_LEN);
#endif
@ -91,11 +97,12 @@ static inline uint16_t mavlink_msg_fence_status_pack(uint8_t system_id, uint8_t
* @param breach_count Number of fence breaches.
* @param breach_type Last breach type.
* @param breach_time [ms] Time (since boot) of last breach.
* @param breach_mitigation Active action to prevent fence breach
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_fence_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint8_t breach_status,uint16_t breach_count,uint8_t breach_type,uint32_t breach_time)
uint8_t breach_status,uint16_t breach_count,uint8_t breach_type,uint32_t breach_time,uint8_t breach_mitigation)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_FENCE_STATUS_LEN];
@ -103,6 +110,7 @@ static inline uint16_t mavlink_msg_fence_status_pack_chan(uint8_t system_id, uin
_mav_put_uint16_t(buf, 4, breach_count);
_mav_put_uint8_t(buf, 6, breach_status);
_mav_put_uint8_t(buf, 7, breach_type);
_mav_put_uint8_t(buf, 8, breach_mitigation);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_FENCE_STATUS_LEN);
#else
@ -111,6 +119,7 @@ static inline uint16_t mavlink_msg_fence_status_pack_chan(uint8_t system_id, uin
packet.breach_count = breach_count;
packet.breach_status = breach_status;
packet.breach_type = breach_type;
packet.breach_mitigation = breach_mitigation;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_FENCE_STATUS_LEN);
#endif
@ -129,7 +138,7 @@ static inline uint16_t mavlink_msg_fence_status_pack_chan(uint8_t system_id, uin
*/
static inline uint16_t mavlink_msg_fence_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_fence_status_t* fence_status)
{
return mavlink_msg_fence_status_pack(system_id, component_id, msg, fence_status->breach_status, fence_status->breach_count, fence_status->breach_type, fence_status->breach_time);
return mavlink_msg_fence_status_pack(system_id, component_id, msg, fence_status->breach_status, fence_status->breach_count, fence_status->breach_type, fence_status->breach_time, fence_status->breach_mitigation);
}
/**
@ -143,7 +152,7 @@ static inline uint16_t mavlink_msg_fence_status_encode(uint8_t system_id, uint8_
*/
static inline uint16_t mavlink_msg_fence_status_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_fence_status_t* fence_status)
{
return mavlink_msg_fence_status_pack_chan(system_id, component_id, chan, msg, fence_status->breach_status, fence_status->breach_count, fence_status->breach_type, fence_status->breach_time);
return mavlink_msg_fence_status_pack_chan(system_id, component_id, chan, msg, fence_status->breach_status, fence_status->breach_count, fence_status->breach_type, fence_status->breach_time, fence_status->breach_mitigation);
}
/**
@ -154,10 +163,11 @@ static inline uint16_t mavlink_msg_fence_status_encode_chan(uint8_t system_id, u
* @param breach_count Number of fence breaches.
* @param breach_type Last breach type.
* @param breach_time [ms] Time (since boot) of last breach.
* @param breach_mitigation Active action to prevent fence breach
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_fence_status_send(mavlink_channel_t chan, uint8_t breach_status, uint16_t breach_count, uint8_t breach_type, uint32_t breach_time)
static inline void mavlink_msg_fence_status_send(mavlink_channel_t chan, uint8_t breach_status, uint16_t breach_count, uint8_t breach_type, uint32_t breach_time, uint8_t breach_mitigation)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_FENCE_STATUS_LEN];
@ -165,6 +175,7 @@ static inline void mavlink_msg_fence_status_send(mavlink_channel_t chan, uint8_t
_mav_put_uint16_t(buf, 4, breach_count);
_mav_put_uint8_t(buf, 6, breach_status);
_mav_put_uint8_t(buf, 7, breach_type);
_mav_put_uint8_t(buf, 8, breach_mitigation);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FENCE_STATUS, buf, MAVLINK_MSG_ID_FENCE_STATUS_MIN_LEN, MAVLINK_MSG_ID_FENCE_STATUS_LEN, MAVLINK_MSG_ID_FENCE_STATUS_CRC);
#else
@ -173,6 +184,7 @@ static inline void mavlink_msg_fence_status_send(mavlink_channel_t chan, uint8_t
packet.breach_count = breach_count;
packet.breach_status = breach_status;
packet.breach_type = breach_type;
packet.breach_mitigation = breach_mitigation;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FENCE_STATUS, (const char *)&packet, MAVLINK_MSG_ID_FENCE_STATUS_MIN_LEN, MAVLINK_MSG_ID_FENCE_STATUS_LEN, MAVLINK_MSG_ID_FENCE_STATUS_CRC);
#endif
@ -186,7 +198,7 @@ static inline void mavlink_msg_fence_status_send(mavlink_channel_t chan, uint8_t
static inline void mavlink_msg_fence_status_send_struct(mavlink_channel_t chan, const mavlink_fence_status_t* fence_status)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mavlink_msg_fence_status_send(chan, fence_status->breach_status, fence_status->breach_count, fence_status->breach_type, fence_status->breach_time);
mavlink_msg_fence_status_send(chan, fence_status->breach_status, fence_status->breach_count, fence_status->breach_type, fence_status->breach_time, fence_status->breach_mitigation);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FENCE_STATUS, (const char *)fence_status, MAVLINK_MSG_ID_FENCE_STATUS_MIN_LEN, MAVLINK_MSG_ID_FENCE_STATUS_LEN, MAVLINK_MSG_ID_FENCE_STATUS_CRC);
#endif
@ -200,7 +212,7 @@ static inline void mavlink_msg_fence_status_send_struct(mavlink_channel_t chan,
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_fence_status_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t breach_status, uint16_t breach_count, uint8_t breach_type, uint32_t breach_time)
static inline void mavlink_msg_fence_status_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t breach_status, uint16_t breach_count, uint8_t breach_type, uint32_t breach_time, uint8_t breach_mitigation)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
@ -208,6 +220,7 @@ static inline void mavlink_msg_fence_status_send_buf(mavlink_message_t *msgbuf,
_mav_put_uint16_t(buf, 4, breach_count);
_mav_put_uint8_t(buf, 6, breach_status);
_mav_put_uint8_t(buf, 7, breach_type);
_mav_put_uint8_t(buf, 8, breach_mitigation);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FENCE_STATUS, buf, MAVLINK_MSG_ID_FENCE_STATUS_MIN_LEN, MAVLINK_MSG_ID_FENCE_STATUS_LEN, MAVLINK_MSG_ID_FENCE_STATUS_CRC);
#else
@ -216,6 +229,7 @@ static inline void mavlink_msg_fence_status_send_buf(mavlink_message_t *msgbuf,
packet->breach_count = breach_count;
packet->breach_status = breach_status;
packet->breach_type = breach_type;
packet->breach_mitigation = breach_mitigation;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FENCE_STATUS, (const char *)packet, MAVLINK_MSG_ID_FENCE_STATUS_MIN_LEN, MAVLINK_MSG_ID_FENCE_STATUS_LEN, MAVLINK_MSG_ID_FENCE_STATUS_CRC);
#endif
@ -267,6 +281,16 @@ static inline uint32_t mavlink_msg_fence_status_get_breach_time(const mavlink_me
return _MAV_RETURN_uint32_t(msg, 0);
}
/**
* @brief Get field breach_mitigation from fence_status message
*
* @return Active action to prevent fence breach
*/
static inline uint8_t mavlink_msg_fence_status_get_breach_mitigation(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 8);
}
/**
* @brief Decode a fence_status message into a struct
*
@ -280,6 +304,7 @@ static inline void mavlink_msg_fence_status_decode(const mavlink_message_t* msg,
fence_status->breach_count = mavlink_msg_fence_status_get_breach_count(msg);
fence_status->breach_status = mavlink_msg_fence_status_get_breach_status(msg);
fence_status->breach_type = mavlink_msg_fence_status_get_breach_type(msg);
fence_status->breach_mitigation = mavlink_msg_fence_status_get_breach_mitigation(msg);
#else
uint8_t len = msg->len < MAVLINK_MSG_ID_FENCE_STATUS_LEN? msg->len : MAVLINK_MSG_ID_FENCE_STATUS_LEN;
memset(fence_status, 0, MAVLINK_MSG_ID_FENCE_STATUS_LEN);

View file

@ -0,0 +1,288 @@
#pragma once
// MESSAGE FLIGHT_INFORMATION PACKING
#define MAVLINK_MSG_ID_FLIGHT_INFORMATION 264
typedef struct __mavlink_flight_information_t {
uint64_t arming_time_utc; /*< [us] Timestamp at arming (time since UNIX epoch) in UTC, 0 for unknown*/
uint64_t takeoff_time_utc; /*< [us] Timestamp at takeoff (time since UNIX epoch) in UTC, 0 for unknown*/
uint64_t flight_uuid; /*< Universally unique identifier (UUID) of flight, should correspond to name of log files*/
uint32_t time_boot_ms; /*< [ms] Timestamp (time since system boot).*/
} mavlink_flight_information_t;
#define MAVLINK_MSG_ID_FLIGHT_INFORMATION_LEN 28
#define MAVLINK_MSG_ID_FLIGHT_INFORMATION_MIN_LEN 28
#define MAVLINK_MSG_ID_264_LEN 28
#define MAVLINK_MSG_ID_264_MIN_LEN 28
#define MAVLINK_MSG_ID_FLIGHT_INFORMATION_CRC 49
#define MAVLINK_MSG_ID_264_CRC 49
#if MAVLINK_COMMAND_24BIT
#define MAVLINK_MESSAGE_INFO_FLIGHT_INFORMATION { \
264, \
"FLIGHT_INFORMATION", \
4, \
{ { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 24, offsetof(mavlink_flight_information_t, time_boot_ms) }, \
{ "arming_time_utc", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_flight_information_t, arming_time_utc) }, \
{ "takeoff_time_utc", NULL, MAVLINK_TYPE_UINT64_T, 0, 8, offsetof(mavlink_flight_information_t, takeoff_time_utc) }, \
{ "flight_uuid", NULL, MAVLINK_TYPE_UINT64_T, 0, 16, offsetof(mavlink_flight_information_t, flight_uuid) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_FLIGHT_INFORMATION { \
"FLIGHT_INFORMATION", \
4, \
{ { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 24, offsetof(mavlink_flight_information_t, time_boot_ms) }, \
{ "arming_time_utc", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_flight_information_t, arming_time_utc) }, \
{ "takeoff_time_utc", NULL, MAVLINK_TYPE_UINT64_T, 0, 8, offsetof(mavlink_flight_information_t, takeoff_time_utc) }, \
{ "flight_uuid", NULL, MAVLINK_TYPE_UINT64_T, 0, 16, offsetof(mavlink_flight_information_t, flight_uuid) }, \
} \
}
#endif
/**
* @brief Pack a flight_information message
* @param system_id ID of this 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 [ms] Timestamp (time since system boot).
* @param arming_time_utc [us] Timestamp at arming (time since UNIX epoch) in UTC, 0 for unknown
* @param takeoff_time_utc [us] Timestamp at takeoff (time since UNIX epoch) in UTC, 0 for unknown
* @param flight_uuid Universally unique identifier (UUID) of flight, should correspond to name of log files
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_flight_information_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint32_t time_boot_ms, uint64_t arming_time_utc, uint64_t takeoff_time_utc, uint64_t flight_uuid)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_FLIGHT_INFORMATION_LEN];
_mav_put_uint64_t(buf, 0, arming_time_utc);
_mav_put_uint64_t(buf, 8, takeoff_time_utc);
_mav_put_uint64_t(buf, 16, flight_uuid);
_mav_put_uint32_t(buf, 24, time_boot_ms);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_FLIGHT_INFORMATION_LEN);
#else
mavlink_flight_information_t packet;
packet.arming_time_utc = arming_time_utc;
packet.takeoff_time_utc = takeoff_time_utc;
packet.flight_uuid = flight_uuid;
packet.time_boot_ms = time_boot_ms;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_FLIGHT_INFORMATION_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_FLIGHT_INFORMATION;
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_FLIGHT_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_FLIGHT_INFORMATION_LEN, MAVLINK_MSG_ID_FLIGHT_INFORMATION_CRC);
}
/**
* @brief Pack a flight_information message on a channel
* @param system_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 [ms] Timestamp (time since system boot).
* @param arming_time_utc [us] Timestamp at arming (time since UNIX epoch) in UTC, 0 for unknown
* @param takeoff_time_utc [us] Timestamp at takeoff (time since UNIX epoch) in UTC, 0 for unknown
* @param flight_uuid Universally unique identifier (UUID) of flight, should correspond to name of log files
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_flight_information_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint32_t time_boot_ms,uint64_t arming_time_utc,uint64_t takeoff_time_utc,uint64_t flight_uuid)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_FLIGHT_INFORMATION_LEN];
_mav_put_uint64_t(buf, 0, arming_time_utc);
_mav_put_uint64_t(buf, 8, takeoff_time_utc);
_mav_put_uint64_t(buf, 16, flight_uuid);
_mav_put_uint32_t(buf, 24, time_boot_ms);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_FLIGHT_INFORMATION_LEN);
#else
mavlink_flight_information_t packet;
packet.arming_time_utc = arming_time_utc;
packet.takeoff_time_utc = takeoff_time_utc;
packet.flight_uuid = flight_uuid;
packet.time_boot_ms = time_boot_ms;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_FLIGHT_INFORMATION_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_FLIGHT_INFORMATION;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_FLIGHT_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_FLIGHT_INFORMATION_LEN, MAVLINK_MSG_ID_FLIGHT_INFORMATION_CRC);
}
/**
* @brief Encode a flight_information 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 flight_information C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_flight_information_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_flight_information_t* flight_information)
{
return mavlink_msg_flight_information_pack(system_id, component_id, msg, flight_information->time_boot_ms, flight_information->arming_time_utc, flight_information->takeoff_time_utc, flight_information->flight_uuid);
}
/**
* @brief Encode a flight_information 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 flight_information C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_flight_information_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_flight_information_t* flight_information)
{
return mavlink_msg_flight_information_pack_chan(system_id, component_id, chan, msg, flight_information->time_boot_ms, flight_information->arming_time_utc, flight_information->takeoff_time_utc, flight_information->flight_uuid);
}
/**
* @brief Send a flight_information message
* @param chan MAVLink channel to send the message
*
* @param time_boot_ms [ms] Timestamp (time since system boot).
* @param arming_time_utc [us] Timestamp at arming (time since UNIX epoch) in UTC, 0 for unknown
* @param takeoff_time_utc [us] Timestamp at takeoff (time since UNIX epoch) in UTC, 0 for unknown
* @param flight_uuid Universally unique identifier (UUID) of flight, should correspond to name of log files
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_flight_information_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint64_t arming_time_utc, uint64_t takeoff_time_utc, uint64_t flight_uuid)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_FLIGHT_INFORMATION_LEN];
_mav_put_uint64_t(buf, 0, arming_time_utc);
_mav_put_uint64_t(buf, 8, takeoff_time_utc);
_mav_put_uint64_t(buf, 16, flight_uuid);
_mav_put_uint32_t(buf, 24, time_boot_ms);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLIGHT_INFORMATION, buf, MAVLINK_MSG_ID_FLIGHT_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_FLIGHT_INFORMATION_LEN, MAVLINK_MSG_ID_FLIGHT_INFORMATION_CRC);
#else
mavlink_flight_information_t packet;
packet.arming_time_utc = arming_time_utc;
packet.takeoff_time_utc = takeoff_time_utc;
packet.flight_uuid = flight_uuid;
packet.time_boot_ms = time_boot_ms;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLIGHT_INFORMATION, (const char *)&packet, MAVLINK_MSG_ID_FLIGHT_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_FLIGHT_INFORMATION_LEN, MAVLINK_MSG_ID_FLIGHT_INFORMATION_CRC);
#endif
}
/**
* @brief Send a flight_information message
* @param chan MAVLink channel to send the message
* @param struct The MAVLink struct to serialize
*/
static inline void mavlink_msg_flight_information_send_struct(mavlink_channel_t chan, const mavlink_flight_information_t* flight_information)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mavlink_msg_flight_information_send(chan, flight_information->time_boot_ms, flight_information->arming_time_utc, flight_information->takeoff_time_utc, flight_information->flight_uuid);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLIGHT_INFORMATION, (const char *)flight_information, MAVLINK_MSG_ID_FLIGHT_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_FLIGHT_INFORMATION_LEN, MAVLINK_MSG_ID_FLIGHT_INFORMATION_CRC);
#endif
}
#if MAVLINK_MSG_ID_FLIGHT_INFORMATION_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_flight_information_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, uint64_t arming_time_utc, uint64_t takeoff_time_utc, uint64_t flight_uuid)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
_mav_put_uint64_t(buf, 0, arming_time_utc);
_mav_put_uint64_t(buf, 8, takeoff_time_utc);
_mav_put_uint64_t(buf, 16, flight_uuid);
_mav_put_uint32_t(buf, 24, time_boot_ms);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLIGHT_INFORMATION, buf, MAVLINK_MSG_ID_FLIGHT_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_FLIGHT_INFORMATION_LEN, MAVLINK_MSG_ID_FLIGHT_INFORMATION_CRC);
#else
mavlink_flight_information_t *packet = (mavlink_flight_information_t *)msgbuf;
packet->arming_time_utc = arming_time_utc;
packet->takeoff_time_utc = takeoff_time_utc;
packet->flight_uuid = flight_uuid;
packet->time_boot_ms = time_boot_ms;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_FLIGHT_INFORMATION, (const char *)packet, MAVLINK_MSG_ID_FLIGHT_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_FLIGHT_INFORMATION_LEN, MAVLINK_MSG_ID_FLIGHT_INFORMATION_CRC);
#endif
}
#endif
#endif
// MESSAGE FLIGHT_INFORMATION UNPACKING
/**
* @brief Get field time_boot_ms from flight_information message
*
* @return [ms] Timestamp (time since system boot).
*/
static inline uint32_t mavlink_msg_flight_information_get_time_boot_ms(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint32_t(msg, 24);
}
/**
* @brief Get field arming_time_utc from flight_information message
*
* @return [us] Timestamp at arming (time since UNIX epoch) in UTC, 0 for unknown
*/
static inline uint64_t mavlink_msg_flight_information_get_arming_time_utc(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint64_t(msg, 0);
}
/**
* @brief Get field takeoff_time_utc from flight_information message
*
* @return [us] Timestamp at takeoff (time since UNIX epoch) in UTC, 0 for unknown
*/
static inline uint64_t mavlink_msg_flight_information_get_takeoff_time_utc(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint64_t(msg, 8);
}
/**
* @brief Get field flight_uuid from flight_information message
*
* @return Universally unique identifier (UUID) of flight, should correspond to name of log files
*/
static inline uint64_t mavlink_msg_flight_information_get_flight_uuid(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint64_t(msg, 16);
}
/**
* @brief Decode a flight_information message into a struct
*
* @param msg The message to decode
* @param flight_information C-struct to decode the message contents into
*/
static inline void mavlink_msg_flight_information_decode(const mavlink_message_t* msg, mavlink_flight_information_t* flight_information)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
flight_information->arming_time_utc = mavlink_msg_flight_information_get_arming_time_utc(msg);
flight_information->takeoff_time_utc = mavlink_msg_flight_information_get_takeoff_time_utc(msg);
flight_information->flight_uuid = mavlink_msg_flight_information_get_flight_uuid(msg);
flight_information->time_boot_ms = mavlink_msg_flight_information_get_time_boot_ms(msg);
#else
uint8_t len = msg->len < MAVLINK_MSG_ID_FLIGHT_INFORMATION_LEN? msg->len : MAVLINK_MSG_ID_FLIGHT_INFORMATION_LEN;
memset(flight_information, 0, MAVLINK_MSG_ID_FLIGHT_INFORMATION_LEN);
memcpy(flight_information, _MAV_PAYLOAD(msg), len);
#endif
}

View file

@ -0,0 +1,463 @@
#pragma once
// MESSAGE GENERATOR_STATUS PACKING
#define MAVLINK_MSG_ID_GENERATOR_STATUS 373
typedef struct __mavlink_generator_status_t {
uint64_t status; /*< Status flags.*/
float battery_current; /*< [A] Current into/out of battery. Positive for out. Negative for in. NaN: field not provided.*/
float load_current; /*< [A] Current going to the UAV. If battery current not available this is the DC current from the generator. Positive for out. Negative for in. NaN: field not provided*/
float power_generated; /*< [W] The power being generated. NaN: field not provided*/
float bus_voltage; /*< [V] Voltage of the bus seen at the generator, or battery bus if battery bus is controlled by generator and at a different voltage to main bus.*/
float bat_current_setpoint; /*< [A] The target battery current. Positive for out. Negative for in. NaN: field not provided*/
uint32_t runtime; /*< [s] Seconds this generator has run since it was rebooted. UINT32_MAX: field not provided.*/
int32_t time_until_maintenance; /*< [s] Seconds until this generator requires maintenance. A negative value indicates maintenance is past-due. INT32_MAX: field not provided.*/
uint16_t generator_speed; /*< [rpm] Speed of electrical generator or alternator. UINT16_MAX: field not provided.*/
int16_t rectifier_temperature; /*< [degC] The temperature of the rectifier or power converter. INT16_MAX: field not provided.*/
int16_t generator_temperature; /*< [degC] The temperature of the mechanical motor, fuel cell core or generator. INT16_MAX: field not provided.*/
} mavlink_generator_status_t;
#define MAVLINK_MSG_ID_GENERATOR_STATUS_LEN 42
#define MAVLINK_MSG_ID_GENERATOR_STATUS_MIN_LEN 42
#define MAVLINK_MSG_ID_373_LEN 42
#define MAVLINK_MSG_ID_373_MIN_LEN 42
#define MAVLINK_MSG_ID_GENERATOR_STATUS_CRC 117
#define MAVLINK_MSG_ID_373_CRC 117
#if MAVLINK_COMMAND_24BIT
#define MAVLINK_MESSAGE_INFO_GENERATOR_STATUS { \
373, \
"GENERATOR_STATUS", \
11, \
{ { "status", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_generator_status_t, status) }, \
{ "generator_speed", NULL, MAVLINK_TYPE_UINT16_T, 0, 36, offsetof(mavlink_generator_status_t, generator_speed) }, \
{ "battery_current", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_generator_status_t, battery_current) }, \
{ "load_current", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_generator_status_t, load_current) }, \
{ "power_generated", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_generator_status_t, power_generated) }, \
{ "bus_voltage", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_generator_status_t, bus_voltage) }, \
{ "rectifier_temperature", NULL, MAVLINK_TYPE_INT16_T, 0, 38, offsetof(mavlink_generator_status_t, rectifier_temperature) }, \
{ "bat_current_setpoint", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_generator_status_t, bat_current_setpoint) }, \
{ "generator_temperature", NULL, MAVLINK_TYPE_INT16_T, 0, 40, offsetof(mavlink_generator_status_t, generator_temperature) }, \
{ "runtime", NULL, MAVLINK_TYPE_UINT32_T, 0, 28, offsetof(mavlink_generator_status_t, runtime) }, \
{ "time_until_maintenance", NULL, MAVLINK_TYPE_INT32_T, 0, 32, offsetof(mavlink_generator_status_t, time_until_maintenance) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_GENERATOR_STATUS { \
"GENERATOR_STATUS", \
11, \
{ { "status", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_generator_status_t, status) }, \
{ "generator_speed", NULL, MAVLINK_TYPE_UINT16_T, 0, 36, offsetof(mavlink_generator_status_t, generator_speed) }, \
{ "battery_current", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_generator_status_t, battery_current) }, \
{ "load_current", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_generator_status_t, load_current) }, \
{ "power_generated", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_generator_status_t, power_generated) }, \
{ "bus_voltage", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_generator_status_t, bus_voltage) }, \
{ "rectifier_temperature", NULL, MAVLINK_TYPE_INT16_T, 0, 38, offsetof(mavlink_generator_status_t, rectifier_temperature) }, \
{ "bat_current_setpoint", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_generator_status_t, bat_current_setpoint) }, \
{ "generator_temperature", NULL, MAVLINK_TYPE_INT16_T, 0, 40, offsetof(mavlink_generator_status_t, generator_temperature) }, \
{ "runtime", NULL, MAVLINK_TYPE_UINT32_T, 0, 28, offsetof(mavlink_generator_status_t, runtime) }, \
{ "time_until_maintenance", NULL, MAVLINK_TYPE_INT32_T, 0, 32, offsetof(mavlink_generator_status_t, time_until_maintenance) }, \
} \
}
#endif
/**
* @brief Pack a generator_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 status Status flags.
* @param generator_speed [rpm] Speed of electrical generator or alternator. UINT16_MAX: field not provided.
* @param battery_current [A] Current into/out of battery. Positive for out. Negative for in. NaN: field not provided.
* @param load_current [A] Current going to the UAV. If battery current not available this is the DC current from the generator. Positive for out. Negative for in. NaN: field not provided
* @param power_generated [W] The power being generated. NaN: field not provided
* @param bus_voltage [V] Voltage of the bus seen at the generator, or battery bus if battery bus is controlled by generator and at a different voltage to main bus.
* @param rectifier_temperature [degC] The temperature of the rectifier or power converter. INT16_MAX: field not provided.
* @param bat_current_setpoint [A] The target battery current. Positive for out. Negative for in. NaN: field not provided
* @param generator_temperature [degC] The temperature of the mechanical motor, fuel cell core or generator. INT16_MAX: field not provided.
* @param runtime [s] Seconds this generator has run since it was rebooted. UINT32_MAX: field not provided.
* @param time_until_maintenance [s] Seconds until this generator requires maintenance. A negative value indicates maintenance is past-due. INT32_MAX: field not provided.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_generator_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint64_t status, uint16_t generator_speed, float battery_current, float load_current, float power_generated, float bus_voltage, int16_t rectifier_temperature, float bat_current_setpoint, int16_t generator_temperature, uint32_t runtime, int32_t time_until_maintenance)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_GENERATOR_STATUS_LEN];
_mav_put_uint64_t(buf, 0, status);
_mav_put_float(buf, 8, battery_current);
_mav_put_float(buf, 12, load_current);
_mav_put_float(buf, 16, power_generated);
_mav_put_float(buf, 20, bus_voltage);
_mav_put_float(buf, 24, bat_current_setpoint);
_mav_put_uint32_t(buf, 28, runtime);
_mav_put_int32_t(buf, 32, time_until_maintenance);
_mav_put_uint16_t(buf, 36, generator_speed);
_mav_put_int16_t(buf, 38, rectifier_temperature);
_mav_put_int16_t(buf, 40, generator_temperature);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GENERATOR_STATUS_LEN);
#else
mavlink_generator_status_t packet;
packet.status = status;
packet.battery_current = battery_current;
packet.load_current = load_current;
packet.power_generated = power_generated;
packet.bus_voltage = bus_voltage;
packet.bat_current_setpoint = bat_current_setpoint;
packet.runtime = runtime;
packet.time_until_maintenance = time_until_maintenance;
packet.generator_speed = generator_speed;
packet.rectifier_temperature = rectifier_temperature;
packet.generator_temperature = generator_temperature;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GENERATOR_STATUS_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_GENERATOR_STATUS;
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GENERATOR_STATUS_MIN_LEN, MAVLINK_MSG_ID_GENERATOR_STATUS_LEN, MAVLINK_MSG_ID_GENERATOR_STATUS_CRC);
}
/**
* @brief Pack a generator_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 status Status flags.
* @param generator_speed [rpm] Speed of electrical generator or alternator. UINT16_MAX: field not provided.
* @param battery_current [A] Current into/out of battery. Positive for out. Negative for in. NaN: field not provided.
* @param load_current [A] Current going to the UAV. If battery current not available this is the DC current from the generator. Positive for out. Negative for in. NaN: field not provided
* @param power_generated [W] The power being generated. NaN: field not provided
* @param bus_voltage [V] Voltage of the bus seen at the generator, or battery bus if battery bus is controlled by generator and at a different voltage to main bus.
* @param rectifier_temperature [degC] The temperature of the rectifier or power converter. INT16_MAX: field not provided.
* @param bat_current_setpoint [A] The target battery current. Positive for out. Negative for in. NaN: field not provided
* @param generator_temperature [degC] The temperature of the mechanical motor, fuel cell core or generator. INT16_MAX: field not provided.
* @param runtime [s] Seconds this generator has run since it was rebooted. UINT32_MAX: field not provided.
* @param time_until_maintenance [s] Seconds until this generator requires maintenance. A negative value indicates maintenance is past-due. INT32_MAX: field not provided.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_generator_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint64_t status,uint16_t generator_speed,float battery_current,float load_current,float power_generated,float bus_voltage,int16_t rectifier_temperature,float bat_current_setpoint,int16_t generator_temperature,uint32_t runtime,int32_t time_until_maintenance)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_GENERATOR_STATUS_LEN];
_mav_put_uint64_t(buf, 0, status);
_mav_put_float(buf, 8, battery_current);
_mav_put_float(buf, 12, load_current);
_mav_put_float(buf, 16, power_generated);
_mav_put_float(buf, 20, bus_voltage);
_mav_put_float(buf, 24, bat_current_setpoint);
_mav_put_uint32_t(buf, 28, runtime);
_mav_put_int32_t(buf, 32, time_until_maintenance);
_mav_put_uint16_t(buf, 36, generator_speed);
_mav_put_int16_t(buf, 38, rectifier_temperature);
_mav_put_int16_t(buf, 40, generator_temperature);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GENERATOR_STATUS_LEN);
#else
mavlink_generator_status_t packet;
packet.status = status;
packet.battery_current = battery_current;
packet.load_current = load_current;
packet.power_generated = power_generated;
packet.bus_voltage = bus_voltage;
packet.bat_current_setpoint = bat_current_setpoint;
packet.runtime = runtime;
packet.time_until_maintenance = time_until_maintenance;
packet.generator_speed = generator_speed;
packet.rectifier_temperature = rectifier_temperature;
packet.generator_temperature = generator_temperature;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GENERATOR_STATUS_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_GENERATOR_STATUS;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GENERATOR_STATUS_MIN_LEN, MAVLINK_MSG_ID_GENERATOR_STATUS_LEN, MAVLINK_MSG_ID_GENERATOR_STATUS_CRC);
}
/**
* @brief Encode a generator_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 generator_status C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_generator_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_generator_status_t* generator_status)
{
return mavlink_msg_generator_status_pack(system_id, component_id, msg, generator_status->status, generator_status->generator_speed, generator_status->battery_current, generator_status->load_current, generator_status->power_generated, generator_status->bus_voltage, generator_status->rectifier_temperature, generator_status->bat_current_setpoint, generator_status->generator_temperature, generator_status->runtime, generator_status->time_until_maintenance);
}
/**
* @brief Encode a generator_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 generator_status C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_generator_status_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_generator_status_t* generator_status)
{
return mavlink_msg_generator_status_pack_chan(system_id, component_id, chan, msg, generator_status->status, generator_status->generator_speed, generator_status->battery_current, generator_status->load_current, generator_status->power_generated, generator_status->bus_voltage, generator_status->rectifier_temperature, generator_status->bat_current_setpoint, generator_status->generator_temperature, generator_status->runtime, generator_status->time_until_maintenance);
}
/**
* @brief Send a generator_status message
* @param chan MAVLink channel to send the message
*
* @param status Status flags.
* @param generator_speed [rpm] Speed of electrical generator or alternator. UINT16_MAX: field not provided.
* @param battery_current [A] Current into/out of battery. Positive for out. Negative for in. NaN: field not provided.
* @param load_current [A] Current going to the UAV. If battery current not available this is the DC current from the generator. Positive for out. Negative for in. NaN: field not provided
* @param power_generated [W] The power being generated. NaN: field not provided
* @param bus_voltage [V] Voltage of the bus seen at the generator, or battery bus if battery bus is controlled by generator and at a different voltage to main bus.
* @param rectifier_temperature [degC] The temperature of the rectifier or power converter. INT16_MAX: field not provided.
* @param bat_current_setpoint [A] The target battery current. Positive for out. Negative for in. NaN: field not provided
* @param generator_temperature [degC] The temperature of the mechanical motor, fuel cell core or generator. INT16_MAX: field not provided.
* @param runtime [s] Seconds this generator has run since it was rebooted. UINT32_MAX: field not provided.
* @param time_until_maintenance [s] Seconds until this generator requires maintenance. A negative value indicates maintenance is past-due. INT32_MAX: field not provided.
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_generator_status_send(mavlink_channel_t chan, uint64_t status, uint16_t generator_speed, float battery_current, float load_current, float power_generated, float bus_voltage, int16_t rectifier_temperature, float bat_current_setpoint, int16_t generator_temperature, uint32_t runtime, int32_t time_until_maintenance)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_GENERATOR_STATUS_LEN];
_mav_put_uint64_t(buf, 0, status);
_mav_put_float(buf, 8, battery_current);
_mav_put_float(buf, 12, load_current);
_mav_put_float(buf, 16, power_generated);
_mav_put_float(buf, 20, bus_voltage);
_mav_put_float(buf, 24, bat_current_setpoint);
_mav_put_uint32_t(buf, 28, runtime);
_mav_put_int32_t(buf, 32, time_until_maintenance);
_mav_put_uint16_t(buf, 36, generator_speed);
_mav_put_int16_t(buf, 38, rectifier_temperature);
_mav_put_int16_t(buf, 40, generator_temperature);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GENERATOR_STATUS, buf, MAVLINK_MSG_ID_GENERATOR_STATUS_MIN_LEN, MAVLINK_MSG_ID_GENERATOR_STATUS_LEN, MAVLINK_MSG_ID_GENERATOR_STATUS_CRC);
#else
mavlink_generator_status_t packet;
packet.status = status;
packet.battery_current = battery_current;
packet.load_current = load_current;
packet.power_generated = power_generated;
packet.bus_voltage = bus_voltage;
packet.bat_current_setpoint = bat_current_setpoint;
packet.runtime = runtime;
packet.time_until_maintenance = time_until_maintenance;
packet.generator_speed = generator_speed;
packet.rectifier_temperature = rectifier_temperature;
packet.generator_temperature = generator_temperature;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GENERATOR_STATUS, (const char *)&packet, MAVLINK_MSG_ID_GENERATOR_STATUS_MIN_LEN, MAVLINK_MSG_ID_GENERATOR_STATUS_LEN, MAVLINK_MSG_ID_GENERATOR_STATUS_CRC);
#endif
}
/**
* @brief Send a generator_status message
* @param chan MAVLink channel to send the message
* @param struct The MAVLink struct to serialize
*/
static inline void mavlink_msg_generator_status_send_struct(mavlink_channel_t chan, const mavlink_generator_status_t* generator_status)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mavlink_msg_generator_status_send(chan, generator_status->status, generator_status->generator_speed, generator_status->battery_current, generator_status->load_current, generator_status->power_generated, generator_status->bus_voltage, generator_status->rectifier_temperature, generator_status->bat_current_setpoint, generator_status->generator_temperature, generator_status->runtime, generator_status->time_until_maintenance);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GENERATOR_STATUS, (const char *)generator_status, MAVLINK_MSG_ID_GENERATOR_STATUS_MIN_LEN, MAVLINK_MSG_ID_GENERATOR_STATUS_LEN, MAVLINK_MSG_ID_GENERATOR_STATUS_CRC);
#endif
}
#if MAVLINK_MSG_ID_GENERATOR_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_generator_status_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t status, uint16_t generator_speed, float battery_current, float load_current, float power_generated, float bus_voltage, int16_t rectifier_temperature, float bat_current_setpoint, int16_t generator_temperature, uint32_t runtime, int32_t time_until_maintenance)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
_mav_put_uint64_t(buf, 0, status);
_mav_put_float(buf, 8, battery_current);
_mav_put_float(buf, 12, load_current);
_mav_put_float(buf, 16, power_generated);
_mav_put_float(buf, 20, bus_voltage);
_mav_put_float(buf, 24, bat_current_setpoint);
_mav_put_uint32_t(buf, 28, runtime);
_mav_put_int32_t(buf, 32, time_until_maintenance);
_mav_put_uint16_t(buf, 36, generator_speed);
_mav_put_int16_t(buf, 38, rectifier_temperature);
_mav_put_int16_t(buf, 40, generator_temperature);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GENERATOR_STATUS, buf, MAVLINK_MSG_ID_GENERATOR_STATUS_MIN_LEN, MAVLINK_MSG_ID_GENERATOR_STATUS_LEN, MAVLINK_MSG_ID_GENERATOR_STATUS_CRC);
#else
mavlink_generator_status_t *packet = (mavlink_generator_status_t *)msgbuf;
packet->status = status;
packet->battery_current = battery_current;
packet->load_current = load_current;
packet->power_generated = power_generated;
packet->bus_voltage = bus_voltage;
packet->bat_current_setpoint = bat_current_setpoint;
packet->runtime = runtime;
packet->time_until_maintenance = time_until_maintenance;
packet->generator_speed = generator_speed;
packet->rectifier_temperature = rectifier_temperature;
packet->generator_temperature = generator_temperature;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GENERATOR_STATUS, (const char *)packet, MAVLINK_MSG_ID_GENERATOR_STATUS_MIN_LEN, MAVLINK_MSG_ID_GENERATOR_STATUS_LEN, MAVLINK_MSG_ID_GENERATOR_STATUS_CRC);
#endif
}
#endif
#endif
// MESSAGE GENERATOR_STATUS UNPACKING
/**
* @brief Get field status from generator_status message
*
* @return Status flags.
*/
static inline uint64_t mavlink_msg_generator_status_get_status(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint64_t(msg, 0);
}
/**
* @brief Get field generator_speed from generator_status message
*
* @return [rpm] Speed of electrical generator or alternator. UINT16_MAX: field not provided.
*/
static inline uint16_t mavlink_msg_generator_status_get_generator_speed(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 36);
}
/**
* @brief Get field battery_current from generator_status message
*
* @return [A] Current into/out of battery. Positive for out. Negative for in. NaN: field not provided.
*/
static inline float mavlink_msg_generator_status_get_battery_current(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 8);
}
/**
* @brief Get field load_current from generator_status message
*
* @return [A] Current going to the UAV. If battery current not available this is the DC current from the generator. Positive for out. Negative for in. NaN: field not provided
*/
static inline float mavlink_msg_generator_status_get_load_current(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 12);
}
/**
* @brief Get field power_generated from generator_status message
*
* @return [W] The power being generated. NaN: field not provided
*/
static inline float mavlink_msg_generator_status_get_power_generated(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 16);
}
/**
* @brief Get field bus_voltage from generator_status message
*
* @return [V] Voltage of the bus seen at the generator, or battery bus if battery bus is controlled by generator and at a different voltage to main bus.
*/
static inline float mavlink_msg_generator_status_get_bus_voltage(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 20);
}
/**
* @brief Get field rectifier_temperature from generator_status message
*
* @return [degC] The temperature of the rectifier or power converter. INT16_MAX: field not provided.
*/
static inline int16_t mavlink_msg_generator_status_get_rectifier_temperature(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 38);
}
/**
* @brief Get field bat_current_setpoint from generator_status message
*
* @return [A] The target battery current. Positive for out. Negative for in. NaN: field not provided
*/
static inline float mavlink_msg_generator_status_get_bat_current_setpoint(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 24);
}
/**
* @brief Get field generator_temperature from generator_status message
*
* @return [degC] The temperature of the mechanical motor, fuel cell core or generator. INT16_MAX: field not provided.
*/
static inline int16_t mavlink_msg_generator_status_get_generator_temperature(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 40);
}
/**
* @brief Get field runtime from generator_status message
*
* @return [s] Seconds this generator has run since it was rebooted. UINT32_MAX: field not provided.
*/
static inline uint32_t mavlink_msg_generator_status_get_runtime(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint32_t(msg, 28);
}
/**
* @brief Get field time_until_maintenance from generator_status message
*
* @return [s] Seconds until this generator requires maintenance. A negative value indicates maintenance is past-due. INT32_MAX: field not provided.
*/
static inline int32_t mavlink_msg_generator_status_get_time_until_maintenance(const mavlink_message_t* msg)
{
return _MAV_RETURN_int32_t(msg, 32);
}
/**
* @brief Decode a generator_status message into a struct
*
* @param msg The message to decode
* @param generator_status C-struct to decode the message contents into
*/
static inline void mavlink_msg_generator_status_decode(const mavlink_message_t* msg, mavlink_generator_status_t* generator_status)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
generator_status->status = mavlink_msg_generator_status_get_status(msg);
generator_status->battery_current = mavlink_msg_generator_status_get_battery_current(msg);
generator_status->load_current = mavlink_msg_generator_status_get_load_current(msg);
generator_status->power_generated = mavlink_msg_generator_status_get_power_generated(msg);
generator_status->bus_voltage = mavlink_msg_generator_status_get_bus_voltage(msg);
generator_status->bat_current_setpoint = mavlink_msg_generator_status_get_bat_current_setpoint(msg);
generator_status->runtime = mavlink_msg_generator_status_get_runtime(msg);
generator_status->time_until_maintenance = mavlink_msg_generator_status_get_time_until_maintenance(msg);
generator_status->generator_speed = mavlink_msg_generator_status_get_generator_speed(msg);
generator_status->rectifier_temperature = mavlink_msg_generator_status_get_rectifier_temperature(msg);
generator_status->generator_temperature = mavlink_msg_generator_status_get_generator_temperature(msg);
#else
uint8_t len = msg->len < MAVLINK_MSG_ID_GENERATOR_STATUS_LEN? msg->len : MAVLINK_MSG_ID_GENERATOR_STATUS_LEN;
memset(generator_status, 0, MAVLINK_MSG_ID_GENERATOR_STATUS_LEN);
memcpy(generator_status, _MAV_PAYLOAD(msg), len);
#endif
}

View file

@ -0,0 +1,405 @@
#pragma once
// MESSAGE GIMBAL_DEVICE_ATTITUDE_STATUS PACKING
#define MAVLINK_MSG_ID_GIMBAL_DEVICE_ATTITUDE_STATUS 285
typedef struct __mavlink_gimbal_device_attitude_status_t {
uint32_t time_boot_ms; /*< [ms] Timestamp (time since system boot).*/
float q[4]; /*< Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation, the frame is depends on whether the flag GIMBAL_DEVICE_FLAGS_YAW_LOCK is set)*/
float angular_velocity_x; /*< [rad/s] X component of angular velocity (NaN if unknown)*/
float angular_velocity_y; /*< [rad/s] Y component of angular velocity (NaN if unknown)*/
float angular_velocity_z; /*< [rad/s] Z component of angular velocity (NaN if unknown)*/
uint32_t failure_flags; /*< Failure flags (0 for no failure)*/
uint16_t flags; /*< Current gimbal flags set.*/
uint8_t target_system; /*< System ID*/
uint8_t target_component; /*< Component ID*/
} mavlink_gimbal_device_attitude_status_t;
#define MAVLINK_MSG_ID_GIMBAL_DEVICE_ATTITUDE_STATUS_LEN 40
#define MAVLINK_MSG_ID_GIMBAL_DEVICE_ATTITUDE_STATUS_MIN_LEN 40
#define MAVLINK_MSG_ID_285_LEN 40
#define MAVLINK_MSG_ID_285_MIN_LEN 40
#define MAVLINK_MSG_ID_GIMBAL_DEVICE_ATTITUDE_STATUS_CRC 137
#define MAVLINK_MSG_ID_285_CRC 137
#define MAVLINK_MSG_GIMBAL_DEVICE_ATTITUDE_STATUS_FIELD_Q_LEN 4
#if MAVLINK_COMMAND_24BIT
#define MAVLINK_MESSAGE_INFO_GIMBAL_DEVICE_ATTITUDE_STATUS { \
285, \
"GIMBAL_DEVICE_ATTITUDE_STATUS", \
9, \
{ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 38, offsetof(mavlink_gimbal_device_attitude_status_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 39, offsetof(mavlink_gimbal_device_attitude_status_t, target_component) }, \
{ "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_gimbal_device_attitude_status_t, time_boot_ms) }, \
{ "flags", NULL, MAVLINK_TYPE_UINT16_T, 0, 36, offsetof(mavlink_gimbal_device_attitude_status_t, flags) }, \
{ "q", NULL, MAVLINK_TYPE_FLOAT, 4, 4, offsetof(mavlink_gimbal_device_attitude_status_t, q) }, \
{ "angular_velocity_x", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_gimbal_device_attitude_status_t, angular_velocity_x) }, \
{ "angular_velocity_y", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_gimbal_device_attitude_status_t, angular_velocity_y) }, \
{ "angular_velocity_z", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_gimbal_device_attitude_status_t, angular_velocity_z) }, \
{ "failure_flags", NULL, MAVLINK_TYPE_UINT32_T, 0, 32, offsetof(mavlink_gimbal_device_attitude_status_t, failure_flags) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_GIMBAL_DEVICE_ATTITUDE_STATUS { \
"GIMBAL_DEVICE_ATTITUDE_STATUS", \
9, \
{ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 38, offsetof(mavlink_gimbal_device_attitude_status_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 39, offsetof(mavlink_gimbal_device_attitude_status_t, target_component) }, \
{ "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_gimbal_device_attitude_status_t, time_boot_ms) }, \
{ "flags", NULL, MAVLINK_TYPE_UINT16_T, 0, 36, offsetof(mavlink_gimbal_device_attitude_status_t, flags) }, \
{ "q", NULL, MAVLINK_TYPE_FLOAT, 4, 4, offsetof(mavlink_gimbal_device_attitude_status_t, q) }, \
{ "angular_velocity_x", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_gimbal_device_attitude_status_t, angular_velocity_x) }, \
{ "angular_velocity_y", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_gimbal_device_attitude_status_t, angular_velocity_y) }, \
{ "angular_velocity_z", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_gimbal_device_attitude_status_t, angular_velocity_z) }, \
{ "failure_flags", NULL, MAVLINK_TYPE_UINT32_T, 0, 32, offsetof(mavlink_gimbal_device_attitude_status_t, failure_flags) }, \
} \
}
#endif
/**
* @brief Pack a gimbal_device_attitude_status message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param target_system System ID
* @param target_component Component ID
* @param time_boot_ms [ms] Timestamp (time since system boot).
* @param flags Current gimbal flags set.
* @param q Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation, the frame is depends on whether the flag GIMBAL_DEVICE_FLAGS_YAW_LOCK is set)
* @param angular_velocity_x [rad/s] X component of angular velocity (NaN if unknown)
* @param angular_velocity_y [rad/s] Y component of angular velocity (NaN if unknown)
* @param angular_velocity_z [rad/s] Z component of angular velocity (NaN if unknown)
* @param failure_flags Failure flags (0 for no failure)
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_gimbal_device_attitude_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t target_system, uint8_t target_component, uint32_t time_boot_ms, uint16_t flags, const float *q, float angular_velocity_x, float angular_velocity_y, float angular_velocity_z, uint32_t failure_flags)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_GIMBAL_DEVICE_ATTITUDE_STATUS_LEN];
_mav_put_uint32_t(buf, 0, time_boot_ms);
_mav_put_float(buf, 20, angular_velocity_x);
_mav_put_float(buf, 24, angular_velocity_y);
_mav_put_float(buf, 28, angular_velocity_z);
_mav_put_uint32_t(buf, 32, failure_flags);
_mav_put_uint16_t(buf, 36, flags);
_mav_put_uint8_t(buf, 38, target_system);
_mav_put_uint8_t(buf, 39, target_component);
_mav_put_float_array(buf, 4, q, 4);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GIMBAL_DEVICE_ATTITUDE_STATUS_LEN);
#else
mavlink_gimbal_device_attitude_status_t packet;
packet.time_boot_ms = time_boot_ms;
packet.angular_velocity_x = angular_velocity_x;
packet.angular_velocity_y = angular_velocity_y;
packet.angular_velocity_z = angular_velocity_z;
packet.failure_flags = failure_flags;
packet.flags = flags;
packet.target_system = target_system;
packet.target_component = target_component;
mav_array_memcpy(packet.q, q, sizeof(float)*4);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GIMBAL_DEVICE_ATTITUDE_STATUS_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_GIMBAL_DEVICE_ATTITUDE_STATUS;
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GIMBAL_DEVICE_ATTITUDE_STATUS_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_DEVICE_ATTITUDE_STATUS_LEN, MAVLINK_MSG_ID_GIMBAL_DEVICE_ATTITUDE_STATUS_CRC);
}
/**
* @brief Pack a gimbal_device_attitude_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 target_system System ID
* @param target_component Component ID
* @param time_boot_ms [ms] Timestamp (time since system boot).
* @param flags Current gimbal flags set.
* @param q Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation, the frame is depends on whether the flag GIMBAL_DEVICE_FLAGS_YAW_LOCK is set)
* @param angular_velocity_x [rad/s] X component of angular velocity (NaN if unknown)
* @param angular_velocity_y [rad/s] Y component of angular velocity (NaN if unknown)
* @param angular_velocity_z [rad/s] Z component of angular velocity (NaN if unknown)
* @param failure_flags Failure flags (0 for no failure)
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_gimbal_device_attitude_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint8_t target_system,uint8_t target_component,uint32_t time_boot_ms,uint16_t flags,const float *q,float angular_velocity_x,float angular_velocity_y,float angular_velocity_z,uint32_t failure_flags)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_GIMBAL_DEVICE_ATTITUDE_STATUS_LEN];
_mav_put_uint32_t(buf, 0, time_boot_ms);
_mav_put_float(buf, 20, angular_velocity_x);
_mav_put_float(buf, 24, angular_velocity_y);
_mav_put_float(buf, 28, angular_velocity_z);
_mav_put_uint32_t(buf, 32, failure_flags);
_mav_put_uint16_t(buf, 36, flags);
_mav_put_uint8_t(buf, 38, target_system);
_mav_put_uint8_t(buf, 39, target_component);
_mav_put_float_array(buf, 4, q, 4);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GIMBAL_DEVICE_ATTITUDE_STATUS_LEN);
#else
mavlink_gimbal_device_attitude_status_t packet;
packet.time_boot_ms = time_boot_ms;
packet.angular_velocity_x = angular_velocity_x;
packet.angular_velocity_y = angular_velocity_y;
packet.angular_velocity_z = angular_velocity_z;
packet.failure_flags = failure_flags;
packet.flags = flags;
packet.target_system = target_system;
packet.target_component = target_component;
mav_array_memcpy(packet.q, q, sizeof(float)*4);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GIMBAL_DEVICE_ATTITUDE_STATUS_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_GIMBAL_DEVICE_ATTITUDE_STATUS;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GIMBAL_DEVICE_ATTITUDE_STATUS_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_DEVICE_ATTITUDE_STATUS_LEN, MAVLINK_MSG_ID_GIMBAL_DEVICE_ATTITUDE_STATUS_CRC);
}
/**
* @brief Encode a gimbal_device_attitude_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 gimbal_device_attitude_status C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_gimbal_device_attitude_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gimbal_device_attitude_status_t* gimbal_device_attitude_status)
{
return mavlink_msg_gimbal_device_attitude_status_pack(system_id, component_id, msg, gimbal_device_attitude_status->target_system, gimbal_device_attitude_status->target_component, gimbal_device_attitude_status->time_boot_ms, gimbal_device_attitude_status->flags, gimbal_device_attitude_status->q, gimbal_device_attitude_status->angular_velocity_x, gimbal_device_attitude_status->angular_velocity_y, gimbal_device_attitude_status->angular_velocity_z, gimbal_device_attitude_status->failure_flags);
}
/**
* @brief Encode a gimbal_device_attitude_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 gimbal_device_attitude_status C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_gimbal_device_attitude_status_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_gimbal_device_attitude_status_t* gimbal_device_attitude_status)
{
return mavlink_msg_gimbal_device_attitude_status_pack_chan(system_id, component_id, chan, msg, gimbal_device_attitude_status->target_system, gimbal_device_attitude_status->target_component, gimbal_device_attitude_status->time_boot_ms, gimbal_device_attitude_status->flags, gimbal_device_attitude_status->q, gimbal_device_attitude_status->angular_velocity_x, gimbal_device_attitude_status->angular_velocity_y, gimbal_device_attitude_status->angular_velocity_z, gimbal_device_attitude_status->failure_flags);
}
/**
* @brief Send a gimbal_device_attitude_status message
* @param chan MAVLink channel to send the message
*
* @param target_system System ID
* @param target_component Component ID
* @param time_boot_ms [ms] Timestamp (time since system boot).
* @param flags Current gimbal flags set.
* @param q Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation, the frame is depends on whether the flag GIMBAL_DEVICE_FLAGS_YAW_LOCK is set)
* @param angular_velocity_x [rad/s] X component of angular velocity (NaN if unknown)
* @param angular_velocity_y [rad/s] Y component of angular velocity (NaN if unknown)
* @param angular_velocity_z [rad/s] Z component of angular velocity (NaN if unknown)
* @param failure_flags Failure flags (0 for no failure)
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_gimbal_device_attitude_status_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint32_t time_boot_ms, uint16_t flags, const float *q, float angular_velocity_x, float angular_velocity_y, float angular_velocity_z, uint32_t failure_flags)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_GIMBAL_DEVICE_ATTITUDE_STATUS_LEN];
_mav_put_uint32_t(buf, 0, time_boot_ms);
_mav_put_float(buf, 20, angular_velocity_x);
_mav_put_float(buf, 24, angular_velocity_y);
_mav_put_float(buf, 28, angular_velocity_z);
_mav_put_uint32_t(buf, 32, failure_flags);
_mav_put_uint16_t(buf, 36, flags);
_mav_put_uint8_t(buf, 38, target_system);
_mav_put_uint8_t(buf, 39, target_component);
_mav_put_float_array(buf, 4, q, 4);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GIMBAL_DEVICE_ATTITUDE_STATUS, buf, MAVLINK_MSG_ID_GIMBAL_DEVICE_ATTITUDE_STATUS_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_DEVICE_ATTITUDE_STATUS_LEN, MAVLINK_MSG_ID_GIMBAL_DEVICE_ATTITUDE_STATUS_CRC);
#else
mavlink_gimbal_device_attitude_status_t packet;
packet.time_boot_ms = time_boot_ms;
packet.angular_velocity_x = angular_velocity_x;
packet.angular_velocity_y = angular_velocity_y;
packet.angular_velocity_z = angular_velocity_z;
packet.failure_flags = failure_flags;
packet.flags = flags;
packet.target_system = target_system;
packet.target_component = target_component;
mav_array_memcpy(packet.q, q, sizeof(float)*4);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GIMBAL_DEVICE_ATTITUDE_STATUS, (const char *)&packet, MAVLINK_MSG_ID_GIMBAL_DEVICE_ATTITUDE_STATUS_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_DEVICE_ATTITUDE_STATUS_LEN, MAVLINK_MSG_ID_GIMBAL_DEVICE_ATTITUDE_STATUS_CRC);
#endif
}
/**
* @brief Send a gimbal_device_attitude_status message
* @param chan MAVLink channel to send the message
* @param struct The MAVLink struct to serialize
*/
static inline void mavlink_msg_gimbal_device_attitude_status_send_struct(mavlink_channel_t chan, const mavlink_gimbal_device_attitude_status_t* gimbal_device_attitude_status)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mavlink_msg_gimbal_device_attitude_status_send(chan, gimbal_device_attitude_status->target_system, gimbal_device_attitude_status->target_component, gimbal_device_attitude_status->time_boot_ms, gimbal_device_attitude_status->flags, gimbal_device_attitude_status->q, gimbal_device_attitude_status->angular_velocity_x, gimbal_device_attitude_status->angular_velocity_y, gimbal_device_attitude_status->angular_velocity_z, gimbal_device_attitude_status->failure_flags);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GIMBAL_DEVICE_ATTITUDE_STATUS, (const char *)gimbal_device_attitude_status, MAVLINK_MSG_ID_GIMBAL_DEVICE_ATTITUDE_STATUS_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_DEVICE_ATTITUDE_STATUS_LEN, MAVLINK_MSG_ID_GIMBAL_DEVICE_ATTITUDE_STATUS_CRC);
#endif
}
#if MAVLINK_MSG_ID_GIMBAL_DEVICE_ATTITUDE_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_gimbal_device_attitude_status_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint32_t time_boot_ms, uint16_t flags, const float *q, float angular_velocity_x, float angular_velocity_y, float angular_velocity_z, uint32_t failure_flags)
{
#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, angular_velocity_x);
_mav_put_float(buf, 24, angular_velocity_y);
_mav_put_float(buf, 28, angular_velocity_z);
_mav_put_uint32_t(buf, 32, failure_flags);
_mav_put_uint16_t(buf, 36, flags);
_mav_put_uint8_t(buf, 38, target_system);
_mav_put_uint8_t(buf, 39, target_component);
_mav_put_float_array(buf, 4, q, 4);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GIMBAL_DEVICE_ATTITUDE_STATUS, buf, MAVLINK_MSG_ID_GIMBAL_DEVICE_ATTITUDE_STATUS_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_DEVICE_ATTITUDE_STATUS_LEN, MAVLINK_MSG_ID_GIMBAL_DEVICE_ATTITUDE_STATUS_CRC);
#else
mavlink_gimbal_device_attitude_status_t *packet = (mavlink_gimbal_device_attitude_status_t *)msgbuf;
packet->time_boot_ms = time_boot_ms;
packet->angular_velocity_x = angular_velocity_x;
packet->angular_velocity_y = angular_velocity_y;
packet->angular_velocity_z = angular_velocity_z;
packet->failure_flags = failure_flags;
packet->flags = flags;
packet->target_system = target_system;
packet->target_component = target_component;
mav_array_memcpy(packet->q, q, sizeof(float)*4);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GIMBAL_DEVICE_ATTITUDE_STATUS, (const char *)packet, MAVLINK_MSG_ID_GIMBAL_DEVICE_ATTITUDE_STATUS_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_DEVICE_ATTITUDE_STATUS_LEN, MAVLINK_MSG_ID_GIMBAL_DEVICE_ATTITUDE_STATUS_CRC);
#endif
}
#endif
#endif
// MESSAGE GIMBAL_DEVICE_ATTITUDE_STATUS UNPACKING
/**
* @brief Get field target_system from gimbal_device_attitude_status message
*
* @return System ID
*/
static inline uint8_t mavlink_msg_gimbal_device_attitude_status_get_target_system(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 38);
}
/**
* @brief Get field target_component from gimbal_device_attitude_status message
*
* @return Component ID
*/
static inline uint8_t mavlink_msg_gimbal_device_attitude_status_get_target_component(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 39);
}
/**
* @brief Get field time_boot_ms from gimbal_device_attitude_status message
*
* @return [ms] Timestamp (time since system boot).
*/
static inline uint32_t mavlink_msg_gimbal_device_attitude_status_get_time_boot_ms(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint32_t(msg, 0);
}
/**
* @brief Get field flags from gimbal_device_attitude_status message
*
* @return Current gimbal flags set.
*/
static inline uint16_t mavlink_msg_gimbal_device_attitude_status_get_flags(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 36);
}
/**
* @brief Get field q from gimbal_device_attitude_status message
*
* @return Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation, the frame is depends on whether the flag GIMBAL_DEVICE_FLAGS_YAW_LOCK is set)
*/
static inline uint16_t mavlink_msg_gimbal_device_attitude_status_get_q(const mavlink_message_t* msg, float *q)
{
return _MAV_RETURN_float_array(msg, q, 4, 4);
}
/**
* @brief Get field angular_velocity_x from gimbal_device_attitude_status message
*
* @return [rad/s] X component of angular velocity (NaN if unknown)
*/
static inline float mavlink_msg_gimbal_device_attitude_status_get_angular_velocity_x(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 20);
}
/**
* @brief Get field angular_velocity_y from gimbal_device_attitude_status message
*
* @return [rad/s] Y component of angular velocity (NaN if unknown)
*/
static inline float mavlink_msg_gimbal_device_attitude_status_get_angular_velocity_y(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 24);
}
/**
* @brief Get field angular_velocity_z from gimbal_device_attitude_status message
*
* @return [rad/s] Z component of angular velocity (NaN if unknown)
*/
static inline float mavlink_msg_gimbal_device_attitude_status_get_angular_velocity_z(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 28);
}
/**
* @brief Get field failure_flags from gimbal_device_attitude_status message
*
* @return Failure flags (0 for no failure)
*/
static inline uint32_t mavlink_msg_gimbal_device_attitude_status_get_failure_flags(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint32_t(msg, 32);
}
/**
* @brief Decode a gimbal_device_attitude_status message into a struct
*
* @param msg The message to decode
* @param gimbal_device_attitude_status C-struct to decode the message contents into
*/
static inline void mavlink_msg_gimbal_device_attitude_status_decode(const mavlink_message_t* msg, mavlink_gimbal_device_attitude_status_t* gimbal_device_attitude_status)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
gimbal_device_attitude_status->time_boot_ms = mavlink_msg_gimbal_device_attitude_status_get_time_boot_ms(msg);
mavlink_msg_gimbal_device_attitude_status_get_q(msg, gimbal_device_attitude_status->q);
gimbal_device_attitude_status->angular_velocity_x = mavlink_msg_gimbal_device_attitude_status_get_angular_velocity_x(msg);
gimbal_device_attitude_status->angular_velocity_y = mavlink_msg_gimbal_device_attitude_status_get_angular_velocity_y(msg);
gimbal_device_attitude_status->angular_velocity_z = mavlink_msg_gimbal_device_attitude_status_get_angular_velocity_z(msg);
gimbal_device_attitude_status->failure_flags = mavlink_msg_gimbal_device_attitude_status_get_failure_flags(msg);
gimbal_device_attitude_status->flags = mavlink_msg_gimbal_device_attitude_status_get_flags(msg);
gimbal_device_attitude_status->target_system = mavlink_msg_gimbal_device_attitude_status_get_target_system(msg);
gimbal_device_attitude_status->target_component = mavlink_msg_gimbal_device_attitude_status_get_target_component(msg);
#else
uint8_t len = msg->len < MAVLINK_MSG_ID_GIMBAL_DEVICE_ATTITUDE_STATUS_LEN? msg->len : MAVLINK_MSG_ID_GIMBAL_DEVICE_ATTITUDE_STATUS_LEN;
memset(gimbal_device_attitude_status, 0, MAVLINK_MSG_ID_GIMBAL_DEVICE_ATTITUDE_STATUS_LEN);
memcpy(gimbal_device_attitude_status, _MAV_PAYLOAD(msg), len);
#endif
}

View file

@ -0,0 +1,557 @@
#pragma once
// MESSAGE GIMBAL_DEVICE_INFORMATION PACKING
#define MAVLINK_MSG_ID_GIMBAL_DEVICE_INFORMATION 283
typedef struct __mavlink_gimbal_device_information_t {
uint64_t uid; /*< UID of gimbal hardware (0 if unknown).*/
uint32_t time_boot_ms; /*< [ms] Timestamp (time since system boot).*/
uint32_t firmware_version; /*< Version of the gimbal firmware, encoded as: (Dev & 0xff) << 24 | (Patch & 0xff) << 16 | (Minor & 0xff) << 8 | (Major & 0xff).*/
uint32_t hardware_version; /*< Version of the gimbal hardware, encoded as: (Dev & 0xff) << 24 | (Patch & 0xff) << 16 | (Minor & 0xff) << 8 | (Major & 0xff).*/
float roll_min; /*< [rad] Minimum hardware roll angle (positive: rolling to the right, negative: rolling to the left)*/
float roll_max; /*< [rad] Maximum hardware roll angle (positive: rolling to the right, negative: rolling to the left)*/
float pitch_min; /*< [rad] Minimum hardware pitch angle (positive: up, negative: down)*/
float pitch_max; /*< [rad] Maximum hardware pitch angle (positive: up, negative: down)*/
float yaw_min; /*< [rad] Minimum hardware yaw angle (positive: to the right, negative: to the left)*/
float yaw_max; /*< [rad] Maximum hardware yaw angle (positive: to the right, negative: to the left)*/
uint16_t cap_flags; /*< Bitmap of gimbal capability flags.*/
uint16_t custom_cap_flags; /*< Bitmap for use for gimbal-specific capability flags.*/
char vendor_name[32]; /*< Name of the gimbal vendor.*/
char model_name[32]; /*< Name of the gimbal model.*/
char custom_name[32]; /*< Custom name of the gimbal given to it by the user.*/
} mavlink_gimbal_device_information_t;
#define MAVLINK_MSG_ID_GIMBAL_DEVICE_INFORMATION_LEN 144
#define MAVLINK_MSG_ID_GIMBAL_DEVICE_INFORMATION_MIN_LEN 144
#define MAVLINK_MSG_ID_283_LEN 144
#define MAVLINK_MSG_ID_283_MIN_LEN 144
#define MAVLINK_MSG_ID_GIMBAL_DEVICE_INFORMATION_CRC 74
#define MAVLINK_MSG_ID_283_CRC 74
#define MAVLINK_MSG_GIMBAL_DEVICE_INFORMATION_FIELD_VENDOR_NAME_LEN 32
#define MAVLINK_MSG_GIMBAL_DEVICE_INFORMATION_FIELD_MODEL_NAME_LEN 32
#define MAVLINK_MSG_GIMBAL_DEVICE_INFORMATION_FIELD_CUSTOM_NAME_LEN 32
#if MAVLINK_COMMAND_24BIT
#define MAVLINK_MESSAGE_INFO_GIMBAL_DEVICE_INFORMATION { \
283, \
"GIMBAL_DEVICE_INFORMATION", \
15, \
{ { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_gimbal_device_information_t, time_boot_ms) }, \
{ "vendor_name", NULL, MAVLINK_TYPE_CHAR, 32, 48, offsetof(mavlink_gimbal_device_information_t, vendor_name) }, \
{ "model_name", NULL, MAVLINK_TYPE_CHAR, 32, 80, offsetof(mavlink_gimbal_device_information_t, model_name) }, \
{ "custom_name", NULL, MAVLINK_TYPE_CHAR, 32, 112, offsetof(mavlink_gimbal_device_information_t, custom_name) }, \
{ "firmware_version", NULL, MAVLINK_TYPE_UINT32_T, 0, 12, offsetof(mavlink_gimbal_device_information_t, firmware_version) }, \
{ "hardware_version", NULL, MAVLINK_TYPE_UINT32_T, 0, 16, offsetof(mavlink_gimbal_device_information_t, hardware_version) }, \
{ "uid", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_gimbal_device_information_t, uid) }, \
{ "cap_flags", NULL, MAVLINK_TYPE_UINT16_T, 0, 44, offsetof(mavlink_gimbal_device_information_t, cap_flags) }, \
{ "custom_cap_flags", NULL, MAVLINK_TYPE_UINT16_T, 0, 46, offsetof(mavlink_gimbal_device_information_t, custom_cap_flags) }, \
{ "roll_min", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_gimbal_device_information_t, roll_min) }, \
{ "roll_max", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_gimbal_device_information_t, roll_max) }, \
{ "pitch_min", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_gimbal_device_information_t, pitch_min) }, \
{ "pitch_max", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_gimbal_device_information_t, pitch_max) }, \
{ "yaw_min", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_gimbal_device_information_t, yaw_min) }, \
{ "yaw_max", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_gimbal_device_information_t, yaw_max) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_GIMBAL_DEVICE_INFORMATION { \
"GIMBAL_DEVICE_INFORMATION", \
15, \
{ { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_gimbal_device_information_t, time_boot_ms) }, \
{ "vendor_name", NULL, MAVLINK_TYPE_CHAR, 32, 48, offsetof(mavlink_gimbal_device_information_t, vendor_name) }, \
{ "model_name", NULL, MAVLINK_TYPE_CHAR, 32, 80, offsetof(mavlink_gimbal_device_information_t, model_name) }, \
{ "custom_name", NULL, MAVLINK_TYPE_CHAR, 32, 112, offsetof(mavlink_gimbal_device_information_t, custom_name) }, \
{ "firmware_version", NULL, MAVLINK_TYPE_UINT32_T, 0, 12, offsetof(mavlink_gimbal_device_information_t, firmware_version) }, \
{ "hardware_version", NULL, MAVLINK_TYPE_UINT32_T, 0, 16, offsetof(mavlink_gimbal_device_information_t, hardware_version) }, \
{ "uid", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_gimbal_device_information_t, uid) }, \
{ "cap_flags", NULL, MAVLINK_TYPE_UINT16_T, 0, 44, offsetof(mavlink_gimbal_device_information_t, cap_flags) }, \
{ "custom_cap_flags", NULL, MAVLINK_TYPE_UINT16_T, 0, 46, offsetof(mavlink_gimbal_device_information_t, custom_cap_flags) }, \
{ "roll_min", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_gimbal_device_information_t, roll_min) }, \
{ "roll_max", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_gimbal_device_information_t, roll_max) }, \
{ "pitch_min", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_gimbal_device_information_t, pitch_min) }, \
{ "pitch_max", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_gimbal_device_information_t, pitch_max) }, \
{ "yaw_min", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_gimbal_device_information_t, yaw_min) }, \
{ "yaw_max", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_gimbal_device_information_t, yaw_max) }, \
} \
}
#endif
/**
* @brief Pack a gimbal_device_information message
* @param system_id ID of this 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 [ms] Timestamp (time since system boot).
* @param vendor_name Name of the gimbal vendor.
* @param model_name Name of the gimbal model.
* @param custom_name Custom name of the gimbal given to it by the user.
* @param firmware_version Version of the gimbal firmware, encoded as: (Dev & 0xff) << 24 | (Patch & 0xff) << 16 | (Minor & 0xff) << 8 | (Major & 0xff).
* @param hardware_version Version of the gimbal hardware, encoded as: (Dev & 0xff) << 24 | (Patch & 0xff) << 16 | (Minor & 0xff) << 8 | (Major & 0xff).
* @param uid UID of gimbal hardware (0 if unknown).
* @param cap_flags Bitmap of gimbal capability flags.
* @param custom_cap_flags Bitmap for use for gimbal-specific capability flags.
* @param roll_min [rad] Minimum hardware roll angle (positive: rolling to the right, negative: rolling to the left)
* @param roll_max [rad] Maximum hardware roll angle (positive: rolling to the right, negative: rolling to the left)
* @param pitch_min [rad] Minimum hardware pitch angle (positive: up, negative: down)
* @param pitch_max [rad] Maximum hardware pitch angle (positive: up, negative: down)
* @param yaw_min [rad] Minimum hardware yaw angle (positive: to the right, negative: to the left)
* @param yaw_max [rad] Maximum hardware yaw angle (positive: to the right, negative: to the left)
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_gimbal_device_information_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint32_t time_boot_ms, const char *vendor_name, const char *model_name, const char *custom_name, uint32_t firmware_version, uint32_t hardware_version, uint64_t uid, uint16_t cap_flags, uint16_t custom_cap_flags, float roll_min, float roll_max, float pitch_min, float pitch_max, float yaw_min, float yaw_max)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_GIMBAL_DEVICE_INFORMATION_LEN];
_mav_put_uint64_t(buf, 0, uid);
_mav_put_uint32_t(buf, 8, time_boot_ms);
_mav_put_uint32_t(buf, 12, firmware_version);
_mav_put_uint32_t(buf, 16, hardware_version);
_mav_put_float(buf, 20, roll_min);
_mav_put_float(buf, 24, roll_max);
_mav_put_float(buf, 28, pitch_min);
_mav_put_float(buf, 32, pitch_max);
_mav_put_float(buf, 36, yaw_min);
_mav_put_float(buf, 40, yaw_max);
_mav_put_uint16_t(buf, 44, cap_flags);
_mav_put_uint16_t(buf, 46, custom_cap_flags);
_mav_put_char_array(buf, 48, vendor_name, 32);
_mav_put_char_array(buf, 80, model_name, 32);
_mav_put_char_array(buf, 112, custom_name, 32);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GIMBAL_DEVICE_INFORMATION_LEN);
#else
mavlink_gimbal_device_information_t packet;
packet.uid = uid;
packet.time_boot_ms = time_boot_ms;
packet.firmware_version = firmware_version;
packet.hardware_version = hardware_version;
packet.roll_min = roll_min;
packet.roll_max = roll_max;
packet.pitch_min = pitch_min;
packet.pitch_max = pitch_max;
packet.yaw_min = yaw_min;
packet.yaw_max = yaw_max;
packet.cap_flags = cap_flags;
packet.custom_cap_flags = custom_cap_flags;
mav_array_memcpy(packet.vendor_name, vendor_name, sizeof(char)*32);
mav_array_memcpy(packet.model_name, model_name, sizeof(char)*32);
mav_array_memcpy(packet.custom_name, custom_name, sizeof(char)*32);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GIMBAL_DEVICE_INFORMATION_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_GIMBAL_DEVICE_INFORMATION;
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GIMBAL_DEVICE_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_DEVICE_INFORMATION_LEN, MAVLINK_MSG_ID_GIMBAL_DEVICE_INFORMATION_CRC);
}
/**
* @brief Pack a gimbal_device_information message on a channel
* @param system_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 [ms] Timestamp (time since system boot).
* @param vendor_name Name of the gimbal vendor.
* @param model_name Name of the gimbal model.
* @param custom_name Custom name of the gimbal given to it by the user.
* @param firmware_version Version of the gimbal firmware, encoded as: (Dev & 0xff) << 24 | (Patch & 0xff) << 16 | (Minor & 0xff) << 8 | (Major & 0xff).
* @param hardware_version Version of the gimbal hardware, encoded as: (Dev & 0xff) << 24 | (Patch & 0xff) << 16 | (Minor & 0xff) << 8 | (Major & 0xff).
* @param uid UID of gimbal hardware (0 if unknown).
* @param cap_flags Bitmap of gimbal capability flags.
* @param custom_cap_flags Bitmap for use for gimbal-specific capability flags.
* @param roll_min [rad] Minimum hardware roll angle (positive: rolling to the right, negative: rolling to the left)
* @param roll_max [rad] Maximum hardware roll angle (positive: rolling to the right, negative: rolling to the left)
* @param pitch_min [rad] Minimum hardware pitch angle (positive: up, negative: down)
* @param pitch_max [rad] Maximum hardware pitch angle (positive: up, negative: down)
* @param yaw_min [rad] Minimum hardware yaw angle (positive: to the right, negative: to the left)
* @param yaw_max [rad] Maximum hardware yaw angle (positive: to the right, negative: to the left)
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_gimbal_device_information_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint32_t time_boot_ms,const char *vendor_name,const char *model_name,const char *custom_name,uint32_t firmware_version,uint32_t hardware_version,uint64_t uid,uint16_t cap_flags,uint16_t custom_cap_flags,float roll_min,float roll_max,float pitch_min,float pitch_max,float yaw_min,float yaw_max)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_GIMBAL_DEVICE_INFORMATION_LEN];
_mav_put_uint64_t(buf, 0, uid);
_mav_put_uint32_t(buf, 8, time_boot_ms);
_mav_put_uint32_t(buf, 12, firmware_version);
_mav_put_uint32_t(buf, 16, hardware_version);
_mav_put_float(buf, 20, roll_min);
_mav_put_float(buf, 24, roll_max);
_mav_put_float(buf, 28, pitch_min);
_mav_put_float(buf, 32, pitch_max);
_mav_put_float(buf, 36, yaw_min);
_mav_put_float(buf, 40, yaw_max);
_mav_put_uint16_t(buf, 44, cap_flags);
_mav_put_uint16_t(buf, 46, custom_cap_flags);
_mav_put_char_array(buf, 48, vendor_name, 32);
_mav_put_char_array(buf, 80, model_name, 32);
_mav_put_char_array(buf, 112, custom_name, 32);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GIMBAL_DEVICE_INFORMATION_LEN);
#else
mavlink_gimbal_device_information_t packet;
packet.uid = uid;
packet.time_boot_ms = time_boot_ms;
packet.firmware_version = firmware_version;
packet.hardware_version = hardware_version;
packet.roll_min = roll_min;
packet.roll_max = roll_max;
packet.pitch_min = pitch_min;
packet.pitch_max = pitch_max;
packet.yaw_min = yaw_min;
packet.yaw_max = yaw_max;
packet.cap_flags = cap_flags;
packet.custom_cap_flags = custom_cap_flags;
mav_array_memcpy(packet.vendor_name, vendor_name, sizeof(char)*32);
mav_array_memcpy(packet.model_name, model_name, sizeof(char)*32);
mav_array_memcpy(packet.custom_name, custom_name, sizeof(char)*32);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GIMBAL_DEVICE_INFORMATION_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_GIMBAL_DEVICE_INFORMATION;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GIMBAL_DEVICE_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_DEVICE_INFORMATION_LEN, MAVLINK_MSG_ID_GIMBAL_DEVICE_INFORMATION_CRC);
}
/**
* @brief Encode a gimbal_device_information 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 gimbal_device_information C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_gimbal_device_information_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gimbal_device_information_t* gimbal_device_information)
{
return mavlink_msg_gimbal_device_information_pack(system_id, component_id, msg, gimbal_device_information->time_boot_ms, gimbal_device_information->vendor_name, gimbal_device_information->model_name, gimbal_device_information->custom_name, gimbal_device_information->firmware_version, gimbal_device_information->hardware_version, gimbal_device_information->uid, gimbal_device_information->cap_flags, gimbal_device_information->custom_cap_flags, gimbal_device_information->roll_min, gimbal_device_information->roll_max, gimbal_device_information->pitch_min, gimbal_device_information->pitch_max, gimbal_device_information->yaw_min, gimbal_device_information->yaw_max);
}
/**
* @brief Encode a gimbal_device_information 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 gimbal_device_information C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_gimbal_device_information_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_gimbal_device_information_t* gimbal_device_information)
{
return mavlink_msg_gimbal_device_information_pack_chan(system_id, component_id, chan, msg, gimbal_device_information->time_boot_ms, gimbal_device_information->vendor_name, gimbal_device_information->model_name, gimbal_device_information->custom_name, gimbal_device_information->firmware_version, gimbal_device_information->hardware_version, gimbal_device_information->uid, gimbal_device_information->cap_flags, gimbal_device_information->custom_cap_flags, gimbal_device_information->roll_min, gimbal_device_information->roll_max, gimbal_device_information->pitch_min, gimbal_device_information->pitch_max, gimbal_device_information->yaw_min, gimbal_device_information->yaw_max);
}
/**
* @brief Send a gimbal_device_information message
* @param chan MAVLink channel to send the message
*
* @param time_boot_ms [ms] Timestamp (time since system boot).
* @param vendor_name Name of the gimbal vendor.
* @param model_name Name of the gimbal model.
* @param custom_name Custom name of the gimbal given to it by the user.
* @param firmware_version Version of the gimbal firmware, encoded as: (Dev & 0xff) << 24 | (Patch & 0xff) << 16 | (Minor & 0xff) << 8 | (Major & 0xff).
* @param hardware_version Version of the gimbal hardware, encoded as: (Dev & 0xff) << 24 | (Patch & 0xff) << 16 | (Minor & 0xff) << 8 | (Major & 0xff).
* @param uid UID of gimbal hardware (0 if unknown).
* @param cap_flags Bitmap of gimbal capability flags.
* @param custom_cap_flags Bitmap for use for gimbal-specific capability flags.
* @param roll_min [rad] Minimum hardware roll angle (positive: rolling to the right, negative: rolling to the left)
* @param roll_max [rad] Maximum hardware roll angle (positive: rolling to the right, negative: rolling to the left)
* @param pitch_min [rad] Minimum hardware pitch angle (positive: up, negative: down)
* @param pitch_max [rad] Maximum hardware pitch angle (positive: up, negative: down)
* @param yaw_min [rad] Minimum hardware yaw angle (positive: to the right, negative: to the left)
* @param yaw_max [rad] Maximum hardware yaw angle (positive: to the right, negative: to the left)
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_gimbal_device_information_send(mavlink_channel_t chan, uint32_t time_boot_ms, const char *vendor_name, const char *model_name, const char *custom_name, uint32_t firmware_version, uint32_t hardware_version, uint64_t uid, uint16_t cap_flags, uint16_t custom_cap_flags, float roll_min, float roll_max, float pitch_min, float pitch_max, float yaw_min, float yaw_max)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_GIMBAL_DEVICE_INFORMATION_LEN];
_mav_put_uint64_t(buf, 0, uid);
_mav_put_uint32_t(buf, 8, time_boot_ms);
_mav_put_uint32_t(buf, 12, firmware_version);
_mav_put_uint32_t(buf, 16, hardware_version);
_mav_put_float(buf, 20, roll_min);
_mav_put_float(buf, 24, roll_max);
_mav_put_float(buf, 28, pitch_min);
_mav_put_float(buf, 32, pitch_max);
_mav_put_float(buf, 36, yaw_min);
_mav_put_float(buf, 40, yaw_max);
_mav_put_uint16_t(buf, 44, cap_flags);
_mav_put_uint16_t(buf, 46, custom_cap_flags);
_mav_put_char_array(buf, 48, vendor_name, 32);
_mav_put_char_array(buf, 80, model_name, 32);
_mav_put_char_array(buf, 112, custom_name, 32);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GIMBAL_DEVICE_INFORMATION, buf, MAVLINK_MSG_ID_GIMBAL_DEVICE_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_DEVICE_INFORMATION_LEN, MAVLINK_MSG_ID_GIMBAL_DEVICE_INFORMATION_CRC);
#else
mavlink_gimbal_device_information_t packet;
packet.uid = uid;
packet.time_boot_ms = time_boot_ms;
packet.firmware_version = firmware_version;
packet.hardware_version = hardware_version;
packet.roll_min = roll_min;
packet.roll_max = roll_max;
packet.pitch_min = pitch_min;
packet.pitch_max = pitch_max;
packet.yaw_min = yaw_min;
packet.yaw_max = yaw_max;
packet.cap_flags = cap_flags;
packet.custom_cap_flags = custom_cap_flags;
mav_array_memcpy(packet.vendor_name, vendor_name, sizeof(char)*32);
mav_array_memcpy(packet.model_name, model_name, sizeof(char)*32);
mav_array_memcpy(packet.custom_name, custom_name, sizeof(char)*32);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GIMBAL_DEVICE_INFORMATION, (const char *)&packet, MAVLINK_MSG_ID_GIMBAL_DEVICE_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_DEVICE_INFORMATION_LEN, MAVLINK_MSG_ID_GIMBAL_DEVICE_INFORMATION_CRC);
#endif
}
/**
* @brief Send a gimbal_device_information message
* @param chan MAVLink channel to send the message
* @param struct The MAVLink struct to serialize
*/
static inline void mavlink_msg_gimbal_device_information_send_struct(mavlink_channel_t chan, const mavlink_gimbal_device_information_t* gimbal_device_information)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mavlink_msg_gimbal_device_information_send(chan, gimbal_device_information->time_boot_ms, gimbal_device_information->vendor_name, gimbal_device_information->model_name, gimbal_device_information->custom_name, gimbal_device_information->firmware_version, gimbal_device_information->hardware_version, gimbal_device_information->uid, gimbal_device_information->cap_flags, gimbal_device_information->custom_cap_flags, gimbal_device_information->roll_min, gimbal_device_information->roll_max, gimbal_device_information->pitch_min, gimbal_device_information->pitch_max, gimbal_device_information->yaw_min, gimbal_device_information->yaw_max);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GIMBAL_DEVICE_INFORMATION, (const char *)gimbal_device_information, MAVLINK_MSG_ID_GIMBAL_DEVICE_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_DEVICE_INFORMATION_LEN, MAVLINK_MSG_ID_GIMBAL_DEVICE_INFORMATION_CRC);
#endif
}
#if MAVLINK_MSG_ID_GIMBAL_DEVICE_INFORMATION_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_gimbal_device_information_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, const char *vendor_name, const char *model_name, const char *custom_name, uint32_t firmware_version, uint32_t hardware_version, uint64_t uid, uint16_t cap_flags, uint16_t custom_cap_flags, float roll_min, float roll_max, float pitch_min, float pitch_max, float yaw_min, float yaw_max)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
_mav_put_uint64_t(buf, 0, uid);
_mav_put_uint32_t(buf, 8, time_boot_ms);
_mav_put_uint32_t(buf, 12, firmware_version);
_mav_put_uint32_t(buf, 16, hardware_version);
_mav_put_float(buf, 20, roll_min);
_mav_put_float(buf, 24, roll_max);
_mav_put_float(buf, 28, pitch_min);
_mav_put_float(buf, 32, pitch_max);
_mav_put_float(buf, 36, yaw_min);
_mav_put_float(buf, 40, yaw_max);
_mav_put_uint16_t(buf, 44, cap_flags);
_mav_put_uint16_t(buf, 46, custom_cap_flags);
_mav_put_char_array(buf, 48, vendor_name, 32);
_mav_put_char_array(buf, 80, model_name, 32);
_mav_put_char_array(buf, 112, custom_name, 32);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GIMBAL_DEVICE_INFORMATION, buf, MAVLINK_MSG_ID_GIMBAL_DEVICE_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_DEVICE_INFORMATION_LEN, MAVLINK_MSG_ID_GIMBAL_DEVICE_INFORMATION_CRC);
#else
mavlink_gimbal_device_information_t *packet = (mavlink_gimbal_device_information_t *)msgbuf;
packet->uid = uid;
packet->time_boot_ms = time_boot_ms;
packet->firmware_version = firmware_version;
packet->hardware_version = hardware_version;
packet->roll_min = roll_min;
packet->roll_max = roll_max;
packet->pitch_min = pitch_min;
packet->pitch_max = pitch_max;
packet->yaw_min = yaw_min;
packet->yaw_max = yaw_max;
packet->cap_flags = cap_flags;
packet->custom_cap_flags = custom_cap_flags;
mav_array_memcpy(packet->vendor_name, vendor_name, sizeof(char)*32);
mav_array_memcpy(packet->model_name, model_name, sizeof(char)*32);
mav_array_memcpy(packet->custom_name, custom_name, sizeof(char)*32);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GIMBAL_DEVICE_INFORMATION, (const char *)packet, MAVLINK_MSG_ID_GIMBAL_DEVICE_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_DEVICE_INFORMATION_LEN, MAVLINK_MSG_ID_GIMBAL_DEVICE_INFORMATION_CRC);
#endif
}
#endif
#endif
// MESSAGE GIMBAL_DEVICE_INFORMATION UNPACKING
/**
* @brief Get field time_boot_ms from gimbal_device_information message
*
* @return [ms] Timestamp (time since system boot).
*/
static inline uint32_t mavlink_msg_gimbal_device_information_get_time_boot_ms(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint32_t(msg, 8);
}
/**
* @brief Get field vendor_name from gimbal_device_information message
*
* @return Name of the gimbal vendor.
*/
static inline uint16_t mavlink_msg_gimbal_device_information_get_vendor_name(const mavlink_message_t* msg, char *vendor_name)
{
return _MAV_RETURN_char_array(msg, vendor_name, 32, 48);
}
/**
* @brief Get field model_name from gimbal_device_information message
*
* @return Name of the gimbal model.
*/
static inline uint16_t mavlink_msg_gimbal_device_information_get_model_name(const mavlink_message_t* msg, char *model_name)
{
return _MAV_RETURN_char_array(msg, model_name, 32, 80);
}
/**
* @brief Get field custom_name from gimbal_device_information message
*
* @return Custom name of the gimbal given to it by the user.
*/
static inline uint16_t mavlink_msg_gimbal_device_information_get_custom_name(const mavlink_message_t* msg, char *custom_name)
{
return _MAV_RETURN_char_array(msg, custom_name, 32, 112);
}
/**
* @brief Get field firmware_version from gimbal_device_information message
*
* @return Version of the gimbal firmware, encoded as: (Dev & 0xff) << 24 | (Patch & 0xff) << 16 | (Minor & 0xff) << 8 | (Major & 0xff).
*/
static inline uint32_t mavlink_msg_gimbal_device_information_get_firmware_version(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint32_t(msg, 12);
}
/**
* @brief Get field hardware_version from gimbal_device_information message
*
* @return Version of the gimbal hardware, encoded as: (Dev & 0xff) << 24 | (Patch & 0xff) << 16 | (Minor & 0xff) << 8 | (Major & 0xff).
*/
static inline uint32_t mavlink_msg_gimbal_device_information_get_hardware_version(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint32_t(msg, 16);
}
/**
* @brief Get field uid from gimbal_device_information message
*
* @return UID of gimbal hardware (0 if unknown).
*/
static inline uint64_t mavlink_msg_gimbal_device_information_get_uid(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint64_t(msg, 0);
}
/**
* @brief Get field cap_flags from gimbal_device_information message
*
* @return Bitmap of gimbal capability flags.
*/
static inline uint16_t mavlink_msg_gimbal_device_information_get_cap_flags(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 44);
}
/**
* @brief Get field custom_cap_flags from gimbal_device_information message
*
* @return Bitmap for use for gimbal-specific capability flags.
*/
static inline uint16_t mavlink_msg_gimbal_device_information_get_custom_cap_flags(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 46);
}
/**
* @brief Get field roll_min from gimbal_device_information message
*
* @return [rad] Minimum hardware roll angle (positive: rolling to the right, negative: rolling to the left)
*/
static inline float mavlink_msg_gimbal_device_information_get_roll_min(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 20);
}
/**
* @brief Get field roll_max from gimbal_device_information message
*
* @return [rad] Maximum hardware roll angle (positive: rolling to the right, negative: rolling to the left)
*/
static inline float mavlink_msg_gimbal_device_information_get_roll_max(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 24);
}
/**
* @brief Get field pitch_min from gimbal_device_information message
*
* @return [rad] Minimum hardware pitch angle (positive: up, negative: down)
*/
static inline float mavlink_msg_gimbal_device_information_get_pitch_min(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 28);
}
/**
* @brief Get field pitch_max from gimbal_device_information message
*
* @return [rad] Maximum hardware pitch angle (positive: up, negative: down)
*/
static inline float mavlink_msg_gimbal_device_information_get_pitch_max(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 32);
}
/**
* @brief Get field yaw_min from gimbal_device_information message
*
* @return [rad] Minimum hardware yaw angle (positive: to the right, negative: to the left)
*/
static inline float mavlink_msg_gimbal_device_information_get_yaw_min(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 36);
}
/**
* @brief Get field yaw_max from gimbal_device_information message
*
* @return [rad] Maximum hardware yaw angle (positive: to the right, negative: to the left)
*/
static inline float mavlink_msg_gimbal_device_information_get_yaw_max(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 40);
}
/**
* @brief Decode a gimbal_device_information message into a struct
*
* @param msg The message to decode
* @param gimbal_device_information C-struct to decode the message contents into
*/
static inline void mavlink_msg_gimbal_device_information_decode(const mavlink_message_t* msg, mavlink_gimbal_device_information_t* gimbal_device_information)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
gimbal_device_information->uid = mavlink_msg_gimbal_device_information_get_uid(msg);
gimbal_device_information->time_boot_ms = mavlink_msg_gimbal_device_information_get_time_boot_ms(msg);
gimbal_device_information->firmware_version = mavlink_msg_gimbal_device_information_get_firmware_version(msg);
gimbal_device_information->hardware_version = mavlink_msg_gimbal_device_information_get_hardware_version(msg);
gimbal_device_information->roll_min = mavlink_msg_gimbal_device_information_get_roll_min(msg);
gimbal_device_information->roll_max = mavlink_msg_gimbal_device_information_get_roll_max(msg);
gimbal_device_information->pitch_min = mavlink_msg_gimbal_device_information_get_pitch_min(msg);
gimbal_device_information->pitch_max = mavlink_msg_gimbal_device_information_get_pitch_max(msg);
gimbal_device_information->yaw_min = mavlink_msg_gimbal_device_information_get_yaw_min(msg);
gimbal_device_information->yaw_max = mavlink_msg_gimbal_device_information_get_yaw_max(msg);
gimbal_device_information->cap_flags = mavlink_msg_gimbal_device_information_get_cap_flags(msg);
gimbal_device_information->custom_cap_flags = mavlink_msg_gimbal_device_information_get_custom_cap_flags(msg);
mavlink_msg_gimbal_device_information_get_vendor_name(msg, gimbal_device_information->vendor_name);
mavlink_msg_gimbal_device_information_get_model_name(msg, gimbal_device_information->model_name);
mavlink_msg_gimbal_device_information_get_custom_name(msg, gimbal_device_information->custom_name);
#else
uint8_t len = msg->len < MAVLINK_MSG_ID_GIMBAL_DEVICE_INFORMATION_LEN? msg->len : MAVLINK_MSG_ID_GIMBAL_DEVICE_INFORMATION_LEN;
memset(gimbal_device_information, 0, MAVLINK_MSG_ID_GIMBAL_DEVICE_INFORMATION_LEN);
memcpy(gimbal_device_information, _MAV_PAYLOAD(msg), len);
#endif
}

View file

@ -0,0 +1,355 @@
#pragma once
// MESSAGE GIMBAL_DEVICE_SET_ATTITUDE PACKING
#define MAVLINK_MSG_ID_GIMBAL_DEVICE_SET_ATTITUDE 284
typedef struct __mavlink_gimbal_device_set_attitude_t {
float q[4]; /*< Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation, the frame is depends on whether the flag GIMBAL_DEVICE_FLAGS_YAW_LOCK is set, set all fields to NaN if only angular velocity should be used)*/
float angular_velocity_x; /*< [rad/s] X component of angular velocity, positive is rolling to the right, NaN to be ignored.*/
float angular_velocity_y; /*< [rad/s] Y component of angular velocity, positive is pitching up, NaN to be ignored.*/
float angular_velocity_z; /*< [rad/s] Z component of angular velocity, positive is yawing to the right, NaN to be ignored.*/
uint16_t flags; /*< Low level gimbal flags.*/
uint8_t target_system; /*< System ID*/
uint8_t target_component; /*< Component ID*/
} mavlink_gimbal_device_set_attitude_t;
#define MAVLINK_MSG_ID_GIMBAL_DEVICE_SET_ATTITUDE_LEN 32
#define MAVLINK_MSG_ID_GIMBAL_DEVICE_SET_ATTITUDE_MIN_LEN 32
#define MAVLINK_MSG_ID_284_LEN 32
#define MAVLINK_MSG_ID_284_MIN_LEN 32
#define MAVLINK_MSG_ID_GIMBAL_DEVICE_SET_ATTITUDE_CRC 99
#define MAVLINK_MSG_ID_284_CRC 99
#define MAVLINK_MSG_GIMBAL_DEVICE_SET_ATTITUDE_FIELD_Q_LEN 4
#if MAVLINK_COMMAND_24BIT
#define MAVLINK_MESSAGE_INFO_GIMBAL_DEVICE_SET_ATTITUDE { \
284, \
"GIMBAL_DEVICE_SET_ATTITUDE", \
7, \
{ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 30, offsetof(mavlink_gimbal_device_set_attitude_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 31, offsetof(mavlink_gimbal_device_set_attitude_t, target_component) }, \
{ "flags", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_gimbal_device_set_attitude_t, flags) }, \
{ "q", NULL, MAVLINK_TYPE_FLOAT, 4, 0, offsetof(mavlink_gimbal_device_set_attitude_t, q) }, \
{ "angular_velocity_x", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_gimbal_device_set_attitude_t, angular_velocity_x) }, \
{ "angular_velocity_y", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_gimbal_device_set_attitude_t, angular_velocity_y) }, \
{ "angular_velocity_z", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_gimbal_device_set_attitude_t, angular_velocity_z) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_GIMBAL_DEVICE_SET_ATTITUDE { \
"GIMBAL_DEVICE_SET_ATTITUDE", \
7, \
{ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 30, offsetof(mavlink_gimbal_device_set_attitude_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 31, offsetof(mavlink_gimbal_device_set_attitude_t, target_component) }, \
{ "flags", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_gimbal_device_set_attitude_t, flags) }, \
{ "q", NULL, MAVLINK_TYPE_FLOAT, 4, 0, offsetof(mavlink_gimbal_device_set_attitude_t, q) }, \
{ "angular_velocity_x", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_gimbal_device_set_attitude_t, angular_velocity_x) }, \
{ "angular_velocity_y", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_gimbal_device_set_attitude_t, angular_velocity_y) }, \
{ "angular_velocity_z", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_gimbal_device_set_attitude_t, angular_velocity_z) }, \
} \
}
#endif
/**
* @brief Pack a gimbal_device_set_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 target_system System ID
* @param target_component Component ID
* @param flags Low level gimbal flags.
* @param q Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation, the frame is depends on whether the flag GIMBAL_DEVICE_FLAGS_YAW_LOCK is set, set all fields to NaN if only angular velocity should be used)
* @param angular_velocity_x [rad/s] X component of angular velocity, positive is rolling to the right, NaN to be ignored.
* @param angular_velocity_y [rad/s] Y component of angular velocity, positive is pitching up, NaN to be ignored.
* @param angular_velocity_z [rad/s] Z component of angular velocity, positive is yawing to the right, NaN to be ignored.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_gimbal_device_set_attitude_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t target_system, uint8_t target_component, uint16_t flags, const float *q, float angular_velocity_x, float angular_velocity_y, float angular_velocity_z)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_GIMBAL_DEVICE_SET_ATTITUDE_LEN];
_mav_put_float(buf, 16, angular_velocity_x);
_mav_put_float(buf, 20, angular_velocity_y);
_mav_put_float(buf, 24, angular_velocity_z);
_mav_put_uint16_t(buf, 28, flags);
_mav_put_uint8_t(buf, 30, target_system);
_mav_put_uint8_t(buf, 31, target_component);
_mav_put_float_array(buf, 0, q, 4);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GIMBAL_DEVICE_SET_ATTITUDE_LEN);
#else
mavlink_gimbal_device_set_attitude_t packet;
packet.angular_velocity_x = angular_velocity_x;
packet.angular_velocity_y = angular_velocity_y;
packet.angular_velocity_z = angular_velocity_z;
packet.flags = flags;
packet.target_system = target_system;
packet.target_component = target_component;
mav_array_memcpy(packet.q, q, sizeof(float)*4);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GIMBAL_DEVICE_SET_ATTITUDE_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_GIMBAL_DEVICE_SET_ATTITUDE;
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GIMBAL_DEVICE_SET_ATTITUDE_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_DEVICE_SET_ATTITUDE_LEN, MAVLINK_MSG_ID_GIMBAL_DEVICE_SET_ATTITUDE_CRC);
}
/**
* @brief Pack a gimbal_device_set_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 target_system System ID
* @param target_component Component ID
* @param flags Low level gimbal flags.
* @param q Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation, the frame is depends on whether the flag GIMBAL_DEVICE_FLAGS_YAW_LOCK is set, set all fields to NaN if only angular velocity should be used)
* @param angular_velocity_x [rad/s] X component of angular velocity, positive is rolling to the right, NaN to be ignored.
* @param angular_velocity_y [rad/s] Y component of angular velocity, positive is pitching up, NaN to be ignored.
* @param angular_velocity_z [rad/s] Z component of angular velocity, positive is yawing to the right, NaN to be ignored.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_gimbal_device_set_attitude_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 flags,const float *q,float angular_velocity_x,float angular_velocity_y,float angular_velocity_z)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_GIMBAL_DEVICE_SET_ATTITUDE_LEN];
_mav_put_float(buf, 16, angular_velocity_x);
_mav_put_float(buf, 20, angular_velocity_y);
_mav_put_float(buf, 24, angular_velocity_z);
_mav_put_uint16_t(buf, 28, flags);
_mav_put_uint8_t(buf, 30, target_system);
_mav_put_uint8_t(buf, 31, target_component);
_mav_put_float_array(buf, 0, q, 4);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GIMBAL_DEVICE_SET_ATTITUDE_LEN);
#else
mavlink_gimbal_device_set_attitude_t packet;
packet.angular_velocity_x = angular_velocity_x;
packet.angular_velocity_y = angular_velocity_y;
packet.angular_velocity_z = angular_velocity_z;
packet.flags = flags;
packet.target_system = target_system;
packet.target_component = target_component;
mav_array_memcpy(packet.q, q, sizeof(float)*4);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GIMBAL_DEVICE_SET_ATTITUDE_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_GIMBAL_DEVICE_SET_ATTITUDE;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GIMBAL_DEVICE_SET_ATTITUDE_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_DEVICE_SET_ATTITUDE_LEN, MAVLINK_MSG_ID_GIMBAL_DEVICE_SET_ATTITUDE_CRC);
}
/**
* @brief Encode a gimbal_device_set_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 gimbal_device_set_attitude C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_gimbal_device_set_attitude_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gimbal_device_set_attitude_t* gimbal_device_set_attitude)
{
return mavlink_msg_gimbal_device_set_attitude_pack(system_id, component_id, msg, gimbal_device_set_attitude->target_system, gimbal_device_set_attitude->target_component, gimbal_device_set_attitude->flags, gimbal_device_set_attitude->q, gimbal_device_set_attitude->angular_velocity_x, gimbal_device_set_attitude->angular_velocity_y, gimbal_device_set_attitude->angular_velocity_z);
}
/**
* @brief Encode a gimbal_device_set_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 gimbal_device_set_attitude C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_gimbal_device_set_attitude_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_gimbal_device_set_attitude_t* gimbal_device_set_attitude)
{
return mavlink_msg_gimbal_device_set_attitude_pack_chan(system_id, component_id, chan, msg, gimbal_device_set_attitude->target_system, gimbal_device_set_attitude->target_component, gimbal_device_set_attitude->flags, gimbal_device_set_attitude->q, gimbal_device_set_attitude->angular_velocity_x, gimbal_device_set_attitude->angular_velocity_y, gimbal_device_set_attitude->angular_velocity_z);
}
/**
* @brief Send a gimbal_device_set_attitude message
* @param chan MAVLink channel to send the message
*
* @param target_system System ID
* @param target_component Component ID
* @param flags Low level gimbal flags.
* @param q Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation, the frame is depends on whether the flag GIMBAL_DEVICE_FLAGS_YAW_LOCK is set, set all fields to NaN if only angular velocity should be used)
* @param angular_velocity_x [rad/s] X component of angular velocity, positive is rolling to the right, NaN to be ignored.
* @param angular_velocity_y [rad/s] Y component of angular velocity, positive is pitching up, NaN to be ignored.
* @param angular_velocity_z [rad/s] Z component of angular velocity, positive is yawing to the right, NaN to be ignored.
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_gimbal_device_set_attitude_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t flags, const float *q, float angular_velocity_x, float angular_velocity_y, float angular_velocity_z)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_GIMBAL_DEVICE_SET_ATTITUDE_LEN];
_mav_put_float(buf, 16, angular_velocity_x);
_mav_put_float(buf, 20, angular_velocity_y);
_mav_put_float(buf, 24, angular_velocity_z);
_mav_put_uint16_t(buf, 28, flags);
_mav_put_uint8_t(buf, 30, target_system);
_mav_put_uint8_t(buf, 31, target_component);
_mav_put_float_array(buf, 0, q, 4);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GIMBAL_DEVICE_SET_ATTITUDE, buf, MAVLINK_MSG_ID_GIMBAL_DEVICE_SET_ATTITUDE_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_DEVICE_SET_ATTITUDE_LEN, MAVLINK_MSG_ID_GIMBAL_DEVICE_SET_ATTITUDE_CRC);
#else
mavlink_gimbal_device_set_attitude_t packet;
packet.angular_velocity_x = angular_velocity_x;
packet.angular_velocity_y = angular_velocity_y;
packet.angular_velocity_z = angular_velocity_z;
packet.flags = flags;
packet.target_system = target_system;
packet.target_component = target_component;
mav_array_memcpy(packet.q, q, sizeof(float)*4);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GIMBAL_DEVICE_SET_ATTITUDE, (const char *)&packet, MAVLINK_MSG_ID_GIMBAL_DEVICE_SET_ATTITUDE_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_DEVICE_SET_ATTITUDE_LEN, MAVLINK_MSG_ID_GIMBAL_DEVICE_SET_ATTITUDE_CRC);
#endif
}
/**
* @brief Send a gimbal_device_set_attitude message
* @param chan MAVLink channel to send the message
* @param struct The MAVLink struct to serialize
*/
static inline void mavlink_msg_gimbal_device_set_attitude_send_struct(mavlink_channel_t chan, const mavlink_gimbal_device_set_attitude_t* gimbal_device_set_attitude)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mavlink_msg_gimbal_device_set_attitude_send(chan, gimbal_device_set_attitude->target_system, gimbal_device_set_attitude->target_component, gimbal_device_set_attitude->flags, gimbal_device_set_attitude->q, gimbal_device_set_attitude->angular_velocity_x, gimbal_device_set_attitude->angular_velocity_y, gimbal_device_set_attitude->angular_velocity_z);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GIMBAL_DEVICE_SET_ATTITUDE, (const char *)gimbal_device_set_attitude, MAVLINK_MSG_ID_GIMBAL_DEVICE_SET_ATTITUDE_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_DEVICE_SET_ATTITUDE_LEN, MAVLINK_MSG_ID_GIMBAL_DEVICE_SET_ATTITUDE_CRC);
#endif
}
#if MAVLINK_MSG_ID_GIMBAL_DEVICE_SET_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_gimbal_device_set_attitude_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t flags, const float *q, float angular_velocity_x, float angular_velocity_y, float angular_velocity_z)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
_mav_put_float(buf, 16, angular_velocity_x);
_mav_put_float(buf, 20, angular_velocity_y);
_mav_put_float(buf, 24, angular_velocity_z);
_mav_put_uint16_t(buf, 28, flags);
_mav_put_uint8_t(buf, 30, target_system);
_mav_put_uint8_t(buf, 31, target_component);
_mav_put_float_array(buf, 0, q, 4);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GIMBAL_DEVICE_SET_ATTITUDE, buf, MAVLINK_MSG_ID_GIMBAL_DEVICE_SET_ATTITUDE_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_DEVICE_SET_ATTITUDE_LEN, MAVLINK_MSG_ID_GIMBAL_DEVICE_SET_ATTITUDE_CRC);
#else
mavlink_gimbal_device_set_attitude_t *packet = (mavlink_gimbal_device_set_attitude_t *)msgbuf;
packet->angular_velocity_x = angular_velocity_x;
packet->angular_velocity_y = angular_velocity_y;
packet->angular_velocity_z = angular_velocity_z;
packet->flags = flags;
packet->target_system = target_system;
packet->target_component = target_component;
mav_array_memcpy(packet->q, q, sizeof(float)*4);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GIMBAL_DEVICE_SET_ATTITUDE, (const char *)packet, MAVLINK_MSG_ID_GIMBAL_DEVICE_SET_ATTITUDE_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_DEVICE_SET_ATTITUDE_LEN, MAVLINK_MSG_ID_GIMBAL_DEVICE_SET_ATTITUDE_CRC);
#endif
}
#endif
#endif
// MESSAGE GIMBAL_DEVICE_SET_ATTITUDE UNPACKING
/**
* @brief Get field target_system from gimbal_device_set_attitude message
*
* @return System ID
*/
static inline uint8_t mavlink_msg_gimbal_device_set_attitude_get_target_system(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 30);
}
/**
* @brief Get field target_component from gimbal_device_set_attitude message
*
* @return Component ID
*/
static inline uint8_t mavlink_msg_gimbal_device_set_attitude_get_target_component(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 31);
}
/**
* @brief Get field flags from gimbal_device_set_attitude message
*
* @return Low level gimbal flags.
*/
static inline uint16_t mavlink_msg_gimbal_device_set_attitude_get_flags(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 28);
}
/**
* @brief Get field q from gimbal_device_set_attitude message
*
* @return Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation, the frame is depends on whether the flag GIMBAL_DEVICE_FLAGS_YAW_LOCK is set, set all fields to NaN if only angular velocity should be used)
*/
static inline uint16_t mavlink_msg_gimbal_device_set_attitude_get_q(const mavlink_message_t* msg, float *q)
{
return _MAV_RETURN_float_array(msg, q, 4, 0);
}
/**
* @brief Get field angular_velocity_x from gimbal_device_set_attitude message
*
* @return [rad/s] X component of angular velocity, positive is rolling to the right, NaN to be ignored.
*/
static inline float mavlink_msg_gimbal_device_set_attitude_get_angular_velocity_x(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 16);
}
/**
* @brief Get field angular_velocity_y from gimbal_device_set_attitude message
*
* @return [rad/s] Y component of angular velocity, positive is pitching up, NaN to be ignored.
*/
static inline float mavlink_msg_gimbal_device_set_attitude_get_angular_velocity_y(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 20);
}
/**
* @brief Get field angular_velocity_z from gimbal_device_set_attitude message
*
* @return [rad/s] Z component of angular velocity, positive is yawing to the right, NaN to be ignored.
*/
static inline float mavlink_msg_gimbal_device_set_attitude_get_angular_velocity_z(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 24);
}
/**
* @brief Decode a gimbal_device_set_attitude message into a struct
*
* @param msg The message to decode
* @param gimbal_device_set_attitude C-struct to decode the message contents into
*/
static inline void mavlink_msg_gimbal_device_set_attitude_decode(const mavlink_message_t* msg, mavlink_gimbal_device_set_attitude_t* gimbal_device_set_attitude)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mavlink_msg_gimbal_device_set_attitude_get_q(msg, gimbal_device_set_attitude->q);
gimbal_device_set_attitude->angular_velocity_x = mavlink_msg_gimbal_device_set_attitude_get_angular_velocity_x(msg);
gimbal_device_set_attitude->angular_velocity_y = mavlink_msg_gimbal_device_set_attitude_get_angular_velocity_y(msg);
gimbal_device_set_attitude->angular_velocity_z = mavlink_msg_gimbal_device_set_attitude_get_angular_velocity_z(msg);
gimbal_device_set_attitude->flags = mavlink_msg_gimbal_device_set_attitude_get_flags(msg);
gimbal_device_set_attitude->target_system = mavlink_msg_gimbal_device_set_attitude_get_target_system(msg);
gimbal_device_set_attitude->target_component = mavlink_msg_gimbal_device_set_attitude_get_target_component(msg);
#else
uint8_t len = msg->len < MAVLINK_MSG_ID_GIMBAL_DEVICE_SET_ATTITUDE_LEN? msg->len : MAVLINK_MSG_ID_GIMBAL_DEVICE_SET_ATTITUDE_LEN;
memset(gimbal_device_set_attitude, 0, MAVLINK_MSG_ID_GIMBAL_DEVICE_SET_ATTITUDE_LEN);
memcpy(gimbal_device_set_attitude, _MAV_PAYLOAD(msg), len);
#endif
}

View file

@ -0,0 +1,413 @@
#pragma once
// MESSAGE GIMBAL_MANAGER_INFORMATION PACKING
#define MAVLINK_MSG_ID_GIMBAL_MANAGER_INFORMATION 280
typedef struct __mavlink_gimbal_manager_information_t {
uint32_t time_boot_ms; /*< [ms] Timestamp (time since system boot).*/
uint32_t cap_flags; /*< Bitmap of gimbal capability flags.*/
float roll_min; /*< [rad] Minimum hardware roll angle (positive: rolling to the right, negative: rolling to the left)*/
float roll_max; /*< [rad] Maximum hardware roll angle (positive: rolling to the right, negative: rolling to the left)*/
float pitch_min; /*< [rad] Minimum pitch angle (positive: up, negative: down)*/
float pitch_max; /*< [rad] Maximum pitch angle (positive: up, negative: down)*/
float yaw_min; /*< [rad] Minimum yaw angle (positive: to the right, negative: to the left)*/
float yaw_max; /*< [rad] Maximum yaw angle (positive: to the right, negative: to the left)*/
uint8_t gimbal_device_id; /*< Gimbal device ID that this gimbal manager is responsible for.*/
} mavlink_gimbal_manager_information_t;
#define MAVLINK_MSG_ID_GIMBAL_MANAGER_INFORMATION_LEN 33
#define MAVLINK_MSG_ID_GIMBAL_MANAGER_INFORMATION_MIN_LEN 33
#define MAVLINK_MSG_ID_280_LEN 33
#define MAVLINK_MSG_ID_280_MIN_LEN 33
#define MAVLINK_MSG_ID_GIMBAL_MANAGER_INFORMATION_CRC 70
#define MAVLINK_MSG_ID_280_CRC 70
#if MAVLINK_COMMAND_24BIT
#define MAVLINK_MESSAGE_INFO_GIMBAL_MANAGER_INFORMATION { \
280, \
"GIMBAL_MANAGER_INFORMATION", \
9, \
{ { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_gimbal_manager_information_t, time_boot_ms) }, \
{ "cap_flags", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_gimbal_manager_information_t, cap_flags) }, \
{ "gimbal_device_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_gimbal_manager_information_t, gimbal_device_id) }, \
{ "roll_min", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_gimbal_manager_information_t, roll_min) }, \
{ "roll_max", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_gimbal_manager_information_t, roll_max) }, \
{ "pitch_min", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_gimbal_manager_information_t, pitch_min) }, \
{ "pitch_max", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_gimbal_manager_information_t, pitch_max) }, \
{ "yaw_min", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_gimbal_manager_information_t, yaw_min) }, \
{ "yaw_max", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_gimbal_manager_information_t, yaw_max) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_GIMBAL_MANAGER_INFORMATION { \
"GIMBAL_MANAGER_INFORMATION", \
9, \
{ { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_gimbal_manager_information_t, time_boot_ms) }, \
{ "cap_flags", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_gimbal_manager_information_t, cap_flags) }, \
{ "gimbal_device_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_gimbal_manager_information_t, gimbal_device_id) }, \
{ "roll_min", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_gimbal_manager_information_t, roll_min) }, \
{ "roll_max", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_gimbal_manager_information_t, roll_max) }, \
{ "pitch_min", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_gimbal_manager_information_t, pitch_min) }, \
{ "pitch_max", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_gimbal_manager_information_t, pitch_max) }, \
{ "yaw_min", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_gimbal_manager_information_t, yaw_min) }, \
{ "yaw_max", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_gimbal_manager_information_t, yaw_max) }, \
} \
}
#endif
/**
* @brief Pack a gimbal_manager_information message
* @param system_id ID of this 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 [ms] Timestamp (time since system boot).
* @param cap_flags Bitmap of gimbal capability flags.
* @param gimbal_device_id Gimbal device ID that this gimbal manager is responsible for.
* @param roll_min [rad] Minimum hardware roll angle (positive: rolling to the right, negative: rolling to the left)
* @param roll_max [rad] Maximum hardware roll angle (positive: rolling to the right, negative: rolling to the left)
* @param pitch_min [rad] Minimum pitch angle (positive: up, negative: down)
* @param pitch_max [rad] Maximum pitch angle (positive: up, negative: down)
* @param yaw_min [rad] Minimum yaw angle (positive: to the right, negative: to the left)
* @param yaw_max [rad] Maximum yaw angle (positive: to the right, negative: to the left)
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_gimbal_manager_information_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint32_t time_boot_ms, uint32_t cap_flags, uint8_t gimbal_device_id, float roll_min, float roll_max, float pitch_min, float pitch_max, float yaw_min, float yaw_max)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_GIMBAL_MANAGER_INFORMATION_LEN];
_mav_put_uint32_t(buf, 0, time_boot_ms);
_mav_put_uint32_t(buf, 4, cap_flags);
_mav_put_float(buf, 8, roll_min);
_mav_put_float(buf, 12, roll_max);
_mav_put_float(buf, 16, pitch_min);
_mav_put_float(buf, 20, pitch_max);
_mav_put_float(buf, 24, yaw_min);
_mav_put_float(buf, 28, yaw_max);
_mav_put_uint8_t(buf, 32, gimbal_device_id);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GIMBAL_MANAGER_INFORMATION_LEN);
#else
mavlink_gimbal_manager_information_t packet;
packet.time_boot_ms = time_boot_ms;
packet.cap_flags = cap_flags;
packet.roll_min = roll_min;
packet.roll_max = roll_max;
packet.pitch_min = pitch_min;
packet.pitch_max = pitch_max;
packet.yaw_min = yaw_min;
packet.yaw_max = yaw_max;
packet.gimbal_device_id = gimbal_device_id;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GIMBAL_MANAGER_INFORMATION_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_GIMBAL_MANAGER_INFORMATION;
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GIMBAL_MANAGER_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_MANAGER_INFORMATION_LEN, MAVLINK_MSG_ID_GIMBAL_MANAGER_INFORMATION_CRC);
}
/**
* @brief Pack a gimbal_manager_information message on a channel
* @param system_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 [ms] Timestamp (time since system boot).
* @param cap_flags Bitmap of gimbal capability flags.
* @param gimbal_device_id Gimbal device ID that this gimbal manager is responsible for.
* @param roll_min [rad] Minimum hardware roll angle (positive: rolling to the right, negative: rolling to the left)
* @param roll_max [rad] Maximum hardware roll angle (positive: rolling to the right, negative: rolling to the left)
* @param pitch_min [rad] Minimum pitch angle (positive: up, negative: down)
* @param pitch_max [rad] Maximum pitch angle (positive: up, negative: down)
* @param yaw_min [rad] Minimum yaw angle (positive: to the right, negative: to the left)
* @param yaw_max [rad] Maximum yaw angle (positive: to the right, negative: to the left)
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_gimbal_manager_information_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint32_t time_boot_ms,uint32_t cap_flags,uint8_t gimbal_device_id,float roll_min,float roll_max,float pitch_min,float pitch_max,float yaw_min,float yaw_max)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_GIMBAL_MANAGER_INFORMATION_LEN];
_mav_put_uint32_t(buf, 0, time_boot_ms);
_mav_put_uint32_t(buf, 4, cap_flags);
_mav_put_float(buf, 8, roll_min);
_mav_put_float(buf, 12, roll_max);
_mav_put_float(buf, 16, pitch_min);
_mav_put_float(buf, 20, pitch_max);
_mav_put_float(buf, 24, yaw_min);
_mav_put_float(buf, 28, yaw_max);
_mav_put_uint8_t(buf, 32, gimbal_device_id);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GIMBAL_MANAGER_INFORMATION_LEN);
#else
mavlink_gimbal_manager_information_t packet;
packet.time_boot_ms = time_boot_ms;
packet.cap_flags = cap_flags;
packet.roll_min = roll_min;
packet.roll_max = roll_max;
packet.pitch_min = pitch_min;
packet.pitch_max = pitch_max;
packet.yaw_min = yaw_min;
packet.yaw_max = yaw_max;
packet.gimbal_device_id = gimbal_device_id;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GIMBAL_MANAGER_INFORMATION_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_GIMBAL_MANAGER_INFORMATION;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GIMBAL_MANAGER_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_MANAGER_INFORMATION_LEN, MAVLINK_MSG_ID_GIMBAL_MANAGER_INFORMATION_CRC);
}
/**
* @brief Encode a gimbal_manager_information 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 gimbal_manager_information C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_gimbal_manager_information_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gimbal_manager_information_t* gimbal_manager_information)
{
return mavlink_msg_gimbal_manager_information_pack(system_id, component_id, msg, gimbal_manager_information->time_boot_ms, gimbal_manager_information->cap_flags, gimbal_manager_information->gimbal_device_id, gimbal_manager_information->roll_min, gimbal_manager_information->roll_max, gimbal_manager_information->pitch_min, gimbal_manager_information->pitch_max, gimbal_manager_information->yaw_min, gimbal_manager_information->yaw_max);
}
/**
* @brief Encode a gimbal_manager_information 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 gimbal_manager_information C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_gimbal_manager_information_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_gimbal_manager_information_t* gimbal_manager_information)
{
return mavlink_msg_gimbal_manager_information_pack_chan(system_id, component_id, chan, msg, gimbal_manager_information->time_boot_ms, gimbal_manager_information->cap_flags, gimbal_manager_information->gimbal_device_id, gimbal_manager_information->roll_min, gimbal_manager_information->roll_max, gimbal_manager_information->pitch_min, gimbal_manager_information->pitch_max, gimbal_manager_information->yaw_min, gimbal_manager_information->yaw_max);
}
/**
* @brief Send a gimbal_manager_information message
* @param chan MAVLink channel to send the message
*
* @param time_boot_ms [ms] Timestamp (time since system boot).
* @param cap_flags Bitmap of gimbal capability flags.
* @param gimbal_device_id Gimbal device ID that this gimbal manager is responsible for.
* @param roll_min [rad] Minimum hardware roll angle (positive: rolling to the right, negative: rolling to the left)
* @param roll_max [rad] Maximum hardware roll angle (positive: rolling to the right, negative: rolling to the left)
* @param pitch_min [rad] Minimum pitch angle (positive: up, negative: down)
* @param pitch_max [rad] Maximum pitch angle (positive: up, negative: down)
* @param yaw_min [rad] Minimum yaw angle (positive: to the right, negative: to the left)
* @param yaw_max [rad] Maximum yaw angle (positive: to the right, negative: to the left)
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_gimbal_manager_information_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint32_t cap_flags, uint8_t gimbal_device_id, float roll_min, float roll_max, float pitch_min, float pitch_max, float yaw_min, float yaw_max)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_GIMBAL_MANAGER_INFORMATION_LEN];
_mav_put_uint32_t(buf, 0, time_boot_ms);
_mav_put_uint32_t(buf, 4, cap_flags);
_mav_put_float(buf, 8, roll_min);
_mav_put_float(buf, 12, roll_max);
_mav_put_float(buf, 16, pitch_min);
_mav_put_float(buf, 20, pitch_max);
_mav_put_float(buf, 24, yaw_min);
_mav_put_float(buf, 28, yaw_max);
_mav_put_uint8_t(buf, 32, gimbal_device_id);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GIMBAL_MANAGER_INFORMATION, buf, MAVLINK_MSG_ID_GIMBAL_MANAGER_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_MANAGER_INFORMATION_LEN, MAVLINK_MSG_ID_GIMBAL_MANAGER_INFORMATION_CRC);
#else
mavlink_gimbal_manager_information_t packet;
packet.time_boot_ms = time_boot_ms;
packet.cap_flags = cap_flags;
packet.roll_min = roll_min;
packet.roll_max = roll_max;
packet.pitch_min = pitch_min;
packet.pitch_max = pitch_max;
packet.yaw_min = yaw_min;
packet.yaw_max = yaw_max;
packet.gimbal_device_id = gimbal_device_id;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GIMBAL_MANAGER_INFORMATION, (const char *)&packet, MAVLINK_MSG_ID_GIMBAL_MANAGER_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_MANAGER_INFORMATION_LEN, MAVLINK_MSG_ID_GIMBAL_MANAGER_INFORMATION_CRC);
#endif
}
/**
* @brief Send a gimbal_manager_information message
* @param chan MAVLink channel to send the message
* @param struct The MAVLink struct to serialize
*/
static inline void mavlink_msg_gimbal_manager_information_send_struct(mavlink_channel_t chan, const mavlink_gimbal_manager_information_t* gimbal_manager_information)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mavlink_msg_gimbal_manager_information_send(chan, gimbal_manager_information->time_boot_ms, gimbal_manager_information->cap_flags, gimbal_manager_information->gimbal_device_id, gimbal_manager_information->roll_min, gimbal_manager_information->roll_max, gimbal_manager_information->pitch_min, gimbal_manager_information->pitch_max, gimbal_manager_information->yaw_min, gimbal_manager_information->yaw_max);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GIMBAL_MANAGER_INFORMATION, (const char *)gimbal_manager_information, MAVLINK_MSG_ID_GIMBAL_MANAGER_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_MANAGER_INFORMATION_LEN, MAVLINK_MSG_ID_GIMBAL_MANAGER_INFORMATION_CRC);
#endif
}
#if MAVLINK_MSG_ID_GIMBAL_MANAGER_INFORMATION_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_gimbal_manager_information_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, uint32_t cap_flags, uint8_t gimbal_device_id, float roll_min, float roll_max, float pitch_min, float pitch_max, float yaw_min, float yaw_max)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
_mav_put_uint32_t(buf, 0, time_boot_ms);
_mav_put_uint32_t(buf, 4, cap_flags);
_mav_put_float(buf, 8, roll_min);
_mav_put_float(buf, 12, roll_max);
_mav_put_float(buf, 16, pitch_min);
_mav_put_float(buf, 20, pitch_max);
_mav_put_float(buf, 24, yaw_min);
_mav_put_float(buf, 28, yaw_max);
_mav_put_uint8_t(buf, 32, gimbal_device_id);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GIMBAL_MANAGER_INFORMATION, buf, MAVLINK_MSG_ID_GIMBAL_MANAGER_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_MANAGER_INFORMATION_LEN, MAVLINK_MSG_ID_GIMBAL_MANAGER_INFORMATION_CRC);
#else
mavlink_gimbal_manager_information_t *packet = (mavlink_gimbal_manager_information_t *)msgbuf;
packet->time_boot_ms = time_boot_ms;
packet->cap_flags = cap_flags;
packet->roll_min = roll_min;
packet->roll_max = roll_max;
packet->pitch_min = pitch_min;
packet->pitch_max = pitch_max;
packet->yaw_min = yaw_min;
packet->yaw_max = yaw_max;
packet->gimbal_device_id = gimbal_device_id;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GIMBAL_MANAGER_INFORMATION, (const char *)packet, MAVLINK_MSG_ID_GIMBAL_MANAGER_INFORMATION_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_MANAGER_INFORMATION_LEN, MAVLINK_MSG_ID_GIMBAL_MANAGER_INFORMATION_CRC);
#endif
}
#endif
#endif
// MESSAGE GIMBAL_MANAGER_INFORMATION UNPACKING
/**
* @brief Get field time_boot_ms from gimbal_manager_information message
*
* @return [ms] Timestamp (time since system boot).
*/
static inline uint32_t mavlink_msg_gimbal_manager_information_get_time_boot_ms(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint32_t(msg, 0);
}
/**
* @brief Get field cap_flags from gimbal_manager_information message
*
* @return Bitmap of gimbal capability flags.
*/
static inline uint32_t mavlink_msg_gimbal_manager_information_get_cap_flags(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint32_t(msg, 4);
}
/**
* @brief Get field gimbal_device_id from gimbal_manager_information message
*
* @return Gimbal device ID that this gimbal manager is responsible for.
*/
static inline uint8_t mavlink_msg_gimbal_manager_information_get_gimbal_device_id(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 32);
}
/**
* @brief Get field roll_min from gimbal_manager_information message
*
* @return [rad] Minimum hardware roll angle (positive: rolling to the right, negative: rolling to the left)
*/
static inline float mavlink_msg_gimbal_manager_information_get_roll_min(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 8);
}
/**
* @brief Get field roll_max from gimbal_manager_information message
*
* @return [rad] Maximum hardware roll angle (positive: rolling to the right, negative: rolling to the left)
*/
static inline float mavlink_msg_gimbal_manager_information_get_roll_max(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 12);
}
/**
* @brief Get field pitch_min from gimbal_manager_information message
*
* @return [rad] Minimum pitch angle (positive: up, negative: down)
*/
static inline float mavlink_msg_gimbal_manager_information_get_pitch_min(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 16);
}
/**
* @brief Get field pitch_max from gimbal_manager_information message
*
* @return [rad] Maximum pitch angle (positive: up, negative: down)
*/
static inline float mavlink_msg_gimbal_manager_information_get_pitch_max(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 20);
}
/**
* @brief Get field yaw_min from gimbal_manager_information message
*
* @return [rad] Minimum yaw angle (positive: to the right, negative: to the left)
*/
static inline float mavlink_msg_gimbal_manager_information_get_yaw_min(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 24);
}
/**
* @brief Get field yaw_max from gimbal_manager_information message
*
* @return [rad] Maximum yaw angle (positive: to the right, negative: to the left)
*/
static inline float mavlink_msg_gimbal_manager_information_get_yaw_max(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 28);
}
/**
* @brief Decode a gimbal_manager_information message into a struct
*
* @param msg The message to decode
* @param gimbal_manager_information C-struct to decode the message contents into
*/
static inline void mavlink_msg_gimbal_manager_information_decode(const mavlink_message_t* msg, mavlink_gimbal_manager_information_t* gimbal_manager_information)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
gimbal_manager_information->time_boot_ms = mavlink_msg_gimbal_manager_information_get_time_boot_ms(msg);
gimbal_manager_information->cap_flags = mavlink_msg_gimbal_manager_information_get_cap_flags(msg);
gimbal_manager_information->roll_min = mavlink_msg_gimbal_manager_information_get_roll_min(msg);
gimbal_manager_information->roll_max = mavlink_msg_gimbal_manager_information_get_roll_max(msg);
gimbal_manager_information->pitch_min = mavlink_msg_gimbal_manager_information_get_pitch_min(msg);
gimbal_manager_information->pitch_max = mavlink_msg_gimbal_manager_information_get_pitch_max(msg);
gimbal_manager_information->yaw_min = mavlink_msg_gimbal_manager_information_get_yaw_min(msg);
gimbal_manager_information->yaw_max = mavlink_msg_gimbal_manager_information_get_yaw_max(msg);
gimbal_manager_information->gimbal_device_id = mavlink_msg_gimbal_manager_information_get_gimbal_device_id(msg);
#else
uint8_t len = msg->len < MAVLINK_MSG_ID_GIMBAL_MANAGER_INFORMATION_LEN? msg->len : MAVLINK_MSG_ID_GIMBAL_MANAGER_INFORMATION_LEN;
memset(gimbal_manager_information, 0, MAVLINK_MSG_ID_GIMBAL_MANAGER_INFORMATION_LEN);
memcpy(gimbal_manager_information, _MAV_PAYLOAD(msg), len);
#endif
}

View file

@ -0,0 +1,380 @@
#pragma once
// MESSAGE GIMBAL_MANAGER_SET_ATTITUDE PACKING
#define MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_ATTITUDE 282
typedef struct __mavlink_gimbal_manager_set_attitude_t {
uint32_t flags; /*< High level gimbal manager flags to use.*/
float q[4]; /*< Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation, the frame is depends on whether the flag GIMBAL_MANAGER_FLAGS_YAW_LOCK is set)*/
float angular_velocity_x; /*< [rad/s] X component of angular velocity, positive is rolling to the right, NaN to be ignored.*/
float angular_velocity_y; /*< [rad/s] Y component of angular velocity, positive is pitching up, NaN to be ignored.*/
float angular_velocity_z; /*< [rad/s] Z component of angular velocity, positive is yawing to the right, NaN to be ignored.*/
uint8_t target_system; /*< System ID*/
uint8_t target_component; /*< Component ID*/
uint8_t gimbal_device_id; /*< Component ID of gimbal device to address (or 1-6 for non-MAVLink gimbal), 0 for all gimbal device components. Send command multiple times for more than one gimbal (but not all gimbals).*/
} mavlink_gimbal_manager_set_attitude_t;
#define MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_ATTITUDE_LEN 35
#define MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_ATTITUDE_MIN_LEN 35
#define MAVLINK_MSG_ID_282_LEN 35
#define MAVLINK_MSG_ID_282_MIN_LEN 35
#define MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_ATTITUDE_CRC 123
#define MAVLINK_MSG_ID_282_CRC 123
#define MAVLINK_MSG_GIMBAL_MANAGER_SET_ATTITUDE_FIELD_Q_LEN 4
#if MAVLINK_COMMAND_24BIT
#define MAVLINK_MESSAGE_INFO_GIMBAL_MANAGER_SET_ATTITUDE { \
282, \
"GIMBAL_MANAGER_SET_ATTITUDE", \
8, \
{ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_gimbal_manager_set_attitude_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_gimbal_manager_set_attitude_t, target_component) }, \
{ "flags", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_gimbal_manager_set_attitude_t, flags) }, \
{ "gimbal_device_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_gimbal_manager_set_attitude_t, gimbal_device_id) }, \
{ "q", NULL, MAVLINK_TYPE_FLOAT, 4, 4, offsetof(mavlink_gimbal_manager_set_attitude_t, q) }, \
{ "angular_velocity_x", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_gimbal_manager_set_attitude_t, angular_velocity_x) }, \
{ "angular_velocity_y", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_gimbal_manager_set_attitude_t, angular_velocity_y) }, \
{ "angular_velocity_z", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_gimbal_manager_set_attitude_t, angular_velocity_z) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_GIMBAL_MANAGER_SET_ATTITUDE { \
"GIMBAL_MANAGER_SET_ATTITUDE", \
8, \
{ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_gimbal_manager_set_attitude_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 33, offsetof(mavlink_gimbal_manager_set_attitude_t, target_component) }, \
{ "flags", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_gimbal_manager_set_attitude_t, flags) }, \
{ "gimbal_device_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_gimbal_manager_set_attitude_t, gimbal_device_id) }, \
{ "q", NULL, MAVLINK_TYPE_FLOAT, 4, 4, offsetof(mavlink_gimbal_manager_set_attitude_t, q) }, \
{ "angular_velocity_x", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_gimbal_manager_set_attitude_t, angular_velocity_x) }, \
{ "angular_velocity_y", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_gimbal_manager_set_attitude_t, angular_velocity_y) }, \
{ "angular_velocity_z", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_gimbal_manager_set_attitude_t, angular_velocity_z) }, \
} \
}
#endif
/**
* @brief Pack a gimbal_manager_set_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 target_system System ID
* @param target_component Component ID
* @param flags High level gimbal manager flags to use.
* @param gimbal_device_id Component ID of gimbal device to address (or 1-6 for non-MAVLink gimbal), 0 for all gimbal device components. Send command multiple times for more than one gimbal (but not all gimbals).
* @param q Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation, the frame is depends on whether the flag GIMBAL_MANAGER_FLAGS_YAW_LOCK is set)
* @param angular_velocity_x [rad/s] X component of angular velocity, positive is rolling to the right, NaN to be ignored.
* @param angular_velocity_y [rad/s] Y component of angular velocity, positive is pitching up, NaN to be ignored.
* @param angular_velocity_z [rad/s] Z component of angular velocity, positive is yawing to the right, NaN to be ignored.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_gimbal_manager_set_attitude_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t target_system, uint8_t target_component, uint32_t flags, uint8_t gimbal_device_id, const float *q, float angular_velocity_x, float angular_velocity_y, float angular_velocity_z)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_ATTITUDE_LEN];
_mav_put_uint32_t(buf, 0, flags);
_mav_put_float(buf, 20, angular_velocity_x);
_mav_put_float(buf, 24, angular_velocity_y);
_mav_put_float(buf, 28, angular_velocity_z);
_mav_put_uint8_t(buf, 32, target_system);
_mav_put_uint8_t(buf, 33, target_component);
_mav_put_uint8_t(buf, 34, gimbal_device_id);
_mav_put_float_array(buf, 4, q, 4);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_ATTITUDE_LEN);
#else
mavlink_gimbal_manager_set_attitude_t packet;
packet.flags = flags;
packet.angular_velocity_x = angular_velocity_x;
packet.angular_velocity_y = angular_velocity_y;
packet.angular_velocity_z = angular_velocity_z;
packet.target_system = target_system;
packet.target_component = target_component;
packet.gimbal_device_id = gimbal_device_id;
mav_array_memcpy(packet.q, q, sizeof(float)*4);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_ATTITUDE_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_ATTITUDE;
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_ATTITUDE_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_ATTITUDE_LEN, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_ATTITUDE_CRC);
}
/**
* @brief Pack a gimbal_manager_set_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 target_system System ID
* @param target_component Component ID
* @param flags High level gimbal manager flags to use.
* @param gimbal_device_id Component ID of gimbal device to address (or 1-6 for non-MAVLink gimbal), 0 for all gimbal device components. Send command multiple times for more than one gimbal (but not all gimbals).
* @param q Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation, the frame is depends on whether the flag GIMBAL_MANAGER_FLAGS_YAW_LOCK is set)
* @param angular_velocity_x [rad/s] X component of angular velocity, positive is rolling to the right, NaN to be ignored.
* @param angular_velocity_y [rad/s] Y component of angular velocity, positive is pitching up, NaN to be ignored.
* @param angular_velocity_z [rad/s] Z component of angular velocity, positive is yawing to the right, NaN to be ignored.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_gimbal_manager_set_attitude_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,uint32_t flags,uint8_t gimbal_device_id,const float *q,float angular_velocity_x,float angular_velocity_y,float angular_velocity_z)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_ATTITUDE_LEN];
_mav_put_uint32_t(buf, 0, flags);
_mav_put_float(buf, 20, angular_velocity_x);
_mav_put_float(buf, 24, angular_velocity_y);
_mav_put_float(buf, 28, angular_velocity_z);
_mav_put_uint8_t(buf, 32, target_system);
_mav_put_uint8_t(buf, 33, target_component);
_mav_put_uint8_t(buf, 34, gimbal_device_id);
_mav_put_float_array(buf, 4, q, 4);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_ATTITUDE_LEN);
#else
mavlink_gimbal_manager_set_attitude_t packet;
packet.flags = flags;
packet.angular_velocity_x = angular_velocity_x;
packet.angular_velocity_y = angular_velocity_y;
packet.angular_velocity_z = angular_velocity_z;
packet.target_system = target_system;
packet.target_component = target_component;
packet.gimbal_device_id = gimbal_device_id;
mav_array_memcpy(packet.q, q, sizeof(float)*4);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_ATTITUDE_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_ATTITUDE;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_ATTITUDE_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_ATTITUDE_LEN, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_ATTITUDE_CRC);
}
/**
* @brief Encode a gimbal_manager_set_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 gimbal_manager_set_attitude C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_gimbal_manager_set_attitude_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gimbal_manager_set_attitude_t* gimbal_manager_set_attitude)
{
return mavlink_msg_gimbal_manager_set_attitude_pack(system_id, component_id, msg, gimbal_manager_set_attitude->target_system, gimbal_manager_set_attitude->target_component, gimbal_manager_set_attitude->flags, gimbal_manager_set_attitude->gimbal_device_id, gimbal_manager_set_attitude->q, gimbal_manager_set_attitude->angular_velocity_x, gimbal_manager_set_attitude->angular_velocity_y, gimbal_manager_set_attitude->angular_velocity_z);
}
/**
* @brief Encode a gimbal_manager_set_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 gimbal_manager_set_attitude C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_gimbal_manager_set_attitude_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_gimbal_manager_set_attitude_t* gimbal_manager_set_attitude)
{
return mavlink_msg_gimbal_manager_set_attitude_pack_chan(system_id, component_id, chan, msg, gimbal_manager_set_attitude->target_system, gimbal_manager_set_attitude->target_component, gimbal_manager_set_attitude->flags, gimbal_manager_set_attitude->gimbal_device_id, gimbal_manager_set_attitude->q, gimbal_manager_set_attitude->angular_velocity_x, gimbal_manager_set_attitude->angular_velocity_y, gimbal_manager_set_attitude->angular_velocity_z);
}
/**
* @brief Send a gimbal_manager_set_attitude message
* @param chan MAVLink channel to send the message
*
* @param target_system System ID
* @param target_component Component ID
* @param flags High level gimbal manager flags to use.
* @param gimbal_device_id Component ID of gimbal device to address (or 1-6 for non-MAVLink gimbal), 0 for all gimbal device components. Send command multiple times for more than one gimbal (but not all gimbals).
* @param q Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation, the frame is depends on whether the flag GIMBAL_MANAGER_FLAGS_YAW_LOCK is set)
* @param angular_velocity_x [rad/s] X component of angular velocity, positive is rolling to the right, NaN to be ignored.
* @param angular_velocity_y [rad/s] Y component of angular velocity, positive is pitching up, NaN to be ignored.
* @param angular_velocity_z [rad/s] Z component of angular velocity, positive is yawing to the right, NaN to be ignored.
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_gimbal_manager_set_attitude_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint32_t flags, uint8_t gimbal_device_id, const float *q, float angular_velocity_x, float angular_velocity_y, float angular_velocity_z)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_ATTITUDE_LEN];
_mav_put_uint32_t(buf, 0, flags);
_mav_put_float(buf, 20, angular_velocity_x);
_mav_put_float(buf, 24, angular_velocity_y);
_mav_put_float(buf, 28, angular_velocity_z);
_mav_put_uint8_t(buf, 32, target_system);
_mav_put_uint8_t(buf, 33, target_component);
_mav_put_uint8_t(buf, 34, gimbal_device_id);
_mav_put_float_array(buf, 4, q, 4);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_ATTITUDE, buf, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_ATTITUDE_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_ATTITUDE_LEN, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_ATTITUDE_CRC);
#else
mavlink_gimbal_manager_set_attitude_t packet;
packet.flags = flags;
packet.angular_velocity_x = angular_velocity_x;
packet.angular_velocity_y = angular_velocity_y;
packet.angular_velocity_z = angular_velocity_z;
packet.target_system = target_system;
packet.target_component = target_component;
packet.gimbal_device_id = gimbal_device_id;
mav_array_memcpy(packet.q, q, sizeof(float)*4);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_ATTITUDE, (const char *)&packet, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_ATTITUDE_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_ATTITUDE_LEN, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_ATTITUDE_CRC);
#endif
}
/**
* @brief Send a gimbal_manager_set_attitude message
* @param chan MAVLink channel to send the message
* @param struct The MAVLink struct to serialize
*/
static inline void mavlink_msg_gimbal_manager_set_attitude_send_struct(mavlink_channel_t chan, const mavlink_gimbal_manager_set_attitude_t* gimbal_manager_set_attitude)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mavlink_msg_gimbal_manager_set_attitude_send(chan, gimbal_manager_set_attitude->target_system, gimbal_manager_set_attitude->target_component, gimbal_manager_set_attitude->flags, gimbal_manager_set_attitude->gimbal_device_id, gimbal_manager_set_attitude->q, gimbal_manager_set_attitude->angular_velocity_x, gimbal_manager_set_attitude->angular_velocity_y, gimbal_manager_set_attitude->angular_velocity_z);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_ATTITUDE, (const char *)gimbal_manager_set_attitude, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_ATTITUDE_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_ATTITUDE_LEN, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_ATTITUDE_CRC);
#endif
}
#if MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_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_gimbal_manager_set_attitude_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint32_t flags, uint8_t gimbal_device_id, const float *q, float angular_velocity_x, float angular_velocity_y, float angular_velocity_z)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
_mav_put_uint32_t(buf, 0, flags);
_mav_put_float(buf, 20, angular_velocity_x);
_mav_put_float(buf, 24, angular_velocity_y);
_mav_put_float(buf, 28, angular_velocity_z);
_mav_put_uint8_t(buf, 32, target_system);
_mav_put_uint8_t(buf, 33, target_component);
_mav_put_uint8_t(buf, 34, gimbal_device_id);
_mav_put_float_array(buf, 4, q, 4);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_ATTITUDE, buf, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_ATTITUDE_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_ATTITUDE_LEN, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_ATTITUDE_CRC);
#else
mavlink_gimbal_manager_set_attitude_t *packet = (mavlink_gimbal_manager_set_attitude_t *)msgbuf;
packet->flags = flags;
packet->angular_velocity_x = angular_velocity_x;
packet->angular_velocity_y = angular_velocity_y;
packet->angular_velocity_z = angular_velocity_z;
packet->target_system = target_system;
packet->target_component = target_component;
packet->gimbal_device_id = gimbal_device_id;
mav_array_memcpy(packet->q, q, sizeof(float)*4);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_ATTITUDE, (const char *)packet, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_ATTITUDE_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_ATTITUDE_LEN, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_ATTITUDE_CRC);
#endif
}
#endif
#endif
// MESSAGE GIMBAL_MANAGER_SET_ATTITUDE UNPACKING
/**
* @brief Get field target_system from gimbal_manager_set_attitude message
*
* @return System ID
*/
static inline uint8_t mavlink_msg_gimbal_manager_set_attitude_get_target_system(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 32);
}
/**
* @brief Get field target_component from gimbal_manager_set_attitude message
*
* @return Component ID
*/
static inline uint8_t mavlink_msg_gimbal_manager_set_attitude_get_target_component(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 33);
}
/**
* @brief Get field flags from gimbal_manager_set_attitude message
*
* @return High level gimbal manager flags to use.
*/
static inline uint32_t mavlink_msg_gimbal_manager_set_attitude_get_flags(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint32_t(msg, 0);
}
/**
* @brief Get field gimbal_device_id from gimbal_manager_set_attitude message
*
* @return Component ID of gimbal device to address (or 1-6 for non-MAVLink gimbal), 0 for all gimbal device components. Send command multiple times for more than one gimbal (but not all gimbals).
*/
static inline uint8_t mavlink_msg_gimbal_manager_set_attitude_get_gimbal_device_id(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 34);
}
/**
* @brief Get field q from gimbal_manager_set_attitude message
*
* @return Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation, the frame is depends on whether the flag GIMBAL_MANAGER_FLAGS_YAW_LOCK is set)
*/
static inline uint16_t mavlink_msg_gimbal_manager_set_attitude_get_q(const mavlink_message_t* msg, float *q)
{
return _MAV_RETURN_float_array(msg, q, 4, 4);
}
/**
* @brief Get field angular_velocity_x from gimbal_manager_set_attitude message
*
* @return [rad/s] X component of angular velocity, positive is rolling to the right, NaN to be ignored.
*/
static inline float mavlink_msg_gimbal_manager_set_attitude_get_angular_velocity_x(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 20);
}
/**
* @brief Get field angular_velocity_y from gimbal_manager_set_attitude message
*
* @return [rad/s] Y component of angular velocity, positive is pitching up, NaN to be ignored.
*/
static inline float mavlink_msg_gimbal_manager_set_attitude_get_angular_velocity_y(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 24);
}
/**
* @brief Get field angular_velocity_z from gimbal_manager_set_attitude message
*
* @return [rad/s] Z component of angular velocity, positive is yawing to the right, NaN to be ignored.
*/
static inline float mavlink_msg_gimbal_manager_set_attitude_get_angular_velocity_z(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 28);
}
/**
* @brief Decode a gimbal_manager_set_attitude message into a struct
*
* @param msg The message to decode
* @param gimbal_manager_set_attitude C-struct to decode the message contents into
*/
static inline void mavlink_msg_gimbal_manager_set_attitude_decode(const mavlink_message_t* msg, mavlink_gimbal_manager_set_attitude_t* gimbal_manager_set_attitude)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
gimbal_manager_set_attitude->flags = mavlink_msg_gimbal_manager_set_attitude_get_flags(msg);
mavlink_msg_gimbal_manager_set_attitude_get_q(msg, gimbal_manager_set_attitude->q);
gimbal_manager_set_attitude->angular_velocity_x = mavlink_msg_gimbal_manager_set_attitude_get_angular_velocity_x(msg);
gimbal_manager_set_attitude->angular_velocity_y = mavlink_msg_gimbal_manager_set_attitude_get_angular_velocity_y(msg);
gimbal_manager_set_attitude->angular_velocity_z = mavlink_msg_gimbal_manager_set_attitude_get_angular_velocity_z(msg);
gimbal_manager_set_attitude->target_system = mavlink_msg_gimbal_manager_set_attitude_get_target_system(msg);
gimbal_manager_set_attitude->target_component = mavlink_msg_gimbal_manager_set_attitude_get_target_component(msg);
gimbal_manager_set_attitude->gimbal_device_id = mavlink_msg_gimbal_manager_set_attitude_get_gimbal_device_id(msg);
#else
uint8_t len = msg->len < MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_ATTITUDE_LEN? msg->len : MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_ATTITUDE_LEN;
memset(gimbal_manager_set_attitude, 0, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_ATTITUDE_LEN);
memcpy(gimbal_manager_set_attitude, _MAV_PAYLOAD(msg), len);
#endif
}

View file

@ -0,0 +1,388 @@
#pragma once
// MESSAGE GIMBAL_MANAGER_SET_MANUAL_CONTROL PACKING
#define MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_MANUAL_CONTROL 288
typedef struct __mavlink_gimbal_manager_set_manual_control_t {
uint32_t flags; /*< High level gimbal manager flags.*/
float pitch; /*< Pitch angle unitless (-1..1, positive: up, negative: down, NaN to be ignored).*/
float yaw; /*< Yaw angle unitless (-1..1, positive: to the right, negative: to the left, NaN to be ignored).*/
float pitch_rate; /*< Pitch angular rate unitless (-1..1, positive: up, negative: down, NaN to be ignored).*/
float yaw_rate; /*< Yaw angular rate unitless (-1..1, positive: to the right, negative: to the left, NaN to be ignored).*/
uint8_t target_system; /*< System ID*/
uint8_t target_component; /*< Component ID*/
uint8_t gimbal_device_id; /*< Component ID of gimbal device to address (or 1-6 for non-MAVLink gimbal), 0 for all gimbal device components. Send command multiple times for more than one gimbal (but not all gimbals).*/
} mavlink_gimbal_manager_set_manual_control_t;
#define MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_MANUAL_CONTROL_LEN 23
#define MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_MANUAL_CONTROL_MIN_LEN 23
#define MAVLINK_MSG_ID_288_LEN 23
#define MAVLINK_MSG_ID_288_MIN_LEN 23
#define MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_MANUAL_CONTROL_CRC 20
#define MAVLINK_MSG_ID_288_CRC 20
#if MAVLINK_COMMAND_24BIT
#define MAVLINK_MESSAGE_INFO_GIMBAL_MANAGER_SET_MANUAL_CONTROL { \
288, \
"GIMBAL_MANAGER_SET_MANUAL_CONTROL", \
8, \
{ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 20, offsetof(mavlink_gimbal_manager_set_manual_control_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 21, offsetof(mavlink_gimbal_manager_set_manual_control_t, target_component) }, \
{ "flags", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_gimbal_manager_set_manual_control_t, flags) }, \
{ "gimbal_device_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 22, offsetof(mavlink_gimbal_manager_set_manual_control_t, gimbal_device_id) }, \
{ "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_gimbal_manager_set_manual_control_t, pitch) }, \
{ "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_gimbal_manager_set_manual_control_t, yaw) }, \
{ "pitch_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_gimbal_manager_set_manual_control_t, pitch_rate) }, \
{ "yaw_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_gimbal_manager_set_manual_control_t, yaw_rate) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_GIMBAL_MANAGER_SET_MANUAL_CONTROL { \
"GIMBAL_MANAGER_SET_MANUAL_CONTROL", \
8, \
{ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 20, offsetof(mavlink_gimbal_manager_set_manual_control_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 21, offsetof(mavlink_gimbal_manager_set_manual_control_t, target_component) }, \
{ "flags", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_gimbal_manager_set_manual_control_t, flags) }, \
{ "gimbal_device_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 22, offsetof(mavlink_gimbal_manager_set_manual_control_t, gimbal_device_id) }, \
{ "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_gimbal_manager_set_manual_control_t, pitch) }, \
{ "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_gimbal_manager_set_manual_control_t, yaw) }, \
{ "pitch_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_gimbal_manager_set_manual_control_t, pitch_rate) }, \
{ "yaw_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_gimbal_manager_set_manual_control_t, yaw_rate) }, \
} \
}
#endif
/**
* @brief Pack a gimbal_manager_set_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_system System ID
* @param target_component Component ID
* @param flags High level gimbal manager flags.
* @param gimbal_device_id Component ID of gimbal device to address (or 1-6 for non-MAVLink gimbal), 0 for all gimbal device components. Send command multiple times for more than one gimbal (but not all gimbals).
* @param pitch Pitch angle unitless (-1..1, positive: up, negative: down, NaN to be ignored).
* @param yaw Yaw angle unitless (-1..1, positive: to the right, negative: to the left, NaN to be ignored).
* @param pitch_rate Pitch angular rate unitless (-1..1, positive: up, negative: down, NaN to be ignored).
* @param yaw_rate Yaw angular rate unitless (-1..1, positive: to the right, negative: to the left, NaN to be ignored).
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_gimbal_manager_set_manual_control_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t target_system, uint8_t target_component, uint32_t flags, uint8_t gimbal_device_id, float pitch, float yaw, float pitch_rate, float yaw_rate)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_MANUAL_CONTROL_LEN];
_mav_put_uint32_t(buf, 0, flags);
_mav_put_float(buf, 4, pitch);
_mav_put_float(buf, 8, yaw);
_mav_put_float(buf, 12, pitch_rate);
_mav_put_float(buf, 16, yaw_rate);
_mav_put_uint8_t(buf, 20, target_system);
_mav_put_uint8_t(buf, 21, target_component);
_mav_put_uint8_t(buf, 22, gimbal_device_id);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_MANUAL_CONTROL_LEN);
#else
mavlink_gimbal_manager_set_manual_control_t packet;
packet.flags = flags;
packet.pitch = pitch;
packet.yaw = yaw;
packet.pitch_rate = pitch_rate;
packet.yaw_rate = yaw_rate;
packet.target_system = target_system;
packet.target_component = target_component;
packet.gimbal_device_id = gimbal_device_id;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_MANUAL_CONTROL_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_MANUAL_CONTROL;
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_MANUAL_CONTROL_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_MANUAL_CONTROL_LEN, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_MANUAL_CONTROL_CRC);
}
/**
* @brief Pack a gimbal_manager_set_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_system System ID
* @param target_component Component ID
* @param flags High level gimbal manager flags.
* @param gimbal_device_id Component ID of gimbal device to address (or 1-6 for non-MAVLink gimbal), 0 for all gimbal device components. Send command multiple times for more than one gimbal (but not all gimbals).
* @param pitch Pitch angle unitless (-1..1, positive: up, negative: down, NaN to be ignored).
* @param yaw Yaw angle unitless (-1..1, positive: to the right, negative: to the left, NaN to be ignored).
* @param pitch_rate Pitch angular rate unitless (-1..1, positive: up, negative: down, NaN to be ignored).
* @param yaw_rate Yaw angular rate unitless (-1..1, positive: to the right, negative: to the left, NaN to be ignored).
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_gimbal_manager_set_manual_control_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint8_t target_system,uint8_t target_component,uint32_t flags,uint8_t gimbal_device_id,float pitch,float yaw,float pitch_rate,float yaw_rate)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_MANUAL_CONTROL_LEN];
_mav_put_uint32_t(buf, 0, flags);
_mav_put_float(buf, 4, pitch);
_mav_put_float(buf, 8, yaw);
_mav_put_float(buf, 12, pitch_rate);
_mav_put_float(buf, 16, yaw_rate);
_mav_put_uint8_t(buf, 20, target_system);
_mav_put_uint8_t(buf, 21, target_component);
_mav_put_uint8_t(buf, 22, gimbal_device_id);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_MANUAL_CONTROL_LEN);
#else
mavlink_gimbal_manager_set_manual_control_t packet;
packet.flags = flags;
packet.pitch = pitch;
packet.yaw = yaw;
packet.pitch_rate = pitch_rate;
packet.yaw_rate = yaw_rate;
packet.target_system = target_system;
packet.target_component = target_component;
packet.gimbal_device_id = gimbal_device_id;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_MANUAL_CONTROL_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_MANUAL_CONTROL;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_MANUAL_CONTROL_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_MANUAL_CONTROL_LEN, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_MANUAL_CONTROL_CRC);
}
/**
* @brief Encode a gimbal_manager_set_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 gimbal_manager_set_manual_control C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_gimbal_manager_set_manual_control_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gimbal_manager_set_manual_control_t* gimbal_manager_set_manual_control)
{
return mavlink_msg_gimbal_manager_set_manual_control_pack(system_id, component_id, msg, gimbal_manager_set_manual_control->target_system, gimbal_manager_set_manual_control->target_component, gimbal_manager_set_manual_control->flags, gimbal_manager_set_manual_control->gimbal_device_id, gimbal_manager_set_manual_control->pitch, gimbal_manager_set_manual_control->yaw, gimbal_manager_set_manual_control->pitch_rate, gimbal_manager_set_manual_control->yaw_rate);
}
/**
* @brief Encode a gimbal_manager_set_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 gimbal_manager_set_manual_control C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_gimbal_manager_set_manual_control_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_gimbal_manager_set_manual_control_t* gimbal_manager_set_manual_control)
{
return mavlink_msg_gimbal_manager_set_manual_control_pack_chan(system_id, component_id, chan, msg, gimbal_manager_set_manual_control->target_system, gimbal_manager_set_manual_control->target_component, gimbal_manager_set_manual_control->flags, gimbal_manager_set_manual_control->gimbal_device_id, gimbal_manager_set_manual_control->pitch, gimbal_manager_set_manual_control->yaw, gimbal_manager_set_manual_control->pitch_rate, gimbal_manager_set_manual_control->yaw_rate);
}
/**
* @brief Send a gimbal_manager_set_manual_control message
* @param chan MAVLink channel to send the message
*
* @param target_system System ID
* @param target_component Component ID
* @param flags High level gimbal manager flags.
* @param gimbal_device_id Component ID of gimbal device to address (or 1-6 for non-MAVLink gimbal), 0 for all gimbal device components. Send command multiple times for more than one gimbal (but not all gimbals).
* @param pitch Pitch angle unitless (-1..1, positive: up, negative: down, NaN to be ignored).
* @param yaw Yaw angle unitless (-1..1, positive: to the right, negative: to the left, NaN to be ignored).
* @param pitch_rate Pitch angular rate unitless (-1..1, positive: up, negative: down, NaN to be ignored).
* @param yaw_rate Yaw angular rate unitless (-1..1, positive: to the right, negative: to the left, NaN to be ignored).
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_gimbal_manager_set_manual_control_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint32_t flags, uint8_t gimbal_device_id, float pitch, float yaw, float pitch_rate, float yaw_rate)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_MANUAL_CONTROL_LEN];
_mav_put_uint32_t(buf, 0, flags);
_mav_put_float(buf, 4, pitch);
_mav_put_float(buf, 8, yaw);
_mav_put_float(buf, 12, pitch_rate);
_mav_put_float(buf, 16, yaw_rate);
_mav_put_uint8_t(buf, 20, target_system);
_mav_put_uint8_t(buf, 21, target_component);
_mav_put_uint8_t(buf, 22, gimbal_device_id);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_MANUAL_CONTROL, buf, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_MANUAL_CONTROL_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_MANUAL_CONTROL_LEN, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_MANUAL_CONTROL_CRC);
#else
mavlink_gimbal_manager_set_manual_control_t packet;
packet.flags = flags;
packet.pitch = pitch;
packet.yaw = yaw;
packet.pitch_rate = pitch_rate;
packet.yaw_rate = yaw_rate;
packet.target_system = target_system;
packet.target_component = target_component;
packet.gimbal_device_id = gimbal_device_id;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_MANUAL_CONTROL, (const char *)&packet, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_MANUAL_CONTROL_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_MANUAL_CONTROL_LEN, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_MANUAL_CONTROL_CRC);
#endif
}
/**
* @brief Send a gimbal_manager_set_manual_control message
* @param chan MAVLink channel to send the message
* @param struct The MAVLink struct to serialize
*/
static inline void mavlink_msg_gimbal_manager_set_manual_control_send_struct(mavlink_channel_t chan, const mavlink_gimbal_manager_set_manual_control_t* gimbal_manager_set_manual_control)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mavlink_msg_gimbal_manager_set_manual_control_send(chan, gimbal_manager_set_manual_control->target_system, gimbal_manager_set_manual_control->target_component, gimbal_manager_set_manual_control->flags, gimbal_manager_set_manual_control->gimbal_device_id, gimbal_manager_set_manual_control->pitch, gimbal_manager_set_manual_control->yaw, gimbal_manager_set_manual_control->pitch_rate, gimbal_manager_set_manual_control->yaw_rate);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_MANUAL_CONTROL, (const char *)gimbal_manager_set_manual_control, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_MANUAL_CONTROL_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_MANUAL_CONTROL_LEN, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_MANUAL_CONTROL_CRC);
#endif
}
#if MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_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_gimbal_manager_set_manual_control_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint32_t flags, uint8_t gimbal_device_id, float pitch, float yaw, float pitch_rate, float yaw_rate)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
_mav_put_uint32_t(buf, 0, flags);
_mav_put_float(buf, 4, pitch);
_mav_put_float(buf, 8, yaw);
_mav_put_float(buf, 12, pitch_rate);
_mav_put_float(buf, 16, yaw_rate);
_mav_put_uint8_t(buf, 20, target_system);
_mav_put_uint8_t(buf, 21, target_component);
_mav_put_uint8_t(buf, 22, gimbal_device_id);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_MANUAL_CONTROL, buf, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_MANUAL_CONTROL_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_MANUAL_CONTROL_LEN, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_MANUAL_CONTROL_CRC);
#else
mavlink_gimbal_manager_set_manual_control_t *packet = (mavlink_gimbal_manager_set_manual_control_t *)msgbuf;
packet->flags = flags;
packet->pitch = pitch;
packet->yaw = yaw;
packet->pitch_rate = pitch_rate;
packet->yaw_rate = yaw_rate;
packet->target_system = target_system;
packet->target_component = target_component;
packet->gimbal_device_id = gimbal_device_id;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_MANUAL_CONTROL, (const char *)packet, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_MANUAL_CONTROL_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_MANUAL_CONTROL_LEN, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_MANUAL_CONTROL_CRC);
#endif
}
#endif
#endif
// MESSAGE GIMBAL_MANAGER_SET_MANUAL_CONTROL UNPACKING
/**
* @brief Get field target_system from gimbal_manager_set_manual_control message
*
* @return System ID
*/
static inline uint8_t mavlink_msg_gimbal_manager_set_manual_control_get_target_system(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 20);
}
/**
* @brief Get field target_component from gimbal_manager_set_manual_control message
*
* @return Component ID
*/
static inline uint8_t mavlink_msg_gimbal_manager_set_manual_control_get_target_component(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 21);
}
/**
* @brief Get field flags from gimbal_manager_set_manual_control message
*
* @return High level gimbal manager flags.
*/
static inline uint32_t mavlink_msg_gimbal_manager_set_manual_control_get_flags(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint32_t(msg, 0);
}
/**
* @brief Get field gimbal_device_id from gimbal_manager_set_manual_control message
*
* @return Component ID of gimbal device to address (or 1-6 for non-MAVLink gimbal), 0 for all gimbal device components. Send command multiple times for more than one gimbal (but not all gimbals).
*/
static inline uint8_t mavlink_msg_gimbal_manager_set_manual_control_get_gimbal_device_id(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 22);
}
/**
* @brief Get field pitch from gimbal_manager_set_manual_control message
*
* @return Pitch angle unitless (-1..1, positive: up, negative: down, NaN to be ignored).
*/
static inline float mavlink_msg_gimbal_manager_set_manual_control_get_pitch(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 4);
}
/**
* @brief Get field yaw from gimbal_manager_set_manual_control message
*
* @return Yaw angle unitless (-1..1, positive: to the right, negative: to the left, NaN to be ignored).
*/
static inline float mavlink_msg_gimbal_manager_set_manual_control_get_yaw(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 8);
}
/**
* @brief Get field pitch_rate from gimbal_manager_set_manual_control message
*
* @return Pitch angular rate unitless (-1..1, positive: up, negative: down, NaN to be ignored).
*/
static inline float mavlink_msg_gimbal_manager_set_manual_control_get_pitch_rate(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 12);
}
/**
* @brief Get field yaw_rate from gimbal_manager_set_manual_control message
*
* @return Yaw angular rate unitless (-1..1, positive: to the right, negative: to the left, NaN to be ignored).
*/
static inline float mavlink_msg_gimbal_manager_set_manual_control_get_yaw_rate(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 16);
}
/**
* @brief Decode a gimbal_manager_set_manual_control message into a struct
*
* @param msg The message to decode
* @param gimbal_manager_set_manual_control C-struct to decode the message contents into
*/
static inline void mavlink_msg_gimbal_manager_set_manual_control_decode(const mavlink_message_t* msg, mavlink_gimbal_manager_set_manual_control_t* gimbal_manager_set_manual_control)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
gimbal_manager_set_manual_control->flags = mavlink_msg_gimbal_manager_set_manual_control_get_flags(msg);
gimbal_manager_set_manual_control->pitch = mavlink_msg_gimbal_manager_set_manual_control_get_pitch(msg);
gimbal_manager_set_manual_control->yaw = mavlink_msg_gimbal_manager_set_manual_control_get_yaw(msg);
gimbal_manager_set_manual_control->pitch_rate = mavlink_msg_gimbal_manager_set_manual_control_get_pitch_rate(msg);
gimbal_manager_set_manual_control->yaw_rate = mavlink_msg_gimbal_manager_set_manual_control_get_yaw_rate(msg);
gimbal_manager_set_manual_control->target_system = mavlink_msg_gimbal_manager_set_manual_control_get_target_system(msg);
gimbal_manager_set_manual_control->target_component = mavlink_msg_gimbal_manager_set_manual_control_get_target_component(msg);
gimbal_manager_set_manual_control->gimbal_device_id = mavlink_msg_gimbal_manager_set_manual_control_get_gimbal_device_id(msg);
#else
uint8_t len = msg->len < MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_MANUAL_CONTROL_LEN? msg->len : MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_MANUAL_CONTROL_LEN;
memset(gimbal_manager_set_manual_control, 0, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_MANUAL_CONTROL_LEN);
memcpy(gimbal_manager_set_manual_control, _MAV_PAYLOAD(msg), len);
#endif
}

View file

@ -0,0 +1,388 @@
#pragma once
// MESSAGE GIMBAL_MANAGER_SET_PITCHYAW PACKING
#define MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_PITCHYAW 287
typedef struct __mavlink_gimbal_manager_set_pitchyaw_t {
uint32_t flags; /*< High level gimbal manager flags to use.*/
float pitch; /*< [rad] Pitch angle (positive: up, negative: down, NaN to be ignored).*/
float yaw; /*< [rad] Yaw angle (positive: to the right, negative: to the left, NaN to be ignored).*/
float pitch_rate; /*< [rad/s] Pitch angular rate (positive: up, negative: down, NaN to be ignored).*/
float yaw_rate; /*< [rad/s] Yaw angular rate (positive: to the right, negative: to the left, NaN to be ignored).*/
uint8_t target_system; /*< System ID*/
uint8_t target_component; /*< Component ID*/
uint8_t gimbal_device_id; /*< Component ID of gimbal device to address (or 1-6 for non-MAVLink gimbal), 0 for all gimbal device components. Send command multiple times for more than one gimbal (but not all gimbals).*/
} mavlink_gimbal_manager_set_pitchyaw_t;
#define MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_PITCHYAW_LEN 23
#define MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_PITCHYAW_MIN_LEN 23
#define MAVLINK_MSG_ID_287_LEN 23
#define MAVLINK_MSG_ID_287_MIN_LEN 23
#define MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_PITCHYAW_CRC 1
#define MAVLINK_MSG_ID_287_CRC 1
#if MAVLINK_COMMAND_24BIT
#define MAVLINK_MESSAGE_INFO_GIMBAL_MANAGER_SET_PITCHYAW { \
287, \
"GIMBAL_MANAGER_SET_PITCHYAW", \
8, \
{ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 20, offsetof(mavlink_gimbal_manager_set_pitchyaw_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 21, offsetof(mavlink_gimbal_manager_set_pitchyaw_t, target_component) }, \
{ "flags", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_gimbal_manager_set_pitchyaw_t, flags) }, \
{ "gimbal_device_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 22, offsetof(mavlink_gimbal_manager_set_pitchyaw_t, gimbal_device_id) }, \
{ "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_gimbal_manager_set_pitchyaw_t, pitch) }, \
{ "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_gimbal_manager_set_pitchyaw_t, yaw) }, \
{ "pitch_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_gimbal_manager_set_pitchyaw_t, pitch_rate) }, \
{ "yaw_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_gimbal_manager_set_pitchyaw_t, yaw_rate) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_GIMBAL_MANAGER_SET_PITCHYAW { \
"GIMBAL_MANAGER_SET_PITCHYAW", \
8, \
{ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 20, offsetof(mavlink_gimbal_manager_set_pitchyaw_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 21, offsetof(mavlink_gimbal_manager_set_pitchyaw_t, target_component) }, \
{ "flags", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_gimbal_manager_set_pitchyaw_t, flags) }, \
{ "gimbal_device_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 22, offsetof(mavlink_gimbal_manager_set_pitchyaw_t, gimbal_device_id) }, \
{ "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_gimbal_manager_set_pitchyaw_t, pitch) }, \
{ "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_gimbal_manager_set_pitchyaw_t, yaw) }, \
{ "pitch_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_gimbal_manager_set_pitchyaw_t, pitch_rate) }, \
{ "yaw_rate", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_gimbal_manager_set_pitchyaw_t, yaw_rate) }, \
} \
}
#endif
/**
* @brief Pack a gimbal_manager_set_pitchyaw message
* @param system_id ID of this 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 flags High level gimbal manager flags to use.
* @param gimbal_device_id Component ID of gimbal device to address (or 1-6 for non-MAVLink gimbal), 0 for all gimbal device components. Send command multiple times for more than one gimbal (but not all gimbals).
* @param pitch [rad] Pitch angle (positive: up, negative: down, NaN to be ignored).
* @param yaw [rad] Yaw angle (positive: to the right, negative: to the left, NaN to be ignored).
* @param pitch_rate [rad/s] Pitch angular rate (positive: up, negative: down, NaN to be ignored).
* @param yaw_rate [rad/s] Yaw angular rate (positive: to the right, negative: to the left, NaN to be ignored).
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_gimbal_manager_set_pitchyaw_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t target_system, uint8_t target_component, uint32_t flags, uint8_t gimbal_device_id, float pitch, float yaw, float pitch_rate, float yaw_rate)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_PITCHYAW_LEN];
_mav_put_uint32_t(buf, 0, flags);
_mav_put_float(buf, 4, pitch);
_mav_put_float(buf, 8, yaw);
_mav_put_float(buf, 12, pitch_rate);
_mav_put_float(buf, 16, yaw_rate);
_mav_put_uint8_t(buf, 20, target_system);
_mav_put_uint8_t(buf, 21, target_component);
_mav_put_uint8_t(buf, 22, gimbal_device_id);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_PITCHYAW_LEN);
#else
mavlink_gimbal_manager_set_pitchyaw_t packet;
packet.flags = flags;
packet.pitch = pitch;
packet.yaw = yaw;
packet.pitch_rate = pitch_rate;
packet.yaw_rate = yaw_rate;
packet.target_system = target_system;
packet.target_component = target_component;
packet.gimbal_device_id = gimbal_device_id;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_PITCHYAW_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_PITCHYAW;
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_PITCHYAW_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_PITCHYAW_LEN, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_PITCHYAW_CRC);
}
/**
* @brief Pack a gimbal_manager_set_pitchyaw message on a channel
* @param system_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 flags High level gimbal manager flags to use.
* @param gimbal_device_id Component ID of gimbal device to address (or 1-6 for non-MAVLink gimbal), 0 for all gimbal device components. Send command multiple times for more than one gimbal (but not all gimbals).
* @param pitch [rad] Pitch angle (positive: up, negative: down, NaN to be ignored).
* @param yaw [rad] Yaw angle (positive: to the right, negative: to the left, NaN to be ignored).
* @param pitch_rate [rad/s] Pitch angular rate (positive: up, negative: down, NaN to be ignored).
* @param yaw_rate [rad/s] Yaw angular rate (positive: to the right, negative: to the left, NaN to be ignored).
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_gimbal_manager_set_pitchyaw_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,uint32_t flags,uint8_t gimbal_device_id,float pitch,float yaw,float pitch_rate,float yaw_rate)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_PITCHYAW_LEN];
_mav_put_uint32_t(buf, 0, flags);
_mav_put_float(buf, 4, pitch);
_mav_put_float(buf, 8, yaw);
_mav_put_float(buf, 12, pitch_rate);
_mav_put_float(buf, 16, yaw_rate);
_mav_put_uint8_t(buf, 20, target_system);
_mav_put_uint8_t(buf, 21, target_component);
_mav_put_uint8_t(buf, 22, gimbal_device_id);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_PITCHYAW_LEN);
#else
mavlink_gimbal_manager_set_pitchyaw_t packet;
packet.flags = flags;
packet.pitch = pitch;
packet.yaw = yaw;
packet.pitch_rate = pitch_rate;
packet.yaw_rate = yaw_rate;
packet.target_system = target_system;
packet.target_component = target_component;
packet.gimbal_device_id = gimbal_device_id;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_PITCHYAW_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_PITCHYAW;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_PITCHYAW_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_PITCHYAW_LEN, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_PITCHYAW_CRC);
}
/**
* @brief Encode a gimbal_manager_set_pitchyaw 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 gimbal_manager_set_pitchyaw C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_gimbal_manager_set_pitchyaw_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gimbal_manager_set_pitchyaw_t* gimbal_manager_set_pitchyaw)
{
return mavlink_msg_gimbal_manager_set_pitchyaw_pack(system_id, component_id, msg, gimbal_manager_set_pitchyaw->target_system, gimbal_manager_set_pitchyaw->target_component, gimbal_manager_set_pitchyaw->flags, gimbal_manager_set_pitchyaw->gimbal_device_id, gimbal_manager_set_pitchyaw->pitch, gimbal_manager_set_pitchyaw->yaw, gimbal_manager_set_pitchyaw->pitch_rate, gimbal_manager_set_pitchyaw->yaw_rate);
}
/**
* @brief Encode a gimbal_manager_set_pitchyaw 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 gimbal_manager_set_pitchyaw C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_gimbal_manager_set_pitchyaw_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_gimbal_manager_set_pitchyaw_t* gimbal_manager_set_pitchyaw)
{
return mavlink_msg_gimbal_manager_set_pitchyaw_pack_chan(system_id, component_id, chan, msg, gimbal_manager_set_pitchyaw->target_system, gimbal_manager_set_pitchyaw->target_component, gimbal_manager_set_pitchyaw->flags, gimbal_manager_set_pitchyaw->gimbal_device_id, gimbal_manager_set_pitchyaw->pitch, gimbal_manager_set_pitchyaw->yaw, gimbal_manager_set_pitchyaw->pitch_rate, gimbal_manager_set_pitchyaw->yaw_rate);
}
/**
* @brief Send a gimbal_manager_set_pitchyaw message
* @param chan MAVLink channel to send the message
*
* @param target_system System ID
* @param target_component Component ID
* @param flags High level gimbal manager flags to use.
* @param gimbal_device_id Component ID of gimbal device to address (or 1-6 for non-MAVLink gimbal), 0 for all gimbal device components. Send command multiple times for more than one gimbal (but not all gimbals).
* @param pitch [rad] Pitch angle (positive: up, negative: down, NaN to be ignored).
* @param yaw [rad] Yaw angle (positive: to the right, negative: to the left, NaN to be ignored).
* @param pitch_rate [rad/s] Pitch angular rate (positive: up, negative: down, NaN to be ignored).
* @param yaw_rate [rad/s] Yaw angular rate (positive: to the right, negative: to the left, NaN to be ignored).
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_gimbal_manager_set_pitchyaw_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint32_t flags, uint8_t gimbal_device_id, float pitch, float yaw, float pitch_rate, float yaw_rate)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_PITCHYAW_LEN];
_mav_put_uint32_t(buf, 0, flags);
_mav_put_float(buf, 4, pitch);
_mav_put_float(buf, 8, yaw);
_mav_put_float(buf, 12, pitch_rate);
_mav_put_float(buf, 16, yaw_rate);
_mav_put_uint8_t(buf, 20, target_system);
_mav_put_uint8_t(buf, 21, target_component);
_mav_put_uint8_t(buf, 22, gimbal_device_id);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_PITCHYAW, buf, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_PITCHYAW_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_PITCHYAW_LEN, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_PITCHYAW_CRC);
#else
mavlink_gimbal_manager_set_pitchyaw_t packet;
packet.flags = flags;
packet.pitch = pitch;
packet.yaw = yaw;
packet.pitch_rate = pitch_rate;
packet.yaw_rate = yaw_rate;
packet.target_system = target_system;
packet.target_component = target_component;
packet.gimbal_device_id = gimbal_device_id;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_PITCHYAW, (const char *)&packet, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_PITCHYAW_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_PITCHYAW_LEN, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_PITCHYAW_CRC);
#endif
}
/**
* @brief Send a gimbal_manager_set_pitchyaw message
* @param chan MAVLink channel to send the message
* @param struct The MAVLink struct to serialize
*/
static inline void mavlink_msg_gimbal_manager_set_pitchyaw_send_struct(mavlink_channel_t chan, const mavlink_gimbal_manager_set_pitchyaw_t* gimbal_manager_set_pitchyaw)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mavlink_msg_gimbal_manager_set_pitchyaw_send(chan, gimbal_manager_set_pitchyaw->target_system, gimbal_manager_set_pitchyaw->target_component, gimbal_manager_set_pitchyaw->flags, gimbal_manager_set_pitchyaw->gimbal_device_id, gimbal_manager_set_pitchyaw->pitch, gimbal_manager_set_pitchyaw->yaw, gimbal_manager_set_pitchyaw->pitch_rate, gimbal_manager_set_pitchyaw->yaw_rate);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_PITCHYAW, (const char *)gimbal_manager_set_pitchyaw, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_PITCHYAW_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_PITCHYAW_LEN, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_PITCHYAW_CRC);
#endif
}
#if MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_PITCHYAW_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_gimbal_manager_set_pitchyaw_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint32_t flags, uint8_t gimbal_device_id, float pitch, float yaw, float pitch_rate, float yaw_rate)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
_mav_put_uint32_t(buf, 0, flags);
_mav_put_float(buf, 4, pitch);
_mav_put_float(buf, 8, yaw);
_mav_put_float(buf, 12, pitch_rate);
_mav_put_float(buf, 16, yaw_rate);
_mav_put_uint8_t(buf, 20, target_system);
_mav_put_uint8_t(buf, 21, target_component);
_mav_put_uint8_t(buf, 22, gimbal_device_id);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_PITCHYAW, buf, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_PITCHYAW_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_PITCHYAW_LEN, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_PITCHYAW_CRC);
#else
mavlink_gimbal_manager_set_pitchyaw_t *packet = (mavlink_gimbal_manager_set_pitchyaw_t *)msgbuf;
packet->flags = flags;
packet->pitch = pitch;
packet->yaw = yaw;
packet->pitch_rate = pitch_rate;
packet->yaw_rate = yaw_rate;
packet->target_system = target_system;
packet->target_component = target_component;
packet->gimbal_device_id = gimbal_device_id;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_PITCHYAW, (const char *)packet, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_PITCHYAW_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_PITCHYAW_LEN, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_PITCHYAW_CRC);
#endif
}
#endif
#endif
// MESSAGE GIMBAL_MANAGER_SET_PITCHYAW UNPACKING
/**
* @brief Get field target_system from gimbal_manager_set_pitchyaw message
*
* @return System ID
*/
static inline uint8_t mavlink_msg_gimbal_manager_set_pitchyaw_get_target_system(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 20);
}
/**
* @brief Get field target_component from gimbal_manager_set_pitchyaw message
*
* @return Component ID
*/
static inline uint8_t mavlink_msg_gimbal_manager_set_pitchyaw_get_target_component(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 21);
}
/**
* @brief Get field flags from gimbal_manager_set_pitchyaw message
*
* @return High level gimbal manager flags to use.
*/
static inline uint32_t mavlink_msg_gimbal_manager_set_pitchyaw_get_flags(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint32_t(msg, 0);
}
/**
* @brief Get field gimbal_device_id from gimbal_manager_set_pitchyaw message
*
* @return Component ID of gimbal device to address (or 1-6 for non-MAVLink gimbal), 0 for all gimbal device components. Send command multiple times for more than one gimbal (but not all gimbals).
*/
static inline uint8_t mavlink_msg_gimbal_manager_set_pitchyaw_get_gimbal_device_id(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 22);
}
/**
* @brief Get field pitch from gimbal_manager_set_pitchyaw message
*
* @return [rad] Pitch angle (positive: up, negative: down, NaN to be ignored).
*/
static inline float mavlink_msg_gimbal_manager_set_pitchyaw_get_pitch(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 4);
}
/**
* @brief Get field yaw from gimbal_manager_set_pitchyaw message
*
* @return [rad] Yaw angle (positive: to the right, negative: to the left, NaN to be ignored).
*/
static inline float mavlink_msg_gimbal_manager_set_pitchyaw_get_yaw(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 8);
}
/**
* @brief Get field pitch_rate from gimbal_manager_set_pitchyaw message
*
* @return [rad/s] Pitch angular rate (positive: up, negative: down, NaN to be ignored).
*/
static inline float mavlink_msg_gimbal_manager_set_pitchyaw_get_pitch_rate(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 12);
}
/**
* @brief Get field yaw_rate from gimbal_manager_set_pitchyaw message
*
* @return [rad/s] Yaw angular rate (positive: to the right, negative: to the left, NaN to be ignored).
*/
static inline float mavlink_msg_gimbal_manager_set_pitchyaw_get_yaw_rate(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 16);
}
/**
* @brief Decode a gimbal_manager_set_pitchyaw message into a struct
*
* @param msg The message to decode
* @param gimbal_manager_set_pitchyaw C-struct to decode the message contents into
*/
static inline void mavlink_msg_gimbal_manager_set_pitchyaw_decode(const mavlink_message_t* msg, mavlink_gimbal_manager_set_pitchyaw_t* gimbal_manager_set_pitchyaw)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
gimbal_manager_set_pitchyaw->flags = mavlink_msg_gimbal_manager_set_pitchyaw_get_flags(msg);
gimbal_manager_set_pitchyaw->pitch = mavlink_msg_gimbal_manager_set_pitchyaw_get_pitch(msg);
gimbal_manager_set_pitchyaw->yaw = mavlink_msg_gimbal_manager_set_pitchyaw_get_yaw(msg);
gimbal_manager_set_pitchyaw->pitch_rate = mavlink_msg_gimbal_manager_set_pitchyaw_get_pitch_rate(msg);
gimbal_manager_set_pitchyaw->yaw_rate = mavlink_msg_gimbal_manager_set_pitchyaw_get_yaw_rate(msg);
gimbal_manager_set_pitchyaw->target_system = mavlink_msg_gimbal_manager_set_pitchyaw_get_target_system(msg);
gimbal_manager_set_pitchyaw->target_component = mavlink_msg_gimbal_manager_set_pitchyaw_get_target_component(msg);
gimbal_manager_set_pitchyaw->gimbal_device_id = mavlink_msg_gimbal_manager_set_pitchyaw_get_gimbal_device_id(msg);
#else
uint8_t len = msg->len < MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_PITCHYAW_LEN? msg->len : MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_PITCHYAW_LEN;
memset(gimbal_manager_set_pitchyaw, 0, MAVLINK_MSG_ID_GIMBAL_MANAGER_SET_PITCHYAW_LEN);
memcpy(gimbal_manager_set_pitchyaw, _MAV_PAYLOAD(msg), len);
#endif
}

View file

@ -0,0 +1,363 @@
#pragma once
// MESSAGE GIMBAL_MANAGER_STATUS PACKING
#define MAVLINK_MSG_ID_GIMBAL_MANAGER_STATUS 281
typedef struct __mavlink_gimbal_manager_status_t {
uint32_t time_boot_ms; /*< [ms] Timestamp (time since system boot).*/
uint32_t flags; /*< High level gimbal manager flags currently applied.*/
uint8_t gimbal_device_id; /*< Gimbal device ID that this gimbal manager is responsible for.*/
uint8_t primary_control_sysid; /*< System ID of MAVLink component with primary control, 0 for none.*/
uint8_t primary_control_compid; /*< Component ID of MAVLink component with primary control, 0 for none.*/
uint8_t secondary_control_sysid; /*< System ID of MAVLink component with secondary control, 0 for none.*/
uint8_t secondary_control_compid; /*< Component ID of MAVLink component with secondary control, 0 for none.*/
} mavlink_gimbal_manager_status_t;
#define MAVLINK_MSG_ID_GIMBAL_MANAGER_STATUS_LEN 13
#define MAVLINK_MSG_ID_GIMBAL_MANAGER_STATUS_MIN_LEN 13
#define MAVLINK_MSG_ID_281_LEN 13
#define MAVLINK_MSG_ID_281_MIN_LEN 13
#define MAVLINK_MSG_ID_GIMBAL_MANAGER_STATUS_CRC 48
#define MAVLINK_MSG_ID_281_CRC 48
#if MAVLINK_COMMAND_24BIT
#define MAVLINK_MESSAGE_INFO_GIMBAL_MANAGER_STATUS { \
281, \
"GIMBAL_MANAGER_STATUS", \
7, \
{ { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_gimbal_manager_status_t, time_boot_ms) }, \
{ "flags", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_gimbal_manager_status_t, flags) }, \
{ "gimbal_device_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_gimbal_manager_status_t, gimbal_device_id) }, \
{ "primary_control_sysid", NULL, MAVLINK_TYPE_UINT8_T, 0, 9, offsetof(mavlink_gimbal_manager_status_t, primary_control_sysid) }, \
{ "primary_control_compid", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_gimbal_manager_status_t, primary_control_compid) }, \
{ "secondary_control_sysid", NULL, MAVLINK_TYPE_UINT8_T, 0, 11, offsetof(mavlink_gimbal_manager_status_t, secondary_control_sysid) }, \
{ "secondary_control_compid", NULL, MAVLINK_TYPE_UINT8_T, 0, 12, offsetof(mavlink_gimbal_manager_status_t, secondary_control_compid) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_GIMBAL_MANAGER_STATUS { \
"GIMBAL_MANAGER_STATUS", \
7, \
{ { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_gimbal_manager_status_t, time_boot_ms) }, \
{ "flags", NULL, MAVLINK_TYPE_UINT32_T, 0, 4, offsetof(mavlink_gimbal_manager_status_t, flags) }, \
{ "gimbal_device_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 8, offsetof(mavlink_gimbal_manager_status_t, gimbal_device_id) }, \
{ "primary_control_sysid", NULL, MAVLINK_TYPE_UINT8_T, 0, 9, offsetof(mavlink_gimbal_manager_status_t, primary_control_sysid) }, \
{ "primary_control_compid", NULL, MAVLINK_TYPE_UINT8_T, 0, 10, offsetof(mavlink_gimbal_manager_status_t, primary_control_compid) }, \
{ "secondary_control_sysid", NULL, MAVLINK_TYPE_UINT8_T, 0, 11, offsetof(mavlink_gimbal_manager_status_t, secondary_control_sysid) }, \
{ "secondary_control_compid", NULL, MAVLINK_TYPE_UINT8_T, 0, 12, offsetof(mavlink_gimbal_manager_status_t, secondary_control_compid) }, \
} \
}
#endif
/**
* @brief Pack a gimbal_manager_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 time_boot_ms [ms] Timestamp (time since system boot).
* @param flags High level gimbal manager flags currently applied.
* @param gimbal_device_id Gimbal device ID that this gimbal manager is responsible for.
* @param primary_control_sysid System ID of MAVLink component with primary control, 0 for none.
* @param primary_control_compid Component ID of MAVLink component with primary control, 0 for none.
* @param secondary_control_sysid System ID of MAVLink component with secondary control, 0 for none.
* @param secondary_control_compid Component ID of MAVLink component with secondary control, 0 for none.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_gimbal_manager_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint32_t time_boot_ms, uint32_t flags, uint8_t gimbal_device_id, uint8_t primary_control_sysid, uint8_t primary_control_compid, uint8_t secondary_control_sysid, uint8_t secondary_control_compid)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_GIMBAL_MANAGER_STATUS_LEN];
_mav_put_uint32_t(buf, 0, time_boot_ms);
_mav_put_uint32_t(buf, 4, flags);
_mav_put_uint8_t(buf, 8, gimbal_device_id);
_mav_put_uint8_t(buf, 9, primary_control_sysid);
_mav_put_uint8_t(buf, 10, primary_control_compid);
_mav_put_uint8_t(buf, 11, secondary_control_sysid);
_mav_put_uint8_t(buf, 12, secondary_control_compid);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GIMBAL_MANAGER_STATUS_LEN);
#else
mavlink_gimbal_manager_status_t packet;
packet.time_boot_ms = time_boot_ms;
packet.flags = flags;
packet.gimbal_device_id = gimbal_device_id;
packet.primary_control_sysid = primary_control_sysid;
packet.primary_control_compid = primary_control_compid;
packet.secondary_control_sysid = secondary_control_sysid;
packet.secondary_control_compid = secondary_control_compid;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GIMBAL_MANAGER_STATUS_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_GIMBAL_MANAGER_STATUS;
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_GIMBAL_MANAGER_STATUS_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_MANAGER_STATUS_LEN, MAVLINK_MSG_ID_GIMBAL_MANAGER_STATUS_CRC);
}
/**
* @brief Pack a gimbal_manager_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 time_boot_ms [ms] Timestamp (time since system boot).
* @param flags High level gimbal manager flags currently applied.
* @param gimbal_device_id Gimbal device ID that this gimbal manager is responsible for.
* @param primary_control_sysid System ID of MAVLink component with primary control, 0 for none.
* @param primary_control_compid Component ID of MAVLink component with primary control, 0 for none.
* @param secondary_control_sysid System ID of MAVLink component with secondary control, 0 for none.
* @param secondary_control_compid Component ID of MAVLink component with secondary control, 0 for none.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_gimbal_manager_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint32_t time_boot_ms,uint32_t flags,uint8_t gimbal_device_id,uint8_t primary_control_sysid,uint8_t primary_control_compid,uint8_t secondary_control_sysid,uint8_t secondary_control_compid)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_GIMBAL_MANAGER_STATUS_LEN];
_mav_put_uint32_t(buf, 0, time_boot_ms);
_mav_put_uint32_t(buf, 4, flags);
_mav_put_uint8_t(buf, 8, gimbal_device_id);
_mav_put_uint8_t(buf, 9, primary_control_sysid);
_mav_put_uint8_t(buf, 10, primary_control_compid);
_mav_put_uint8_t(buf, 11, secondary_control_sysid);
_mav_put_uint8_t(buf, 12, secondary_control_compid);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GIMBAL_MANAGER_STATUS_LEN);
#else
mavlink_gimbal_manager_status_t packet;
packet.time_boot_ms = time_boot_ms;
packet.flags = flags;
packet.gimbal_device_id = gimbal_device_id;
packet.primary_control_sysid = primary_control_sysid;
packet.primary_control_compid = primary_control_compid;
packet.secondary_control_sysid = secondary_control_sysid;
packet.secondary_control_compid = secondary_control_compid;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GIMBAL_MANAGER_STATUS_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_GIMBAL_MANAGER_STATUS;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_GIMBAL_MANAGER_STATUS_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_MANAGER_STATUS_LEN, MAVLINK_MSG_ID_GIMBAL_MANAGER_STATUS_CRC);
}
/**
* @brief Encode a gimbal_manager_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 gimbal_manager_status C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_gimbal_manager_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gimbal_manager_status_t* gimbal_manager_status)
{
return mavlink_msg_gimbal_manager_status_pack(system_id, component_id, msg, gimbal_manager_status->time_boot_ms, gimbal_manager_status->flags, gimbal_manager_status->gimbal_device_id, gimbal_manager_status->primary_control_sysid, gimbal_manager_status->primary_control_compid, gimbal_manager_status->secondary_control_sysid, gimbal_manager_status->secondary_control_compid);
}
/**
* @brief Encode a gimbal_manager_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 gimbal_manager_status C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_gimbal_manager_status_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_gimbal_manager_status_t* gimbal_manager_status)
{
return mavlink_msg_gimbal_manager_status_pack_chan(system_id, component_id, chan, msg, gimbal_manager_status->time_boot_ms, gimbal_manager_status->flags, gimbal_manager_status->gimbal_device_id, gimbal_manager_status->primary_control_sysid, gimbal_manager_status->primary_control_compid, gimbal_manager_status->secondary_control_sysid, gimbal_manager_status->secondary_control_compid);
}
/**
* @brief Send a gimbal_manager_status message
* @param chan MAVLink channel to send the message
*
* @param time_boot_ms [ms] Timestamp (time since system boot).
* @param flags High level gimbal manager flags currently applied.
* @param gimbal_device_id Gimbal device ID that this gimbal manager is responsible for.
* @param primary_control_sysid System ID of MAVLink component with primary control, 0 for none.
* @param primary_control_compid Component ID of MAVLink component with primary control, 0 for none.
* @param secondary_control_sysid System ID of MAVLink component with secondary control, 0 for none.
* @param secondary_control_compid Component ID of MAVLink component with secondary control, 0 for none.
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_gimbal_manager_status_send(mavlink_channel_t chan, uint32_t time_boot_ms, uint32_t flags, uint8_t gimbal_device_id, uint8_t primary_control_sysid, uint8_t primary_control_compid, uint8_t secondary_control_sysid, uint8_t secondary_control_compid)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_GIMBAL_MANAGER_STATUS_LEN];
_mav_put_uint32_t(buf, 0, time_boot_ms);
_mav_put_uint32_t(buf, 4, flags);
_mav_put_uint8_t(buf, 8, gimbal_device_id);
_mav_put_uint8_t(buf, 9, primary_control_sysid);
_mav_put_uint8_t(buf, 10, primary_control_compid);
_mav_put_uint8_t(buf, 11, secondary_control_sysid);
_mav_put_uint8_t(buf, 12, secondary_control_compid);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GIMBAL_MANAGER_STATUS, buf, MAVLINK_MSG_ID_GIMBAL_MANAGER_STATUS_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_MANAGER_STATUS_LEN, MAVLINK_MSG_ID_GIMBAL_MANAGER_STATUS_CRC);
#else
mavlink_gimbal_manager_status_t packet;
packet.time_boot_ms = time_boot_ms;
packet.flags = flags;
packet.gimbal_device_id = gimbal_device_id;
packet.primary_control_sysid = primary_control_sysid;
packet.primary_control_compid = primary_control_compid;
packet.secondary_control_sysid = secondary_control_sysid;
packet.secondary_control_compid = secondary_control_compid;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GIMBAL_MANAGER_STATUS, (const char *)&packet, MAVLINK_MSG_ID_GIMBAL_MANAGER_STATUS_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_MANAGER_STATUS_LEN, MAVLINK_MSG_ID_GIMBAL_MANAGER_STATUS_CRC);
#endif
}
/**
* @brief Send a gimbal_manager_status message
* @param chan MAVLink channel to send the message
* @param struct The MAVLink struct to serialize
*/
static inline void mavlink_msg_gimbal_manager_status_send_struct(mavlink_channel_t chan, const mavlink_gimbal_manager_status_t* gimbal_manager_status)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mavlink_msg_gimbal_manager_status_send(chan, gimbal_manager_status->time_boot_ms, gimbal_manager_status->flags, gimbal_manager_status->gimbal_device_id, gimbal_manager_status->primary_control_sysid, gimbal_manager_status->primary_control_compid, gimbal_manager_status->secondary_control_sysid, gimbal_manager_status->secondary_control_compid);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GIMBAL_MANAGER_STATUS, (const char *)gimbal_manager_status, MAVLINK_MSG_ID_GIMBAL_MANAGER_STATUS_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_MANAGER_STATUS_LEN, MAVLINK_MSG_ID_GIMBAL_MANAGER_STATUS_CRC);
#endif
}
#if MAVLINK_MSG_ID_GIMBAL_MANAGER_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_gimbal_manager_status_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, uint32_t flags, uint8_t gimbal_device_id, uint8_t primary_control_sysid, uint8_t primary_control_compid, uint8_t secondary_control_sysid, uint8_t secondary_control_compid)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
_mav_put_uint32_t(buf, 0, time_boot_ms);
_mav_put_uint32_t(buf, 4, flags);
_mav_put_uint8_t(buf, 8, gimbal_device_id);
_mav_put_uint8_t(buf, 9, primary_control_sysid);
_mav_put_uint8_t(buf, 10, primary_control_compid);
_mav_put_uint8_t(buf, 11, secondary_control_sysid);
_mav_put_uint8_t(buf, 12, secondary_control_compid);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GIMBAL_MANAGER_STATUS, buf, MAVLINK_MSG_ID_GIMBAL_MANAGER_STATUS_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_MANAGER_STATUS_LEN, MAVLINK_MSG_ID_GIMBAL_MANAGER_STATUS_CRC);
#else
mavlink_gimbal_manager_status_t *packet = (mavlink_gimbal_manager_status_t *)msgbuf;
packet->time_boot_ms = time_boot_ms;
packet->flags = flags;
packet->gimbal_device_id = gimbal_device_id;
packet->primary_control_sysid = primary_control_sysid;
packet->primary_control_compid = primary_control_compid;
packet->secondary_control_sysid = secondary_control_sysid;
packet->secondary_control_compid = secondary_control_compid;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GIMBAL_MANAGER_STATUS, (const char *)packet, MAVLINK_MSG_ID_GIMBAL_MANAGER_STATUS_MIN_LEN, MAVLINK_MSG_ID_GIMBAL_MANAGER_STATUS_LEN, MAVLINK_MSG_ID_GIMBAL_MANAGER_STATUS_CRC);
#endif
}
#endif
#endif
// MESSAGE GIMBAL_MANAGER_STATUS UNPACKING
/**
* @brief Get field time_boot_ms from gimbal_manager_status message
*
* @return [ms] Timestamp (time since system boot).
*/
static inline uint32_t mavlink_msg_gimbal_manager_status_get_time_boot_ms(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint32_t(msg, 0);
}
/**
* @brief Get field flags from gimbal_manager_status message
*
* @return High level gimbal manager flags currently applied.
*/
static inline uint32_t mavlink_msg_gimbal_manager_status_get_flags(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint32_t(msg, 4);
}
/**
* @brief Get field gimbal_device_id from gimbal_manager_status message
*
* @return Gimbal device ID that this gimbal manager is responsible for.
*/
static inline uint8_t mavlink_msg_gimbal_manager_status_get_gimbal_device_id(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 8);
}
/**
* @brief Get field primary_control_sysid from gimbal_manager_status message
*
* @return System ID of MAVLink component with primary control, 0 for none.
*/
static inline uint8_t mavlink_msg_gimbal_manager_status_get_primary_control_sysid(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 9);
}
/**
* @brief Get field primary_control_compid from gimbal_manager_status message
*
* @return Component ID of MAVLink component with primary control, 0 for none.
*/
static inline uint8_t mavlink_msg_gimbal_manager_status_get_primary_control_compid(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 10);
}
/**
* @brief Get field secondary_control_sysid from gimbal_manager_status message
*
* @return System ID of MAVLink component with secondary control, 0 for none.
*/
static inline uint8_t mavlink_msg_gimbal_manager_status_get_secondary_control_sysid(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 11);
}
/**
* @brief Get field secondary_control_compid from gimbal_manager_status message
*
* @return Component ID of MAVLink component with secondary control, 0 for none.
*/
static inline uint8_t mavlink_msg_gimbal_manager_status_get_secondary_control_compid(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 12);
}
/**
* @brief Decode a gimbal_manager_status message into a struct
*
* @param msg The message to decode
* @param gimbal_manager_status C-struct to decode the message contents into
*/
static inline void mavlink_msg_gimbal_manager_status_decode(const mavlink_message_t* msg, mavlink_gimbal_manager_status_t* gimbal_manager_status)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
gimbal_manager_status->time_boot_ms = mavlink_msg_gimbal_manager_status_get_time_boot_ms(msg);
gimbal_manager_status->flags = mavlink_msg_gimbal_manager_status_get_flags(msg);
gimbal_manager_status->gimbal_device_id = mavlink_msg_gimbal_manager_status_get_gimbal_device_id(msg);
gimbal_manager_status->primary_control_sysid = mavlink_msg_gimbal_manager_status_get_primary_control_sysid(msg);
gimbal_manager_status->primary_control_compid = mavlink_msg_gimbal_manager_status_get_primary_control_compid(msg);
gimbal_manager_status->secondary_control_sysid = mavlink_msg_gimbal_manager_status_get_secondary_control_sysid(msg);
gimbal_manager_status->secondary_control_compid = mavlink_msg_gimbal_manager_status_get_secondary_control_compid(msg);
#else
uint8_t len = msg->len < MAVLINK_MSG_ID_GIMBAL_MANAGER_STATUS_LEN? msg->len : MAVLINK_MSG_ID_GIMBAL_MANAGER_STATUS_LEN;
memset(gimbal_manager_status, 0, MAVLINK_MSG_ID_GIMBAL_MANAGER_STATUS_LEN);
memcpy(gimbal_manager_status, _MAV_PAYLOAD(msg), len);
#endif
}

View file

@ -12,23 +12,25 @@ typedef struct __mavlink_global_vision_position_estimate_t {
float roll; /*< [rad] Roll angle*/
float pitch; /*< [rad] Pitch angle*/
float yaw; /*< [rad] Yaw angle*/
float covariance[21]; /*< Row-major representation of pose 6x6 cross-covariance matrix upper right triangle (states: x_global, y_global, z_global, roll, pitch, yaw; first six entries are the first ROW, next five entries are the second ROW, etc.). If unknown, assign NaN value to first element in the array.*/
uint8_t reset_counter; /*< Estimate reset counter. This should be incremented when the estimate resets in any of the dimensions (position, velocity, attitude, angular speed). This is designed to be used when e.g an external SLAM system detects a loop-closure and the estimate jumps.*/
} mavlink_global_vision_position_estimate_t;
#define MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN 32
#define MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN 117
#define MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_MIN_LEN 32
#define MAVLINK_MSG_ID_101_LEN 32
#define MAVLINK_MSG_ID_101_LEN 117
#define MAVLINK_MSG_ID_101_MIN_LEN 32
#define MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_CRC 102
#define MAVLINK_MSG_ID_101_CRC 102
#define MAVLINK_MSG_GLOBAL_VISION_POSITION_ESTIMATE_FIELD_COVARIANCE_LEN 21
#if MAVLINK_COMMAND_24BIT
#define MAVLINK_MESSAGE_INFO_GLOBAL_VISION_POSITION_ESTIMATE { \
101, \
"GLOBAL_VISION_POSITION_ESTIMATE", \
7, \
9, \
{ { "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) }, \
@ -36,12 +38,14 @@ typedef struct __mavlink_global_vision_position_estimate_t {
{ "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) }, \
{ "covariance", NULL, MAVLINK_TYPE_FLOAT, 21, 32, offsetof(mavlink_global_vision_position_estimate_t, covariance) }, \
{ "reset_counter", NULL, MAVLINK_TYPE_UINT8_T, 0, 116, offsetof(mavlink_global_vision_position_estimate_t, reset_counter) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_GLOBAL_VISION_POSITION_ESTIMATE { \
"GLOBAL_VISION_POSITION_ESTIMATE", \
7, \
9, \
{ { "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) }, \
@ -49,6 +53,8 @@ typedef struct __mavlink_global_vision_position_estimate_t {
{ "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) }, \
{ "covariance", NULL, MAVLINK_TYPE_FLOAT, 21, 32, offsetof(mavlink_global_vision_position_estimate_t, covariance) }, \
{ "reset_counter", NULL, MAVLINK_TYPE_UINT8_T, 0, 116, offsetof(mavlink_global_vision_position_estimate_t, reset_counter) }, \
} \
}
#endif
@ -66,10 +72,12 @@ typedef struct __mavlink_global_vision_position_estimate_t {
* @param roll [rad] Roll angle
* @param pitch [rad] Pitch angle
* @param yaw [rad] Yaw angle
* @param covariance Row-major representation of pose 6x6 cross-covariance matrix upper right triangle (states: x_global, y_global, z_global, roll, pitch, yaw; first six entries are the first ROW, next five entries are the second ROW, etc.). If unknown, assign NaN value to first element in the array.
* @param reset_counter Estimate reset counter. This should be incremented when the estimate resets in any of the dimensions (position, velocity, attitude, angular speed). This is designed to be used when e.g an external SLAM system detects a loop-closure and the estimate jumps.
* @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)
uint64_t usec, float x, float y, float z, float roll, float pitch, float yaw, const float *covariance, uint8_t reset_counter)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN];
@ -80,7 +88,8 @@ static inline uint16_t mavlink_msg_global_vision_position_estimate_pack(uint8_t
_mav_put_float(buf, 20, roll);
_mav_put_float(buf, 24, pitch);
_mav_put_float(buf, 28, yaw);
_mav_put_uint8_t(buf, 116, reset_counter);
_mav_put_float_array(buf, 32, covariance, 21);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN);
#else
mavlink_global_vision_position_estimate_t packet;
@ -91,7 +100,8 @@ static inline uint16_t mavlink_msg_global_vision_position_estimate_pack(uint8_t
packet.roll = roll;
packet.pitch = pitch;
packet.yaw = yaw;
packet.reset_counter = reset_counter;
mav_array_memcpy(packet.covariance, covariance, sizeof(float)*21);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN);
#endif
@ -112,11 +122,13 @@ static inline uint16_t mavlink_msg_global_vision_position_estimate_pack(uint8_t
* @param roll [rad] Roll angle
* @param pitch [rad] Pitch angle
* @param yaw [rad] Yaw angle
* @param covariance Row-major representation of pose 6x6 cross-covariance matrix upper right triangle (states: x_global, y_global, z_global, roll, pitch, yaw; first six entries are the first ROW, next five entries are the second ROW, etc.). If unknown, assign NaN value to first element in the array.
* @param reset_counter Estimate reset counter. This should be incremented when the estimate resets in any of the dimensions (position, velocity, attitude, angular speed). This is designed to be used when e.g an external SLAM system detects a loop-closure and the estimate jumps.
* @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)
uint64_t usec,float x,float y,float z,float roll,float pitch,float yaw,const float *covariance,uint8_t reset_counter)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN];
@ -127,7 +139,8 @@ static inline uint16_t mavlink_msg_global_vision_position_estimate_pack_chan(uin
_mav_put_float(buf, 20, roll);
_mav_put_float(buf, 24, pitch);
_mav_put_float(buf, 28, yaw);
_mav_put_uint8_t(buf, 116, reset_counter);
_mav_put_float_array(buf, 32, covariance, 21);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN);
#else
mavlink_global_vision_position_estimate_t packet;
@ -138,7 +151,8 @@ static inline uint16_t mavlink_msg_global_vision_position_estimate_pack_chan(uin
packet.roll = roll;
packet.pitch = pitch;
packet.yaw = yaw;
packet.reset_counter = reset_counter;
mav_array_memcpy(packet.covariance, covariance, sizeof(float)*21);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN);
#endif
@ -156,7 +170,7 @@ static inline uint16_t mavlink_msg_global_vision_position_estimate_pack_chan(uin
*/
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);
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, global_vision_position_estimate->covariance, global_vision_position_estimate->reset_counter);
}
/**
@ -170,7 +184,7 @@ static inline uint16_t mavlink_msg_global_vision_position_estimate_encode(uint8_
*/
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);
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, global_vision_position_estimate->covariance, global_vision_position_estimate->reset_counter);
}
/**
@ -184,10 +198,12 @@ static inline uint16_t mavlink_msg_global_vision_position_estimate_encode_chan(u
* @param roll [rad] Roll angle
* @param pitch [rad] Pitch angle
* @param yaw [rad] Yaw angle
* @param covariance Row-major representation of pose 6x6 cross-covariance matrix upper right triangle (states: x_global, y_global, z_global, roll, pitch, yaw; first six entries are the first ROW, next five entries are the second ROW, etc.). If unknown, assign NaN value to first element in the array.
* @param reset_counter Estimate reset counter. This should be incremented when the estimate resets in any of the dimensions (position, velocity, attitude, angular speed). This is designed to be used when e.g an external SLAM system detects a loop-closure and the estimate jumps.
*/
#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)
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, const float *covariance, uint8_t reset_counter)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN];
@ -198,7 +214,8 @@ static inline void mavlink_msg_global_vision_position_estimate_send(mavlink_chan
_mav_put_float(buf, 20, roll);
_mav_put_float(buf, 24, pitch);
_mav_put_float(buf, 28, yaw);
_mav_put_uint8_t(buf, 116, reset_counter);
_mav_put_float_array(buf, 32, covariance, 21);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE, buf, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_MIN_LEN, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_CRC);
#else
mavlink_global_vision_position_estimate_t packet;
@ -209,7 +226,8 @@ static inline void mavlink_msg_global_vision_position_estimate_send(mavlink_chan
packet.roll = roll;
packet.pitch = pitch;
packet.yaw = yaw;
packet.reset_counter = reset_counter;
mav_array_memcpy(packet.covariance, covariance, sizeof(float)*21);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE, (const char *)&packet, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_MIN_LEN, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_CRC);
#endif
}
@ -222,7 +240,7 @@ static inline void mavlink_msg_global_vision_position_estimate_send(mavlink_chan
static inline void mavlink_msg_global_vision_position_estimate_send_struct(mavlink_channel_t chan, const mavlink_global_vision_position_estimate_t* global_vision_position_estimate)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mavlink_msg_global_vision_position_estimate_send(chan, 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);
mavlink_msg_global_vision_position_estimate_send(chan, 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, global_vision_position_estimate->covariance, global_vision_position_estimate->reset_counter);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE, (const char *)global_vision_position_estimate, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_MIN_LEN, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_CRC);
#endif
@ -236,7 +254,7 @@ static inline void mavlink_msg_global_vision_position_estimate_send_struct(mavli
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)
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, const float *covariance, uint8_t reset_counter)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
@ -247,7 +265,8 @@ static inline void mavlink_msg_global_vision_position_estimate_send_buf(mavlink_
_mav_put_float(buf, 20, roll);
_mav_put_float(buf, 24, pitch);
_mav_put_float(buf, 28, yaw);
_mav_put_uint8_t(buf, 116, reset_counter);
_mav_put_float_array(buf, 32, covariance, 21);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE, buf, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_MIN_LEN, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_CRC);
#else
mavlink_global_vision_position_estimate_t *packet = (mavlink_global_vision_position_estimate_t *)msgbuf;
@ -258,7 +277,8 @@ static inline void mavlink_msg_global_vision_position_estimate_send_buf(mavlink_
packet->roll = roll;
packet->pitch = pitch;
packet->yaw = yaw;
packet->reset_counter = reset_counter;
mav_array_memcpy(packet->covariance, covariance, sizeof(float)*21);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE, (const char *)packet, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_MIN_LEN, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_CRC);
#endif
}
@ -339,6 +359,26 @@ static inline float mavlink_msg_global_vision_position_estimate_get_yaw(const ma
return _MAV_RETURN_float(msg, 28);
}
/**
* @brief Get field covariance from global_vision_position_estimate message
*
* @return Row-major representation of pose 6x6 cross-covariance matrix upper right triangle (states: x_global, y_global, z_global, roll, pitch, yaw; first six entries are the first ROW, next five entries are the second ROW, etc.). If unknown, assign NaN value to first element in the array.
*/
static inline uint16_t mavlink_msg_global_vision_position_estimate_get_covariance(const mavlink_message_t* msg, float *covariance)
{
return _MAV_RETURN_float_array(msg, covariance, 21, 32);
}
/**
* @brief Get field reset_counter from global_vision_position_estimate message
*
* @return Estimate reset counter. This should be incremented when the estimate resets in any of the dimensions (position, velocity, attitude, angular speed). This is designed to be used when e.g an external SLAM system detects a loop-closure and the estimate jumps.
*/
static inline uint8_t mavlink_msg_global_vision_position_estimate_get_reset_counter(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 116);
}
/**
* @brief Decode a global_vision_position_estimate message into a struct
*
@ -355,6 +395,8 @@ static inline void mavlink_msg_global_vision_position_estimate_decode(const mavl
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);
mavlink_msg_global_vision_position_estimate_get_covariance(msg, global_vision_position_estimate->covariance);
global_vision_position_estimate->reset_counter = mavlink_msg_global_vision_position_estimate_get_reset_counter(msg);
#else
uint8_t len = msg->len < MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN? msg->len : MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN;
memset(global_vision_position_estimate, 0, MAVLINK_MSG_ID_GLOBAL_VISION_POSITION_ESTIMATE_LEN);

View file

@ -3,25 +3,26 @@
#define MAVLINK_MSG_ID_GPS2_RAW 124
MAVPACKED(
typedef struct __mavlink_gps2_raw_t {
uint64_t time_usec; /*< [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.*/
int32_t lat; /*< [degE7] Latitude (WGS84)*/
int32_t lon; /*< [degE7] Longitude (WGS84)*/
int32_t alt; /*< [mm] Altitude (MSL). Positive for up.*/
uint32_t dgps_age; /*< [ms] Age of DGPS info*/
uint16_t eph; /*< [cm] GPS HDOP horizontal dilution of position. If unknown, set to: UINT16_MAX*/
uint16_t epv; /*< [cm] GPS VDOP vertical dilution of position. If unknown, set to: UINT16_MAX*/
uint16_t eph; /*< GPS HDOP horizontal dilution of position (unitless). If unknown, set to: UINT16_MAX*/
uint16_t epv; /*< GPS VDOP vertical dilution of position (unitless). If unknown, set to: UINT16_MAX*/
uint16_t vel; /*< [cm/s] GPS ground speed. If unknown, set to: UINT16_MAX*/
uint16_t cog; /*< [cdeg] Course over ground (NOT heading, but direction of movement): 0.0..359.99 degrees. If unknown, set to: UINT16_MAX*/
uint8_t fix_type; /*< GPS fix type.*/
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;
uint16_t yaw; /*< [cdeg] Yaw in earth frame from north. Use 0 if this GPS does not provide yaw. Use 65535 if this GPS is configured to provide yaw and is currently unable to provide it. Use 36000 for north.*/
}) mavlink_gps2_raw_t;
#define MAVLINK_MSG_ID_GPS2_RAW_LEN 35
#define MAVLINK_MSG_ID_GPS2_RAW_LEN 37
#define MAVLINK_MSG_ID_GPS2_RAW_MIN_LEN 35
#define MAVLINK_MSG_ID_124_LEN 35
#define MAVLINK_MSG_ID_124_LEN 37
#define MAVLINK_MSG_ID_124_MIN_LEN 35
#define MAVLINK_MSG_ID_GPS2_RAW_CRC 87
@ -33,7 +34,7 @@ typedef struct __mavlink_gps2_raw_t {
#define MAVLINK_MESSAGE_INFO_GPS2_RAW { \
124, \
"GPS2_RAW", \
12, \
13, \
{ { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_gps2_raw_t, time_usec) }, \
{ "fix_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_gps2_raw_t, fix_type) }, \
{ "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_gps2_raw_t, lat) }, \
@ -46,12 +47,13 @@ typedef struct __mavlink_gps2_raw_t {
{ "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) }, \
{ "dgps_age", NULL, MAVLINK_TYPE_UINT32_T, 0, 20, offsetof(mavlink_gps2_raw_t, dgps_age) }, \
{ "yaw", NULL, MAVLINK_TYPE_UINT16_T, 0, 35, offsetof(mavlink_gps2_raw_t, yaw) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_GPS2_RAW { \
"GPS2_RAW", \
12, \
13, \
{ { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_gps2_raw_t, time_usec) }, \
{ "fix_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 32, offsetof(mavlink_gps2_raw_t, fix_type) }, \
{ "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_gps2_raw_t, lat) }, \
@ -64,6 +66,7 @@ typedef struct __mavlink_gps2_raw_t {
{ "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) }, \
{ "dgps_age", NULL, MAVLINK_TYPE_UINT32_T, 0, 20, offsetof(mavlink_gps2_raw_t, dgps_age) }, \
{ "yaw", NULL, MAVLINK_TYPE_UINT16_T, 0, 35, offsetof(mavlink_gps2_raw_t, yaw) }, \
} \
}
#endif
@ -79,17 +82,18 @@ typedef struct __mavlink_gps2_raw_t {
* @param lat [degE7] Latitude (WGS84)
* @param lon [degE7] Longitude (WGS84)
* @param alt [mm] Altitude (MSL). Positive for up.
* @param eph [cm] GPS HDOP horizontal dilution of position. If unknown, set to: UINT16_MAX
* @param epv [cm] GPS VDOP vertical dilution of position. If unknown, set to: UINT16_MAX
* @param eph GPS HDOP horizontal dilution of position (unitless). If unknown, set to: UINT16_MAX
* @param epv GPS VDOP vertical dilution of position (unitless). If unknown, set to: UINT16_MAX
* @param vel [cm/s] GPS ground speed. If unknown, set to: UINT16_MAX
* @param cog [cdeg] Course over ground (NOT heading, but direction of movement): 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 [ms] Age of DGPS info
* @param yaw [cdeg] Yaw in earth frame from north. Use 0 if this GPS does not provide yaw. Use 65535 if this GPS is configured to provide yaw and is currently unable to provide it. Use 36000 for north.
* @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)
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, uint16_t yaw)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_GPS2_RAW_LEN];
@ -105,6 +109,7 @@ static inline uint16_t mavlink_msg_gps2_raw_pack(uint8_t system_id, uint8_t comp
_mav_put_uint8_t(buf, 32, fix_type);
_mav_put_uint8_t(buf, 33, satellites_visible);
_mav_put_uint8_t(buf, 34, dgps_numch);
_mav_put_uint16_t(buf, 35, yaw);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GPS2_RAW_LEN);
#else
@ -121,6 +126,7 @@ static inline uint16_t mavlink_msg_gps2_raw_pack(uint8_t system_id, uint8_t comp
packet.fix_type = fix_type;
packet.satellites_visible = satellites_visible;
packet.dgps_numch = dgps_numch;
packet.yaw = yaw;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GPS2_RAW_LEN);
#endif
@ -140,18 +146,19 @@ static inline uint16_t mavlink_msg_gps2_raw_pack(uint8_t system_id, uint8_t comp
* @param lat [degE7] Latitude (WGS84)
* @param lon [degE7] Longitude (WGS84)
* @param alt [mm] Altitude (MSL). Positive for up.
* @param eph [cm] GPS HDOP horizontal dilution of position. If unknown, set to: UINT16_MAX
* @param epv [cm] GPS VDOP vertical dilution of position. If unknown, set to: UINT16_MAX
* @param eph GPS HDOP horizontal dilution of position (unitless). If unknown, set to: UINT16_MAX
* @param epv GPS VDOP vertical dilution of position (unitless). If unknown, set to: UINT16_MAX
* @param vel [cm/s] GPS ground speed. If unknown, set to: UINT16_MAX
* @param cog [cdeg] Course over ground (NOT heading, but direction of movement): 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 [ms] Age of DGPS info
* @param yaw [cdeg] Yaw in earth frame from north. Use 0 if this GPS does not provide yaw. Use 65535 if this GPS is configured to provide yaw and is currently unable to provide it. Use 36000 for north.
* @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)
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,uint16_t yaw)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_GPS2_RAW_LEN];
@ -167,6 +174,7 @@ static inline uint16_t mavlink_msg_gps2_raw_pack_chan(uint8_t system_id, uint8_t
_mav_put_uint8_t(buf, 32, fix_type);
_mav_put_uint8_t(buf, 33, satellites_visible);
_mav_put_uint8_t(buf, 34, dgps_numch);
_mav_put_uint16_t(buf, 35, yaw);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GPS2_RAW_LEN);
#else
@ -183,6 +191,7 @@ static inline uint16_t mavlink_msg_gps2_raw_pack_chan(uint8_t system_id, uint8_t
packet.fix_type = fix_type;
packet.satellites_visible = satellites_visible;
packet.dgps_numch = dgps_numch;
packet.yaw = yaw;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GPS2_RAW_LEN);
#endif
@ -201,7 +210,7 @@ static inline uint16_t mavlink_msg_gps2_raw_pack_chan(uint8_t system_id, uint8_t
*/
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);
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, gps2_raw->yaw);
}
/**
@ -215,7 +224,7 @@ static inline uint16_t mavlink_msg_gps2_raw_encode(uint8_t system_id, uint8_t co
*/
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);
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, gps2_raw->yaw);
}
/**
@ -227,17 +236,18 @@ static inline uint16_t mavlink_msg_gps2_raw_encode_chan(uint8_t system_id, uint8
* @param lat [degE7] Latitude (WGS84)
* @param lon [degE7] Longitude (WGS84)
* @param alt [mm] Altitude (MSL). Positive for up.
* @param eph [cm] GPS HDOP horizontal dilution of position. If unknown, set to: UINT16_MAX
* @param epv [cm] GPS VDOP vertical dilution of position. If unknown, set to: UINT16_MAX
* @param eph GPS HDOP horizontal dilution of position (unitless). If unknown, set to: UINT16_MAX
* @param epv GPS VDOP vertical dilution of position (unitless). If unknown, set to: UINT16_MAX
* @param vel [cm/s] GPS ground speed. If unknown, set to: UINT16_MAX
* @param cog [cdeg] Course over ground (NOT heading, but direction of movement): 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 [ms] Age of DGPS info
* @param yaw [cdeg] Yaw in earth frame from north. Use 0 if this GPS does not provide yaw. Use 65535 if this GPS is configured to provide yaw and is currently unable to provide it. Use 36000 for north.
*/
#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)
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, uint16_t yaw)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_GPS2_RAW_LEN];
@ -253,6 +263,7 @@ static inline void mavlink_msg_gps2_raw_send(mavlink_channel_t chan, uint64_t ti
_mav_put_uint8_t(buf, 32, fix_type);
_mav_put_uint8_t(buf, 33, satellites_visible);
_mav_put_uint8_t(buf, 34, dgps_numch);
_mav_put_uint16_t(buf, 35, yaw);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RAW, buf, MAVLINK_MSG_ID_GPS2_RAW_MIN_LEN, MAVLINK_MSG_ID_GPS2_RAW_LEN, MAVLINK_MSG_ID_GPS2_RAW_CRC);
#else
@ -269,6 +280,7 @@ static inline void mavlink_msg_gps2_raw_send(mavlink_channel_t chan, uint64_t ti
packet.fix_type = fix_type;
packet.satellites_visible = satellites_visible;
packet.dgps_numch = dgps_numch;
packet.yaw = yaw;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RAW, (const char *)&packet, MAVLINK_MSG_ID_GPS2_RAW_MIN_LEN, MAVLINK_MSG_ID_GPS2_RAW_LEN, MAVLINK_MSG_ID_GPS2_RAW_CRC);
#endif
@ -282,7 +294,7 @@ static inline void mavlink_msg_gps2_raw_send(mavlink_channel_t chan, uint64_t ti
static inline void mavlink_msg_gps2_raw_send_struct(mavlink_channel_t chan, const mavlink_gps2_raw_t* gps2_raw)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mavlink_msg_gps2_raw_send(chan, 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);
mavlink_msg_gps2_raw_send(chan, 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, gps2_raw->yaw);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RAW, (const char *)gps2_raw, MAVLINK_MSG_ID_GPS2_RAW_MIN_LEN, MAVLINK_MSG_ID_GPS2_RAW_LEN, MAVLINK_MSG_ID_GPS2_RAW_CRC);
#endif
@ -296,7 +308,7 @@ static inline void mavlink_msg_gps2_raw_send_struct(mavlink_channel_t chan, cons
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)
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, uint16_t yaw)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
@ -312,6 +324,7 @@ static inline void mavlink_msg_gps2_raw_send_buf(mavlink_message_t *msgbuf, mavl
_mav_put_uint8_t(buf, 32, fix_type);
_mav_put_uint8_t(buf, 33, satellites_visible);
_mav_put_uint8_t(buf, 34, dgps_numch);
_mav_put_uint16_t(buf, 35, yaw);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RAW, buf, MAVLINK_MSG_ID_GPS2_RAW_MIN_LEN, MAVLINK_MSG_ID_GPS2_RAW_LEN, MAVLINK_MSG_ID_GPS2_RAW_CRC);
#else
@ -328,6 +341,7 @@ static inline void mavlink_msg_gps2_raw_send_buf(mavlink_message_t *msgbuf, mavl
packet->fix_type = fix_type;
packet->satellites_visible = satellites_visible;
packet->dgps_numch = dgps_numch;
packet->yaw = yaw;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS2_RAW, (const char *)packet, MAVLINK_MSG_ID_GPS2_RAW_MIN_LEN, MAVLINK_MSG_ID_GPS2_RAW_LEN, MAVLINK_MSG_ID_GPS2_RAW_CRC);
#endif
@ -392,7 +406,7 @@ static inline int32_t mavlink_msg_gps2_raw_get_alt(const mavlink_message_t* msg)
/**
* @brief Get field eph from gps2_raw message
*
* @return [cm] GPS HDOP horizontal dilution of position. If unknown, set to: UINT16_MAX
* @return GPS HDOP horizontal dilution of position (unitless). If unknown, set to: UINT16_MAX
*/
static inline uint16_t mavlink_msg_gps2_raw_get_eph(const mavlink_message_t* msg)
{
@ -402,7 +416,7 @@ static inline uint16_t mavlink_msg_gps2_raw_get_eph(const mavlink_message_t* msg
/**
* @brief Get field epv from gps2_raw message
*
* @return [cm] GPS VDOP vertical dilution of position. If unknown, set to: UINT16_MAX
* @return GPS VDOP vertical dilution of position (unitless). If unknown, set to: UINT16_MAX
*/
static inline uint16_t mavlink_msg_gps2_raw_get_epv(const mavlink_message_t* msg)
{
@ -459,6 +473,16 @@ static inline uint32_t mavlink_msg_gps2_raw_get_dgps_age(const mavlink_message_t
return _MAV_RETURN_uint32_t(msg, 20);
}
/**
* @brief Get field yaw from gps2_raw message
*
* @return [cdeg] Yaw in earth frame from north. Use 0 if this GPS does not provide yaw. Use 65535 if this GPS is configured to provide yaw and is currently unable to provide it. Use 36000 for north.
*/
static inline uint16_t mavlink_msg_gps2_raw_get_yaw(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 35);
}
/**
* @brief Decode a gps2_raw message into a struct
*
@ -480,6 +504,7 @@ static inline void mavlink_msg_gps2_raw_decode(const mavlink_message_t* msg, mav
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);
gps2_raw->yaw = mavlink_msg_gps2_raw_get_yaw(msg);
#else
uint8_t len = msg->len < MAVLINK_MSG_ID_GPS2_RAW_LEN? msg->len : MAVLINK_MSG_ID_GPS2_RAW_LEN;
memset(gps2_raw, 0, MAVLINK_MSG_ID_GPS2_RAW_LEN);

View file

@ -3,16 +3,17 @@
#define MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN 49
MAVPACKED(
typedef struct __mavlink_gps_global_origin_t {
int32_t latitude; /*< [degE7] Latitude (WGS84)*/
int32_t longitude; /*< [degE7] Longitude (WGS84)*/
int32_t altitude; /*< [mm] Altitude (MSL). Positive for up.*/
} mavlink_gps_global_origin_t;
uint64_t time_usec; /*< [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.*/
}) mavlink_gps_global_origin_t;
#define MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN 12
#define MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN 20
#define MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_MIN_LEN 12
#define MAVLINK_MSG_ID_49_LEN 12
#define MAVLINK_MSG_ID_49_LEN 20
#define MAVLINK_MSG_ID_49_MIN_LEN 12
#define MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_CRC 39
@ -24,19 +25,21 @@ typedef struct __mavlink_gps_global_origin_t {
#define MAVLINK_MESSAGE_INFO_GPS_GLOBAL_ORIGIN { \
49, \
"GPS_GLOBAL_ORIGIN", \
3, \
4, \
{ { "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) }, \
{ "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 12, offsetof(mavlink_gps_global_origin_t, time_usec) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_GPS_GLOBAL_ORIGIN { \
"GPS_GLOBAL_ORIGIN", \
3, \
4, \
{ { "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) }, \
{ "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 12, offsetof(mavlink_gps_global_origin_t, time_usec) }, \
} \
}
#endif
@ -50,16 +53,18 @@ typedef struct __mavlink_gps_global_origin_t {
* @param latitude [degE7] Latitude (WGS84)
* @param longitude [degE7] Longitude (WGS84)
* @param altitude [mm] Altitude (MSL). Positive for up.
* @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
* @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)
int32_t latitude, int32_t longitude, int32_t altitude, uint64_t time_usec)
{
#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);
_mav_put_uint64_t(buf, 12, time_usec);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN);
#else
@ -67,6 +72,7 @@ static inline uint16_t mavlink_msg_gps_global_origin_pack(uint8_t system_id, uin
packet.latitude = latitude;
packet.longitude = longitude;
packet.altitude = altitude;
packet.time_usec = time_usec;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN);
#endif
@ -84,17 +90,19 @@ static inline uint16_t mavlink_msg_gps_global_origin_pack(uint8_t system_id, uin
* @param latitude [degE7] Latitude (WGS84)
* @param longitude [degE7] Longitude (WGS84)
* @param altitude [mm] Altitude (MSL). Positive for up.
* @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
* @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)
int32_t latitude,int32_t longitude,int32_t altitude,uint64_t time_usec)
{
#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);
_mav_put_uint64_t(buf, 12, time_usec);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN);
#else
@ -102,6 +110,7 @@ static inline uint16_t mavlink_msg_gps_global_origin_pack_chan(uint8_t system_id
packet.latitude = latitude;
packet.longitude = longitude;
packet.altitude = altitude;
packet.time_usec = time_usec;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN);
#endif
@ -120,7 +129,7 @@ static inline uint16_t mavlink_msg_gps_global_origin_pack_chan(uint8_t system_id
*/
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);
return mavlink_msg_gps_global_origin_pack(system_id, component_id, msg, gps_global_origin->latitude, gps_global_origin->longitude, gps_global_origin->altitude, gps_global_origin->time_usec);
}
/**
@ -134,7 +143,7 @@ static inline uint16_t mavlink_msg_gps_global_origin_encode(uint8_t system_id, u
*/
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);
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, gps_global_origin->time_usec);
}
/**
@ -144,16 +153,18 @@ static inline uint16_t mavlink_msg_gps_global_origin_encode_chan(uint8_t system_
* @param latitude [degE7] Latitude (WGS84)
* @param longitude [degE7] Longitude (WGS84)
* @param altitude [mm] Altitude (MSL). Positive for up.
* @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
*/
#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)
static inline void mavlink_msg_gps_global_origin_send(mavlink_channel_t chan, int32_t latitude, int32_t longitude, int32_t altitude, uint64_t time_usec)
{
#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);
_mav_put_uint64_t(buf, 12, time_usec);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN, buf, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_MIN_LEN, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_CRC);
#else
@ -161,6 +172,7 @@ static inline void mavlink_msg_gps_global_origin_send(mavlink_channel_t chan, in
packet.latitude = latitude;
packet.longitude = longitude;
packet.altitude = altitude;
packet.time_usec = time_usec;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN, (const char *)&packet, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_MIN_LEN, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_CRC);
#endif
@ -174,7 +186,7 @@ static inline void mavlink_msg_gps_global_origin_send(mavlink_channel_t chan, in
static inline void mavlink_msg_gps_global_origin_send_struct(mavlink_channel_t chan, const mavlink_gps_global_origin_t* gps_global_origin)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mavlink_msg_gps_global_origin_send(chan, gps_global_origin->latitude, gps_global_origin->longitude, gps_global_origin->altitude);
mavlink_msg_gps_global_origin_send(chan, gps_global_origin->latitude, gps_global_origin->longitude, gps_global_origin->altitude, gps_global_origin->time_usec);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN, (const char *)gps_global_origin, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_MIN_LEN, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_CRC);
#endif
@ -188,13 +200,14 @@ static inline void mavlink_msg_gps_global_origin_send_struct(mavlink_channel_t c
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)
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, uint64_t time_usec)
{
#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);
_mav_put_uint64_t(buf, 12, time_usec);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN, buf, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_MIN_LEN, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_CRC);
#else
@ -202,6 +215,7 @@ static inline void mavlink_msg_gps_global_origin_send_buf(mavlink_message_t *msg
packet->latitude = latitude;
packet->longitude = longitude;
packet->altitude = altitude;
packet->time_usec = time_usec;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN, (const char *)packet, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_MIN_LEN, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_CRC);
#endif
@ -243,6 +257,16 @@ static inline int32_t mavlink_msg_gps_global_origin_get_altitude(const mavlink_m
return _MAV_RETURN_int32_t(msg, 8);
}
/**
* @brief Get field time_usec from gps_global_origin message
*
* @return [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
*/
static inline uint64_t mavlink_msg_gps_global_origin_get_time_usec(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint64_t(msg, 12);
}
/**
* @brief Decode a gps_global_origin message into a struct
*
@ -255,6 +279,7 @@ static inline void mavlink_msg_gps_global_origin_decode(const mavlink_message_t*
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);
gps_global_origin->time_usec = mavlink_msg_gps_global_origin_get_time_usec(msg);
#else
uint8_t len = msg->len < MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN? msg->len : MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN;
memset(gps_global_origin, 0, MAVLINK_MSG_ID_GPS_GLOBAL_ORIGIN_LEN);

View file

@ -3,15 +3,15 @@
#define MAVLINK_MSG_ID_GPS_INPUT 232
MAVPACKED(
typedef struct __mavlink_gps_input_t {
uint64_t time_usec; /*< [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.*/
uint32_t time_week_ms; /*< [ms] GPS time (from start of GPS week)*/
int32_t lat; /*< [degE7] Latitude (WGS84)*/
int32_t lon; /*< [degE7] Longitude (WGS84)*/
float alt; /*< [m] Altitude (MSL). Positive for up.*/
float hdop; /*< [m] GPS HDOP horizontal dilution of position*/
float vdop; /*< [m] GPS VDOP vertical dilution of position*/
float hdop; /*< GPS HDOP horizontal dilution of position (unitless). If unknown, set to: UINT16_MAX*/
float vdop; /*< GPS VDOP vertical dilution of position (unitless). If unknown, set to: UINT16_MAX*/
float vn; /*< [m/s] GPS velocity in north direction in earth-fixed NED frame*/
float ve; /*< [m/s] GPS velocity in east direction in earth-fixed NED frame*/
float vd; /*< [m/s] GPS velocity in down direction in earth-fixed NED frame*/
@ -23,11 +23,12 @@ typedef struct __mavlink_gps_input_t {
uint8_t gps_id; /*< ID of the GPS for multiple GPS inputs*/
uint8_t fix_type; /*< 0-1: no fix, 2: 2D fix, 3: 3D fix. 4: 3D with DGPS. 5: 3D with RTK*/
uint8_t satellites_visible; /*< Number of satellites visible.*/
} mavlink_gps_input_t;
uint16_t yaw; /*< [cdeg] Yaw of vehicle relative to Earth's North, zero means not available, use 36000 for north*/
}) mavlink_gps_input_t;
#define MAVLINK_MSG_ID_GPS_INPUT_LEN 63
#define MAVLINK_MSG_ID_GPS_INPUT_LEN 65
#define MAVLINK_MSG_ID_GPS_INPUT_MIN_LEN 63
#define MAVLINK_MSG_ID_232_LEN 63
#define MAVLINK_MSG_ID_232_LEN 65
#define MAVLINK_MSG_ID_232_MIN_LEN 63
#define MAVLINK_MSG_ID_GPS_INPUT_CRC 151
@ -39,7 +40,7 @@ typedef struct __mavlink_gps_input_t {
#define MAVLINK_MESSAGE_INFO_GPS_INPUT { \
232, \
"GPS_INPUT", \
18, \
19, \
{ { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_gps_input_t, time_usec) }, \
{ "gps_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 60, offsetof(mavlink_gps_input_t, gps_id) }, \
{ "ignore_flags", NULL, MAVLINK_TYPE_UINT16_T, 0, 56, offsetof(mavlink_gps_input_t, ignore_flags) }, \
@ -58,12 +59,13 @@ typedef struct __mavlink_gps_input_t {
{ "horiz_accuracy", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_gps_input_t, horiz_accuracy) }, \
{ "vert_accuracy", NULL, MAVLINK_TYPE_FLOAT, 0, 52, offsetof(mavlink_gps_input_t, vert_accuracy) }, \
{ "satellites_visible", NULL, MAVLINK_TYPE_UINT8_T, 0, 62, offsetof(mavlink_gps_input_t, satellites_visible) }, \
{ "yaw", NULL, MAVLINK_TYPE_UINT16_T, 0, 63, offsetof(mavlink_gps_input_t, yaw) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_GPS_INPUT { \
"GPS_INPUT", \
18, \
19, \
{ { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_gps_input_t, time_usec) }, \
{ "gps_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 60, offsetof(mavlink_gps_input_t, gps_id) }, \
{ "ignore_flags", NULL, MAVLINK_TYPE_UINT16_T, 0, 56, offsetof(mavlink_gps_input_t, ignore_flags) }, \
@ -82,6 +84,7 @@ typedef struct __mavlink_gps_input_t {
{ "horiz_accuracy", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_gps_input_t, horiz_accuracy) }, \
{ "vert_accuracy", NULL, MAVLINK_TYPE_FLOAT, 0, 52, offsetof(mavlink_gps_input_t, vert_accuracy) }, \
{ "satellites_visible", NULL, MAVLINK_TYPE_UINT8_T, 0, 62, offsetof(mavlink_gps_input_t, satellites_visible) }, \
{ "yaw", NULL, MAVLINK_TYPE_UINT16_T, 0, 63, offsetof(mavlink_gps_input_t, yaw) }, \
} \
}
#endif
@ -101,8 +104,8 @@ typedef struct __mavlink_gps_input_t {
* @param lat [degE7] Latitude (WGS84)
* @param lon [degE7] Longitude (WGS84)
* @param alt [m] Altitude (MSL). Positive for up.
* @param hdop [m] GPS HDOP horizontal dilution of position
* @param vdop [m] GPS VDOP vertical dilution of position
* @param hdop GPS HDOP horizontal dilution of position (unitless). If unknown, set to: UINT16_MAX
* @param vdop GPS VDOP vertical dilution of position (unitless). If unknown, set to: UINT16_MAX
* @param vn [m/s] GPS velocity in north direction in earth-fixed NED frame
* @param ve [m/s] GPS velocity in east direction in earth-fixed NED frame
* @param vd [m/s] GPS velocity in down direction in earth-fixed NED frame
@ -110,10 +113,11 @@ typedef struct __mavlink_gps_input_t {
* @param horiz_accuracy [m] GPS horizontal accuracy
* @param vert_accuracy [m] GPS vertical accuracy
* @param satellites_visible Number of satellites visible.
* @param yaw [cdeg] Yaw of vehicle relative to Earth's North, zero means not available, use 36000 for north
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_gps_input_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint64_t time_usec, uint8_t gps_id, uint16_t ignore_flags, uint32_t time_week_ms, uint16_t time_week, uint8_t fix_type, int32_t lat, int32_t lon, float alt, float hdop, float vdop, float vn, float ve, float vd, float speed_accuracy, float horiz_accuracy, float vert_accuracy, uint8_t satellites_visible)
uint64_t time_usec, uint8_t gps_id, uint16_t ignore_flags, uint32_t time_week_ms, uint16_t time_week, uint8_t fix_type, int32_t lat, int32_t lon, float alt, float hdop, float vdop, float vn, float ve, float vd, float speed_accuracy, float horiz_accuracy, float vert_accuracy, uint8_t satellites_visible, uint16_t yaw)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_GPS_INPUT_LEN];
@ -135,6 +139,7 @@ static inline uint16_t mavlink_msg_gps_input_pack(uint8_t system_id, uint8_t com
_mav_put_uint8_t(buf, 60, gps_id);
_mav_put_uint8_t(buf, 61, fix_type);
_mav_put_uint8_t(buf, 62, satellites_visible);
_mav_put_uint16_t(buf, 63, yaw);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GPS_INPUT_LEN);
#else
@ -157,6 +162,7 @@ static inline uint16_t mavlink_msg_gps_input_pack(uint8_t system_id, uint8_t com
packet.gps_id = gps_id;
packet.fix_type = fix_type;
packet.satellites_visible = satellites_visible;
packet.yaw = yaw;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GPS_INPUT_LEN);
#endif
@ -180,8 +186,8 @@ static inline uint16_t mavlink_msg_gps_input_pack(uint8_t system_id, uint8_t com
* @param lat [degE7] Latitude (WGS84)
* @param lon [degE7] Longitude (WGS84)
* @param alt [m] Altitude (MSL). Positive for up.
* @param hdop [m] GPS HDOP horizontal dilution of position
* @param vdop [m] GPS VDOP vertical dilution of position
* @param hdop GPS HDOP horizontal dilution of position (unitless). If unknown, set to: UINT16_MAX
* @param vdop GPS VDOP vertical dilution of position (unitless). If unknown, set to: UINT16_MAX
* @param vn [m/s] GPS velocity in north direction in earth-fixed NED frame
* @param ve [m/s] GPS velocity in east direction in earth-fixed NED frame
* @param vd [m/s] GPS velocity in down direction in earth-fixed NED frame
@ -189,11 +195,12 @@ static inline uint16_t mavlink_msg_gps_input_pack(uint8_t system_id, uint8_t com
* @param horiz_accuracy [m] GPS horizontal accuracy
* @param vert_accuracy [m] GPS vertical accuracy
* @param satellites_visible Number of satellites visible.
* @param yaw [cdeg] Yaw of vehicle relative to Earth's North, zero means not available, use 36000 for north
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_gps_input_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint64_t time_usec,uint8_t gps_id,uint16_t ignore_flags,uint32_t time_week_ms,uint16_t time_week,uint8_t fix_type,int32_t lat,int32_t lon,float alt,float hdop,float vdop,float vn,float ve,float vd,float speed_accuracy,float horiz_accuracy,float vert_accuracy,uint8_t satellites_visible)
uint64_t time_usec,uint8_t gps_id,uint16_t ignore_flags,uint32_t time_week_ms,uint16_t time_week,uint8_t fix_type,int32_t lat,int32_t lon,float alt,float hdop,float vdop,float vn,float ve,float vd,float speed_accuracy,float horiz_accuracy,float vert_accuracy,uint8_t satellites_visible,uint16_t yaw)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_GPS_INPUT_LEN];
@ -215,6 +222,7 @@ static inline uint16_t mavlink_msg_gps_input_pack_chan(uint8_t system_id, uint8_
_mav_put_uint8_t(buf, 60, gps_id);
_mav_put_uint8_t(buf, 61, fix_type);
_mav_put_uint8_t(buf, 62, satellites_visible);
_mav_put_uint16_t(buf, 63, yaw);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GPS_INPUT_LEN);
#else
@ -237,6 +245,7 @@ static inline uint16_t mavlink_msg_gps_input_pack_chan(uint8_t system_id, uint8_
packet.gps_id = gps_id;
packet.fix_type = fix_type;
packet.satellites_visible = satellites_visible;
packet.yaw = yaw;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GPS_INPUT_LEN);
#endif
@ -255,7 +264,7 @@ static inline uint16_t mavlink_msg_gps_input_pack_chan(uint8_t system_id, uint8_
*/
static inline uint16_t mavlink_msg_gps_input_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_gps_input_t* gps_input)
{
return mavlink_msg_gps_input_pack(system_id, component_id, msg, gps_input->time_usec, gps_input->gps_id, gps_input->ignore_flags, gps_input->time_week_ms, gps_input->time_week, gps_input->fix_type, gps_input->lat, gps_input->lon, gps_input->alt, gps_input->hdop, gps_input->vdop, gps_input->vn, gps_input->ve, gps_input->vd, gps_input->speed_accuracy, gps_input->horiz_accuracy, gps_input->vert_accuracy, gps_input->satellites_visible);
return mavlink_msg_gps_input_pack(system_id, component_id, msg, gps_input->time_usec, gps_input->gps_id, gps_input->ignore_flags, gps_input->time_week_ms, gps_input->time_week, gps_input->fix_type, gps_input->lat, gps_input->lon, gps_input->alt, gps_input->hdop, gps_input->vdop, gps_input->vn, gps_input->ve, gps_input->vd, gps_input->speed_accuracy, gps_input->horiz_accuracy, gps_input->vert_accuracy, gps_input->satellites_visible, gps_input->yaw);
}
/**
@ -269,7 +278,7 @@ static inline uint16_t mavlink_msg_gps_input_encode(uint8_t system_id, uint8_t c
*/
static inline uint16_t mavlink_msg_gps_input_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_gps_input_t* gps_input)
{
return mavlink_msg_gps_input_pack_chan(system_id, component_id, chan, msg, gps_input->time_usec, gps_input->gps_id, gps_input->ignore_flags, gps_input->time_week_ms, gps_input->time_week, gps_input->fix_type, gps_input->lat, gps_input->lon, gps_input->alt, gps_input->hdop, gps_input->vdop, gps_input->vn, gps_input->ve, gps_input->vd, gps_input->speed_accuracy, gps_input->horiz_accuracy, gps_input->vert_accuracy, gps_input->satellites_visible);
return mavlink_msg_gps_input_pack_chan(system_id, component_id, chan, msg, gps_input->time_usec, gps_input->gps_id, gps_input->ignore_flags, gps_input->time_week_ms, gps_input->time_week, gps_input->fix_type, gps_input->lat, gps_input->lon, gps_input->alt, gps_input->hdop, gps_input->vdop, gps_input->vn, gps_input->ve, gps_input->vd, gps_input->speed_accuracy, gps_input->horiz_accuracy, gps_input->vert_accuracy, gps_input->satellites_visible, gps_input->yaw);
}
/**
@ -285,8 +294,8 @@ static inline uint16_t mavlink_msg_gps_input_encode_chan(uint8_t system_id, uint
* @param lat [degE7] Latitude (WGS84)
* @param lon [degE7] Longitude (WGS84)
* @param alt [m] Altitude (MSL). Positive for up.
* @param hdop [m] GPS HDOP horizontal dilution of position
* @param vdop [m] GPS VDOP vertical dilution of position
* @param hdop GPS HDOP horizontal dilution of position (unitless). If unknown, set to: UINT16_MAX
* @param vdop GPS VDOP vertical dilution of position (unitless). If unknown, set to: UINT16_MAX
* @param vn [m/s] GPS velocity in north direction in earth-fixed NED frame
* @param ve [m/s] GPS velocity in east direction in earth-fixed NED frame
* @param vd [m/s] GPS velocity in down direction in earth-fixed NED frame
@ -294,10 +303,11 @@ static inline uint16_t mavlink_msg_gps_input_encode_chan(uint8_t system_id, uint
* @param horiz_accuracy [m] GPS horizontal accuracy
* @param vert_accuracy [m] GPS vertical accuracy
* @param satellites_visible Number of satellites visible.
* @param yaw [cdeg] Yaw of vehicle relative to Earth's North, zero means not available, use 36000 for north
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_gps_input_send(mavlink_channel_t chan, uint64_t time_usec, uint8_t gps_id, uint16_t ignore_flags, uint32_t time_week_ms, uint16_t time_week, uint8_t fix_type, int32_t lat, int32_t lon, float alt, float hdop, float vdop, float vn, float ve, float vd, float speed_accuracy, float horiz_accuracy, float vert_accuracy, uint8_t satellites_visible)
static inline void mavlink_msg_gps_input_send(mavlink_channel_t chan, uint64_t time_usec, uint8_t gps_id, uint16_t ignore_flags, uint32_t time_week_ms, uint16_t time_week, uint8_t fix_type, int32_t lat, int32_t lon, float alt, float hdop, float vdop, float vn, float ve, float vd, float speed_accuracy, float horiz_accuracy, float vert_accuracy, uint8_t satellites_visible, uint16_t yaw)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_GPS_INPUT_LEN];
@ -319,6 +329,7 @@ static inline void mavlink_msg_gps_input_send(mavlink_channel_t chan, uint64_t t
_mav_put_uint8_t(buf, 60, gps_id);
_mav_put_uint8_t(buf, 61, fix_type);
_mav_put_uint8_t(buf, 62, satellites_visible);
_mav_put_uint16_t(buf, 63, yaw);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_INPUT, buf, MAVLINK_MSG_ID_GPS_INPUT_MIN_LEN, MAVLINK_MSG_ID_GPS_INPUT_LEN, MAVLINK_MSG_ID_GPS_INPUT_CRC);
#else
@ -341,6 +352,7 @@ static inline void mavlink_msg_gps_input_send(mavlink_channel_t chan, uint64_t t
packet.gps_id = gps_id;
packet.fix_type = fix_type;
packet.satellites_visible = satellites_visible;
packet.yaw = yaw;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_INPUT, (const char *)&packet, MAVLINK_MSG_ID_GPS_INPUT_MIN_LEN, MAVLINK_MSG_ID_GPS_INPUT_LEN, MAVLINK_MSG_ID_GPS_INPUT_CRC);
#endif
@ -354,7 +366,7 @@ static inline void mavlink_msg_gps_input_send(mavlink_channel_t chan, uint64_t t
static inline void mavlink_msg_gps_input_send_struct(mavlink_channel_t chan, const mavlink_gps_input_t* gps_input)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mavlink_msg_gps_input_send(chan, gps_input->time_usec, gps_input->gps_id, gps_input->ignore_flags, gps_input->time_week_ms, gps_input->time_week, gps_input->fix_type, gps_input->lat, gps_input->lon, gps_input->alt, gps_input->hdop, gps_input->vdop, gps_input->vn, gps_input->ve, gps_input->vd, gps_input->speed_accuracy, gps_input->horiz_accuracy, gps_input->vert_accuracy, gps_input->satellites_visible);
mavlink_msg_gps_input_send(chan, gps_input->time_usec, gps_input->gps_id, gps_input->ignore_flags, gps_input->time_week_ms, gps_input->time_week, gps_input->fix_type, gps_input->lat, gps_input->lon, gps_input->alt, gps_input->hdop, gps_input->vdop, gps_input->vn, gps_input->ve, gps_input->vd, gps_input->speed_accuracy, gps_input->horiz_accuracy, gps_input->vert_accuracy, gps_input->satellites_visible, gps_input->yaw);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_INPUT, (const char *)gps_input, MAVLINK_MSG_ID_GPS_INPUT_MIN_LEN, MAVLINK_MSG_ID_GPS_INPUT_LEN, MAVLINK_MSG_ID_GPS_INPUT_CRC);
#endif
@ -368,7 +380,7 @@ static inline void mavlink_msg_gps_input_send_struct(mavlink_channel_t chan, con
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_input_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, uint8_t gps_id, uint16_t ignore_flags, uint32_t time_week_ms, uint16_t time_week, uint8_t fix_type, int32_t lat, int32_t lon, float alt, float hdop, float vdop, float vn, float ve, float vd, float speed_accuracy, float horiz_accuracy, float vert_accuracy, uint8_t satellites_visible)
static inline void mavlink_msg_gps_input_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, uint8_t gps_id, uint16_t ignore_flags, uint32_t time_week_ms, uint16_t time_week, uint8_t fix_type, int32_t lat, int32_t lon, float alt, float hdop, float vdop, float vn, float ve, float vd, float speed_accuracy, float horiz_accuracy, float vert_accuracy, uint8_t satellites_visible, uint16_t yaw)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
@ -390,6 +402,7 @@ static inline void mavlink_msg_gps_input_send_buf(mavlink_message_t *msgbuf, mav
_mav_put_uint8_t(buf, 60, gps_id);
_mav_put_uint8_t(buf, 61, fix_type);
_mav_put_uint8_t(buf, 62, satellites_visible);
_mav_put_uint16_t(buf, 63, yaw);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_INPUT, buf, MAVLINK_MSG_ID_GPS_INPUT_MIN_LEN, MAVLINK_MSG_ID_GPS_INPUT_LEN, MAVLINK_MSG_ID_GPS_INPUT_CRC);
#else
@ -412,6 +425,7 @@ static inline void mavlink_msg_gps_input_send_buf(mavlink_message_t *msgbuf, mav
packet->gps_id = gps_id;
packet->fix_type = fix_type;
packet->satellites_visible = satellites_visible;
packet->yaw = yaw;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_INPUT, (const char *)packet, MAVLINK_MSG_ID_GPS_INPUT_MIN_LEN, MAVLINK_MSG_ID_GPS_INPUT_LEN, MAVLINK_MSG_ID_GPS_INPUT_CRC);
#endif
@ -516,7 +530,7 @@ static inline float mavlink_msg_gps_input_get_alt(const mavlink_message_t* msg)
/**
* @brief Get field hdop from gps_input message
*
* @return [m] GPS HDOP horizontal dilution of position
* @return GPS HDOP horizontal dilution of position (unitless). If unknown, set to: UINT16_MAX
*/
static inline float mavlink_msg_gps_input_get_hdop(const mavlink_message_t* msg)
{
@ -526,7 +540,7 @@ static inline float mavlink_msg_gps_input_get_hdop(const mavlink_message_t* msg)
/**
* @brief Get field vdop from gps_input message
*
* @return [m] GPS VDOP vertical dilution of position
* @return GPS VDOP vertical dilution of position (unitless). If unknown, set to: UINT16_MAX
*/
static inline float mavlink_msg_gps_input_get_vdop(const mavlink_message_t* msg)
{
@ -603,6 +617,16 @@ static inline uint8_t mavlink_msg_gps_input_get_satellites_visible(const mavlink
return _MAV_RETURN_uint8_t(msg, 62);
}
/**
* @brief Get field yaw from gps_input message
*
* @return [cdeg] Yaw of vehicle relative to Earth's North, zero means not available, use 36000 for north
*/
static inline uint16_t mavlink_msg_gps_input_get_yaw(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 63);
}
/**
* @brief Decode a gps_input message into a struct
*
@ -630,6 +654,7 @@ static inline void mavlink_msg_gps_input_decode(const mavlink_message_t* msg, ma
gps_input->gps_id = mavlink_msg_gps_input_get_gps_id(msg);
gps_input->fix_type = mavlink_msg_gps_input_get_fix_type(msg);
gps_input->satellites_visible = mavlink_msg_gps_input_get_satellites_visible(msg);
gps_input->yaw = mavlink_msg_gps_input_get_yaw(msg);
#else
uint8_t len = msg->len < MAVLINK_MSG_ID_GPS_INPUT_LEN? msg->len : MAVLINK_MSG_ID_GPS_INPUT_LEN;
memset(gps_input, 0, MAVLINK_MSG_ID_GPS_INPUT_LEN);

View file

@ -3,7 +3,7 @@
#define MAVLINK_MSG_ID_GPS_RAW_INT 24
MAVPACKED(
typedef struct __mavlink_gps_raw_int_t {
uint64_t time_usec; /*< [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.*/
int32_t lat; /*< [degE7] Latitude (WGS84, EGM96 ellipsoid)*/
@ -15,11 +15,17 @@ typedef struct __mavlink_gps_raw_int_t {
uint16_t cog; /*< [cdeg] 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; /*< GPS fix type.*/
uint8_t satellites_visible; /*< Number of satellites visible. If unknown, set to 255*/
} mavlink_gps_raw_int_t;
int32_t alt_ellipsoid; /*< [mm] Altitude (above WGS84, EGM96 ellipsoid). Positive for up.*/
uint32_t h_acc; /*< [mm] Position uncertainty.*/
uint32_t v_acc; /*< [mm] Altitude uncertainty.*/
uint32_t vel_acc; /*< [mm] Speed uncertainty.*/
uint32_t hdg_acc; /*< [degE5] Heading / track uncertainty*/
uint16_t yaw; /*< [cdeg] Yaw in earth frame from north. Use 0 if this GPS does not provide yaw. Use 65535 if this GPS is configured to provide yaw and is currently unable to provide it. Use 36000 for north.*/
}) mavlink_gps_raw_int_t;
#define MAVLINK_MSG_ID_GPS_RAW_INT_LEN 30
#define MAVLINK_MSG_ID_GPS_RAW_INT_LEN 52
#define MAVLINK_MSG_ID_GPS_RAW_INT_MIN_LEN 30
#define MAVLINK_MSG_ID_24_LEN 30
#define MAVLINK_MSG_ID_24_LEN 52
#define MAVLINK_MSG_ID_24_MIN_LEN 30
#define MAVLINK_MSG_ID_GPS_RAW_INT_CRC 24
@ -31,7 +37,7 @@ typedef struct __mavlink_gps_raw_int_t {
#define MAVLINK_MESSAGE_INFO_GPS_RAW_INT { \
24, \
"GPS_RAW_INT", \
10, \
16, \
{ { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_gps_raw_int_t, time_usec) }, \
{ "fix_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 28, offsetof(mavlink_gps_raw_int_t, fix_type) }, \
{ "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_gps_raw_int_t, lat) }, \
@ -42,12 +48,18 @@ typedef struct __mavlink_gps_raw_int_t {
{ "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) }, \
{ "satellites_visible", NULL, MAVLINK_TYPE_UINT8_T, 0, 29, offsetof(mavlink_gps_raw_int_t, satellites_visible) }, \
{ "alt_ellipsoid", NULL, MAVLINK_TYPE_INT32_T, 0, 30, offsetof(mavlink_gps_raw_int_t, alt_ellipsoid) }, \
{ "h_acc", NULL, MAVLINK_TYPE_UINT32_T, 0, 34, offsetof(mavlink_gps_raw_int_t, h_acc) }, \
{ "v_acc", NULL, MAVLINK_TYPE_UINT32_T, 0, 38, offsetof(mavlink_gps_raw_int_t, v_acc) }, \
{ "vel_acc", NULL, MAVLINK_TYPE_UINT32_T, 0, 42, offsetof(mavlink_gps_raw_int_t, vel_acc) }, \
{ "hdg_acc", NULL, MAVLINK_TYPE_UINT32_T, 0, 46, offsetof(mavlink_gps_raw_int_t, hdg_acc) }, \
{ "yaw", NULL, MAVLINK_TYPE_UINT16_T, 0, 50, offsetof(mavlink_gps_raw_int_t, yaw) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_GPS_RAW_INT { \
"GPS_RAW_INT", \
10, \
16, \
{ { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_gps_raw_int_t, time_usec) }, \
{ "fix_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 28, offsetof(mavlink_gps_raw_int_t, fix_type) }, \
{ "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_gps_raw_int_t, lat) }, \
@ -58,6 +70,12 @@ typedef struct __mavlink_gps_raw_int_t {
{ "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) }, \
{ "satellites_visible", NULL, MAVLINK_TYPE_UINT8_T, 0, 29, offsetof(mavlink_gps_raw_int_t, satellites_visible) }, \
{ "alt_ellipsoid", NULL, MAVLINK_TYPE_INT32_T, 0, 30, offsetof(mavlink_gps_raw_int_t, alt_ellipsoid) }, \
{ "h_acc", NULL, MAVLINK_TYPE_UINT32_T, 0, 34, offsetof(mavlink_gps_raw_int_t, h_acc) }, \
{ "v_acc", NULL, MAVLINK_TYPE_UINT32_T, 0, 38, offsetof(mavlink_gps_raw_int_t, v_acc) }, \
{ "vel_acc", NULL, MAVLINK_TYPE_UINT32_T, 0, 42, offsetof(mavlink_gps_raw_int_t, vel_acc) }, \
{ "hdg_acc", NULL, MAVLINK_TYPE_UINT32_T, 0, 46, offsetof(mavlink_gps_raw_int_t, hdg_acc) }, \
{ "yaw", NULL, MAVLINK_TYPE_UINT16_T, 0, 50, offsetof(mavlink_gps_raw_int_t, yaw) }, \
} \
}
#endif
@ -78,10 +96,16 @@ typedef struct __mavlink_gps_raw_int_t {
* @param vel [cm/s] GPS ground speed. If unknown, set to: UINT16_MAX
* @param cog [cdeg] 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 alt_ellipsoid [mm] Altitude (above WGS84, EGM96 ellipsoid). Positive for up.
* @param h_acc [mm] Position uncertainty.
* @param v_acc [mm] Altitude uncertainty.
* @param vel_acc [mm] Speed uncertainty.
* @param hdg_acc [degE5] Heading / track uncertainty
* @param yaw [cdeg] Yaw in earth frame from north. Use 0 if this GPS does not provide yaw. Use 65535 if this GPS is configured to provide yaw and is currently unable to provide it. Use 36000 for north.
* @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)
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, int32_t alt_ellipsoid, uint32_t h_acc, uint32_t v_acc, uint32_t vel_acc, uint32_t hdg_acc, uint16_t yaw)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_GPS_RAW_INT_LEN];
@ -95,6 +119,12 @@ static inline uint16_t mavlink_msg_gps_raw_int_pack(uint8_t system_id, uint8_t c
_mav_put_uint16_t(buf, 26, cog);
_mav_put_uint8_t(buf, 28, fix_type);
_mav_put_uint8_t(buf, 29, satellites_visible);
_mav_put_int32_t(buf, 30, alt_ellipsoid);
_mav_put_uint32_t(buf, 34, h_acc);
_mav_put_uint32_t(buf, 38, v_acc);
_mav_put_uint32_t(buf, 42, vel_acc);
_mav_put_uint32_t(buf, 46, hdg_acc);
_mav_put_uint16_t(buf, 50, yaw);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GPS_RAW_INT_LEN);
#else
@ -109,6 +139,12 @@ static inline uint16_t mavlink_msg_gps_raw_int_pack(uint8_t system_id, uint8_t c
packet.cog = cog;
packet.fix_type = fix_type;
packet.satellites_visible = satellites_visible;
packet.alt_ellipsoid = alt_ellipsoid;
packet.h_acc = h_acc;
packet.v_acc = v_acc;
packet.vel_acc = vel_acc;
packet.hdg_acc = hdg_acc;
packet.yaw = yaw;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GPS_RAW_INT_LEN);
#endif
@ -133,11 +169,17 @@ static inline uint16_t mavlink_msg_gps_raw_int_pack(uint8_t system_id, uint8_t c
* @param vel [cm/s] GPS ground speed. If unknown, set to: UINT16_MAX
* @param cog [cdeg] 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 alt_ellipsoid [mm] Altitude (above WGS84, EGM96 ellipsoid). Positive for up.
* @param h_acc [mm] Position uncertainty.
* @param v_acc [mm] Altitude uncertainty.
* @param vel_acc [mm] Speed uncertainty.
* @param hdg_acc [degE5] Heading / track uncertainty
* @param yaw [cdeg] Yaw in earth frame from north. Use 0 if this GPS does not provide yaw. Use 65535 if this GPS is configured to provide yaw and is currently unable to provide it. Use 36000 for north.
* @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)
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,int32_t alt_ellipsoid,uint32_t h_acc,uint32_t v_acc,uint32_t vel_acc,uint32_t hdg_acc,uint16_t yaw)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_GPS_RAW_INT_LEN];
@ -151,6 +193,12 @@ static inline uint16_t mavlink_msg_gps_raw_int_pack_chan(uint8_t system_id, uint
_mav_put_uint16_t(buf, 26, cog);
_mav_put_uint8_t(buf, 28, fix_type);
_mav_put_uint8_t(buf, 29, satellites_visible);
_mav_put_int32_t(buf, 30, alt_ellipsoid);
_mav_put_uint32_t(buf, 34, h_acc);
_mav_put_uint32_t(buf, 38, v_acc);
_mav_put_uint32_t(buf, 42, vel_acc);
_mav_put_uint32_t(buf, 46, hdg_acc);
_mav_put_uint16_t(buf, 50, yaw);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_GPS_RAW_INT_LEN);
#else
@ -165,6 +213,12 @@ static inline uint16_t mavlink_msg_gps_raw_int_pack_chan(uint8_t system_id, uint
packet.cog = cog;
packet.fix_type = fix_type;
packet.satellites_visible = satellites_visible;
packet.alt_ellipsoid = alt_ellipsoid;
packet.h_acc = h_acc;
packet.v_acc = v_acc;
packet.vel_acc = vel_acc;
packet.hdg_acc = hdg_acc;
packet.yaw = yaw;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_GPS_RAW_INT_LEN);
#endif
@ -183,7 +237,7 @@ static inline uint16_t mavlink_msg_gps_raw_int_pack_chan(uint8_t system_id, uint
*/
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);
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, gps_raw_int->alt_ellipsoid, gps_raw_int->h_acc, gps_raw_int->v_acc, gps_raw_int->vel_acc, gps_raw_int->hdg_acc, gps_raw_int->yaw);
}
/**
@ -197,7 +251,7 @@ static inline uint16_t mavlink_msg_gps_raw_int_encode(uint8_t system_id, uint8_t
*/
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);
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, gps_raw_int->alt_ellipsoid, gps_raw_int->h_acc, gps_raw_int->v_acc, gps_raw_int->vel_acc, gps_raw_int->hdg_acc, gps_raw_int->yaw);
}
/**
@ -214,10 +268,16 @@ static inline uint16_t mavlink_msg_gps_raw_int_encode_chan(uint8_t system_id, ui
* @param vel [cm/s] GPS ground speed. If unknown, set to: UINT16_MAX
* @param cog [cdeg] 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 alt_ellipsoid [mm] Altitude (above WGS84, EGM96 ellipsoid). Positive for up.
* @param h_acc [mm] Position uncertainty.
* @param v_acc [mm] Altitude uncertainty.
* @param vel_acc [mm] Speed uncertainty.
* @param hdg_acc [degE5] Heading / track uncertainty
* @param yaw [cdeg] Yaw in earth frame from north. Use 0 if this GPS does not provide yaw. Use 65535 if this GPS is configured to provide yaw and is currently unable to provide it. Use 36000 for north.
*/
#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)
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, int32_t alt_ellipsoid, uint32_t h_acc, uint32_t v_acc, uint32_t vel_acc, uint32_t hdg_acc, uint16_t yaw)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_GPS_RAW_INT_LEN];
@ -231,6 +291,12 @@ static inline void mavlink_msg_gps_raw_int_send(mavlink_channel_t chan, uint64_t
_mav_put_uint16_t(buf, 26, cog);
_mav_put_uint8_t(buf, 28, fix_type);
_mav_put_uint8_t(buf, 29, satellites_visible);
_mav_put_int32_t(buf, 30, alt_ellipsoid);
_mav_put_uint32_t(buf, 34, h_acc);
_mav_put_uint32_t(buf, 38, v_acc);
_mav_put_uint32_t(buf, 42, vel_acc);
_mav_put_uint32_t(buf, 46, hdg_acc);
_mav_put_uint16_t(buf, 50, yaw);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RAW_INT, buf, MAVLINK_MSG_ID_GPS_RAW_INT_MIN_LEN, MAVLINK_MSG_ID_GPS_RAW_INT_LEN, MAVLINK_MSG_ID_GPS_RAW_INT_CRC);
#else
@ -245,6 +311,12 @@ static inline void mavlink_msg_gps_raw_int_send(mavlink_channel_t chan, uint64_t
packet.cog = cog;
packet.fix_type = fix_type;
packet.satellites_visible = satellites_visible;
packet.alt_ellipsoid = alt_ellipsoid;
packet.h_acc = h_acc;
packet.v_acc = v_acc;
packet.vel_acc = vel_acc;
packet.hdg_acc = hdg_acc;
packet.yaw = yaw;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RAW_INT, (const char *)&packet, MAVLINK_MSG_ID_GPS_RAW_INT_MIN_LEN, MAVLINK_MSG_ID_GPS_RAW_INT_LEN, MAVLINK_MSG_ID_GPS_RAW_INT_CRC);
#endif
@ -258,7 +330,7 @@ static inline void mavlink_msg_gps_raw_int_send(mavlink_channel_t chan, uint64_t
static inline void mavlink_msg_gps_raw_int_send_struct(mavlink_channel_t chan, const mavlink_gps_raw_int_t* gps_raw_int)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mavlink_msg_gps_raw_int_send(chan, 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);
mavlink_msg_gps_raw_int_send(chan, 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, gps_raw_int->alt_ellipsoid, gps_raw_int->h_acc, gps_raw_int->v_acc, gps_raw_int->vel_acc, gps_raw_int->hdg_acc, gps_raw_int->yaw);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RAW_INT, (const char *)gps_raw_int, MAVLINK_MSG_ID_GPS_RAW_INT_MIN_LEN, MAVLINK_MSG_ID_GPS_RAW_INT_LEN, MAVLINK_MSG_ID_GPS_RAW_INT_CRC);
#endif
@ -272,7 +344,7 @@ static inline void mavlink_msg_gps_raw_int_send_struct(mavlink_channel_t chan, c
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)
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, int32_t alt_ellipsoid, uint32_t h_acc, uint32_t v_acc, uint32_t vel_acc, uint32_t hdg_acc, uint16_t yaw)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
@ -286,6 +358,12 @@ static inline void mavlink_msg_gps_raw_int_send_buf(mavlink_message_t *msgbuf, m
_mav_put_uint16_t(buf, 26, cog);
_mav_put_uint8_t(buf, 28, fix_type);
_mav_put_uint8_t(buf, 29, satellites_visible);
_mav_put_int32_t(buf, 30, alt_ellipsoid);
_mav_put_uint32_t(buf, 34, h_acc);
_mav_put_uint32_t(buf, 38, v_acc);
_mav_put_uint32_t(buf, 42, vel_acc);
_mav_put_uint32_t(buf, 46, hdg_acc);
_mav_put_uint16_t(buf, 50, yaw);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RAW_INT, buf, MAVLINK_MSG_ID_GPS_RAW_INT_MIN_LEN, MAVLINK_MSG_ID_GPS_RAW_INT_LEN, MAVLINK_MSG_ID_GPS_RAW_INT_CRC);
#else
@ -300,6 +378,12 @@ static inline void mavlink_msg_gps_raw_int_send_buf(mavlink_message_t *msgbuf, m
packet->cog = cog;
packet->fix_type = fix_type;
packet->satellites_visible = satellites_visible;
packet->alt_ellipsoid = alt_ellipsoid;
packet->h_acc = h_acc;
packet->v_acc = v_acc;
packet->vel_acc = vel_acc;
packet->hdg_acc = hdg_acc;
packet->yaw = yaw;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_GPS_RAW_INT, (const char *)packet, MAVLINK_MSG_ID_GPS_RAW_INT_MIN_LEN, MAVLINK_MSG_ID_GPS_RAW_INT_LEN, MAVLINK_MSG_ID_GPS_RAW_INT_CRC);
#endif
@ -411,6 +495,66 @@ static inline uint8_t mavlink_msg_gps_raw_int_get_satellites_visible(const mavli
return _MAV_RETURN_uint8_t(msg, 29);
}
/**
* @brief Get field alt_ellipsoid from gps_raw_int message
*
* @return [mm] Altitude (above WGS84, EGM96 ellipsoid). Positive for up.
*/
static inline int32_t mavlink_msg_gps_raw_int_get_alt_ellipsoid(const mavlink_message_t* msg)
{
return _MAV_RETURN_int32_t(msg, 30);
}
/**
* @brief Get field h_acc from gps_raw_int message
*
* @return [mm] Position uncertainty.
*/
static inline uint32_t mavlink_msg_gps_raw_int_get_h_acc(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint32_t(msg, 34);
}
/**
* @brief Get field v_acc from gps_raw_int message
*
* @return [mm] Altitude uncertainty.
*/
static inline uint32_t mavlink_msg_gps_raw_int_get_v_acc(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint32_t(msg, 38);
}
/**
* @brief Get field vel_acc from gps_raw_int message
*
* @return [mm] Speed uncertainty.
*/
static inline uint32_t mavlink_msg_gps_raw_int_get_vel_acc(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint32_t(msg, 42);
}
/**
* @brief Get field hdg_acc from gps_raw_int message
*
* @return [degE5] Heading / track uncertainty
*/
static inline uint32_t mavlink_msg_gps_raw_int_get_hdg_acc(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint32_t(msg, 46);
}
/**
* @brief Get field yaw from gps_raw_int message
*
* @return [cdeg] Yaw in earth frame from north. Use 0 if this GPS does not provide yaw. Use 65535 if this GPS is configured to provide yaw and is currently unable to provide it. Use 36000 for north.
*/
static inline uint16_t mavlink_msg_gps_raw_int_get_yaw(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 50);
}
/**
* @brief Decode a gps_raw_int message into a struct
*
@ -430,6 +574,12 @@ static inline void mavlink_msg_gps_raw_int_decode(const mavlink_message_t* 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);
gps_raw_int->alt_ellipsoid = mavlink_msg_gps_raw_int_get_alt_ellipsoid(msg);
gps_raw_int->h_acc = mavlink_msg_gps_raw_int_get_h_acc(msg);
gps_raw_int->v_acc = mavlink_msg_gps_raw_int_get_v_acc(msg);
gps_raw_int->vel_acc = mavlink_msg_gps_raw_int_get_vel_acc(msg);
gps_raw_int->hdg_acc = mavlink_msg_gps_raw_int_get_hdg_acc(msg);
gps_raw_int->yaw = mavlink_msg_gps_raw_int_get_yaw(msg);
#else
uint8_t len = msg->len < MAVLINK_MSG_ID_GPS_RAW_INT_LEN? msg->len : MAVLINK_MSG_ID_GPS_RAW_INT_LEN;
memset(gps_raw_int, 0, MAVLINK_MSG_ID_GPS_RAW_INT_LEN);

View file

@ -15,16 +15,17 @@ typedef struct __mavlink_highres_imu_t {
float xmag; /*< [gauss] X Magnetic field*/
float ymag; /*< [gauss] Y Magnetic field*/
float zmag; /*< [gauss] Z Magnetic field*/
float abs_pressure; /*< [mbar] Absolute pressure*/
float diff_pressure; /*< [mbar] Differential pressure*/
float abs_pressure; /*< [hPa] Absolute pressure*/
float diff_pressure; /*< [hPa] Differential pressure*/
float pressure_alt; /*< Altitude calculated from pressure*/
float temperature; /*< [degC] Temperature*/
uint16_t fields_updated; /*< Bitmap for fields that have updated since last message, bit 0 = xacc, bit 12: temperature*/
uint8_t id; /*< Id. Ids are numbered from 0 and map to IMUs numbered from 1 (e.g. IMU1 will have a message with id=0)*/
} mavlink_highres_imu_t;
#define MAVLINK_MSG_ID_HIGHRES_IMU_LEN 62
#define MAVLINK_MSG_ID_HIGHRES_IMU_LEN 63
#define MAVLINK_MSG_ID_HIGHRES_IMU_MIN_LEN 62
#define MAVLINK_MSG_ID_105_LEN 62
#define MAVLINK_MSG_ID_105_LEN 63
#define MAVLINK_MSG_ID_105_MIN_LEN 62
#define MAVLINK_MSG_ID_HIGHRES_IMU_CRC 93
@ -36,7 +37,7 @@ typedef struct __mavlink_highres_imu_t {
#define MAVLINK_MESSAGE_INFO_HIGHRES_IMU { \
105, \
"HIGHRES_IMU", \
15, \
16, \
{ { "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) }, \
@ -52,12 +53,13 @@ typedef struct __mavlink_highres_imu_t {
{ "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) }, \
{ "id", NULL, MAVLINK_TYPE_UINT8_T, 0, 62, offsetof(mavlink_highres_imu_t, id) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_HIGHRES_IMU { \
"HIGHRES_IMU", \
15, \
16, \
{ { "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) }, \
@ -73,6 +75,7 @@ typedef struct __mavlink_highres_imu_t {
{ "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) }, \
{ "id", NULL, MAVLINK_TYPE_UINT8_T, 0, 62, offsetof(mavlink_highres_imu_t, id) }, \
} \
}
#endif
@ -93,15 +96,16 @@ typedef struct __mavlink_highres_imu_t {
* @param xmag [gauss] X Magnetic field
* @param ymag [gauss] Y Magnetic field
* @param zmag [gauss] Z Magnetic field
* @param abs_pressure [mbar] Absolute pressure
* @param diff_pressure [mbar] Differential pressure
* @param abs_pressure [hPa] Absolute pressure
* @param diff_pressure [hPa] Differential pressure
* @param pressure_alt Altitude calculated from pressure
* @param temperature [degC] Temperature
* @param fields_updated Bitmap for fields that have updated since last message, bit 0 = xacc, bit 12: temperature
* @param id Id. Ids are numbered from 0 and map to IMUs numbered from 1 (e.g. IMU1 will have a message with id=0)
* @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)
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, uint8_t id)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_HIGHRES_IMU_LEN];
@ -120,6 +124,7 @@ static inline uint16_t mavlink_msg_highres_imu_pack(uint8_t system_id, uint8_t c
_mav_put_float(buf, 52, pressure_alt);
_mav_put_float(buf, 56, temperature);
_mav_put_uint16_t(buf, 60, fields_updated);
_mav_put_uint8_t(buf, 62, id);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HIGHRES_IMU_LEN);
#else
@ -139,6 +144,7 @@ static inline uint16_t mavlink_msg_highres_imu_pack(uint8_t system_id, uint8_t c
packet.pressure_alt = pressure_alt;
packet.temperature = temperature;
packet.fields_updated = fields_updated;
packet.id = id;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HIGHRES_IMU_LEN);
#endif
@ -163,16 +169,17 @@ static inline uint16_t mavlink_msg_highres_imu_pack(uint8_t system_id, uint8_t c
* @param xmag [gauss] X Magnetic field
* @param ymag [gauss] Y Magnetic field
* @param zmag [gauss] Z Magnetic field
* @param abs_pressure [mbar] Absolute pressure
* @param diff_pressure [mbar] Differential pressure
* @param abs_pressure [hPa] Absolute pressure
* @param diff_pressure [hPa] Differential pressure
* @param pressure_alt Altitude calculated from pressure
* @param temperature [degC] Temperature
* @param fields_updated Bitmap for fields that have updated since last message, bit 0 = xacc, bit 12: temperature
* @param id Id. Ids are numbered from 0 and map to IMUs numbered from 1 (e.g. IMU1 will have a message with id=0)
* @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)
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,uint8_t id)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_HIGHRES_IMU_LEN];
@ -191,6 +198,7 @@ static inline uint16_t mavlink_msg_highres_imu_pack_chan(uint8_t system_id, uint
_mav_put_float(buf, 52, pressure_alt);
_mav_put_float(buf, 56, temperature);
_mav_put_uint16_t(buf, 60, fields_updated);
_mav_put_uint8_t(buf, 62, id);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HIGHRES_IMU_LEN);
#else
@ -210,6 +218,7 @@ static inline uint16_t mavlink_msg_highres_imu_pack_chan(uint8_t system_id, uint
packet.pressure_alt = pressure_alt;
packet.temperature = temperature;
packet.fields_updated = fields_updated;
packet.id = id;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HIGHRES_IMU_LEN);
#endif
@ -228,7 +237,7 @@ static inline uint16_t mavlink_msg_highres_imu_pack_chan(uint8_t system_id, uint
*/
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);
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, highres_imu->id);
}
/**
@ -242,7 +251,7 @@ static inline uint16_t mavlink_msg_highres_imu_encode(uint8_t system_id, uint8_t
*/
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);
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, highres_imu->id);
}
/**
@ -259,15 +268,16 @@ static inline uint16_t mavlink_msg_highres_imu_encode_chan(uint8_t system_id, ui
* @param xmag [gauss] X Magnetic field
* @param ymag [gauss] Y Magnetic field
* @param zmag [gauss] Z Magnetic field
* @param abs_pressure [mbar] Absolute pressure
* @param diff_pressure [mbar] Differential pressure
* @param abs_pressure [hPa] Absolute pressure
* @param diff_pressure [hPa] Differential pressure
* @param pressure_alt Altitude calculated from pressure
* @param temperature [degC] Temperature
* @param fields_updated Bitmap for fields that have updated since last message, bit 0 = xacc, bit 12: temperature
* @param id Id. Ids are numbered from 0 and map to IMUs numbered from 1 (e.g. IMU1 will have a message with id=0)
*/
#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)
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, uint8_t id)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_HIGHRES_IMU_LEN];
@ -286,6 +296,7 @@ static inline void mavlink_msg_highres_imu_send(mavlink_channel_t chan, uint64_t
_mav_put_float(buf, 52, pressure_alt);
_mav_put_float(buf, 56, temperature);
_mav_put_uint16_t(buf, 60, fields_updated);
_mav_put_uint8_t(buf, 62, id);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIGHRES_IMU, buf, MAVLINK_MSG_ID_HIGHRES_IMU_MIN_LEN, MAVLINK_MSG_ID_HIGHRES_IMU_LEN, MAVLINK_MSG_ID_HIGHRES_IMU_CRC);
#else
@ -305,6 +316,7 @@ static inline void mavlink_msg_highres_imu_send(mavlink_channel_t chan, uint64_t
packet.pressure_alt = pressure_alt;
packet.temperature = temperature;
packet.fields_updated = fields_updated;
packet.id = id;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIGHRES_IMU, (const char *)&packet, MAVLINK_MSG_ID_HIGHRES_IMU_MIN_LEN, MAVLINK_MSG_ID_HIGHRES_IMU_LEN, MAVLINK_MSG_ID_HIGHRES_IMU_CRC);
#endif
@ -318,7 +330,7 @@ static inline void mavlink_msg_highres_imu_send(mavlink_channel_t chan, uint64_t
static inline void mavlink_msg_highres_imu_send_struct(mavlink_channel_t chan, const mavlink_highres_imu_t* highres_imu)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mavlink_msg_highres_imu_send(chan, 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);
mavlink_msg_highres_imu_send(chan, 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, highres_imu->id);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIGHRES_IMU, (const char *)highres_imu, MAVLINK_MSG_ID_HIGHRES_IMU_MIN_LEN, MAVLINK_MSG_ID_HIGHRES_IMU_LEN, MAVLINK_MSG_ID_HIGHRES_IMU_CRC);
#endif
@ -332,7 +344,7 @@ static inline void mavlink_msg_highres_imu_send_struct(mavlink_channel_t chan, c
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)
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, uint8_t id)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
@ -351,6 +363,7 @@ static inline void mavlink_msg_highres_imu_send_buf(mavlink_message_t *msgbuf, m
_mav_put_float(buf, 52, pressure_alt);
_mav_put_float(buf, 56, temperature);
_mav_put_uint16_t(buf, 60, fields_updated);
_mav_put_uint8_t(buf, 62, id);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIGHRES_IMU, buf, MAVLINK_MSG_ID_HIGHRES_IMU_MIN_LEN, MAVLINK_MSG_ID_HIGHRES_IMU_LEN, MAVLINK_MSG_ID_HIGHRES_IMU_CRC);
#else
@ -370,6 +383,7 @@ static inline void mavlink_msg_highres_imu_send_buf(mavlink_message_t *msgbuf, m
packet->pressure_alt = pressure_alt;
packet->temperature = temperature;
packet->fields_updated = fields_updated;
packet->id = id;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIGHRES_IMU, (const char *)packet, MAVLINK_MSG_ID_HIGHRES_IMU_MIN_LEN, MAVLINK_MSG_ID_HIGHRES_IMU_LEN, MAVLINK_MSG_ID_HIGHRES_IMU_CRC);
#endif
@ -484,7 +498,7 @@ static inline float mavlink_msg_highres_imu_get_zmag(const mavlink_message_t* ms
/**
* @brief Get field abs_pressure from highres_imu message
*
* @return [mbar] Absolute pressure
* @return [hPa] Absolute pressure
*/
static inline float mavlink_msg_highres_imu_get_abs_pressure(const mavlink_message_t* msg)
{
@ -494,7 +508,7 @@ static inline float mavlink_msg_highres_imu_get_abs_pressure(const mavlink_messa
/**
* @brief Get field diff_pressure from highres_imu message
*
* @return [mbar] Differential pressure
* @return [hPa] Differential pressure
*/
static inline float mavlink_msg_highres_imu_get_diff_pressure(const mavlink_message_t* msg)
{
@ -531,6 +545,16 @@ static inline uint16_t mavlink_msg_highres_imu_get_fields_updated(const mavlink_
return _MAV_RETURN_uint16_t(msg, 60);
}
/**
* @brief Get field id from highres_imu message
*
* @return Id. Ids are numbered from 0 and map to IMUs numbered from 1 (e.g. IMU1 will have a message with id=0)
*/
static inline uint8_t mavlink_msg_highres_imu_get_id(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 62);
}
/**
* @brief Decode a highres_imu message into a struct
*
@ -555,6 +579,7 @@ static inline void mavlink_msg_highres_imu_decode(const mavlink_message_t* 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);
highres_imu->id = mavlink_msg_highres_imu_get_id(msg);
#else
uint8_t len = msg->len < MAVLINK_MSG_ID_HIGHRES_IMU_LEN? msg->len : MAVLINK_MSG_ID_HIGHRES_IMU_LEN;
memset(highres_imu, 0, MAVLINK_MSG_ID_HIGHRES_IMU_LEN);

View file

@ -3,14 +3,14 @@
#define MAVLINK_MSG_ID_HIL_GPS 113
MAVPACKED(
typedef struct __mavlink_hil_gps_t {
uint64_t time_usec; /*< [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.*/
int32_t lat; /*< [degE7] Latitude (WGS84)*/
int32_t lon; /*< [degE7] Longitude (WGS84)*/
int32_t alt; /*< [mm] Altitude (MSL). Positive for up.*/
uint16_t eph; /*< [cm] GPS HDOP horizontal dilution of position. If unknown, set to: 65535*/
uint16_t epv; /*< [cm] GPS VDOP vertical dilution of position. If unknown, set to: 65535*/
uint16_t eph; /*< GPS HDOP horizontal dilution of position (unitless). If unknown, set to: UINT16_MAX*/
uint16_t epv; /*< GPS VDOP vertical dilution of position (unitless). If unknown, set to: UINT16_MAX*/
uint16_t vel; /*< [cm/s] GPS ground speed. If unknown, set to: 65535*/
int16_t vn; /*< [cm/s] GPS velocity in north direction in earth-fixed NED frame*/
int16_t ve; /*< [cm/s] GPS velocity in east direction in earth-fixed NED frame*/
@ -18,11 +18,13 @@ typedef struct __mavlink_hil_gps_t {
uint16_t cog; /*< [cdeg] Course over ground (NOT heading, but direction of movement), 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;
uint8_t id; /*< GPS ID (zero indexed). Used for multiple GPS inputs*/
uint16_t yaw; /*< [cdeg] Yaw of vehicle relative to Earth's North, zero means not available, use 36000 for north*/
}) mavlink_hil_gps_t;
#define MAVLINK_MSG_ID_HIL_GPS_LEN 36
#define MAVLINK_MSG_ID_HIL_GPS_LEN 39
#define MAVLINK_MSG_ID_HIL_GPS_MIN_LEN 36
#define MAVLINK_MSG_ID_113_LEN 36
#define MAVLINK_MSG_ID_113_LEN 39
#define MAVLINK_MSG_ID_113_MIN_LEN 36
#define MAVLINK_MSG_ID_HIL_GPS_CRC 124
@ -34,7 +36,7 @@ typedef struct __mavlink_hil_gps_t {
#define MAVLINK_MESSAGE_INFO_HIL_GPS { \
113, \
"HIL_GPS", \
13, \
15, \
{ { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_hil_gps_t, time_usec) }, \
{ "fix_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_hil_gps_t, fix_type) }, \
{ "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_hil_gps_t, lat) }, \
@ -48,12 +50,14 @@ typedef struct __mavlink_hil_gps_t {
{ "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) }, \
{ "satellites_visible", NULL, MAVLINK_TYPE_UINT8_T, 0, 35, offsetof(mavlink_hil_gps_t, satellites_visible) }, \
{ "id", NULL, MAVLINK_TYPE_UINT8_T, 0, 36, offsetof(mavlink_hil_gps_t, id) }, \
{ "yaw", NULL, MAVLINK_TYPE_UINT16_T, 0, 37, offsetof(mavlink_hil_gps_t, yaw) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_HIL_GPS { \
"HIL_GPS", \
13, \
15, \
{ { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_hil_gps_t, time_usec) }, \
{ "fix_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 34, offsetof(mavlink_hil_gps_t, fix_type) }, \
{ "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_hil_gps_t, lat) }, \
@ -67,6 +71,8 @@ typedef struct __mavlink_hil_gps_t {
{ "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) }, \
{ "satellites_visible", NULL, MAVLINK_TYPE_UINT8_T, 0, 35, offsetof(mavlink_hil_gps_t, satellites_visible) }, \
{ "id", NULL, MAVLINK_TYPE_UINT8_T, 0, 36, offsetof(mavlink_hil_gps_t, id) }, \
{ "yaw", NULL, MAVLINK_TYPE_UINT16_T, 0, 37, offsetof(mavlink_hil_gps_t, yaw) }, \
} \
}
#endif
@ -82,18 +88,20 @@ typedef struct __mavlink_hil_gps_t {
* @param lat [degE7] Latitude (WGS84)
* @param lon [degE7] Longitude (WGS84)
* @param alt [mm] Altitude (MSL). Positive for up.
* @param eph [cm] GPS HDOP horizontal dilution of position. If unknown, set to: 65535
* @param epv [cm] GPS VDOP vertical dilution of position. If unknown, set to: 65535
* @param eph GPS HDOP horizontal dilution of position (unitless). If unknown, set to: UINT16_MAX
* @param epv GPS VDOP vertical dilution of position (unitless). If unknown, set to: UINT16_MAX
* @param vel [cm/s] GPS ground speed. If unknown, set to: 65535
* @param vn [cm/s] GPS velocity in north direction in earth-fixed NED frame
* @param ve [cm/s] GPS velocity in east direction in earth-fixed NED frame
* @param vd [cm/s] GPS velocity in down direction in earth-fixed NED frame
* @param cog [cdeg] Course over ground (NOT heading, but direction of movement), 0.0..359.99 degrees. If unknown, set to: 65535
* @param satellites_visible Number of satellites visible. If unknown, set to 255
* @param id GPS ID (zero indexed). Used for multiple GPS inputs
* @param yaw [cdeg] Yaw of vehicle relative to Earth's North, zero means not available, use 36000 for north
* @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)
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, uint8_t id, uint16_t yaw)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_HIL_GPS_LEN];
@ -110,6 +118,8 @@ static inline uint16_t mavlink_msg_hil_gps_pack(uint8_t system_id, uint8_t compo
_mav_put_uint16_t(buf, 32, cog);
_mav_put_uint8_t(buf, 34, fix_type);
_mav_put_uint8_t(buf, 35, satellites_visible);
_mav_put_uint8_t(buf, 36, id);
_mav_put_uint16_t(buf, 37, yaw);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HIL_GPS_LEN);
#else
@ -127,6 +137,8 @@ static inline uint16_t mavlink_msg_hil_gps_pack(uint8_t system_id, uint8_t compo
packet.cog = cog;
packet.fix_type = fix_type;
packet.satellites_visible = satellites_visible;
packet.id = id;
packet.yaw = yaw;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HIL_GPS_LEN);
#endif
@ -146,19 +158,21 @@ static inline uint16_t mavlink_msg_hil_gps_pack(uint8_t system_id, uint8_t compo
* @param lat [degE7] Latitude (WGS84)
* @param lon [degE7] Longitude (WGS84)
* @param alt [mm] Altitude (MSL). Positive for up.
* @param eph [cm] GPS HDOP horizontal dilution of position. If unknown, set to: 65535
* @param epv [cm] GPS VDOP vertical dilution of position. If unknown, set to: 65535
* @param eph GPS HDOP horizontal dilution of position (unitless). If unknown, set to: UINT16_MAX
* @param epv GPS VDOP vertical dilution of position (unitless). If unknown, set to: UINT16_MAX
* @param vel [cm/s] GPS ground speed. If unknown, set to: 65535
* @param vn [cm/s] GPS velocity in north direction in earth-fixed NED frame
* @param ve [cm/s] GPS velocity in east direction in earth-fixed NED frame
* @param vd [cm/s] GPS velocity in down direction in earth-fixed NED frame
* @param cog [cdeg] Course over ground (NOT heading, but direction of movement), 0.0..359.99 degrees. If unknown, set to: 65535
* @param satellites_visible Number of satellites visible. If unknown, set to 255
* @param id GPS ID (zero indexed). Used for multiple GPS inputs
* @param yaw [cdeg] Yaw of vehicle relative to Earth's North, zero means not available, use 36000 for north
* @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)
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,uint8_t id,uint16_t yaw)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_HIL_GPS_LEN];
@ -175,6 +189,8 @@ static inline uint16_t mavlink_msg_hil_gps_pack_chan(uint8_t system_id, uint8_t
_mav_put_uint16_t(buf, 32, cog);
_mav_put_uint8_t(buf, 34, fix_type);
_mav_put_uint8_t(buf, 35, satellites_visible);
_mav_put_uint8_t(buf, 36, id);
_mav_put_uint16_t(buf, 37, yaw);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HIL_GPS_LEN);
#else
@ -192,6 +208,8 @@ static inline uint16_t mavlink_msg_hil_gps_pack_chan(uint8_t system_id, uint8_t
packet.cog = cog;
packet.fix_type = fix_type;
packet.satellites_visible = satellites_visible;
packet.id = id;
packet.yaw = yaw;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HIL_GPS_LEN);
#endif
@ -210,7 +228,7 @@ static inline uint16_t mavlink_msg_hil_gps_pack_chan(uint8_t system_id, uint8_t
*/
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);
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, hil_gps->id, hil_gps->yaw);
}
/**
@ -224,7 +242,7 @@ static inline uint16_t mavlink_msg_hil_gps_encode(uint8_t system_id, uint8_t com
*/
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);
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, hil_gps->id, hil_gps->yaw);
}
/**
@ -236,18 +254,20 @@ static inline uint16_t mavlink_msg_hil_gps_encode_chan(uint8_t system_id, uint8_
* @param lat [degE7] Latitude (WGS84)
* @param lon [degE7] Longitude (WGS84)
* @param alt [mm] Altitude (MSL). Positive for up.
* @param eph [cm] GPS HDOP horizontal dilution of position. If unknown, set to: 65535
* @param epv [cm] GPS VDOP vertical dilution of position. If unknown, set to: 65535
* @param eph GPS HDOP horizontal dilution of position (unitless). If unknown, set to: UINT16_MAX
* @param epv GPS VDOP vertical dilution of position (unitless). If unknown, set to: UINT16_MAX
* @param vel [cm/s] GPS ground speed. If unknown, set to: 65535
* @param vn [cm/s] GPS velocity in north direction in earth-fixed NED frame
* @param ve [cm/s] GPS velocity in east direction in earth-fixed NED frame
* @param vd [cm/s] GPS velocity in down direction in earth-fixed NED frame
* @param cog [cdeg] Course over ground (NOT heading, but direction of movement), 0.0..359.99 degrees. If unknown, set to: 65535
* @param satellites_visible Number of satellites visible. If unknown, set to 255
* @param id GPS ID (zero indexed). Used for multiple GPS inputs
* @param yaw [cdeg] Yaw of vehicle relative to Earth's North, zero means not available, use 36000 for north
*/
#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)
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, uint8_t id, uint16_t yaw)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_HIL_GPS_LEN];
@ -264,6 +284,8 @@ static inline void mavlink_msg_hil_gps_send(mavlink_channel_t chan, uint64_t tim
_mav_put_uint16_t(buf, 32, cog);
_mav_put_uint8_t(buf, 34, fix_type);
_mav_put_uint8_t(buf, 35, satellites_visible);
_mav_put_uint8_t(buf, 36, id);
_mav_put_uint16_t(buf, 37, yaw);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_GPS, buf, MAVLINK_MSG_ID_HIL_GPS_MIN_LEN, MAVLINK_MSG_ID_HIL_GPS_LEN, MAVLINK_MSG_ID_HIL_GPS_CRC);
#else
@ -281,6 +303,8 @@ static inline void mavlink_msg_hil_gps_send(mavlink_channel_t chan, uint64_t tim
packet.cog = cog;
packet.fix_type = fix_type;
packet.satellites_visible = satellites_visible;
packet.id = id;
packet.yaw = yaw;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_GPS, (const char *)&packet, MAVLINK_MSG_ID_HIL_GPS_MIN_LEN, MAVLINK_MSG_ID_HIL_GPS_LEN, MAVLINK_MSG_ID_HIL_GPS_CRC);
#endif
@ -294,7 +318,7 @@ static inline void mavlink_msg_hil_gps_send(mavlink_channel_t chan, uint64_t tim
static inline void mavlink_msg_hil_gps_send_struct(mavlink_channel_t chan, const mavlink_hil_gps_t* hil_gps)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mavlink_msg_hil_gps_send(chan, 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);
mavlink_msg_hil_gps_send(chan, 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, hil_gps->id, hil_gps->yaw);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_GPS, (const char *)hil_gps, MAVLINK_MSG_ID_HIL_GPS_MIN_LEN, MAVLINK_MSG_ID_HIL_GPS_LEN, MAVLINK_MSG_ID_HIL_GPS_CRC);
#endif
@ -308,7 +332,7 @@ static inline void mavlink_msg_hil_gps_send_struct(mavlink_channel_t chan, const
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)
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, uint8_t id, uint16_t yaw)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
@ -325,6 +349,8 @@ static inline void mavlink_msg_hil_gps_send_buf(mavlink_message_t *msgbuf, mavli
_mav_put_uint16_t(buf, 32, cog);
_mav_put_uint8_t(buf, 34, fix_type);
_mav_put_uint8_t(buf, 35, satellites_visible);
_mav_put_uint8_t(buf, 36, id);
_mav_put_uint16_t(buf, 37, yaw);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_GPS, buf, MAVLINK_MSG_ID_HIL_GPS_MIN_LEN, MAVLINK_MSG_ID_HIL_GPS_LEN, MAVLINK_MSG_ID_HIL_GPS_CRC);
#else
@ -342,6 +368,8 @@ static inline void mavlink_msg_hil_gps_send_buf(mavlink_message_t *msgbuf, mavli
packet->cog = cog;
packet->fix_type = fix_type;
packet->satellites_visible = satellites_visible;
packet->id = id;
packet->yaw = yaw;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_GPS, (const char *)packet, MAVLINK_MSG_ID_HIL_GPS_MIN_LEN, MAVLINK_MSG_ID_HIL_GPS_LEN, MAVLINK_MSG_ID_HIL_GPS_CRC);
#endif
@ -406,7 +434,7 @@ static inline int32_t mavlink_msg_hil_gps_get_alt(const mavlink_message_t* msg)
/**
* @brief Get field eph from hil_gps message
*
* @return [cm] GPS HDOP horizontal dilution of position. If unknown, set to: 65535
* @return GPS HDOP horizontal dilution of position (unitless). If unknown, set to: UINT16_MAX
*/
static inline uint16_t mavlink_msg_hil_gps_get_eph(const mavlink_message_t* msg)
{
@ -416,7 +444,7 @@ static inline uint16_t mavlink_msg_hil_gps_get_eph(const mavlink_message_t* msg)
/**
* @brief Get field epv from hil_gps message
*
* @return [cm] GPS VDOP vertical dilution of position. If unknown, set to: 65535
* @return GPS VDOP vertical dilution of position (unitless). If unknown, set to: UINT16_MAX
*/
static inline uint16_t mavlink_msg_hil_gps_get_epv(const mavlink_message_t* msg)
{
@ -483,6 +511,26 @@ static inline uint8_t mavlink_msg_hil_gps_get_satellites_visible(const mavlink_m
return _MAV_RETURN_uint8_t(msg, 35);
}
/**
* @brief Get field id from hil_gps message
*
* @return GPS ID (zero indexed). Used for multiple GPS inputs
*/
static inline uint8_t mavlink_msg_hil_gps_get_id(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 36);
}
/**
* @brief Get field yaw from hil_gps message
*
* @return [cdeg] Yaw of vehicle relative to Earth's North, zero means not available, use 36000 for north
*/
static inline uint16_t mavlink_msg_hil_gps_get_yaw(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 37);
}
/**
* @brief Decode a hil_gps message into a struct
*
@ -505,6 +553,8 @@ static inline void mavlink_msg_hil_gps_decode(const mavlink_message_t* msg, mavl
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);
hil_gps->id = mavlink_msg_hil_gps_get_id(msg);
hil_gps->yaw = mavlink_msg_hil_gps_get_yaw(msg);
#else
uint8_t len = msg->len < MAVLINK_MSG_ID_HIL_GPS_LEN? msg->len : MAVLINK_MSG_ID_HIL_GPS_LEN;
memset(hil_gps, 0, MAVLINK_MSG_ID_HIL_GPS_LEN);

View file

@ -15,16 +15,17 @@ typedef struct __mavlink_hil_sensor_t {
float xmag; /*< [gauss] X Magnetic field*/
float ymag; /*< [gauss] Y Magnetic field*/
float zmag; /*< [gauss] Z Magnetic field*/
float abs_pressure; /*< [mbar] Absolute pressure*/
float diff_pressure; /*< [mbar] Differential pressure (airspeed)*/
float abs_pressure; /*< [hPa] Absolute pressure*/
float diff_pressure; /*< [hPa] Differential pressure (airspeed)*/
float pressure_alt; /*< Altitude calculated from pressure*/
float temperature; /*< [degC] Temperature*/
uint32_t fields_updated; /*< Bitmap for fields that have updated since last message, bit 0 = xacc, bit 12: temperature, bit 31: full reset of attitude/position/velocities/etc was performed in sim.*/
uint8_t id; /*< Sensor ID (zero indexed). Used for multiple sensor inputs*/
} mavlink_hil_sensor_t;
#define MAVLINK_MSG_ID_HIL_SENSOR_LEN 64
#define MAVLINK_MSG_ID_HIL_SENSOR_LEN 65
#define MAVLINK_MSG_ID_HIL_SENSOR_MIN_LEN 64
#define MAVLINK_MSG_ID_107_LEN 64
#define MAVLINK_MSG_ID_107_LEN 65
#define MAVLINK_MSG_ID_107_MIN_LEN 64
#define MAVLINK_MSG_ID_HIL_SENSOR_CRC 108
@ -36,7 +37,7 @@ typedef struct __mavlink_hil_sensor_t {
#define MAVLINK_MESSAGE_INFO_HIL_SENSOR { \
107, \
"HIL_SENSOR", \
15, \
16, \
{ { "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) }, \
@ -52,12 +53,13 @@ typedef struct __mavlink_hil_sensor_t {
{ "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) }, \
{ "id", NULL, MAVLINK_TYPE_UINT8_T, 0, 64, offsetof(mavlink_hil_sensor_t, id) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_HIL_SENSOR { \
"HIL_SENSOR", \
15, \
16, \
{ { "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) }, \
@ -73,6 +75,7 @@ typedef struct __mavlink_hil_sensor_t {
{ "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) }, \
{ "id", NULL, MAVLINK_TYPE_UINT8_T, 0, 64, offsetof(mavlink_hil_sensor_t, id) }, \
} \
}
#endif
@ -93,15 +96,16 @@ typedef struct __mavlink_hil_sensor_t {
* @param xmag [gauss] X Magnetic field
* @param ymag [gauss] Y Magnetic field
* @param zmag [gauss] Z Magnetic field
* @param abs_pressure [mbar] Absolute pressure
* @param diff_pressure [mbar] Differential pressure (airspeed)
* @param abs_pressure [hPa] Absolute pressure
* @param diff_pressure [hPa] Differential pressure (airspeed)
* @param pressure_alt Altitude calculated from pressure
* @param temperature [degC] Temperature
* @param fields_updated Bitmap for fields that have updated since last message, bit 0 = xacc, bit 12: temperature, bit 31: full reset of attitude/position/velocities/etc was performed in sim.
* @param id Sensor ID (zero indexed). Used for multiple sensor inputs
* @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)
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, uint8_t id)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_HIL_SENSOR_LEN];
@ -120,6 +124,7 @@ static inline uint16_t mavlink_msg_hil_sensor_pack(uint8_t system_id, uint8_t co
_mav_put_float(buf, 52, pressure_alt);
_mav_put_float(buf, 56, temperature);
_mav_put_uint32_t(buf, 60, fields_updated);
_mav_put_uint8_t(buf, 64, id);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HIL_SENSOR_LEN);
#else
@ -139,6 +144,7 @@ static inline uint16_t mavlink_msg_hil_sensor_pack(uint8_t system_id, uint8_t co
packet.pressure_alt = pressure_alt;
packet.temperature = temperature;
packet.fields_updated = fields_updated;
packet.id = id;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HIL_SENSOR_LEN);
#endif
@ -163,16 +169,17 @@ static inline uint16_t mavlink_msg_hil_sensor_pack(uint8_t system_id, uint8_t co
* @param xmag [gauss] X Magnetic field
* @param ymag [gauss] Y Magnetic field
* @param zmag [gauss] Z Magnetic field
* @param abs_pressure [mbar] Absolute pressure
* @param diff_pressure [mbar] Differential pressure (airspeed)
* @param abs_pressure [hPa] Absolute pressure
* @param diff_pressure [hPa] Differential pressure (airspeed)
* @param pressure_alt Altitude calculated from pressure
* @param temperature [degC] Temperature
* @param fields_updated Bitmap for fields that have updated since last message, bit 0 = xacc, bit 12: temperature, bit 31: full reset of attitude/position/velocities/etc was performed in sim.
* @param id Sensor ID (zero indexed). Used for multiple sensor inputs
* @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)
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,uint8_t id)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_HIL_SENSOR_LEN];
@ -191,6 +198,7 @@ static inline uint16_t mavlink_msg_hil_sensor_pack_chan(uint8_t system_id, uint8
_mav_put_float(buf, 52, pressure_alt);
_mav_put_float(buf, 56, temperature);
_mav_put_uint32_t(buf, 60, fields_updated);
_mav_put_uint8_t(buf, 64, id);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HIL_SENSOR_LEN);
#else
@ -210,6 +218,7 @@ static inline uint16_t mavlink_msg_hil_sensor_pack_chan(uint8_t system_id, uint8
packet.pressure_alt = pressure_alt;
packet.temperature = temperature;
packet.fields_updated = fields_updated;
packet.id = id;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HIL_SENSOR_LEN);
#endif
@ -228,7 +237,7 @@ static inline uint16_t mavlink_msg_hil_sensor_pack_chan(uint8_t system_id, uint8
*/
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);
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, hil_sensor->id);
}
/**
@ -242,7 +251,7 @@ static inline uint16_t mavlink_msg_hil_sensor_encode(uint8_t system_id, uint8_t
*/
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);
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, hil_sensor->id);
}
/**
@ -259,15 +268,16 @@ static inline uint16_t mavlink_msg_hil_sensor_encode_chan(uint8_t system_id, uin
* @param xmag [gauss] X Magnetic field
* @param ymag [gauss] Y Magnetic field
* @param zmag [gauss] Z Magnetic field
* @param abs_pressure [mbar] Absolute pressure
* @param diff_pressure [mbar] Differential pressure (airspeed)
* @param abs_pressure [hPa] Absolute pressure
* @param diff_pressure [hPa] Differential pressure (airspeed)
* @param pressure_alt Altitude calculated from pressure
* @param temperature [degC] Temperature
* @param fields_updated Bitmap for fields that have updated since last message, bit 0 = xacc, bit 12: temperature, bit 31: full reset of attitude/position/velocities/etc was performed in sim.
* @param id Sensor ID (zero indexed). Used for multiple sensor inputs
*/
#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)
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, uint8_t id)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_HIL_SENSOR_LEN];
@ -286,6 +296,7 @@ static inline void mavlink_msg_hil_sensor_send(mavlink_channel_t chan, uint64_t
_mav_put_float(buf, 52, pressure_alt);
_mav_put_float(buf, 56, temperature);
_mav_put_uint32_t(buf, 60, fields_updated);
_mav_put_uint8_t(buf, 64, id);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_SENSOR, buf, MAVLINK_MSG_ID_HIL_SENSOR_MIN_LEN, MAVLINK_MSG_ID_HIL_SENSOR_LEN, MAVLINK_MSG_ID_HIL_SENSOR_CRC);
#else
@ -305,6 +316,7 @@ static inline void mavlink_msg_hil_sensor_send(mavlink_channel_t chan, uint64_t
packet.pressure_alt = pressure_alt;
packet.temperature = temperature;
packet.fields_updated = fields_updated;
packet.id = id;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_SENSOR, (const char *)&packet, MAVLINK_MSG_ID_HIL_SENSOR_MIN_LEN, MAVLINK_MSG_ID_HIL_SENSOR_LEN, MAVLINK_MSG_ID_HIL_SENSOR_CRC);
#endif
@ -318,7 +330,7 @@ static inline void mavlink_msg_hil_sensor_send(mavlink_channel_t chan, uint64_t
static inline void mavlink_msg_hil_sensor_send_struct(mavlink_channel_t chan, const mavlink_hil_sensor_t* hil_sensor)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mavlink_msg_hil_sensor_send(chan, 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);
mavlink_msg_hil_sensor_send(chan, 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, hil_sensor->id);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_SENSOR, (const char *)hil_sensor, MAVLINK_MSG_ID_HIL_SENSOR_MIN_LEN, MAVLINK_MSG_ID_HIL_SENSOR_LEN, MAVLINK_MSG_ID_HIL_SENSOR_CRC);
#endif
@ -332,7 +344,7 @@ static inline void mavlink_msg_hil_sensor_send_struct(mavlink_channel_t chan, co
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)
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, uint8_t id)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
@ -351,6 +363,7 @@ static inline void mavlink_msg_hil_sensor_send_buf(mavlink_message_t *msgbuf, ma
_mav_put_float(buf, 52, pressure_alt);
_mav_put_float(buf, 56, temperature);
_mav_put_uint32_t(buf, 60, fields_updated);
_mav_put_uint8_t(buf, 64, id);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_SENSOR, buf, MAVLINK_MSG_ID_HIL_SENSOR_MIN_LEN, MAVLINK_MSG_ID_HIL_SENSOR_LEN, MAVLINK_MSG_ID_HIL_SENSOR_CRC);
#else
@ -370,6 +383,7 @@ static inline void mavlink_msg_hil_sensor_send_buf(mavlink_message_t *msgbuf, ma
packet->pressure_alt = pressure_alt;
packet->temperature = temperature;
packet->fields_updated = fields_updated;
packet->id = id;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HIL_SENSOR, (const char *)packet, MAVLINK_MSG_ID_HIL_SENSOR_MIN_LEN, MAVLINK_MSG_ID_HIL_SENSOR_LEN, MAVLINK_MSG_ID_HIL_SENSOR_CRC);
#endif
@ -484,7 +498,7 @@ static inline float mavlink_msg_hil_sensor_get_zmag(const mavlink_message_t* msg
/**
* @brief Get field abs_pressure from hil_sensor message
*
* @return [mbar] Absolute pressure
* @return [hPa] Absolute pressure
*/
static inline float mavlink_msg_hil_sensor_get_abs_pressure(const mavlink_message_t* msg)
{
@ -494,7 +508,7 @@ static inline float mavlink_msg_hil_sensor_get_abs_pressure(const mavlink_messag
/**
* @brief Get field diff_pressure from hil_sensor message
*
* @return [mbar] Differential pressure (airspeed)
* @return [hPa] Differential pressure (airspeed)
*/
static inline float mavlink_msg_hil_sensor_get_diff_pressure(const mavlink_message_t* msg)
{
@ -531,6 +545,16 @@ static inline uint32_t mavlink_msg_hil_sensor_get_fields_updated(const mavlink_m
return _MAV_RETURN_uint32_t(msg, 60);
}
/**
* @brief Get field id from hil_sensor message
*
* @return Sensor ID (zero indexed). Used for multiple sensor inputs
*/
static inline uint8_t mavlink_msg_hil_sensor_get_id(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 64);
}
/**
* @brief Decode a hil_sensor message into a struct
*
@ -555,6 +579,7 @@ static inline void mavlink_msg_hil_sensor_decode(const mavlink_message_t* msg, m
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);
hil_sensor->id = mavlink_msg_hil_sensor_get_id(msg);
#else
uint8_t len = msg->len < MAVLINK_MSG_ID_HIL_SENSOR_LEN? msg->len : MAVLINK_MSG_ID_HIL_SENSOR_LEN;
memset(hil_sensor, 0, MAVLINK_MSG_ID_HIL_SENSOR_LEN);

View file

@ -3,7 +3,7 @@
#define MAVLINK_MSG_ID_HOME_POSITION 242
MAVPACKED(
typedef struct __mavlink_home_position_t {
int32_t latitude; /*< [degE7] Latitude (WGS84)*/
int32_t longitude; /*< [degE7] Longitude (WGS84)*/
@ -15,11 +15,12 @@ typedef struct __mavlink_home_position_t {
float approach_x; /*< [m] Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone.*/
float approach_y; /*< [m] Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone.*/
float approach_z; /*< [m] Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone.*/
} mavlink_home_position_t;
uint64_t time_usec; /*< [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.*/
}) mavlink_home_position_t;
#define MAVLINK_MSG_ID_HOME_POSITION_LEN 52
#define MAVLINK_MSG_ID_HOME_POSITION_LEN 60
#define MAVLINK_MSG_ID_HOME_POSITION_MIN_LEN 52
#define MAVLINK_MSG_ID_242_LEN 52
#define MAVLINK_MSG_ID_242_LEN 60
#define MAVLINK_MSG_ID_242_MIN_LEN 52
#define MAVLINK_MSG_ID_HOME_POSITION_CRC 104
@ -31,7 +32,7 @@ typedef struct __mavlink_home_position_t {
#define MAVLINK_MESSAGE_INFO_HOME_POSITION { \
242, \
"HOME_POSITION", \
10, \
11, \
{ { "latitude", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_home_position_t, latitude) }, \
{ "longitude", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_home_position_t, longitude) }, \
{ "altitude", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_home_position_t, altitude) }, \
@ -42,12 +43,13 @@ typedef struct __mavlink_home_position_t {
{ "approach_x", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_home_position_t, approach_x) }, \
{ "approach_y", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_home_position_t, approach_y) }, \
{ "approach_z", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_home_position_t, approach_z) }, \
{ "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 52, offsetof(mavlink_home_position_t, time_usec) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_HOME_POSITION { \
"HOME_POSITION", \
10, \
11, \
{ { "latitude", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_home_position_t, latitude) }, \
{ "longitude", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_home_position_t, longitude) }, \
{ "altitude", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_home_position_t, altitude) }, \
@ -58,6 +60,7 @@ typedef struct __mavlink_home_position_t {
{ "approach_x", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_home_position_t, approach_x) }, \
{ "approach_y", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_home_position_t, approach_y) }, \
{ "approach_z", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_home_position_t, approach_z) }, \
{ "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 52, offsetof(mavlink_home_position_t, time_usec) }, \
} \
}
#endif
@ -78,10 +81,11 @@ typedef struct __mavlink_home_position_t {
* @param approach_x [m] Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone.
* @param approach_y [m] Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone.
* @param approach_z [m] Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone.
* @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_home_position_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
int32_t latitude, int32_t longitude, int32_t altitude, float x, float y, float z, const float *q, float approach_x, float approach_y, float approach_z)
int32_t latitude, int32_t longitude, int32_t altitude, float x, float y, float z, const float *q, float approach_x, float approach_y, float approach_z, uint64_t time_usec)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_HOME_POSITION_LEN];
@ -94,6 +98,7 @@ static inline uint16_t mavlink_msg_home_position_pack(uint8_t system_id, uint8_t
_mav_put_float(buf, 40, approach_x);
_mav_put_float(buf, 44, approach_y);
_mav_put_float(buf, 48, approach_z);
_mav_put_uint64_t(buf, 52, time_usec);
_mav_put_float_array(buf, 24, q, 4);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HOME_POSITION_LEN);
#else
@ -107,6 +112,7 @@ static inline uint16_t mavlink_msg_home_position_pack(uint8_t system_id, uint8_t
packet.approach_x = approach_x;
packet.approach_y = approach_y;
packet.approach_z = approach_z;
packet.time_usec = time_usec;
mav_array_memcpy(packet.q, q, sizeof(float)*4);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HOME_POSITION_LEN);
#endif
@ -131,11 +137,12 @@ static inline uint16_t mavlink_msg_home_position_pack(uint8_t system_id, uint8_t
* @param approach_x [m] Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone.
* @param approach_y [m] Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone.
* @param approach_z [m] Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone.
* @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_home_position_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,float x,float y,float z,const float *q,float approach_x,float approach_y,float approach_z)
int32_t latitude,int32_t longitude,int32_t altitude,float x,float y,float z,const float *q,float approach_x,float approach_y,float approach_z,uint64_t time_usec)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_HOME_POSITION_LEN];
@ -148,6 +155,7 @@ static inline uint16_t mavlink_msg_home_position_pack_chan(uint8_t system_id, ui
_mav_put_float(buf, 40, approach_x);
_mav_put_float(buf, 44, approach_y);
_mav_put_float(buf, 48, approach_z);
_mav_put_uint64_t(buf, 52, time_usec);
_mav_put_float_array(buf, 24, q, 4);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_HOME_POSITION_LEN);
#else
@ -161,6 +169,7 @@ static inline uint16_t mavlink_msg_home_position_pack_chan(uint8_t system_id, ui
packet.approach_x = approach_x;
packet.approach_y = approach_y;
packet.approach_z = approach_z;
packet.time_usec = time_usec;
mav_array_memcpy(packet.q, q, sizeof(float)*4);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_HOME_POSITION_LEN);
#endif
@ -179,7 +188,7 @@ static inline uint16_t mavlink_msg_home_position_pack_chan(uint8_t system_id, ui
*/
static inline uint16_t mavlink_msg_home_position_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_home_position_t* home_position)
{
return mavlink_msg_home_position_pack(system_id, component_id, msg, home_position->latitude, home_position->longitude, home_position->altitude, home_position->x, home_position->y, home_position->z, home_position->q, home_position->approach_x, home_position->approach_y, home_position->approach_z);
return mavlink_msg_home_position_pack(system_id, component_id, msg, home_position->latitude, home_position->longitude, home_position->altitude, home_position->x, home_position->y, home_position->z, home_position->q, home_position->approach_x, home_position->approach_y, home_position->approach_z, home_position->time_usec);
}
/**
@ -193,7 +202,7 @@ static inline uint16_t mavlink_msg_home_position_encode(uint8_t system_id, uint8
*/
static inline uint16_t mavlink_msg_home_position_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_home_position_t* home_position)
{
return mavlink_msg_home_position_pack_chan(system_id, component_id, chan, msg, home_position->latitude, home_position->longitude, home_position->altitude, home_position->x, home_position->y, home_position->z, home_position->q, home_position->approach_x, home_position->approach_y, home_position->approach_z);
return mavlink_msg_home_position_pack_chan(system_id, component_id, chan, msg, home_position->latitude, home_position->longitude, home_position->altitude, home_position->x, home_position->y, home_position->z, home_position->q, home_position->approach_x, home_position->approach_y, home_position->approach_z, home_position->time_usec);
}
/**
@ -210,10 +219,11 @@ static inline uint16_t mavlink_msg_home_position_encode_chan(uint8_t system_id,
* @param approach_x [m] Local X position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone.
* @param approach_y [m] Local Y position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone.
* @param approach_z [m] Local Z position of the end of the approach vector. Multicopters should set this position based on their takeoff path. Grass-landing fixed wing aircraft should set it the same way as multicopters. Runway-landing fixed wing aircraft should set it to the opposite direction of the takeoff, assuming the takeoff happened from the threshold / touchdown zone.
* @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_home_position_send(mavlink_channel_t chan, int32_t latitude, int32_t longitude, int32_t altitude, float x, float y, float z, const float *q, float approach_x, float approach_y, float approach_z)
static inline void mavlink_msg_home_position_send(mavlink_channel_t chan, int32_t latitude, int32_t longitude, int32_t altitude, float x, float y, float z, const float *q, float approach_x, float approach_y, float approach_z, uint64_t time_usec)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_HOME_POSITION_LEN];
@ -226,6 +236,7 @@ static inline void mavlink_msg_home_position_send(mavlink_channel_t chan, int32_
_mav_put_float(buf, 40, approach_x);
_mav_put_float(buf, 44, approach_y);
_mav_put_float(buf, 48, approach_z);
_mav_put_uint64_t(buf, 52, time_usec);
_mav_put_float_array(buf, 24, q, 4);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HOME_POSITION, buf, MAVLINK_MSG_ID_HOME_POSITION_MIN_LEN, MAVLINK_MSG_ID_HOME_POSITION_LEN, MAVLINK_MSG_ID_HOME_POSITION_CRC);
#else
@ -239,6 +250,7 @@ static inline void mavlink_msg_home_position_send(mavlink_channel_t chan, int32_
packet.approach_x = approach_x;
packet.approach_y = approach_y;
packet.approach_z = approach_z;
packet.time_usec = time_usec;
mav_array_memcpy(packet.q, q, sizeof(float)*4);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HOME_POSITION, (const char *)&packet, MAVLINK_MSG_ID_HOME_POSITION_MIN_LEN, MAVLINK_MSG_ID_HOME_POSITION_LEN, MAVLINK_MSG_ID_HOME_POSITION_CRC);
#endif
@ -252,7 +264,7 @@ static inline void mavlink_msg_home_position_send(mavlink_channel_t chan, int32_
static inline void mavlink_msg_home_position_send_struct(mavlink_channel_t chan, const mavlink_home_position_t* home_position)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mavlink_msg_home_position_send(chan, home_position->latitude, home_position->longitude, home_position->altitude, home_position->x, home_position->y, home_position->z, home_position->q, home_position->approach_x, home_position->approach_y, home_position->approach_z);
mavlink_msg_home_position_send(chan, home_position->latitude, home_position->longitude, home_position->altitude, home_position->x, home_position->y, home_position->z, home_position->q, home_position->approach_x, home_position->approach_y, home_position->approach_z, home_position->time_usec);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HOME_POSITION, (const char *)home_position, MAVLINK_MSG_ID_HOME_POSITION_MIN_LEN, MAVLINK_MSG_ID_HOME_POSITION_LEN, MAVLINK_MSG_ID_HOME_POSITION_CRC);
#endif
@ -266,7 +278,7 @@ static inline void mavlink_msg_home_position_send_struct(mavlink_channel_t chan,
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_home_position_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, int32_t latitude, int32_t longitude, int32_t altitude, float x, float y, float z, const float *q, float approach_x, float approach_y, float approach_z)
static inline void mavlink_msg_home_position_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, int32_t latitude, int32_t longitude, int32_t altitude, float x, float y, float z, const float *q, float approach_x, float approach_y, float approach_z, uint64_t time_usec)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
@ -279,6 +291,7 @@ static inline void mavlink_msg_home_position_send_buf(mavlink_message_t *msgbuf,
_mav_put_float(buf, 40, approach_x);
_mav_put_float(buf, 44, approach_y);
_mav_put_float(buf, 48, approach_z);
_mav_put_uint64_t(buf, 52, time_usec);
_mav_put_float_array(buf, 24, q, 4);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HOME_POSITION, buf, MAVLINK_MSG_ID_HOME_POSITION_MIN_LEN, MAVLINK_MSG_ID_HOME_POSITION_LEN, MAVLINK_MSG_ID_HOME_POSITION_CRC);
#else
@ -292,6 +305,7 @@ static inline void mavlink_msg_home_position_send_buf(mavlink_message_t *msgbuf,
packet->approach_x = approach_x;
packet->approach_y = approach_y;
packet->approach_z = approach_z;
packet->time_usec = time_usec;
mav_array_memcpy(packet->q, q, sizeof(float)*4);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_HOME_POSITION, (const char *)packet, MAVLINK_MSG_ID_HOME_POSITION_MIN_LEN, MAVLINK_MSG_ID_HOME_POSITION_LEN, MAVLINK_MSG_ID_HOME_POSITION_CRC);
#endif
@ -403,6 +417,16 @@ static inline float mavlink_msg_home_position_get_approach_z(const mavlink_messa
return _MAV_RETURN_float(msg, 48);
}
/**
* @brief Get field time_usec from home_position message
*
* @return [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
*/
static inline uint64_t mavlink_msg_home_position_get_time_usec(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint64_t(msg, 52);
}
/**
* @brief Decode a home_position message into a struct
*
@ -422,6 +446,7 @@ static inline void mavlink_msg_home_position_decode(const mavlink_message_t* msg
home_position->approach_x = mavlink_msg_home_position_get_approach_x(msg);
home_position->approach_y = mavlink_msg_home_position_get_approach_y(msg);
home_position->approach_z = mavlink_msg_home_position_get_approach_z(msg);
home_position->time_usec = mavlink_msg_home_position_get_time_usec(msg);
#else
uint8_t len = msg->len < MAVLINK_MSG_ID_HOME_POSITION_LEN? msg->len : MAVLINK_MSG_ID_HOME_POSITION_LEN;
memset(home_position, 0, MAVLINK_MSG_ID_HOME_POSITION_LEN);

View file

@ -0,0 +1,388 @@
#pragma once
// MESSAGE ISBD_LINK_STATUS PACKING
#define MAVLINK_MSG_ID_ISBD_LINK_STATUS 335
typedef struct __mavlink_isbd_link_status_t {
uint64_t timestamp; /*< [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.*/
uint64_t last_heartbeat; /*< [us] Timestamp of the last successful sbd session. The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.*/
uint16_t failed_sessions; /*< Number of failed SBD sessions.*/
uint16_t successful_sessions; /*< Number of successful SBD sessions.*/
uint8_t signal_quality; /*< Signal quality equal to the number of bars displayed on the ISU signal strength indicator. Range is 0 to 5, where 0 indicates no signal and 5 indicates maximum signal strength.*/
uint8_t ring_pending; /*< 1: Ring call pending, 0: No call pending.*/
uint8_t tx_session_pending; /*< 1: Transmission session pending, 0: No transmission session pending.*/
uint8_t rx_session_pending; /*< 1: Receiving session pending, 0: No receiving session pending.*/
} mavlink_isbd_link_status_t;
#define MAVLINK_MSG_ID_ISBD_LINK_STATUS_LEN 24
#define MAVLINK_MSG_ID_ISBD_LINK_STATUS_MIN_LEN 24
#define MAVLINK_MSG_ID_335_LEN 24
#define MAVLINK_MSG_ID_335_MIN_LEN 24
#define MAVLINK_MSG_ID_ISBD_LINK_STATUS_CRC 225
#define MAVLINK_MSG_ID_335_CRC 225
#if MAVLINK_COMMAND_24BIT
#define MAVLINK_MESSAGE_INFO_ISBD_LINK_STATUS { \
335, \
"ISBD_LINK_STATUS", \
8, \
{ { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_isbd_link_status_t, timestamp) }, \
{ "last_heartbeat", NULL, MAVLINK_TYPE_UINT64_T, 0, 8, offsetof(mavlink_isbd_link_status_t, last_heartbeat) }, \
{ "failed_sessions", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_isbd_link_status_t, failed_sessions) }, \
{ "successful_sessions", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_isbd_link_status_t, successful_sessions) }, \
{ "signal_quality", NULL, MAVLINK_TYPE_UINT8_T, 0, 20, offsetof(mavlink_isbd_link_status_t, signal_quality) }, \
{ "ring_pending", NULL, MAVLINK_TYPE_UINT8_T, 0, 21, offsetof(mavlink_isbd_link_status_t, ring_pending) }, \
{ "tx_session_pending", NULL, MAVLINK_TYPE_UINT8_T, 0, 22, offsetof(mavlink_isbd_link_status_t, tx_session_pending) }, \
{ "rx_session_pending", NULL, MAVLINK_TYPE_UINT8_T, 0, 23, offsetof(mavlink_isbd_link_status_t, rx_session_pending) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_ISBD_LINK_STATUS { \
"ISBD_LINK_STATUS", \
8, \
{ { "timestamp", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_isbd_link_status_t, timestamp) }, \
{ "last_heartbeat", NULL, MAVLINK_TYPE_UINT64_T, 0, 8, offsetof(mavlink_isbd_link_status_t, last_heartbeat) }, \
{ "failed_sessions", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_isbd_link_status_t, failed_sessions) }, \
{ "successful_sessions", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_isbd_link_status_t, successful_sessions) }, \
{ "signal_quality", NULL, MAVLINK_TYPE_UINT8_T, 0, 20, offsetof(mavlink_isbd_link_status_t, signal_quality) }, \
{ "ring_pending", NULL, MAVLINK_TYPE_UINT8_T, 0, 21, offsetof(mavlink_isbd_link_status_t, ring_pending) }, \
{ "tx_session_pending", NULL, MAVLINK_TYPE_UINT8_T, 0, 22, offsetof(mavlink_isbd_link_status_t, tx_session_pending) }, \
{ "rx_session_pending", NULL, MAVLINK_TYPE_UINT8_T, 0, 23, offsetof(mavlink_isbd_link_status_t, rx_session_pending) }, \
} \
}
#endif
/**
* @brief Pack a isbd_link_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 timestamp [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
* @param last_heartbeat [us] Timestamp of the last successful sbd session. The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
* @param failed_sessions Number of failed SBD sessions.
* @param successful_sessions Number of successful SBD sessions.
* @param signal_quality Signal quality equal to the number of bars displayed on the ISU signal strength indicator. Range is 0 to 5, where 0 indicates no signal and 5 indicates maximum signal strength.
* @param ring_pending 1: Ring call pending, 0: No call pending.
* @param tx_session_pending 1: Transmission session pending, 0: No transmission session pending.
* @param rx_session_pending 1: Receiving session pending, 0: No receiving session pending.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_isbd_link_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint64_t timestamp, uint64_t last_heartbeat, uint16_t failed_sessions, uint16_t successful_sessions, uint8_t signal_quality, uint8_t ring_pending, uint8_t tx_session_pending, uint8_t rx_session_pending)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_ISBD_LINK_STATUS_LEN];
_mav_put_uint64_t(buf, 0, timestamp);
_mav_put_uint64_t(buf, 8, last_heartbeat);
_mav_put_uint16_t(buf, 16, failed_sessions);
_mav_put_uint16_t(buf, 18, successful_sessions);
_mav_put_uint8_t(buf, 20, signal_quality);
_mav_put_uint8_t(buf, 21, ring_pending);
_mav_put_uint8_t(buf, 22, tx_session_pending);
_mav_put_uint8_t(buf, 23, rx_session_pending);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ISBD_LINK_STATUS_LEN);
#else
mavlink_isbd_link_status_t packet;
packet.timestamp = timestamp;
packet.last_heartbeat = last_heartbeat;
packet.failed_sessions = failed_sessions;
packet.successful_sessions = successful_sessions;
packet.signal_quality = signal_quality;
packet.ring_pending = ring_pending;
packet.tx_session_pending = tx_session_pending;
packet.rx_session_pending = rx_session_pending;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ISBD_LINK_STATUS_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_ISBD_LINK_STATUS;
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ISBD_LINK_STATUS_MIN_LEN, MAVLINK_MSG_ID_ISBD_LINK_STATUS_LEN, MAVLINK_MSG_ID_ISBD_LINK_STATUS_CRC);
}
/**
* @brief Pack a isbd_link_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 timestamp [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
* @param last_heartbeat [us] Timestamp of the last successful sbd session. The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
* @param failed_sessions Number of failed SBD sessions.
* @param successful_sessions Number of successful SBD sessions.
* @param signal_quality Signal quality equal to the number of bars displayed on the ISU signal strength indicator. Range is 0 to 5, where 0 indicates no signal and 5 indicates maximum signal strength.
* @param ring_pending 1: Ring call pending, 0: No call pending.
* @param tx_session_pending 1: Transmission session pending, 0: No transmission session pending.
* @param rx_session_pending 1: Receiving session pending, 0: No receiving session pending.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_isbd_link_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint64_t timestamp,uint64_t last_heartbeat,uint16_t failed_sessions,uint16_t successful_sessions,uint8_t signal_quality,uint8_t ring_pending,uint8_t tx_session_pending,uint8_t rx_session_pending)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_ISBD_LINK_STATUS_LEN];
_mav_put_uint64_t(buf, 0, timestamp);
_mav_put_uint64_t(buf, 8, last_heartbeat);
_mav_put_uint16_t(buf, 16, failed_sessions);
_mav_put_uint16_t(buf, 18, successful_sessions);
_mav_put_uint8_t(buf, 20, signal_quality);
_mav_put_uint8_t(buf, 21, ring_pending);
_mav_put_uint8_t(buf, 22, tx_session_pending);
_mav_put_uint8_t(buf, 23, rx_session_pending);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ISBD_LINK_STATUS_LEN);
#else
mavlink_isbd_link_status_t packet;
packet.timestamp = timestamp;
packet.last_heartbeat = last_heartbeat;
packet.failed_sessions = failed_sessions;
packet.successful_sessions = successful_sessions;
packet.signal_quality = signal_quality;
packet.ring_pending = ring_pending;
packet.tx_session_pending = tx_session_pending;
packet.rx_session_pending = rx_session_pending;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ISBD_LINK_STATUS_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_ISBD_LINK_STATUS;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ISBD_LINK_STATUS_MIN_LEN, MAVLINK_MSG_ID_ISBD_LINK_STATUS_LEN, MAVLINK_MSG_ID_ISBD_LINK_STATUS_CRC);
}
/**
* @brief Encode a isbd_link_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 isbd_link_status C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_isbd_link_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_isbd_link_status_t* isbd_link_status)
{
return mavlink_msg_isbd_link_status_pack(system_id, component_id, msg, isbd_link_status->timestamp, isbd_link_status->last_heartbeat, isbd_link_status->failed_sessions, isbd_link_status->successful_sessions, isbd_link_status->signal_quality, isbd_link_status->ring_pending, isbd_link_status->tx_session_pending, isbd_link_status->rx_session_pending);
}
/**
* @brief Encode a isbd_link_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 isbd_link_status C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_isbd_link_status_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_isbd_link_status_t* isbd_link_status)
{
return mavlink_msg_isbd_link_status_pack_chan(system_id, component_id, chan, msg, isbd_link_status->timestamp, isbd_link_status->last_heartbeat, isbd_link_status->failed_sessions, isbd_link_status->successful_sessions, isbd_link_status->signal_quality, isbd_link_status->ring_pending, isbd_link_status->tx_session_pending, isbd_link_status->rx_session_pending);
}
/**
* @brief Send a isbd_link_status message
* @param chan MAVLink channel to send the message
*
* @param timestamp [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
* @param last_heartbeat [us] Timestamp of the last successful sbd session. The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
* @param failed_sessions Number of failed SBD sessions.
* @param successful_sessions Number of successful SBD sessions.
* @param signal_quality Signal quality equal to the number of bars displayed on the ISU signal strength indicator. Range is 0 to 5, where 0 indicates no signal and 5 indicates maximum signal strength.
* @param ring_pending 1: Ring call pending, 0: No call pending.
* @param tx_session_pending 1: Transmission session pending, 0: No transmission session pending.
* @param rx_session_pending 1: Receiving session pending, 0: No receiving session pending.
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_isbd_link_status_send(mavlink_channel_t chan, uint64_t timestamp, uint64_t last_heartbeat, uint16_t failed_sessions, uint16_t successful_sessions, uint8_t signal_quality, uint8_t ring_pending, uint8_t tx_session_pending, uint8_t rx_session_pending)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_ISBD_LINK_STATUS_LEN];
_mav_put_uint64_t(buf, 0, timestamp);
_mav_put_uint64_t(buf, 8, last_heartbeat);
_mav_put_uint16_t(buf, 16, failed_sessions);
_mav_put_uint16_t(buf, 18, successful_sessions);
_mav_put_uint8_t(buf, 20, signal_quality);
_mav_put_uint8_t(buf, 21, ring_pending);
_mav_put_uint8_t(buf, 22, tx_session_pending);
_mav_put_uint8_t(buf, 23, rx_session_pending);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ISBD_LINK_STATUS, buf, MAVLINK_MSG_ID_ISBD_LINK_STATUS_MIN_LEN, MAVLINK_MSG_ID_ISBD_LINK_STATUS_LEN, MAVLINK_MSG_ID_ISBD_LINK_STATUS_CRC);
#else
mavlink_isbd_link_status_t packet;
packet.timestamp = timestamp;
packet.last_heartbeat = last_heartbeat;
packet.failed_sessions = failed_sessions;
packet.successful_sessions = successful_sessions;
packet.signal_quality = signal_quality;
packet.ring_pending = ring_pending;
packet.tx_session_pending = tx_session_pending;
packet.rx_session_pending = rx_session_pending;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ISBD_LINK_STATUS, (const char *)&packet, MAVLINK_MSG_ID_ISBD_LINK_STATUS_MIN_LEN, MAVLINK_MSG_ID_ISBD_LINK_STATUS_LEN, MAVLINK_MSG_ID_ISBD_LINK_STATUS_CRC);
#endif
}
/**
* @brief Send a isbd_link_status message
* @param chan MAVLink channel to send the message
* @param struct The MAVLink struct to serialize
*/
static inline void mavlink_msg_isbd_link_status_send_struct(mavlink_channel_t chan, const mavlink_isbd_link_status_t* isbd_link_status)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mavlink_msg_isbd_link_status_send(chan, isbd_link_status->timestamp, isbd_link_status->last_heartbeat, isbd_link_status->failed_sessions, isbd_link_status->successful_sessions, isbd_link_status->signal_quality, isbd_link_status->ring_pending, isbd_link_status->tx_session_pending, isbd_link_status->rx_session_pending);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ISBD_LINK_STATUS, (const char *)isbd_link_status, MAVLINK_MSG_ID_ISBD_LINK_STATUS_MIN_LEN, MAVLINK_MSG_ID_ISBD_LINK_STATUS_LEN, MAVLINK_MSG_ID_ISBD_LINK_STATUS_CRC);
#endif
}
#if MAVLINK_MSG_ID_ISBD_LINK_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_isbd_link_status_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t timestamp, uint64_t last_heartbeat, uint16_t failed_sessions, uint16_t successful_sessions, uint8_t signal_quality, uint8_t ring_pending, uint8_t tx_session_pending, uint8_t rx_session_pending)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
_mav_put_uint64_t(buf, 0, timestamp);
_mav_put_uint64_t(buf, 8, last_heartbeat);
_mav_put_uint16_t(buf, 16, failed_sessions);
_mav_put_uint16_t(buf, 18, successful_sessions);
_mav_put_uint8_t(buf, 20, signal_quality);
_mav_put_uint8_t(buf, 21, ring_pending);
_mav_put_uint8_t(buf, 22, tx_session_pending);
_mav_put_uint8_t(buf, 23, rx_session_pending);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ISBD_LINK_STATUS, buf, MAVLINK_MSG_ID_ISBD_LINK_STATUS_MIN_LEN, MAVLINK_MSG_ID_ISBD_LINK_STATUS_LEN, MAVLINK_MSG_ID_ISBD_LINK_STATUS_CRC);
#else
mavlink_isbd_link_status_t *packet = (mavlink_isbd_link_status_t *)msgbuf;
packet->timestamp = timestamp;
packet->last_heartbeat = last_heartbeat;
packet->failed_sessions = failed_sessions;
packet->successful_sessions = successful_sessions;
packet->signal_quality = signal_quality;
packet->ring_pending = ring_pending;
packet->tx_session_pending = tx_session_pending;
packet->rx_session_pending = rx_session_pending;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ISBD_LINK_STATUS, (const char *)packet, MAVLINK_MSG_ID_ISBD_LINK_STATUS_MIN_LEN, MAVLINK_MSG_ID_ISBD_LINK_STATUS_LEN, MAVLINK_MSG_ID_ISBD_LINK_STATUS_CRC);
#endif
}
#endif
#endif
// MESSAGE ISBD_LINK_STATUS UNPACKING
/**
* @brief Get field timestamp from isbd_link_status message
*
* @return [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
*/
static inline uint64_t mavlink_msg_isbd_link_status_get_timestamp(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint64_t(msg, 0);
}
/**
* @brief Get field last_heartbeat from isbd_link_status message
*
* @return [us] Timestamp of the last successful sbd session. The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
*/
static inline uint64_t mavlink_msg_isbd_link_status_get_last_heartbeat(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint64_t(msg, 8);
}
/**
* @brief Get field failed_sessions from isbd_link_status message
*
* @return Number of failed SBD sessions.
*/
static inline uint16_t mavlink_msg_isbd_link_status_get_failed_sessions(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 16);
}
/**
* @brief Get field successful_sessions from isbd_link_status message
*
* @return Number of successful SBD sessions.
*/
static inline uint16_t mavlink_msg_isbd_link_status_get_successful_sessions(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 18);
}
/**
* @brief Get field signal_quality from isbd_link_status message
*
* @return Signal quality equal to the number of bars displayed on the ISU signal strength indicator. Range is 0 to 5, where 0 indicates no signal and 5 indicates maximum signal strength.
*/
static inline uint8_t mavlink_msg_isbd_link_status_get_signal_quality(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 20);
}
/**
* @brief Get field ring_pending from isbd_link_status message
*
* @return 1: Ring call pending, 0: No call pending.
*/
static inline uint8_t mavlink_msg_isbd_link_status_get_ring_pending(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 21);
}
/**
* @brief Get field tx_session_pending from isbd_link_status message
*
* @return 1: Transmission session pending, 0: No transmission session pending.
*/
static inline uint8_t mavlink_msg_isbd_link_status_get_tx_session_pending(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 22);
}
/**
* @brief Get field rx_session_pending from isbd_link_status message
*
* @return 1: Receiving session pending, 0: No receiving session pending.
*/
static inline uint8_t mavlink_msg_isbd_link_status_get_rx_session_pending(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 23);
}
/**
* @brief Decode a isbd_link_status message into a struct
*
* @param msg The message to decode
* @param isbd_link_status C-struct to decode the message contents into
*/
static inline void mavlink_msg_isbd_link_status_decode(const mavlink_message_t* msg, mavlink_isbd_link_status_t* isbd_link_status)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
isbd_link_status->timestamp = mavlink_msg_isbd_link_status_get_timestamp(msg);
isbd_link_status->last_heartbeat = mavlink_msg_isbd_link_status_get_last_heartbeat(msg);
isbd_link_status->failed_sessions = mavlink_msg_isbd_link_status_get_failed_sessions(msg);
isbd_link_status->successful_sessions = mavlink_msg_isbd_link_status_get_successful_sessions(msg);
isbd_link_status->signal_quality = mavlink_msg_isbd_link_status_get_signal_quality(msg);
isbd_link_status->ring_pending = mavlink_msg_isbd_link_status_get_ring_pending(msg);
isbd_link_status->tx_session_pending = mavlink_msg_isbd_link_status_get_tx_session_pending(msg);
isbd_link_status->rx_session_pending = mavlink_msg_isbd_link_status_get_rx_session_pending(msg);
#else
uint8_t len = msg->len < MAVLINK_MSG_ID_ISBD_LINK_STATUS_LEN? msg->len : MAVLINK_MSG_ID_ISBD_LINK_STATUS_LEN;
memset(isbd_link_status, 0, MAVLINK_MSG_ID_ISBD_LINK_STATUS_LEN);
memcpy(isbd_link_status, _MAV_PAYLOAD(msg), len);
#endif
}

View file

@ -3,7 +3,7 @@
#define MAVLINK_MSG_ID_LANDING_TARGET 149
MAVPACKED(
typedef struct __mavlink_landing_target_t {
uint64_t time_usec; /*< [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.*/
float angle_x; /*< [rad] X-axis angular offset of the target from the center of the image*/
@ -13,23 +13,29 @@ typedef struct __mavlink_landing_target_t {
float size_y; /*< [rad] Size of target along y-axis*/
uint8_t target_num; /*< The ID of the target if multiple targets are present*/
uint8_t frame; /*< Coordinate frame used for following fields.*/
} mavlink_landing_target_t;
float x; /*< [m] X Position of the landing target in MAV_FRAME*/
float y; /*< [m] Y Position of the landing target in MAV_FRAME*/
float z; /*< [m] Z Position of the landing target in MAV_FRAME*/
float q[4]; /*< Quaternion of landing target orientation (w, x, y, z order, zero-rotation is 1, 0, 0, 0)*/
uint8_t type; /*< Type of landing target*/
uint8_t position_valid; /*< Boolean indicating whether the position fields (x, y, z, q, type) contain valid target position information (valid: 1, invalid: 0). Default is 0 (invalid).*/
}) mavlink_landing_target_t;
#define MAVLINK_MSG_ID_LANDING_TARGET_LEN 30
#define MAVLINK_MSG_ID_LANDING_TARGET_LEN 60
#define MAVLINK_MSG_ID_LANDING_TARGET_MIN_LEN 30
#define MAVLINK_MSG_ID_149_LEN 30
#define MAVLINK_MSG_ID_149_LEN 60
#define MAVLINK_MSG_ID_149_MIN_LEN 30
#define MAVLINK_MSG_ID_LANDING_TARGET_CRC 200
#define MAVLINK_MSG_ID_149_CRC 200
#define MAVLINK_MSG_LANDING_TARGET_FIELD_Q_LEN 4
#if MAVLINK_COMMAND_24BIT
#define MAVLINK_MESSAGE_INFO_LANDING_TARGET { \
149, \
"LANDING_TARGET", \
8, \
14, \
{ { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_landing_target_t, time_usec) }, \
{ "target_num", NULL, MAVLINK_TYPE_UINT8_T, 0, 28, offsetof(mavlink_landing_target_t, target_num) }, \
{ "frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 29, offsetof(mavlink_landing_target_t, frame) }, \
@ -38,12 +44,18 @@ typedef struct __mavlink_landing_target_t {
{ "distance", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_landing_target_t, distance) }, \
{ "size_x", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_landing_target_t, size_x) }, \
{ "size_y", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_landing_target_t, size_y) }, \
{ "x", NULL, MAVLINK_TYPE_FLOAT, 0, 30, offsetof(mavlink_landing_target_t, x) }, \
{ "y", NULL, MAVLINK_TYPE_FLOAT, 0, 34, offsetof(mavlink_landing_target_t, y) }, \
{ "z", NULL, MAVLINK_TYPE_FLOAT, 0, 38, offsetof(mavlink_landing_target_t, z) }, \
{ "q", NULL, MAVLINK_TYPE_FLOAT, 4, 42, offsetof(mavlink_landing_target_t, q) }, \
{ "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 58, offsetof(mavlink_landing_target_t, type) }, \
{ "position_valid", NULL, MAVLINK_TYPE_UINT8_T, 0, 59, offsetof(mavlink_landing_target_t, position_valid) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_LANDING_TARGET { \
"LANDING_TARGET", \
8, \
14, \
{ { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_landing_target_t, time_usec) }, \
{ "target_num", NULL, MAVLINK_TYPE_UINT8_T, 0, 28, offsetof(mavlink_landing_target_t, target_num) }, \
{ "frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 29, offsetof(mavlink_landing_target_t, frame) }, \
@ -52,6 +64,12 @@ typedef struct __mavlink_landing_target_t {
{ "distance", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_landing_target_t, distance) }, \
{ "size_x", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_landing_target_t, size_x) }, \
{ "size_y", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_landing_target_t, size_y) }, \
{ "x", NULL, MAVLINK_TYPE_FLOAT, 0, 30, offsetof(mavlink_landing_target_t, x) }, \
{ "y", NULL, MAVLINK_TYPE_FLOAT, 0, 34, offsetof(mavlink_landing_target_t, y) }, \
{ "z", NULL, MAVLINK_TYPE_FLOAT, 0, 38, offsetof(mavlink_landing_target_t, z) }, \
{ "q", NULL, MAVLINK_TYPE_FLOAT, 4, 42, offsetof(mavlink_landing_target_t, q) }, \
{ "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 58, offsetof(mavlink_landing_target_t, type) }, \
{ "position_valid", NULL, MAVLINK_TYPE_UINT8_T, 0, 59, offsetof(mavlink_landing_target_t, position_valid) }, \
} \
}
#endif
@ -70,10 +88,16 @@ typedef struct __mavlink_landing_target_t {
* @param distance [m] Distance to the target from the vehicle
* @param size_x [rad] Size of target along x-axis
* @param size_y [rad] Size of target along y-axis
* @param x [m] X Position of the landing target in MAV_FRAME
* @param y [m] Y Position of the landing target in MAV_FRAME
* @param z [m] Z Position of the landing target in MAV_FRAME
* @param q Quaternion of landing target orientation (w, x, y, z order, zero-rotation is 1, 0, 0, 0)
* @param type Type of landing target
* @param position_valid Boolean indicating whether the position fields (x, y, z, q, type) contain valid target position information (valid: 1, invalid: 0). Default is 0 (invalid).
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_landing_target_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint64_t time_usec, uint8_t target_num, uint8_t frame, float angle_x, float angle_y, float distance, float size_x, float size_y)
uint64_t time_usec, uint8_t target_num, uint8_t frame, float angle_x, float angle_y, float distance, float size_x, float size_y, float x, float y, float z, const float *q, uint8_t type, uint8_t position_valid)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_LANDING_TARGET_LEN];
@ -85,7 +109,12 @@ static inline uint16_t mavlink_msg_landing_target_pack(uint8_t system_id, uint8_
_mav_put_float(buf, 24, size_y);
_mav_put_uint8_t(buf, 28, target_num);
_mav_put_uint8_t(buf, 29, frame);
_mav_put_float(buf, 30, x);
_mav_put_float(buf, 34, y);
_mav_put_float(buf, 38, z);
_mav_put_uint8_t(buf, 58, type);
_mav_put_uint8_t(buf, 59, position_valid);
_mav_put_float_array(buf, 42, q, 4);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LANDING_TARGET_LEN);
#else
mavlink_landing_target_t packet;
@ -97,7 +126,12 @@ static inline uint16_t mavlink_msg_landing_target_pack(uint8_t system_id, uint8_
packet.size_y = size_y;
packet.target_num = target_num;
packet.frame = frame;
packet.x = x;
packet.y = y;
packet.z = z;
packet.type = type;
packet.position_valid = position_valid;
mav_array_memcpy(packet.q, q, sizeof(float)*4);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LANDING_TARGET_LEN);
#endif
@ -119,11 +153,17 @@ static inline uint16_t mavlink_msg_landing_target_pack(uint8_t system_id, uint8_
* @param distance [m] Distance to the target from the vehicle
* @param size_x [rad] Size of target along x-axis
* @param size_y [rad] Size of target along y-axis
* @param x [m] X Position of the landing target in MAV_FRAME
* @param y [m] Y Position of the landing target in MAV_FRAME
* @param z [m] Z Position of the landing target in MAV_FRAME
* @param q Quaternion of landing target orientation (w, x, y, z order, zero-rotation is 1, 0, 0, 0)
* @param type Type of landing target
* @param position_valid Boolean indicating whether the position fields (x, y, z, q, type) contain valid target position information (valid: 1, invalid: 0). Default is 0 (invalid).
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_landing_target_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint64_t time_usec,uint8_t target_num,uint8_t frame,float angle_x,float angle_y,float distance,float size_x,float size_y)
uint64_t time_usec,uint8_t target_num,uint8_t frame,float angle_x,float angle_y,float distance,float size_x,float size_y,float x,float y,float z,const float *q,uint8_t type,uint8_t position_valid)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_LANDING_TARGET_LEN];
@ -135,7 +175,12 @@ static inline uint16_t mavlink_msg_landing_target_pack_chan(uint8_t system_id, u
_mav_put_float(buf, 24, size_y);
_mav_put_uint8_t(buf, 28, target_num);
_mav_put_uint8_t(buf, 29, frame);
_mav_put_float(buf, 30, x);
_mav_put_float(buf, 34, y);
_mav_put_float(buf, 38, z);
_mav_put_uint8_t(buf, 58, type);
_mav_put_uint8_t(buf, 59, position_valid);
_mav_put_float_array(buf, 42, q, 4);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LANDING_TARGET_LEN);
#else
mavlink_landing_target_t packet;
@ -147,7 +192,12 @@ static inline uint16_t mavlink_msg_landing_target_pack_chan(uint8_t system_id, u
packet.size_y = size_y;
packet.target_num = target_num;
packet.frame = frame;
packet.x = x;
packet.y = y;
packet.z = z;
packet.type = type;
packet.position_valid = position_valid;
mav_array_memcpy(packet.q, q, sizeof(float)*4);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LANDING_TARGET_LEN);
#endif
@ -165,7 +215,7 @@ static inline uint16_t mavlink_msg_landing_target_pack_chan(uint8_t system_id, u
*/
static inline uint16_t mavlink_msg_landing_target_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_landing_target_t* landing_target)
{
return mavlink_msg_landing_target_pack(system_id, component_id, msg, landing_target->time_usec, landing_target->target_num, landing_target->frame, landing_target->angle_x, landing_target->angle_y, landing_target->distance, landing_target->size_x, landing_target->size_y);
return mavlink_msg_landing_target_pack(system_id, component_id, msg, landing_target->time_usec, landing_target->target_num, landing_target->frame, landing_target->angle_x, landing_target->angle_y, landing_target->distance, landing_target->size_x, landing_target->size_y, landing_target->x, landing_target->y, landing_target->z, landing_target->q, landing_target->type, landing_target->position_valid);
}
/**
@ -179,7 +229,7 @@ static inline uint16_t mavlink_msg_landing_target_encode(uint8_t system_id, uint
*/
static inline uint16_t mavlink_msg_landing_target_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_landing_target_t* landing_target)
{
return mavlink_msg_landing_target_pack_chan(system_id, component_id, chan, msg, landing_target->time_usec, landing_target->target_num, landing_target->frame, landing_target->angle_x, landing_target->angle_y, landing_target->distance, landing_target->size_x, landing_target->size_y);
return mavlink_msg_landing_target_pack_chan(system_id, component_id, chan, msg, landing_target->time_usec, landing_target->target_num, landing_target->frame, landing_target->angle_x, landing_target->angle_y, landing_target->distance, landing_target->size_x, landing_target->size_y, landing_target->x, landing_target->y, landing_target->z, landing_target->q, landing_target->type, landing_target->position_valid);
}
/**
@ -194,10 +244,16 @@ static inline uint16_t mavlink_msg_landing_target_encode_chan(uint8_t system_id,
* @param distance [m] Distance to the target from the vehicle
* @param size_x [rad] Size of target along x-axis
* @param size_y [rad] Size of target along y-axis
* @param x [m] X Position of the landing target in MAV_FRAME
* @param y [m] Y Position of the landing target in MAV_FRAME
* @param z [m] Z Position of the landing target in MAV_FRAME
* @param q Quaternion of landing target orientation (w, x, y, z order, zero-rotation is 1, 0, 0, 0)
* @param type Type of landing target
* @param position_valid Boolean indicating whether the position fields (x, y, z, q, type) contain valid target position information (valid: 1, invalid: 0). Default is 0 (invalid).
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_landing_target_send(mavlink_channel_t chan, uint64_t time_usec, uint8_t target_num, uint8_t frame, float angle_x, float angle_y, float distance, float size_x, float size_y)
static inline void mavlink_msg_landing_target_send(mavlink_channel_t chan, uint64_t time_usec, uint8_t target_num, uint8_t frame, float angle_x, float angle_y, float distance, float size_x, float size_y, float x, float y, float z, const float *q, uint8_t type, uint8_t position_valid)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_LANDING_TARGET_LEN];
@ -209,7 +265,12 @@ static inline void mavlink_msg_landing_target_send(mavlink_channel_t chan, uint6
_mav_put_float(buf, 24, size_y);
_mav_put_uint8_t(buf, 28, target_num);
_mav_put_uint8_t(buf, 29, frame);
_mav_put_float(buf, 30, x);
_mav_put_float(buf, 34, y);
_mav_put_float(buf, 38, z);
_mav_put_uint8_t(buf, 58, type);
_mav_put_uint8_t(buf, 59, position_valid);
_mav_put_float_array(buf, 42, q, 4);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LANDING_TARGET, buf, MAVLINK_MSG_ID_LANDING_TARGET_MIN_LEN, MAVLINK_MSG_ID_LANDING_TARGET_LEN, MAVLINK_MSG_ID_LANDING_TARGET_CRC);
#else
mavlink_landing_target_t packet;
@ -221,7 +282,12 @@ static inline void mavlink_msg_landing_target_send(mavlink_channel_t chan, uint6
packet.size_y = size_y;
packet.target_num = target_num;
packet.frame = frame;
packet.x = x;
packet.y = y;
packet.z = z;
packet.type = type;
packet.position_valid = position_valid;
mav_array_memcpy(packet.q, q, sizeof(float)*4);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LANDING_TARGET, (const char *)&packet, MAVLINK_MSG_ID_LANDING_TARGET_MIN_LEN, MAVLINK_MSG_ID_LANDING_TARGET_LEN, MAVLINK_MSG_ID_LANDING_TARGET_CRC);
#endif
}
@ -234,7 +300,7 @@ static inline void mavlink_msg_landing_target_send(mavlink_channel_t chan, uint6
static inline void mavlink_msg_landing_target_send_struct(mavlink_channel_t chan, const mavlink_landing_target_t* landing_target)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mavlink_msg_landing_target_send(chan, landing_target->time_usec, landing_target->target_num, landing_target->frame, landing_target->angle_x, landing_target->angle_y, landing_target->distance, landing_target->size_x, landing_target->size_y);
mavlink_msg_landing_target_send(chan, landing_target->time_usec, landing_target->target_num, landing_target->frame, landing_target->angle_x, landing_target->angle_y, landing_target->distance, landing_target->size_x, landing_target->size_y, landing_target->x, landing_target->y, landing_target->z, landing_target->q, landing_target->type, landing_target->position_valid);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LANDING_TARGET, (const char *)landing_target, MAVLINK_MSG_ID_LANDING_TARGET_MIN_LEN, MAVLINK_MSG_ID_LANDING_TARGET_LEN, MAVLINK_MSG_ID_LANDING_TARGET_CRC);
#endif
@ -248,7 +314,7 @@ static inline void mavlink_msg_landing_target_send_struct(mavlink_channel_t chan
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_landing_target_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, uint8_t target_num, uint8_t frame, float angle_x, float angle_y, float distance, float size_x, float size_y)
static inline void mavlink_msg_landing_target_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, uint8_t target_num, uint8_t frame, float angle_x, float angle_y, float distance, float size_x, float size_y, float x, float y, float z, const float *q, uint8_t type, uint8_t position_valid)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
@ -260,7 +326,12 @@ static inline void mavlink_msg_landing_target_send_buf(mavlink_message_t *msgbuf
_mav_put_float(buf, 24, size_y);
_mav_put_uint8_t(buf, 28, target_num);
_mav_put_uint8_t(buf, 29, frame);
_mav_put_float(buf, 30, x);
_mav_put_float(buf, 34, y);
_mav_put_float(buf, 38, z);
_mav_put_uint8_t(buf, 58, type);
_mav_put_uint8_t(buf, 59, position_valid);
_mav_put_float_array(buf, 42, q, 4);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LANDING_TARGET, buf, MAVLINK_MSG_ID_LANDING_TARGET_MIN_LEN, MAVLINK_MSG_ID_LANDING_TARGET_LEN, MAVLINK_MSG_ID_LANDING_TARGET_CRC);
#else
mavlink_landing_target_t *packet = (mavlink_landing_target_t *)msgbuf;
@ -272,7 +343,12 @@ static inline void mavlink_msg_landing_target_send_buf(mavlink_message_t *msgbuf
packet->size_y = size_y;
packet->target_num = target_num;
packet->frame = frame;
packet->x = x;
packet->y = y;
packet->z = z;
packet->type = type;
packet->position_valid = position_valid;
mav_array_memcpy(packet->q, q, sizeof(float)*4);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LANDING_TARGET, (const char *)packet, MAVLINK_MSG_ID_LANDING_TARGET_MIN_LEN, MAVLINK_MSG_ID_LANDING_TARGET_LEN, MAVLINK_MSG_ID_LANDING_TARGET_CRC);
#endif
}
@ -363,6 +439,66 @@ static inline float mavlink_msg_landing_target_get_size_y(const mavlink_message_
return _MAV_RETURN_float(msg, 24);
}
/**
* @brief Get field x from landing_target message
*
* @return [m] X Position of the landing target in MAV_FRAME
*/
static inline float mavlink_msg_landing_target_get_x(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 30);
}
/**
* @brief Get field y from landing_target message
*
* @return [m] Y Position of the landing target in MAV_FRAME
*/
static inline float mavlink_msg_landing_target_get_y(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 34);
}
/**
* @brief Get field z from landing_target message
*
* @return [m] Z Position of the landing target in MAV_FRAME
*/
static inline float mavlink_msg_landing_target_get_z(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 38);
}
/**
* @brief Get field q from landing_target message
*
* @return Quaternion of landing target orientation (w, x, y, z order, zero-rotation is 1, 0, 0, 0)
*/
static inline uint16_t mavlink_msg_landing_target_get_q(const mavlink_message_t* msg, float *q)
{
return _MAV_RETURN_float_array(msg, q, 4, 42);
}
/**
* @brief Get field type from landing_target message
*
* @return Type of landing target
*/
static inline uint8_t mavlink_msg_landing_target_get_type(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 58);
}
/**
* @brief Get field position_valid from landing_target message
*
* @return Boolean indicating whether the position fields (x, y, z, q, type) contain valid target position information (valid: 1, invalid: 0). Default is 0 (invalid).
*/
static inline uint8_t mavlink_msg_landing_target_get_position_valid(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 59);
}
/**
* @brief Decode a landing_target message into a struct
*
@ -380,6 +516,12 @@ static inline void mavlink_msg_landing_target_decode(const mavlink_message_t* ms
landing_target->size_y = mavlink_msg_landing_target_get_size_y(msg);
landing_target->target_num = mavlink_msg_landing_target_get_target_num(msg);
landing_target->frame = mavlink_msg_landing_target_get_frame(msg);
landing_target->x = mavlink_msg_landing_target_get_x(msg);
landing_target->y = mavlink_msg_landing_target_get_y(msg);
landing_target->z = mavlink_msg_landing_target_get_z(msg);
mavlink_msg_landing_target_get_q(msg, landing_target->q);
landing_target->type = mavlink_msg_landing_target_get_type(msg);
landing_target->position_valid = mavlink_msg_landing_target_get_position_valid(msg);
#else
uint8_t len = msg->len < MAVLINK_MSG_ID_LANDING_TARGET_LEN? msg->len : MAVLINK_MSG_ID_LANDING_TARGET_LEN;
memset(landing_target, 0, MAVLINK_MSG_ID_LANDING_TARGET_LEN);

View file

@ -0,0 +1,263 @@
#pragma once
// MESSAGE LOGGING_ACK PACKING
#define MAVLINK_MSG_ID_LOGGING_ACK 268
typedef struct __mavlink_logging_ack_t {
uint16_t sequence; /*< sequence number (must match the one in LOGGING_DATA_ACKED)*/
uint8_t target_system; /*< system ID of the target*/
uint8_t target_component; /*< component ID of the target*/
} mavlink_logging_ack_t;
#define MAVLINK_MSG_ID_LOGGING_ACK_LEN 4
#define MAVLINK_MSG_ID_LOGGING_ACK_MIN_LEN 4
#define MAVLINK_MSG_ID_268_LEN 4
#define MAVLINK_MSG_ID_268_MIN_LEN 4
#define MAVLINK_MSG_ID_LOGGING_ACK_CRC 14
#define MAVLINK_MSG_ID_268_CRC 14
#if MAVLINK_COMMAND_24BIT
#define MAVLINK_MESSAGE_INFO_LOGGING_ACK { \
268, \
"LOGGING_ACK", \
3, \
{ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_logging_ack_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_logging_ack_t, target_component) }, \
{ "sequence", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_logging_ack_t, sequence) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_LOGGING_ACK { \
"LOGGING_ACK", \
3, \
{ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_logging_ack_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_logging_ack_t, target_component) }, \
{ "sequence", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_logging_ack_t, sequence) }, \
} \
}
#endif
/**
* @brief Pack a logging_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 of the target
* @param target_component component ID of the target
* @param sequence sequence number (must match the one in LOGGING_DATA_ACKED)
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_logging_ack_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t target_system, uint8_t target_component, uint16_t sequence)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_LOGGING_ACK_LEN];
_mav_put_uint16_t(buf, 0, sequence);
_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_LOGGING_ACK_LEN);
#else
mavlink_logging_ack_t packet;
packet.sequence = sequence;
packet.target_system = target_system;
packet.target_component = target_component;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOGGING_ACK_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_LOGGING_ACK;
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LOGGING_ACK_MIN_LEN, MAVLINK_MSG_ID_LOGGING_ACK_LEN, MAVLINK_MSG_ID_LOGGING_ACK_CRC);
}
/**
* @brief Pack a logging_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 of the target
* @param target_component component ID of the target
* @param sequence sequence number (must match the one in LOGGING_DATA_ACKED)
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_logging_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,uint16_t sequence)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_LOGGING_ACK_LEN];
_mav_put_uint16_t(buf, 0, sequence);
_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_LOGGING_ACK_LEN);
#else
mavlink_logging_ack_t packet;
packet.sequence = sequence;
packet.target_system = target_system;
packet.target_component = target_component;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOGGING_ACK_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_LOGGING_ACK;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LOGGING_ACK_MIN_LEN, MAVLINK_MSG_ID_LOGGING_ACK_LEN, MAVLINK_MSG_ID_LOGGING_ACK_CRC);
}
/**
* @brief Encode a logging_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 logging_ack C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_logging_ack_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_logging_ack_t* logging_ack)
{
return mavlink_msg_logging_ack_pack(system_id, component_id, msg, logging_ack->target_system, logging_ack->target_component, logging_ack->sequence);
}
/**
* @brief Encode a logging_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 logging_ack C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_logging_ack_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_logging_ack_t* logging_ack)
{
return mavlink_msg_logging_ack_pack_chan(system_id, component_id, chan, msg, logging_ack->target_system, logging_ack->target_component, logging_ack->sequence);
}
/**
* @brief Send a logging_ack message
* @param chan MAVLink channel to send the message
*
* @param target_system system ID of the target
* @param target_component component ID of the target
* @param sequence sequence number (must match the one in LOGGING_DATA_ACKED)
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_logging_ack_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t sequence)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_LOGGING_ACK_LEN];
_mav_put_uint16_t(buf, 0, sequence);
_mav_put_uint8_t(buf, 2, target_system);
_mav_put_uint8_t(buf, 3, target_component);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOGGING_ACK, buf, MAVLINK_MSG_ID_LOGGING_ACK_MIN_LEN, MAVLINK_MSG_ID_LOGGING_ACK_LEN, MAVLINK_MSG_ID_LOGGING_ACK_CRC);
#else
mavlink_logging_ack_t packet;
packet.sequence = sequence;
packet.target_system = target_system;
packet.target_component = target_component;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOGGING_ACK, (const char *)&packet, MAVLINK_MSG_ID_LOGGING_ACK_MIN_LEN, MAVLINK_MSG_ID_LOGGING_ACK_LEN, MAVLINK_MSG_ID_LOGGING_ACK_CRC);
#endif
}
/**
* @brief Send a logging_ack message
* @param chan MAVLink channel to send the message
* @param struct The MAVLink struct to serialize
*/
static inline void mavlink_msg_logging_ack_send_struct(mavlink_channel_t chan, const mavlink_logging_ack_t* logging_ack)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mavlink_msg_logging_ack_send(chan, logging_ack->target_system, logging_ack->target_component, logging_ack->sequence);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOGGING_ACK, (const char *)logging_ack, MAVLINK_MSG_ID_LOGGING_ACK_MIN_LEN, MAVLINK_MSG_ID_LOGGING_ACK_LEN, MAVLINK_MSG_ID_LOGGING_ACK_CRC);
#endif
}
#if MAVLINK_MSG_ID_LOGGING_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_logging_ack_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t sequence)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
_mav_put_uint16_t(buf, 0, sequence);
_mav_put_uint8_t(buf, 2, target_system);
_mav_put_uint8_t(buf, 3, target_component);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOGGING_ACK, buf, MAVLINK_MSG_ID_LOGGING_ACK_MIN_LEN, MAVLINK_MSG_ID_LOGGING_ACK_LEN, MAVLINK_MSG_ID_LOGGING_ACK_CRC);
#else
mavlink_logging_ack_t *packet = (mavlink_logging_ack_t *)msgbuf;
packet->sequence = sequence;
packet->target_system = target_system;
packet->target_component = target_component;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOGGING_ACK, (const char *)packet, MAVLINK_MSG_ID_LOGGING_ACK_MIN_LEN, MAVLINK_MSG_ID_LOGGING_ACK_LEN, MAVLINK_MSG_ID_LOGGING_ACK_CRC);
#endif
}
#endif
#endif
// MESSAGE LOGGING_ACK UNPACKING
/**
* @brief Get field target_system from logging_ack message
*
* @return system ID of the target
*/
static inline uint8_t mavlink_msg_logging_ack_get_target_system(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 2);
}
/**
* @brief Get field target_component from logging_ack message
*
* @return component ID of the target
*/
static inline uint8_t mavlink_msg_logging_ack_get_target_component(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 3);
}
/**
* @brief Get field sequence from logging_ack message
*
* @return sequence number (must match the one in LOGGING_DATA_ACKED)
*/
static inline uint16_t mavlink_msg_logging_ack_get_sequence(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 0);
}
/**
* @brief Decode a logging_ack message into a struct
*
* @param msg The message to decode
* @param logging_ack C-struct to decode the message contents into
*/
static inline void mavlink_msg_logging_ack_decode(const mavlink_message_t* msg, mavlink_logging_ack_t* logging_ack)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
logging_ack->sequence = mavlink_msg_logging_ack_get_sequence(msg);
logging_ack->target_system = mavlink_msg_logging_ack_get_target_system(msg);
logging_ack->target_component = mavlink_msg_logging_ack_get_target_component(msg);
#else
uint8_t len = msg->len < MAVLINK_MSG_ID_LOGGING_ACK_LEN? msg->len : MAVLINK_MSG_ID_LOGGING_ACK_LEN;
memset(logging_ack, 0, MAVLINK_MSG_ID_LOGGING_ACK_LEN);
memcpy(logging_ack, _MAV_PAYLOAD(msg), len);
#endif
}

View file

@ -0,0 +1,330 @@
#pragma once
// MESSAGE LOGGING_DATA PACKING
#define MAVLINK_MSG_ID_LOGGING_DATA 266
typedef struct __mavlink_logging_data_t {
uint16_t sequence; /*< sequence number (can wrap)*/
uint8_t target_system; /*< system ID of the target*/
uint8_t target_component; /*< component ID of the target*/
uint8_t length; /*< [bytes] data length*/
uint8_t first_message_offset; /*< [bytes] offset into data where first message starts. This can be used for recovery, when a previous message got lost (set to 255 if no start exists).*/
uint8_t data[249]; /*< logged data*/
} mavlink_logging_data_t;
#define MAVLINK_MSG_ID_LOGGING_DATA_LEN 255
#define MAVLINK_MSG_ID_LOGGING_DATA_MIN_LEN 255
#define MAVLINK_MSG_ID_266_LEN 255
#define MAVLINK_MSG_ID_266_MIN_LEN 255
#define MAVLINK_MSG_ID_LOGGING_DATA_CRC 193
#define MAVLINK_MSG_ID_266_CRC 193
#define MAVLINK_MSG_LOGGING_DATA_FIELD_DATA_LEN 249
#if MAVLINK_COMMAND_24BIT
#define MAVLINK_MESSAGE_INFO_LOGGING_DATA { \
266, \
"LOGGING_DATA", \
6, \
{ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_logging_data_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_logging_data_t, target_component) }, \
{ "sequence", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_logging_data_t, sequence) }, \
{ "length", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_logging_data_t, length) }, \
{ "first_message_offset", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_logging_data_t, first_message_offset) }, \
{ "data", NULL, MAVLINK_TYPE_UINT8_T, 249, 6, offsetof(mavlink_logging_data_t, data) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_LOGGING_DATA { \
"LOGGING_DATA", \
6, \
{ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_logging_data_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_logging_data_t, target_component) }, \
{ "sequence", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_logging_data_t, sequence) }, \
{ "length", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_logging_data_t, length) }, \
{ "first_message_offset", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_logging_data_t, first_message_offset) }, \
{ "data", NULL, MAVLINK_TYPE_UINT8_T, 249, 6, offsetof(mavlink_logging_data_t, data) }, \
} \
}
#endif
/**
* @brief Pack a logging_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 of the target
* @param target_component component ID of the target
* @param sequence sequence number (can wrap)
* @param length [bytes] data length
* @param first_message_offset [bytes] offset into data where first message starts. This can be used for recovery, when a previous message got lost (set to 255 if no start exists).
* @param data logged data
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_logging_data_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t target_system, uint8_t target_component, uint16_t sequence, uint8_t length, uint8_t first_message_offset, const uint8_t *data)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_LOGGING_DATA_LEN];
_mav_put_uint16_t(buf, 0, sequence);
_mav_put_uint8_t(buf, 2, target_system);
_mav_put_uint8_t(buf, 3, target_component);
_mav_put_uint8_t(buf, 4, length);
_mav_put_uint8_t(buf, 5, first_message_offset);
_mav_put_uint8_t_array(buf, 6, data, 249);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOGGING_DATA_LEN);
#else
mavlink_logging_data_t packet;
packet.sequence = sequence;
packet.target_system = target_system;
packet.target_component = target_component;
packet.length = length;
packet.first_message_offset = first_message_offset;
mav_array_memcpy(packet.data, data, sizeof(uint8_t)*249);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOGGING_DATA_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_LOGGING_DATA;
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LOGGING_DATA_MIN_LEN, MAVLINK_MSG_ID_LOGGING_DATA_LEN, MAVLINK_MSG_ID_LOGGING_DATA_CRC);
}
/**
* @brief Pack a logging_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 of the target
* @param target_component component ID of the target
* @param sequence sequence number (can wrap)
* @param length [bytes] data length
* @param first_message_offset [bytes] offset into data where first message starts. This can be used for recovery, when a previous message got lost (set to 255 if no start exists).
* @param data logged data
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_logging_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 sequence,uint8_t length,uint8_t first_message_offset,const uint8_t *data)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_LOGGING_DATA_LEN];
_mav_put_uint16_t(buf, 0, sequence);
_mav_put_uint8_t(buf, 2, target_system);
_mav_put_uint8_t(buf, 3, target_component);
_mav_put_uint8_t(buf, 4, length);
_mav_put_uint8_t(buf, 5, first_message_offset);
_mav_put_uint8_t_array(buf, 6, data, 249);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOGGING_DATA_LEN);
#else
mavlink_logging_data_t packet;
packet.sequence = sequence;
packet.target_system = target_system;
packet.target_component = target_component;
packet.length = length;
packet.first_message_offset = first_message_offset;
mav_array_memcpy(packet.data, data, sizeof(uint8_t)*249);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOGGING_DATA_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_LOGGING_DATA;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LOGGING_DATA_MIN_LEN, MAVLINK_MSG_ID_LOGGING_DATA_LEN, MAVLINK_MSG_ID_LOGGING_DATA_CRC);
}
/**
* @brief Encode a logging_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 logging_data C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_logging_data_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_logging_data_t* logging_data)
{
return mavlink_msg_logging_data_pack(system_id, component_id, msg, logging_data->target_system, logging_data->target_component, logging_data->sequence, logging_data->length, logging_data->first_message_offset, logging_data->data);
}
/**
* @brief Encode a logging_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 logging_data C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_logging_data_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_logging_data_t* logging_data)
{
return mavlink_msg_logging_data_pack_chan(system_id, component_id, chan, msg, logging_data->target_system, logging_data->target_component, logging_data->sequence, logging_data->length, logging_data->first_message_offset, logging_data->data);
}
/**
* @brief Send a logging_data message
* @param chan MAVLink channel to send the message
*
* @param target_system system ID of the target
* @param target_component component ID of the target
* @param sequence sequence number (can wrap)
* @param length [bytes] data length
* @param first_message_offset [bytes] offset into data where first message starts. This can be used for recovery, when a previous message got lost (set to 255 if no start exists).
* @param data logged data
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_logging_data_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t sequence, uint8_t length, uint8_t first_message_offset, const uint8_t *data)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_LOGGING_DATA_LEN];
_mav_put_uint16_t(buf, 0, sequence);
_mav_put_uint8_t(buf, 2, target_system);
_mav_put_uint8_t(buf, 3, target_component);
_mav_put_uint8_t(buf, 4, length);
_mav_put_uint8_t(buf, 5, first_message_offset);
_mav_put_uint8_t_array(buf, 6, data, 249);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOGGING_DATA, buf, MAVLINK_MSG_ID_LOGGING_DATA_MIN_LEN, MAVLINK_MSG_ID_LOGGING_DATA_LEN, MAVLINK_MSG_ID_LOGGING_DATA_CRC);
#else
mavlink_logging_data_t packet;
packet.sequence = sequence;
packet.target_system = target_system;
packet.target_component = target_component;
packet.length = length;
packet.first_message_offset = first_message_offset;
mav_array_memcpy(packet.data, data, sizeof(uint8_t)*249);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOGGING_DATA, (const char *)&packet, MAVLINK_MSG_ID_LOGGING_DATA_MIN_LEN, MAVLINK_MSG_ID_LOGGING_DATA_LEN, MAVLINK_MSG_ID_LOGGING_DATA_CRC);
#endif
}
/**
* @brief Send a logging_data message
* @param chan MAVLink channel to send the message
* @param struct The MAVLink struct to serialize
*/
static inline void mavlink_msg_logging_data_send_struct(mavlink_channel_t chan, const mavlink_logging_data_t* logging_data)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mavlink_msg_logging_data_send(chan, logging_data->target_system, logging_data->target_component, logging_data->sequence, logging_data->length, logging_data->first_message_offset, logging_data->data);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOGGING_DATA, (const char *)logging_data, MAVLINK_MSG_ID_LOGGING_DATA_MIN_LEN, MAVLINK_MSG_ID_LOGGING_DATA_LEN, MAVLINK_MSG_ID_LOGGING_DATA_CRC);
#endif
}
#if MAVLINK_MSG_ID_LOGGING_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_logging_data_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t sequence, uint8_t length, uint8_t first_message_offset, const uint8_t *data)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
_mav_put_uint16_t(buf, 0, sequence);
_mav_put_uint8_t(buf, 2, target_system);
_mav_put_uint8_t(buf, 3, target_component);
_mav_put_uint8_t(buf, 4, length);
_mav_put_uint8_t(buf, 5, first_message_offset);
_mav_put_uint8_t_array(buf, 6, data, 249);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOGGING_DATA, buf, MAVLINK_MSG_ID_LOGGING_DATA_MIN_LEN, MAVLINK_MSG_ID_LOGGING_DATA_LEN, MAVLINK_MSG_ID_LOGGING_DATA_CRC);
#else
mavlink_logging_data_t *packet = (mavlink_logging_data_t *)msgbuf;
packet->sequence = sequence;
packet->target_system = target_system;
packet->target_component = target_component;
packet->length = length;
packet->first_message_offset = first_message_offset;
mav_array_memcpy(packet->data, data, sizeof(uint8_t)*249);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOGGING_DATA, (const char *)packet, MAVLINK_MSG_ID_LOGGING_DATA_MIN_LEN, MAVLINK_MSG_ID_LOGGING_DATA_LEN, MAVLINK_MSG_ID_LOGGING_DATA_CRC);
#endif
}
#endif
#endif
// MESSAGE LOGGING_DATA UNPACKING
/**
* @brief Get field target_system from logging_data message
*
* @return system ID of the target
*/
static inline uint8_t mavlink_msg_logging_data_get_target_system(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 2);
}
/**
* @brief Get field target_component from logging_data message
*
* @return component ID of the target
*/
static inline uint8_t mavlink_msg_logging_data_get_target_component(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 3);
}
/**
* @brief Get field sequence from logging_data message
*
* @return sequence number (can wrap)
*/
static inline uint16_t mavlink_msg_logging_data_get_sequence(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 0);
}
/**
* @brief Get field length from logging_data message
*
* @return [bytes] data length
*/
static inline uint8_t mavlink_msg_logging_data_get_length(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 4);
}
/**
* @brief Get field first_message_offset from logging_data message
*
* @return [bytes] offset into data where first message starts. This can be used for recovery, when a previous message got lost (set to 255 if no start exists).
*/
static inline uint8_t mavlink_msg_logging_data_get_first_message_offset(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 5);
}
/**
* @brief Get field data from logging_data message
*
* @return logged data
*/
static inline uint16_t mavlink_msg_logging_data_get_data(const mavlink_message_t* msg, uint8_t *data)
{
return _MAV_RETURN_uint8_t_array(msg, data, 249, 6);
}
/**
* @brief Decode a logging_data message into a struct
*
* @param msg The message to decode
* @param logging_data C-struct to decode the message contents into
*/
static inline void mavlink_msg_logging_data_decode(const mavlink_message_t* msg, mavlink_logging_data_t* logging_data)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
logging_data->sequence = mavlink_msg_logging_data_get_sequence(msg);
logging_data->target_system = mavlink_msg_logging_data_get_target_system(msg);
logging_data->target_component = mavlink_msg_logging_data_get_target_component(msg);
logging_data->length = mavlink_msg_logging_data_get_length(msg);
logging_data->first_message_offset = mavlink_msg_logging_data_get_first_message_offset(msg);
mavlink_msg_logging_data_get_data(msg, logging_data->data);
#else
uint8_t len = msg->len < MAVLINK_MSG_ID_LOGGING_DATA_LEN? msg->len : MAVLINK_MSG_ID_LOGGING_DATA_LEN;
memset(logging_data, 0, MAVLINK_MSG_ID_LOGGING_DATA_LEN);
memcpy(logging_data, _MAV_PAYLOAD(msg), len);
#endif
}

View file

@ -0,0 +1,330 @@
#pragma once
// MESSAGE LOGGING_DATA_ACKED PACKING
#define MAVLINK_MSG_ID_LOGGING_DATA_ACKED 267
typedef struct __mavlink_logging_data_acked_t {
uint16_t sequence; /*< sequence number (can wrap)*/
uint8_t target_system; /*< system ID of the target*/
uint8_t target_component; /*< component ID of the target*/
uint8_t length; /*< [bytes] data length*/
uint8_t first_message_offset; /*< [bytes] offset into data where first message starts. This can be used for recovery, when a previous message got lost (set to 255 if no start exists).*/
uint8_t data[249]; /*< logged data*/
} mavlink_logging_data_acked_t;
#define MAVLINK_MSG_ID_LOGGING_DATA_ACKED_LEN 255
#define MAVLINK_MSG_ID_LOGGING_DATA_ACKED_MIN_LEN 255
#define MAVLINK_MSG_ID_267_LEN 255
#define MAVLINK_MSG_ID_267_MIN_LEN 255
#define MAVLINK_MSG_ID_LOGGING_DATA_ACKED_CRC 35
#define MAVLINK_MSG_ID_267_CRC 35
#define MAVLINK_MSG_LOGGING_DATA_ACKED_FIELD_DATA_LEN 249
#if MAVLINK_COMMAND_24BIT
#define MAVLINK_MESSAGE_INFO_LOGGING_DATA_ACKED { \
267, \
"LOGGING_DATA_ACKED", \
6, \
{ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_logging_data_acked_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_logging_data_acked_t, target_component) }, \
{ "sequence", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_logging_data_acked_t, sequence) }, \
{ "length", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_logging_data_acked_t, length) }, \
{ "first_message_offset", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_logging_data_acked_t, first_message_offset) }, \
{ "data", NULL, MAVLINK_TYPE_UINT8_T, 249, 6, offsetof(mavlink_logging_data_acked_t, data) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_LOGGING_DATA_ACKED { \
"LOGGING_DATA_ACKED", \
6, \
{ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_logging_data_acked_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_logging_data_acked_t, target_component) }, \
{ "sequence", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_logging_data_acked_t, sequence) }, \
{ "length", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_logging_data_acked_t, length) }, \
{ "first_message_offset", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_logging_data_acked_t, first_message_offset) }, \
{ "data", NULL, MAVLINK_TYPE_UINT8_T, 249, 6, offsetof(mavlink_logging_data_acked_t, data) }, \
} \
}
#endif
/**
* @brief Pack a logging_data_acked message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param target_system system ID of the target
* @param target_component component ID of the target
* @param sequence sequence number (can wrap)
* @param length [bytes] data length
* @param first_message_offset [bytes] offset into data where first message starts. This can be used for recovery, when a previous message got lost (set to 255 if no start exists).
* @param data logged data
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_logging_data_acked_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t target_system, uint8_t target_component, uint16_t sequence, uint8_t length, uint8_t first_message_offset, const uint8_t *data)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_LOGGING_DATA_ACKED_LEN];
_mav_put_uint16_t(buf, 0, sequence);
_mav_put_uint8_t(buf, 2, target_system);
_mav_put_uint8_t(buf, 3, target_component);
_mav_put_uint8_t(buf, 4, length);
_mav_put_uint8_t(buf, 5, first_message_offset);
_mav_put_uint8_t_array(buf, 6, data, 249);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOGGING_DATA_ACKED_LEN);
#else
mavlink_logging_data_acked_t packet;
packet.sequence = sequence;
packet.target_system = target_system;
packet.target_component = target_component;
packet.length = length;
packet.first_message_offset = first_message_offset;
mav_array_memcpy(packet.data, data, sizeof(uint8_t)*249);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOGGING_DATA_ACKED_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_LOGGING_DATA_ACKED;
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_LOGGING_DATA_ACKED_MIN_LEN, MAVLINK_MSG_ID_LOGGING_DATA_ACKED_LEN, MAVLINK_MSG_ID_LOGGING_DATA_ACKED_CRC);
}
/**
* @brief Pack a logging_data_acked message on a channel
* @param system_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 of the target
* @param target_component component ID of the target
* @param sequence sequence number (can wrap)
* @param length [bytes] data length
* @param first_message_offset [bytes] offset into data where first message starts. This can be used for recovery, when a previous message got lost (set to 255 if no start exists).
* @param data logged data
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_logging_data_acked_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 sequence,uint8_t length,uint8_t first_message_offset,const uint8_t *data)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_LOGGING_DATA_ACKED_LEN];
_mav_put_uint16_t(buf, 0, sequence);
_mav_put_uint8_t(buf, 2, target_system);
_mav_put_uint8_t(buf, 3, target_component);
_mav_put_uint8_t(buf, 4, length);
_mav_put_uint8_t(buf, 5, first_message_offset);
_mav_put_uint8_t_array(buf, 6, data, 249);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_LOGGING_DATA_ACKED_LEN);
#else
mavlink_logging_data_acked_t packet;
packet.sequence = sequence;
packet.target_system = target_system;
packet.target_component = target_component;
packet.length = length;
packet.first_message_offset = first_message_offset;
mav_array_memcpy(packet.data, data, sizeof(uint8_t)*249);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_LOGGING_DATA_ACKED_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_LOGGING_DATA_ACKED;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_LOGGING_DATA_ACKED_MIN_LEN, MAVLINK_MSG_ID_LOGGING_DATA_ACKED_LEN, MAVLINK_MSG_ID_LOGGING_DATA_ACKED_CRC);
}
/**
* @brief Encode a logging_data_acked 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 logging_data_acked C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_logging_data_acked_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_logging_data_acked_t* logging_data_acked)
{
return mavlink_msg_logging_data_acked_pack(system_id, component_id, msg, logging_data_acked->target_system, logging_data_acked->target_component, logging_data_acked->sequence, logging_data_acked->length, logging_data_acked->first_message_offset, logging_data_acked->data);
}
/**
* @brief Encode a logging_data_acked 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 logging_data_acked C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_logging_data_acked_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_logging_data_acked_t* logging_data_acked)
{
return mavlink_msg_logging_data_acked_pack_chan(system_id, component_id, chan, msg, logging_data_acked->target_system, logging_data_acked->target_component, logging_data_acked->sequence, logging_data_acked->length, logging_data_acked->first_message_offset, logging_data_acked->data);
}
/**
* @brief Send a logging_data_acked message
* @param chan MAVLink channel to send the message
*
* @param target_system system ID of the target
* @param target_component component ID of the target
* @param sequence sequence number (can wrap)
* @param length [bytes] data length
* @param first_message_offset [bytes] offset into data where first message starts. This can be used for recovery, when a previous message got lost (set to 255 if no start exists).
* @param data logged data
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_logging_data_acked_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t sequence, uint8_t length, uint8_t first_message_offset, const uint8_t *data)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_LOGGING_DATA_ACKED_LEN];
_mav_put_uint16_t(buf, 0, sequence);
_mav_put_uint8_t(buf, 2, target_system);
_mav_put_uint8_t(buf, 3, target_component);
_mav_put_uint8_t(buf, 4, length);
_mav_put_uint8_t(buf, 5, first_message_offset);
_mav_put_uint8_t_array(buf, 6, data, 249);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOGGING_DATA_ACKED, buf, MAVLINK_MSG_ID_LOGGING_DATA_ACKED_MIN_LEN, MAVLINK_MSG_ID_LOGGING_DATA_ACKED_LEN, MAVLINK_MSG_ID_LOGGING_DATA_ACKED_CRC);
#else
mavlink_logging_data_acked_t packet;
packet.sequence = sequence;
packet.target_system = target_system;
packet.target_component = target_component;
packet.length = length;
packet.first_message_offset = first_message_offset;
mav_array_memcpy(packet.data, data, sizeof(uint8_t)*249);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOGGING_DATA_ACKED, (const char *)&packet, MAVLINK_MSG_ID_LOGGING_DATA_ACKED_MIN_LEN, MAVLINK_MSG_ID_LOGGING_DATA_ACKED_LEN, MAVLINK_MSG_ID_LOGGING_DATA_ACKED_CRC);
#endif
}
/**
* @brief Send a logging_data_acked message
* @param chan MAVLink channel to send the message
* @param struct The MAVLink struct to serialize
*/
static inline void mavlink_msg_logging_data_acked_send_struct(mavlink_channel_t chan, const mavlink_logging_data_acked_t* logging_data_acked)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mavlink_msg_logging_data_acked_send(chan, logging_data_acked->target_system, logging_data_acked->target_component, logging_data_acked->sequence, logging_data_acked->length, logging_data_acked->first_message_offset, logging_data_acked->data);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOGGING_DATA_ACKED, (const char *)logging_data_acked, MAVLINK_MSG_ID_LOGGING_DATA_ACKED_MIN_LEN, MAVLINK_MSG_ID_LOGGING_DATA_ACKED_LEN, MAVLINK_MSG_ID_LOGGING_DATA_ACKED_CRC);
#endif
}
#if MAVLINK_MSG_ID_LOGGING_DATA_ACKED_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_logging_data_acked_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t sequence, uint8_t length, uint8_t first_message_offset, const uint8_t *data)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
_mav_put_uint16_t(buf, 0, sequence);
_mav_put_uint8_t(buf, 2, target_system);
_mav_put_uint8_t(buf, 3, target_component);
_mav_put_uint8_t(buf, 4, length);
_mav_put_uint8_t(buf, 5, first_message_offset);
_mav_put_uint8_t_array(buf, 6, data, 249);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOGGING_DATA_ACKED, buf, MAVLINK_MSG_ID_LOGGING_DATA_ACKED_MIN_LEN, MAVLINK_MSG_ID_LOGGING_DATA_ACKED_LEN, MAVLINK_MSG_ID_LOGGING_DATA_ACKED_CRC);
#else
mavlink_logging_data_acked_t *packet = (mavlink_logging_data_acked_t *)msgbuf;
packet->sequence = sequence;
packet->target_system = target_system;
packet->target_component = target_component;
packet->length = length;
packet->first_message_offset = first_message_offset;
mav_array_memcpy(packet->data, data, sizeof(uint8_t)*249);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_LOGGING_DATA_ACKED, (const char *)packet, MAVLINK_MSG_ID_LOGGING_DATA_ACKED_MIN_LEN, MAVLINK_MSG_ID_LOGGING_DATA_ACKED_LEN, MAVLINK_MSG_ID_LOGGING_DATA_ACKED_CRC);
#endif
}
#endif
#endif
// MESSAGE LOGGING_DATA_ACKED UNPACKING
/**
* @brief Get field target_system from logging_data_acked message
*
* @return system ID of the target
*/
static inline uint8_t mavlink_msg_logging_data_acked_get_target_system(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 2);
}
/**
* @brief Get field target_component from logging_data_acked message
*
* @return component ID of the target
*/
static inline uint8_t mavlink_msg_logging_data_acked_get_target_component(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 3);
}
/**
* @brief Get field sequence from logging_data_acked message
*
* @return sequence number (can wrap)
*/
static inline uint16_t mavlink_msg_logging_data_acked_get_sequence(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 0);
}
/**
* @brief Get field length from logging_data_acked message
*
* @return [bytes] data length
*/
static inline uint8_t mavlink_msg_logging_data_acked_get_length(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 4);
}
/**
* @brief Get field first_message_offset from logging_data_acked message
*
* @return [bytes] offset into data where first message starts. This can be used for recovery, when a previous message got lost (set to 255 if no start exists).
*/
static inline uint8_t mavlink_msg_logging_data_acked_get_first_message_offset(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 5);
}
/**
* @brief Get field data from logging_data_acked message
*
* @return logged data
*/
static inline uint16_t mavlink_msg_logging_data_acked_get_data(const mavlink_message_t* msg, uint8_t *data)
{
return _MAV_RETURN_uint8_t_array(msg, data, 249, 6);
}
/**
* @brief Decode a logging_data_acked message into a struct
*
* @param msg The message to decode
* @param logging_data_acked C-struct to decode the message contents into
*/
static inline void mavlink_msg_logging_data_acked_decode(const mavlink_message_t* msg, mavlink_logging_data_acked_t* logging_data_acked)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
logging_data_acked->sequence = mavlink_msg_logging_data_acked_get_sequence(msg);
logging_data_acked->target_system = mavlink_msg_logging_data_acked_get_target_system(msg);
logging_data_acked->target_component = mavlink_msg_logging_data_acked_get_target_component(msg);
logging_data_acked->length = mavlink_msg_logging_data_acked_get_length(msg);
logging_data_acked->first_message_offset = mavlink_msg_logging_data_acked_get_first_message_offset(msg);
mavlink_msg_logging_data_acked_get_data(msg, logging_data_acked->data);
#else
uint8_t len = msg->len < MAVLINK_MSG_ID_LOGGING_DATA_ACKED_LEN? msg->len : MAVLINK_MSG_ID_LOGGING_DATA_ACKED_LEN;
memset(logging_data_acked, 0, MAVLINK_MSG_ID_LOGGING_DATA_ACKED_LEN);
memcpy(logging_data_acked, _MAV_PAYLOAD(msg), len);
#endif
}

View file

@ -0,0 +1,638 @@
#pragma once
// MESSAGE MAG_CAL_REPORT PACKING
#define MAVLINK_MSG_ID_MAG_CAL_REPORT 192
MAVPACKED(
typedef struct __mavlink_mag_cal_report_t {
float fitness; /*< [mgauss] RMS milligauss residuals.*/
float ofs_x; /*< X offset.*/
float ofs_y; /*< Y offset.*/
float ofs_z; /*< Z offset.*/
float diag_x; /*< X diagonal (matrix 11).*/
float diag_y; /*< Y diagonal (matrix 22).*/
float diag_z; /*< Z diagonal (matrix 33).*/
float offdiag_x; /*< X off-diagonal (matrix 12 and 21).*/
float offdiag_y; /*< Y off-diagonal (matrix 13 and 31).*/
float offdiag_z; /*< Z off-diagonal (matrix 32 and 23).*/
uint8_t compass_id; /*< Compass being calibrated.*/
uint8_t cal_mask; /*< Bitmask of compasses being calibrated.*/
uint8_t cal_status; /*< Calibration Status.*/
uint8_t autosaved; /*< 0=requires a MAV_CMD_DO_ACCEPT_MAG_CAL, 1=saved to parameters.*/
float orientation_confidence; /*< Confidence in orientation (higher is better).*/
uint8_t old_orientation; /*< orientation before calibration.*/
uint8_t new_orientation; /*< orientation after calibration.*/
float scale_factor; /*< field radius correction factor*/
}) mavlink_mag_cal_report_t;
#define MAVLINK_MSG_ID_MAG_CAL_REPORT_LEN 54
#define MAVLINK_MSG_ID_MAG_CAL_REPORT_MIN_LEN 44
#define MAVLINK_MSG_ID_192_LEN 54
#define MAVLINK_MSG_ID_192_MIN_LEN 44
#define MAVLINK_MSG_ID_MAG_CAL_REPORT_CRC 36
#define MAVLINK_MSG_ID_192_CRC 36
#if MAVLINK_COMMAND_24BIT
#define MAVLINK_MESSAGE_INFO_MAG_CAL_REPORT { \
192, \
"MAG_CAL_REPORT", \
18, \
{ { "compass_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 40, offsetof(mavlink_mag_cal_report_t, compass_id) }, \
{ "cal_mask", NULL, MAVLINK_TYPE_UINT8_T, 0, 41, offsetof(mavlink_mag_cal_report_t, cal_mask) }, \
{ "cal_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 42, offsetof(mavlink_mag_cal_report_t, cal_status) }, \
{ "autosaved", NULL, MAVLINK_TYPE_UINT8_T, 0, 43, offsetof(mavlink_mag_cal_report_t, autosaved) }, \
{ "fitness", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_mag_cal_report_t, fitness) }, \
{ "ofs_x", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_mag_cal_report_t, ofs_x) }, \
{ "ofs_y", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_mag_cal_report_t, ofs_y) }, \
{ "ofs_z", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_mag_cal_report_t, ofs_z) }, \
{ "diag_x", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_mag_cal_report_t, diag_x) }, \
{ "diag_y", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_mag_cal_report_t, diag_y) }, \
{ "diag_z", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_mag_cal_report_t, diag_z) }, \
{ "offdiag_x", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_mag_cal_report_t, offdiag_x) }, \
{ "offdiag_y", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_mag_cal_report_t, offdiag_y) }, \
{ "offdiag_z", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_mag_cal_report_t, offdiag_z) }, \
{ "orientation_confidence", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_mag_cal_report_t, orientation_confidence) }, \
{ "old_orientation", NULL, MAVLINK_TYPE_UINT8_T, 0, 48, offsetof(mavlink_mag_cal_report_t, old_orientation) }, \
{ "new_orientation", NULL, MAVLINK_TYPE_UINT8_T, 0, 49, offsetof(mavlink_mag_cal_report_t, new_orientation) }, \
{ "scale_factor", NULL, MAVLINK_TYPE_FLOAT, 0, 50, offsetof(mavlink_mag_cal_report_t, scale_factor) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_MAG_CAL_REPORT { \
"MAG_CAL_REPORT", \
18, \
{ { "compass_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 40, offsetof(mavlink_mag_cal_report_t, compass_id) }, \
{ "cal_mask", NULL, MAVLINK_TYPE_UINT8_T, 0, 41, offsetof(mavlink_mag_cal_report_t, cal_mask) }, \
{ "cal_status", NULL, MAVLINK_TYPE_UINT8_T, 0, 42, offsetof(mavlink_mag_cal_report_t, cal_status) }, \
{ "autosaved", NULL, MAVLINK_TYPE_UINT8_T, 0, 43, offsetof(mavlink_mag_cal_report_t, autosaved) }, \
{ "fitness", NULL, MAVLINK_TYPE_FLOAT, 0, 0, offsetof(mavlink_mag_cal_report_t, fitness) }, \
{ "ofs_x", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_mag_cal_report_t, ofs_x) }, \
{ "ofs_y", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_mag_cal_report_t, ofs_y) }, \
{ "ofs_z", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_mag_cal_report_t, ofs_z) }, \
{ "diag_x", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_mag_cal_report_t, diag_x) }, \
{ "diag_y", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_mag_cal_report_t, diag_y) }, \
{ "diag_z", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_mag_cal_report_t, diag_z) }, \
{ "offdiag_x", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_mag_cal_report_t, offdiag_x) }, \
{ "offdiag_y", NULL, MAVLINK_TYPE_FLOAT, 0, 32, offsetof(mavlink_mag_cal_report_t, offdiag_y) }, \
{ "offdiag_z", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_mag_cal_report_t, offdiag_z) }, \
{ "orientation_confidence", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_mag_cal_report_t, orientation_confidence) }, \
{ "old_orientation", NULL, MAVLINK_TYPE_UINT8_T, 0, 48, offsetof(mavlink_mag_cal_report_t, old_orientation) }, \
{ "new_orientation", NULL, MAVLINK_TYPE_UINT8_T, 0, 49, offsetof(mavlink_mag_cal_report_t, new_orientation) }, \
{ "scale_factor", NULL, MAVLINK_TYPE_FLOAT, 0, 50, offsetof(mavlink_mag_cal_report_t, scale_factor) }, \
} \
}
#endif
/**
* @brief Pack a mag_cal_report message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param compass_id Compass being calibrated.
* @param cal_mask Bitmask of compasses being calibrated.
* @param cal_status Calibration Status.
* @param autosaved 0=requires a MAV_CMD_DO_ACCEPT_MAG_CAL, 1=saved to parameters.
* @param fitness [mgauss] RMS milligauss residuals.
* @param ofs_x X offset.
* @param ofs_y Y offset.
* @param ofs_z Z offset.
* @param diag_x X diagonal (matrix 11).
* @param diag_y Y diagonal (matrix 22).
* @param diag_z Z diagonal (matrix 33).
* @param offdiag_x X off-diagonal (matrix 12 and 21).
* @param offdiag_y Y off-diagonal (matrix 13 and 31).
* @param offdiag_z Z off-diagonal (matrix 32 and 23).
* @param orientation_confidence Confidence in orientation (higher is better).
* @param old_orientation orientation before calibration.
* @param new_orientation orientation after calibration.
* @param scale_factor field radius correction factor
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_mag_cal_report_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t compass_id, uint8_t cal_mask, uint8_t cal_status, uint8_t autosaved, float fitness, float ofs_x, float ofs_y, float ofs_z, float diag_x, float diag_y, float diag_z, float offdiag_x, float offdiag_y, float offdiag_z, float orientation_confidence, uint8_t old_orientation, uint8_t new_orientation, float scale_factor)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_MAG_CAL_REPORT_LEN];
_mav_put_float(buf, 0, fitness);
_mav_put_float(buf, 4, ofs_x);
_mav_put_float(buf, 8, ofs_y);
_mav_put_float(buf, 12, ofs_z);
_mav_put_float(buf, 16, diag_x);
_mav_put_float(buf, 20, diag_y);
_mav_put_float(buf, 24, diag_z);
_mav_put_float(buf, 28, offdiag_x);
_mav_put_float(buf, 32, offdiag_y);
_mav_put_float(buf, 36, offdiag_z);
_mav_put_uint8_t(buf, 40, compass_id);
_mav_put_uint8_t(buf, 41, cal_mask);
_mav_put_uint8_t(buf, 42, cal_status);
_mav_put_uint8_t(buf, 43, autosaved);
_mav_put_float(buf, 44, orientation_confidence);
_mav_put_uint8_t(buf, 48, old_orientation);
_mav_put_uint8_t(buf, 49, new_orientation);
_mav_put_float(buf, 50, scale_factor);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MAG_CAL_REPORT_LEN);
#else
mavlink_mag_cal_report_t packet;
packet.fitness = fitness;
packet.ofs_x = ofs_x;
packet.ofs_y = ofs_y;
packet.ofs_z = ofs_z;
packet.diag_x = diag_x;
packet.diag_y = diag_y;
packet.diag_z = diag_z;
packet.offdiag_x = offdiag_x;
packet.offdiag_y = offdiag_y;
packet.offdiag_z = offdiag_z;
packet.compass_id = compass_id;
packet.cal_mask = cal_mask;
packet.cal_status = cal_status;
packet.autosaved = autosaved;
packet.orientation_confidence = orientation_confidence;
packet.old_orientation = old_orientation;
packet.new_orientation = new_orientation;
packet.scale_factor = scale_factor;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MAG_CAL_REPORT_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_MAG_CAL_REPORT;
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MAG_CAL_REPORT_MIN_LEN, MAVLINK_MSG_ID_MAG_CAL_REPORT_LEN, MAVLINK_MSG_ID_MAG_CAL_REPORT_CRC);
}
/**
* @brief Pack a mag_cal_report message on a channel
* @param system_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 compass_id Compass being calibrated.
* @param cal_mask Bitmask of compasses being calibrated.
* @param cal_status Calibration Status.
* @param autosaved 0=requires a MAV_CMD_DO_ACCEPT_MAG_CAL, 1=saved to parameters.
* @param fitness [mgauss] RMS milligauss residuals.
* @param ofs_x X offset.
* @param ofs_y Y offset.
* @param ofs_z Z offset.
* @param diag_x X diagonal (matrix 11).
* @param diag_y Y diagonal (matrix 22).
* @param diag_z Z diagonal (matrix 33).
* @param offdiag_x X off-diagonal (matrix 12 and 21).
* @param offdiag_y Y off-diagonal (matrix 13 and 31).
* @param offdiag_z Z off-diagonal (matrix 32 and 23).
* @param orientation_confidence Confidence in orientation (higher is better).
* @param old_orientation orientation before calibration.
* @param new_orientation orientation after calibration.
* @param scale_factor field radius correction factor
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_mag_cal_report_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint8_t compass_id,uint8_t cal_mask,uint8_t cal_status,uint8_t autosaved,float fitness,float ofs_x,float ofs_y,float ofs_z,float diag_x,float diag_y,float diag_z,float offdiag_x,float offdiag_y,float offdiag_z,float orientation_confidence,uint8_t old_orientation,uint8_t new_orientation,float scale_factor)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_MAG_CAL_REPORT_LEN];
_mav_put_float(buf, 0, fitness);
_mav_put_float(buf, 4, ofs_x);
_mav_put_float(buf, 8, ofs_y);
_mav_put_float(buf, 12, ofs_z);
_mav_put_float(buf, 16, diag_x);
_mav_put_float(buf, 20, diag_y);
_mav_put_float(buf, 24, diag_z);
_mav_put_float(buf, 28, offdiag_x);
_mav_put_float(buf, 32, offdiag_y);
_mav_put_float(buf, 36, offdiag_z);
_mav_put_uint8_t(buf, 40, compass_id);
_mav_put_uint8_t(buf, 41, cal_mask);
_mav_put_uint8_t(buf, 42, cal_status);
_mav_put_uint8_t(buf, 43, autosaved);
_mav_put_float(buf, 44, orientation_confidence);
_mav_put_uint8_t(buf, 48, old_orientation);
_mav_put_uint8_t(buf, 49, new_orientation);
_mav_put_float(buf, 50, scale_factor);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MAG_CAL_REPORT_LEN);
#else
mavlink_mag_cal_report_t packet;
packet.fitness = fitness;
packet.ofs_x = ofs_x;
packet.ofs_y = ofs_y;
packet.ofs_z = ofs_z;
packet.diag_x = diag_x;
packet.diag_y = diag_y;
packet.diag_z = diag_z;
packet.offdiag_x = offdiag_x;
packet.offdiag_y = offdiag_y;
packet.offdiag_z = offdiag_z;
packet.compass_id = compass_id;
packet.cal_mask = cal_mask;
packet.cal_status = cal_status;
packet.autosaved = autosaved;
packet.orientation_confidence = orientation_confidence;
packet.old_orientation = old_orientation;
packet.new_orientation = new_orientation;
packet.scale_factor = scale_factor;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MAG_CAL_REPORT_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_MAG_CAL_REPORT;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MAG_CAL_REPORT_MIN_LEN, MAVLINK_MSG_ID_MAG_CAL_REPORT_LEN, MAVLINK_MSG_ID_MAG_CAL_REPORT_CRC);
}
/**
* @brief Encode a mag_cal_report 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 mag_cal_report C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_mag_cal_report_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mag_cal_report_t* mag_cal_report)
{
return mavlink_msg_mag_cal_report_pack(system_id, component_id, msg, mag_cal_report->compass_id, mag_cal_report->cal_mask, mag_cal_report->cal_status, mag_cal_report->autosaved, mag_cal_report->fitness, mag_cal_report->ofs_x, mag_cal_report->ofs_y, mag_cal_report->ofs_z, mag_cal_report->diag_x, mag_cal_report->diag_y, mag_cal_report->diag_z, mag_cal_report->offdiag_x, mag_cal_report->offdiag_y, mag_cal_report->offdiag_z, mag_cal_report->orientation_confidence, mag_cal_report->old_orientation, mag_cal_report->new_orientation, mag_cal_report->scale_factor);
}
/**
* @brief Encode a mag_cal_report 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 mag_cal_report C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_mag_cal_report_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_mag_cal_report_t* mag_cal_report)
{
return mavlink_msg_mag_cal_report_pack_chan(system_id, component_id, chan, msg, mag_cal_report->compass_id, mag_cal_report->cal_mask, mag_cal_report->cal_status, mag_cal_report->autosaved, mag_cal_report->fitness, mag_cal_report->ofs_x, mag_cal_report->ofs_y, mag_cal_report->ofs_z, mag_cal_report->diag_x, mag_cal_report->diag_y, mag_cal_report->diag_z, mag_cal_report->offdiag_x, mag_cal_report->offdiag_y, mag_cal_report->offdiag_z, mag_cal_report->orientation_confidence, mag_cal_report->old_orientation, mag_cal_report->new_orientation, mag_cal_report->scale_factor);
}
/**
* @brief Send a mag_cal_report message
* @param chan MAVLink channel to send the message
*
* @param compass_id Compass being calibrated.
* @param cal_mask Bitmask of compasses being calibrated.
* @param cal_status Calibration Status.
* @param autosaved 0=requires a MAV_CMD_DO_ACCEPT_MAG_CAL, 1=saved to parameters.
* @param fitness [mgauss] RMS milligauss residuals.
* @param ofs_x X offset.
* @param ofs_y Y offset.
* @param ofs_z Z offset.
* @param diag_x X diagonal (matrix 11).
* @param diag_y Y diagonal (matrix 22).
* @param diag_z Z diagonal (matrix 33).
* @param offdiag_x X off-diagonal (matrix 12 and 21).
* @param offdiag_y Y off-diagonal (matrix 13 and 31).
* @param offdiag_z Z off-diagonal (matrix 32 and 23).
* @param orientation_confidence Confidence in orientation (higher is better).
* @param old_orientation orientation before calibration.
* @param new_orientation orientation after calibration.
* @param scale_factor field radius correction factor
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_mag_cal_report_send(mavlink_channel_t chan, uint8_t compass_id, uint8_t cal_mask, uint8_t cal_status, uint8_t autosaved, float fitness, float ofs_x, float ofs_y, float ofs_z, float diag_x, float diag_y, float diag_z, float offdiag_x, float offdiag_y, float offdiag_z, float orientation_confidence, uint8_t old_orientation, uint8_t new_orientation, float scale_factor)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_MAG_CAL_REPORT_LEN];
_mav_put_float(buf, 0, fitness);
_mav_put_float(buf, 4, ofs_x);
_mav_put_float(buf, 8, ofs_y);
_mav_put_float(buf, 12, ofs_z);
_mav_put_float(buf, 16, diag_x);
_mav_put_float(buf, 20, diag_y);
_mav_put_float(buf, 24, diag_z);
_mav_put_float(buf, 28, offdiag_x);
_mav_put_float(buf, 32, offdiag_y);
_mav_put_float(buf, 36, offdiag_z);
_mav_put_uint8_t(buf, 40, compass_id);
_mav_put_uint8_t(buf, 41, cal_mask);
_mav_put_uint8_t(buf, 42, cal_status);
_mav_put_uint8_t(buf, 43, autosaved);
_mav_put_float(buf, 44, orientation_confidence);
_mav_put_uint8_t(buf, 48, old_orientation);
_mav_put_uint8_t(buf, 49, new_orientation);
_mav_put_float(buf, 50, scale_factor);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MAG_CAL_REPORT, buf, MAVLINK_MSG_ID_MAG_CAL_REPORT_MIN_LEN, MAVLINK_MSG_ID_MAG_CAL_REPORT_LEN, MAVLINK_MSG_ID_MAG_CAL_REPORT_CRC);
#else
mavlink_mag_cal_report_t packet;
packet.fitness = fitness;
packet.ofs_x = ofs_x;
packet.ofs_y = ofs_y;
packet.ofs_z = ofs_z;
packet.diag_x = diag_x;
packet.diag_y = diag_y;
packet.diag_z = diag_z;
packet.offdiag_x = offdiag_x;
packet.offdiag_y = offdiag_y;
packet.offdiag_z = offdiag_z;
packet.compass_id = compass_id;
packet.cal_mask = cal_mask;
packet.cal_status = cal_status;
packet.autosaved = autosaved;
packet.orientation_confidence = orientation_confidence;
packet.old_orientation = old_orientation;
packet.new_orientation = new_orientation;
packet.scale_factor = scale_factor;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MAG_CAL_REPORT, (const char *)&packet, MAVLINK_MSG_ID_MAG_CAL_REPORT_MIN_LEN, MAVLINK_MSG_ID_MAG_CAL_REPORT_LEN, MAVLINK_MSG_ID_MAG_CAL_REPORT_CRC);
#endif
}
/**
* @brief Send a mag_cal_report message
* @param chan MAVLink channel to send the message
* @param struct The MAVLink struct to serialize
*/
static inline void mavlink_msg_mag_cal_report_send_struct(mavlink_channel_t chan, const mavlink_mag_cal_report_t* mag_cal_report)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mavlink_msg_mag_cal_report_send(chan, mag_cal_report->compass_id, mag_cal_report->cal_mask, mag_cal_report->cal_status, mag_cal_report->autosaved, mag_cal_report->fitness, mag_cal_report->ofs_x, mag_cal_report->ofs_y, mag_cal_report->ofs_z, mag_cal_report->diag_x, mag_cal_report->diag_y, mag_cal_report->diag_z, mag_cal_report->offdiag_x, mag_cal_report->offdiag_y, mag_cal_report->offdiag_z, mag_cal_report->orientation_confidence, mag_cal_report->old_orientation, mag_cal_report->new_orientation, mag_cal_report->scale_factor);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MAG_CAL_REPORT, (const char *)mag_cal_report, MAVLINK_MSG_ID_MAG_CAL_REPORT_MIN_LEN, MAVLINK_MSG_ID_MAG_CAL_REPORT_LEN, MAVLINK_MSG_ID_MAG_CAL_REPORT_CRC);
#endif
}
#if MAVLINK_MSG_ID_MAG_CAL_REPORT_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_mag_cal_report_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t compass_id, uint8_t cal_mask, uint8_t cal_status, uint8_t autosaved, float fitness, float ofs_x, float ofs_y, float ofs_z, float diag_x, float diag_y, float diag_z, float offdiag_x, float offdiag_y, float offdiag_z, float orientation_confidence, uint8_t old_orientation, uint8_t new_orientation, float scale_factor)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
_mav_put_float(buf, 0, fitness);
_mav_put_float(buf, 4, ofs_x);
_mav_put_float(buf, 8, ofs_y);
_mav_put_float(buf, 12, ofs_z);
_mav_put_float(buf, 16, diag_x);
_mav_put_float(buf, 20, diag_y);
_mav_put_float(buf, 24, diag_z);
_mav_put_float(buf, 28, offdiag_x);
_mav_put_float(buf, 32, offdiag_y);
_mav_put_float(buf, 36, offdiag_z);
_mav_put_uint8_t(buf, 40, compass_id);
_mav_put_uint8_t(buf, 41, cal_mask);
_mav_put_uint8_t(buf, 42, cal_status);
_mav_put_uint8_t(buf, 43, autosaved);
_mav_put_float(buf, 44, orientation_confidence);
_mav_put_uint8_t(buf, 48, old_orientation);
_mav_put_uint8_t(buf, 49, new_orientation);
_mav_put_float(buf, 50, scale_factor);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MAG_CAL_REPORT, buf, MAVLINK_MSG_ID_MAG_CAL_REPORT_MIN_LEN, MAVLINK_MSG_ID_MAG_CAL_REPORT_LEN, MAVLINK_MSG_ID_MAG_CAL_REPORT_CRC);
#else
mavlink_mag_cal_report_t *packet = (mavlink_mag_cal_report_t *)msgbuf;
packet->fitness = fitness;
packet->ofs_x = ofs_x;
packet->ofs_y = ofs_y;
packet->ofs_z = ofs_z;
packet->diag_x = diag_x;
packet->diag_y = diag_y;
packet->diag_z = diag_z;
packet->offdiag_x = offdiag_x;
packet->offdiag_y = offdiag_y;
packet->offdiag_z = offdiag_z;
packet->compass_id = compass_id;
packet->cal_mask = cal_mask;
packet->cal_status = cal_status;
packet->autosaved = autosaved;
packet->orientation_confidence = orientation_confidence;
packet->old_orientation = old_orientation;
packet->new_orientation = new_orientation;
packet->scale_factor = scale_factor;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MAG_CAL_REPORT, (const char *)packet, MAVLINK_MSG_ID_MAG_CAL_REPORT_MIN_LEN, MAVLINK_MSG_ID_MAG_CAL_REPORT_LEN, MAVLINK_MSG_ID_MAG_CAL_REPORT_CRC);
#endif
}
#endif
#endif
// MESSAGE MAG_CAL_REPORT UNPACKING
/**
* @brief Get field compass_id from mag_cal_report message
*
* @return Compass being calibrated.
*/
static inline uint8_t mavlink_msg_mag_cal_report_get_compass_id(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 40);
}
/**
* @brief Get field cal_mask from mag_cal_report message
*
* @return Bitmask of compasses being calibrated.
*/
static inline uint8_t mavlink_msg_mag_cal_report_get_cal_mask(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 41);
}
/**
* @brief Get field cal_status from mag_cal_report message
*
* @return Calibration Status.
*/
static inline uint8_t mavlink_msg_mag_cal_report_get_cal_status(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 42);
}
/**
* @brief Get field autosaved from mag_cal_report message
*
* @return 0=requires a MAV_CMD_DO_ACCEPT_MAG_CAL, 1=saved to parameters.
*/
static inline uint8_t mavlink_msg_mag_cal_report_get_autosaved(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 43);
}
/**
* @brief Get field fitness from mag_cal_report message
*
* @return [mgauss] RMS milligauss residuals.
*/
static inline float mavlink_msg_mag_cal_report_get_fitness(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 0);
}
/**
* @brief Get field ofs_x from mag_cal_report message
*
* @return X offset.
*/
static inline float mavlink_msg_mag_cal_report_get_ofs_x(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 4);
}
/**
* @brief Get field ofs_y from mag_cal_report message
*
* @return Y offset.
*/
static inline float mavlink_msg_mag_cal_report_get_ofs_y(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 8);
}
/**
* @brief Get field ofs_z from mag_cal_report message
*
* @return Z offset.
*/
static inline float mavlink_msg_mag_cal_report_get_ofs_z(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 12);
}
/**
* @brief Get field diag_x from mag_cal_report message
*
* @return X diagonal (matrix 11).
*/
static inline float mavlink_msg_mag_cal_report_get_diag_x(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 16);
}
/**
* @brief Get field diag_y from mag_cal_report message
*
* @return Y diagonal (matrix 22).
*/
static inline float mavlink_msg_mag_cal_report_get_diag_y(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 20);
}
/**
* @brief Get field diag_z from mag_cal_report message
*
* @return Z diagonal (matrix 33).
*/
static inline float mavlink_msg_mag_cal_report_get_diag_z(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 24);
}
/**
* @brief Get field offdiag_x from mag_cal_report message
*
* @return X off-diagonal (matrix 12 and 21).
*/
static inline float mavlink_msg_mag_cal_report_get_offdiag_x(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 28);
}
/**
* @brief Get field offdiag_y from mag_cal_report message
*
* @return Y off-diagonal (matrix 13 and 31).
*/
static inline float mavlink_msg_mag_cal_report_get_offdiag_y(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 32);
}
/**
* @brief Get field offdiag_z from mag_cal_report message
*
* @return Z off-diagonal (matrix 32 and 23).
*/
static inline float mavlink_msg_mag_cal_report_get_offdiag_z(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 36);
}
/**
* @brief Get field orientation_confidence from mag_cal_report message
*
* @return Confidence in orientation (higher is better).
*/
static inline float mavlink_msg_mag_cal_report_get_orientation_confidence(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 44);
}
/**
* @brief Get field old_orientation from mag_cal_report message
*
* @return orientation before calibration.
*/
static inline uint8_t mavlink_msg_mag_cal_report_get_old_orientation(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 48);
}
/**
* @brief Get field new_orientation from mag_cal_report message
*
* @return orientation after calibration.
*/
static inline uint8_t mavlink_msg_mag_cal_report_get_new_orientation(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 49);
}
/**
* @brief Get field scale_factor from mag_cal_report message
*
* @return field radius correction factor
*/
static inline float mavlink_msg_mag_cal_report_get_scale_factor(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 50);
}
/**
* @brief Decode a mag_cal_report message into a struct
*
* @param msg The message to decode
* @param mag_cal_report C-struct to decode the message contents into
*/
static inline void mavlink_msg_mag_cal_report_decode(const mavlink_message_t* msg, mavlink_mag_cal_report_t* mag_cal_report)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mag_cal_report->fitness = mavlink_msg_mag_cal_report_get_fitness(msg);
mag_cal_report->ofs_x = mavlink_msg_mag_cal_report_get_ofs_x(msg);
mag_cal_report->ofs_y = mavlink_msg_mag_cal_report_get_ofs_y(msg);
mag_cal_report->ofs_z = mavlink_msg_mag_cal_report_get_ofs_z(msg);
mag_cal_report->diag_x = mavlink_msg_mag_cal_report_get_diag_x(msg);
mag_cal_report->diag_y = mavlink_msg_mag_cal_report_get_diag_y(msg);
mag_cal_report->diag_z = mavlink_msg_mag_cal_report_get_diag_z(msg);
mag_cal_report->offdiag_x = mavlink_msg_mag_cal_report_get_offdiag_x(msg);
mag_cal_report->offdiag_y = mavlink_msg_mag_cal_report_get_offdiag_y(msg);
mag_cal_report->offdiag_z = mavlink_msg_mag_cal_report_get_offdiag_z(msg);
mag_cal_report->compass_id = mavlink_msg_mag_cal_report_get_compass_id(msg);
mag_cal_report->cal_mask = mavlink_msg_mag_cal_report_get_cal_mask(msg);
mag_cal_report->cal_status = mavlink_msg_mag_cal_report_get_cal_status(msg);
mag_cal_report->autosaved = mavlink_msg_mag_cal_report_get_autosaved(msg);
mag_cal_report->orientation_confidence = mavlink_msg_mag_cal_report_get_orientation_confidence(msg);
mag_cal_report->old_orientation = mavlink_msg_mag_cal_report_get_old_orientation(msg);
mag_cal_report->new_orientation = mavlink_msg_mag_cal_report_get_new_orientation(msg);
mag_cal_report->scale_factor = mavlink_msg_mag_cal_report_get_scale_factor(msg);
#else
uint8_t len = msg->len < MAVLINK_MSG_ID_MAG_CAL_REPORT_LEN? msg->len : MAVLINK_MSG_ID_MAG_CAL_REPORT_LEN;
memset(mag_cal_report, 0, MAVLINK_MSG_ID_MAG_CAL_REPORT_LEN);
memcpy(mag_cal_report, _MAV_PAYLOAD(msg), len);
#endif
}

View file

@ -8,11 +8,12 @@ typedef struct __mavlink_mission_ack_t {
uint8_t target_system; /*< System ID*/
uint8_t target_component; /*< Component ID*/
uint8_t type; /*< Mission result.*/
uint8_t mission_type; /*< Mission type.*/
} mavlink_mission_ack_t;
#define MAVLINK_MSG_ID_MISSION_ACK_LEN 3
#define MAVLINK_MSG_ID_MISSION_ACK_LEN 4
#define MAVLINK_MSG_ID_MISSION_ACK_MIN_LEN 3
#define MAVLINK_MSG_ID_47_LEN 3
#define MAVLINK_MSG_ID_47_LEN 4
#define MAVLINK_MSG_ID_47_MIN_LEN 3
#define MAVLINK_MSG_ID_MISSION_ACK_CRC 153
@ -24,19 +25,21 @@ typedef struct __mavlink_mission_ack_t {
#define MAVLINK_MESSAGE_INFO_MISSION_ACK { \
47, \
"MISSION_ACK", \
3, \
4, \
{ { "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) }, \
{ "mission_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_mission_ack_t, mission_type) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_MISSION_ACK { \
"MISSION_ACK", \
3, \
4, \
{ { "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) }, \
{ "mission_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_mission_ack_t, mission_type) }, \
} \
}
#endif
@ -50,16 +53,18 @@ typedef struct __mavlink_mission_ack_t {
* @param target_system System ID
* @param target_component Component ID
* @param type Mission result.
* @param mission_type Mission type.
* @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)
uint8_t target_system, uint8_t target_component, uint8_t type, uint8_t mission_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);
_mav_put_uint8_t(buf, 3, mission_type);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_ACK_LEN);
#else
@ -67,6 +72,7 @@ static inline uint16_t mavlink_msg_mission_ack_pack(uint8_t system_id, uint8_t c
packet.target_system = target_system;
packet.target_component = target_component;
packet.type = type;
packet.mission_type = mission_type;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_ACK_LEN);
#endif
@ -84,17 +90,19 @@ static inline uint16_t mavlink_msg_mission_ack_pack(uint8_t system_id, uint8_t c
* @param target_system System ID
* @param target_component Component ID
* @param type Mission result.
* @param mission_type Mission type.
* @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)
uint8_t target_system,uint8_t target_component,uint8_t type,uint8_t mission_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);
_mav_put_uint8_t(buf, 3, mission_type);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_ACK_LEN);
#else
@ -102,6 +110,7 @@ static inline uint16_t mavlink_msg_mission_ack_pack_chan(uint8_t system_id, uint
packet.target_system = target_system;
packet.target_component = target_component;
packet.type = type;
packet.mission_type = mission_type;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_ACK_LEN);
#endif
@ -120,7 +129,7 @@ static inline uint16_t mavlink_msg_mission_ack_pack_chan(uint8_t system_id, uint
*/
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);
return mavlink_msg_mission_ack_pack(system_id, component_id, msg, mission_ack->target_system, mission_ack->target_component, mission_ack->type, mission_ack->mission_type);
}
/**
@ -134,7 +143,7 @@ static inline uint16_t mavlink_msg_mission_ack_encode(uint8_t system_id, uint8_t
*/
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);
return mavlink_msg_mission_ack_pack_chan(system_id, component_id, chan, msg, mission_ack->target_system, mission_ack->target_component, mission_ack->type, mission_ack->mission_type);
}
/**
@ -144,16 +153,18 @@ static inline uint16_t mavlink_msg_mission_ack_encode_chan(uint8_t system_id, ui
* @param target_system System ID
* @param target_component Component ID
* @param type Mission result.
* @param mission_type Mission type.
*/
#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)
static inline void mavlink_msg_mission_ack_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t type, uint8_t mission_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);
_mav_put_uint8_t(buf, 3, mission_type);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ACK, buf, MAVLINK_MSG_ID_MISSION_ACK_MIN_LEN, MAVLINK_MSG_ID_MISSION_ACK_LEN, MAVLINK_MSG_ID_MISSION_ACK_CRC);
#else
@ -161,6 +172,7 @@ static inline void mavlink_msg_mission_ack_send(mavlink_channel_t chan, uint8_t
packet.target_system = target_system;
packet.target_component = target_component;
packet.type = type;
packet.mission_type = mission_type;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ACK, (const char *)&packet, MAVLINK_MSG_ID_MISSION_ACK_MIN_LEN, MAVLINK_MSG_ID_MISSION_ACK_LEN, MAVLINK_MSG_ID_MISSION_ACK_CRC);
#endif
@ -174,7 +186,7 @@ static inline void mavlink_msg_mission_ack_send(mavlink_channel_t chan, uint8_t
static inline void mavlink_msg_mission_ack_send_struct(mavlink_channel_t chan, const mavlink_mission_ack_t* mission_ack)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mavlink_msg_mission_ack_send(chan, mission_ack->target_system, mission_ack->target_component, mission_ack->type);
mavlink_msg_mission_ack_send(chan, mission_ack->target_system, mission_ack->target_component, mission_ack->type, mission_ack->mission_type);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ACK, (const char *)mission_ack, MAVLINK_MSG_ID_MISSION_ACK_MIN_LEN, MAVLINK_MSG_ID_MISSION_ACK_LEN, MAVLINK_MSG_ID_MISSION_ACK_CRC);
#endif
@ -188,13 +200,14 @@ static inline void mavlink_msg_mission_ack_send_struct(mavlink_channel_t chan, c
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)
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, uint8_t mission_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);
_mav_put_uint8_t(buf, 3, mission_type);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ACK, buf, MAVLINK_MSG_ID_MISSION_ACK_MIN_LEN, MAVLINK_MSG_ID_MISSION_ACK_LEN, MAVLINK_MSG_ID_MISSION_ACK_CRC);
#else
@ -202,6 +215,7 @@ static inline void mavlink_msg_mission_ack_send_buf(mavlink_message_t *msgbuf, m
packet->target_system = target_system;
packet->target_component = target_component;
packet->type = type;
packet->mission_type = mission_type;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ACK, (const char *)packet, MAVLINK_MSG_ID_MISSION_ACK_MIN_LEN, MAVLINK_MSG_ID_MISSION_ACK_LEN, MAVLINK_MSG_ID_MISSION_ACK_CRC);
#endif
@ -243,6 +257,16 @@ static inline uint8_t mavlink_msg_mission_ack_get_type(const mavlink_message_t*
return _MAV_RETURN_uint8_t(msg, 2);
}
/**
* @brief Get field mission_type from mission_ack message
*
* @return Mission type.
*/
static inline uint8_t mavlink_msg_mission_ack_get_mission_type(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 3);
}
/**
* @brief Decode a mission_ack message into a struct
*
@ -255,6 +279,7 @@ static inline void mavlink_msg_mission_ack_decode(const mavlink_message_t* msg,
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);
mission_ack->mission_type = mavlink_msg_mission_ack_get_mission_type(msg);
#else
uint8_t len = msg->len < MAVLINK_MSG_ID_MISSION_ACK_LEN? msg->len : MAVLINK_MSG_ID_MISSION_ACK_LEN;
memset(mission_ack, 0, MAVLINK_MSG_ID_MISSION_ACK_LEN);

View file

@ -7,11 +7,12 @@
typedef struct __mavlink_mission_clear_all_t {
uint8_t target_system; /*< System ID*/
uint8_t target_component; /*< Component ID*/
uint8_t mission_type; /*< Mission type.*/
} mavlink_mission_clear_all_t;
#define MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN 2
#define MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN 3
#define MAVLINK_MSG_ID_MISSION_CLEAR_ALL_MIN_LEN 2
#define MAVLINK_MSG_ID_45_LEN 2
#define MAVLINK_MSG_ID_45_LEN 3
#define MAVLINK_MSG_ID_45_MIN_LEN 2
#define MAVLINK_MSG_ID_MISSION_CLEAR_ALL_CRC 232
@ -23,17 +24,19 @@ typedef struct __mavlink_mission_clear_all_t {
#define MAVLINK_MESSAGE_INFO_MISSION_CLEAR_ALL { \
45, \
"MISSION_CLEAR_ALL", \
2, \
3, \
{ { "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) }, \
{ "mission_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_mission_clear_all_t, mission_type) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_MISSION_CLEAR_ALL { \
"MISSION_CLEAR_ALL", \
2, \
3, \
{ { "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) }, \
{ "mission_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_mission_clear_all_t, mission_type) }, \
} \
}
#endif
@ -46,21 +49,24 @@ typedef struct __mavlink_mission_clear_all_t {
*
* @param target_system System ID
* @param target_component Component ID
* @param mission_type Mission type.
* @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)
uint8_t target_system, uint8_t target_component, uint8_t mission_type)
{
#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);
_mav_put_uint8_t(buf, 2, mission_type);
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;
packet.mission_type = mission_type;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN);
#endif
@ -77,22 +83,25 @@ static inline uint16_t mavlink_msg_mission_clear_all_pack(uint8_t system_id, uin
* @param msg The MAVLink message to compress the data into
* @param target_system System ID
* @param target_component Component ID
* @param mission_type Mission type.
* @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)
uint8_t target_system,uint8_t target_component,uint8_t mission_type)
{
#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);
_mav_put_uint8_t(buf, 2, mission_type);
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;
packet.mission_type = mission_type;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN);
#endif
@ -111,7 +120,7 @@ static inline uint16_t mavlink_msg_mission_clear_all_pack_chan(uint8_t system_id
*/
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);
return mavlink_msg_mission_clear_all_pack(system_id, component_id, msg, mission_clear_all->target_system, mission_clear_all->target_component, mission_clear_all->mission_type);
}
/**
@ -125,7 +134,7 @@ static inline uint16_t mavlink_msg_mission_clear_all_encode(uint8_t system_id, u
*/
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);
return mavlink_msg_mission_clear_all_pack_chan(system_id, component_id, chan, msg, mission_clear_all->target_system, mission_clear_all->target_component, mission_clear_all->mission_type);
}
/**
@ -134,21 +143,24 @@ static inline uint16_t mavlink_msg_mission_clear_all_encode_chan(uint8_t system_
*
* @param target_system System ID
* @param target_component Component ID
* @param mission_type Mission type.
*/
#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)
static inline void mavlink_msg_mission_clear_all_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t mission_type)
{
#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);
_mav_put_uint8_t(buf, 2, mission_type);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_CLEAR_ALL, buf, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_MIN_LEN, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_CRC);
#else
mavlink_mission_clear_all_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
packet.mission_type = mission_type;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_CLEAR_ALL, (const char *)&packet, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_MIN_LEN, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_CRC);
#endif
@ -162,7 +174,7 @@ static inline void mavlink_msg_mission_clear_all_send(mavlink_channel_t chan, ui
static inline void mavlink_msg_mission_clear_all_send_struct(mavlink_channel_t chan, const mavlink_mission_clear_all_t* mission_clear_all)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mavlink_msg_mission_clear_all_send(chan, mission_clear_all->target_system, mission_clear_all->target_component);
mavlink_msg_mission_clear_all_send(chan, mission_clear_all->target_system, mission_clear_all->target_component, mission_clear_all->mission_type);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_CLEAR_ALL, (const char *)mission_clear_all, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_MIN_LEN, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_CRC);
#endif
@ -176,18 +188,20 @@ static inline void mavlink_msg_mission_clear_all_send_struct(mavlink_channel_t c
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)
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, uint8_t mission_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, mission_type);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_CLEAR_ALL, buf, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_MIN_LEN, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_CRC);
#else
mavlink_mission_clear_all_t *packet = (mavlink_mission_clear_all_t *)msgbuf;
packet->target_system = target_system;
packet->target_component = target_component;
packet->mission_type = mission_type;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_CLEAR_ALL, (const char *)packet, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_MIN_LEN, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_CRC);
#endif
@ -219,6 +233,16 @@ static inline uint8_t mavlink_msg_mission_clear_all_get_target_component(const m
return _MAV_RETURN_uint8_t(msg, 1);
}
/**
* @brief Get field mission_type from mission_clear_all message
*
* @return Mission type.
*/
static inline uint8_t mavlink_msg_mission_clear_all_get_mission_type(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 2);
}
/**
* @brief Decode a mission_clear_all message into a struct
*
@ -230,6 +254,7 @@ static inline void mavlink_msg_mission_clear_all_decode(const mavlink_message_t*
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
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);
mission_clear_all->mission_type = mavlink_msg_mission_clear_all_get_mission_type(msg);
#else
uint8_t len = msg->len < MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN? msg->len : MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN;
memset(mission_clear_all, 0, MAVLINK_MSG_ID_MISSION_CLEAR_ALL_LEN);

View file

@ -8,11 +8,12 @@ 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*/
uint8_t mission_type; /*< Mission type.*/
} mavlink_mission_count_t;
#define MAVLINK_MSG_ID_MISSION_COUNT_LEN 4
#define MAVLINK_MSG_ID_MISSION_COUNT_LEN 5
#define MAVLINK_MSG_ID_MISSION_COUNT_MIN_LEN 4
#define MAVLINK_MSG_ID_44_LEN 4
#define MAVLINK_MSG_ID_44_LEN 5
#define MAVLINK_MSG_ID_44_MIN_LEN 4
#define MAVLINK_MSG_ID_MISSION_COUNT_CRC 221
@ -24,19 +25,21 @@ typedef struct __mavlink_mission_count_t {
#define MAVLINK_MESSAGE_INFO_MISSION_COUNT { \
44, \
"MISSION_COUNT", \
3, \
4, \
{ { "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) }, \
{ "count", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_mission_count_t, count) }, \
{ "mission_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_mission_count_t, mission_type) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_MISSION_COUNT { \
"MISSION_COUNT", \
3, \
4, \
{ { "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) }, \
{ "count", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_mission_count_t, count) }, \
{ "mission_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_mission_count_t, mission_type) }, \
} \
}
#endif
@ -50,16 +53,18 @@ typedef struct __mavlink_mission_count_t {
* @param target_system System ID
* @param target_component Component ID
* @param count Number of mission items in the sequence
* @param mission_type Mission type.
* @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)
uint8_t target_system, uint8_t target_component, uint16_t count, uint8_t mission_type)
{
#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);
_mav_put_uint8_t(buf, 4, mission_type);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_COUNT_LEN);
#else
@ -67,6 +72,7 @@ static inline uint16_t mavlink_msg_mission_count_pack(uint8_t system_id, uint8_t
packet.count = count;
packet.target_system = target_system;
packet.target_component = target_component;
packet.mission_type = mission_type;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_COUNT_LEN);
#endif
@ -84,17 +90,19 @@ static inline uint16_t mavlink_msg_mission_count_pack(uint8_t system_id, uint8_t
* @param target_system System ID
* @param target_component Component ID
* @param count Number of mission items in the sequence
* @param mission_type Mission type.
* @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)
uint8_t target_system,uint8_t target_component,uint16_t count,uint8_t mission_type)
{
#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);
_mav_put_uint8_t(buf, 4, mission_type);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_COUNT_LEN);
#else
@ -102,6 +110,7 @@ static inline uint16_t mavlink_msg_mission_count_pack_chan(uint8_t system_id, ui
packet.count = count;
packet.target_system = target_system;
packet.target_component = target_component;
packet.mission_type = mission_type;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_COUNT_LEN);
#endif
@ -120,7 +129,7 @@ static inline uint16_t mavlink_msg_mission_count_pack_chan(uint8_t system_id, ui
*/
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);
return mavlink_msg_mission_count_pack(system_id, component_id, msg, mission_count->target_system, mission_count->target_component, mission_count->count, mission_count->mission_type);
}
/**
@ -134,7 +143,7 @@ static inline uint16_t mavlink_msg_mission_count_encode(uint8_t system_id, uint8
*/
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);
return mavlink_msg_mission_count_pack_chan(system_id, component_id, chan, msg, mission_count->target_system, mission_count->target_component, mission_count->count, mission_count->mission_type);
}
/**
@ -144,16 +153,18 @@ static inline uint16_t mavlink_msg_mission_count_encode_chan(uint8_t system_id,
* @param target_system System ID
* @param target_component Component ID
* @param count Number of mission items in the sequence
* @param mission_type Mission type.
*/
#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)
static inline void mavlink_msg_mission_count_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t count, uint8_t mission_type)
{
#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);
_mav_put_uint8_t(buf, 4, mission_type);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_COUNT, buf, MAVLINK_MSG_ID_MISSION_COUNT_MIN_LEN, MAVLINK_MSG_ID_MISSION_COUNT_LEN, MAVLINK_MSG_ID_MISSION_COUNT_CRC);
#else
@ -161,6 +172,7 @@ static inline void mavlink_msg_mission_count_send(mavlink_channel_t chan, uint8_
packet.count = count;
packet.target_system = target_system;
packet.target_component = target_component;
packet.mission_type = mission_type;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_COUNT, (const char *)&packet, MAVLINK_MSG_ID_MISSION_COUNT_MIN_LEN, MAVLINK_MSG_ID_MISSION_COUNT_LEN, MAVLINK_MSG_ID_MISSION_COUNT_CRC);
#endif
@ -174,7 +186,7 @@ static inline void mavlink_msg_mission_count_send(mavlink_channel_t chan, uint8_
static inline void mavlink_msg_mission_count_send_struct(mavlink_channel_t chan, const mavlink_mission_count_t* mission_count)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mavlink_msg_mission_count_send(chan, mission_count->target_system, mission_count->target_component, mission_count->count);
mavlink_msg_mission_count_send(chan, mission_count->target_system, mission_count->target_component, mission_count->count, mission_count->mission_type);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_COUNT, (const char *)mission_count, MAVLINK_MSG_ID_MISSION_COUNT_MIN_LEN, MAVLINK_MSG_ID_MISSION_COUNT_LEN, MAVLINK_MSG_ID_MISSION_COUNT_CRC);
#endif
@ -188,13 +200,14 @@ static inline void mavlink_msg_mission_count_send_struct(mavlink_channel_t chan,
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)
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, uint8_t mission_type)
{
#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);
_mav_put_uint8_t(buf, 4, mission_type);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_COUNT, buf, MAVLINK_MSG_ID_MISSION_COUNT_MIN_LEN, MAVLINK_MSG_ID_MISSION_COUNT_LEN, MAVLINK_MSG_ID_MISSION_COUNT_CRC);
#else
@ -202,6 +215,7 @@ static inline void mavlink_msg_mission_count_send_buf(mavlink_message_t *msgbuf,
packet->count = count;
packet->target_system = target_system;
packet->target_component = target_component;
packet->mission_type = mission_type;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_COUNT, (const char *)packet, MAVLINK_MSG_ID_MISSION_COUNT_MIN_LEN, MAVLINK_MSG_ID_MISSION_COUNT_LEN, MAVLINK_MSG_ID_MISSION_COUNT_CRC);
#endif
@ -243,6 +257,16 @@ static inline uint16_t mavlink_msg_mission_count_get_count(const mavlink_message
return _MAV_RETURN_uint16_t(msg, 0);
}
/**
* @brief Get field mission_type from mission_count message
*
* @return Mission type.
*/
static inline uint8_t mavlink_msg_mission_count_get_mission_type(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 4);
}
/**
* @brief Decode a mission_count message into a struct
*
@ -255,6 +279,7 @@ static inline void mavlink_msg_mission_count_decode(const mavlink_message_t* msg
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);
mission_count->mission_type = mavlink_msg_mission_count_get_mission_type(msg);
#else
uint8_t len = msg->len < MAVLINK_MSG_ID_MISSION_COUNT_LEN? msg->len : MAVLINK_MSG_ID_MISSION_COUNT_LEN;
memset(mission_count, 0, MAVLINK_MSG_ID_MISSION_COUNT_LEN);

View file

@ -19,11 +19,12 @@ typedef struct __mavlink_mission_item_t {
uint8_t frame; /*< The coordinate system of the waypoint.*/
uint8_t current; /*< false:0, true:1*/
uint8_t autocontinue; /*< Autocontinue to next waypoint*/
uint8_t mission_type; /*< Mission type.*/
} mavlink_mission_item_t;
#define MAVLINK_MSG_ID_MISSION_ITEM_LEN 37
#define MAVLINK_MSG_ID_MISSION_ITEM_LEN 38
#define MAVLINK_MSG_ID_MISSION_ITEM_MIN_LEN 37
#define MAVLINK_MSG_ID_39_LEN 37
#define MAVLINK_MSG_ID_39_LEN 38
#define MAVLINK_MSG_ID_39_MIN_LEN 37
#define MAVLINK_MSG_ID_MISSION_ITEM_CRC 254
@ -35,7 +36,7 @@ typedef struct __mavlink_mission_item_t {
#define MAVLINK_MESSAGE_INFO_MISSION_ITEM { \
39, \
"MISSION_ITEM", \
14, \
15, \
{ { "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) }, \
{ "seq", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_mission_item_t, seq) }, \
@ -50,12 +51,13 @@ typedef struct __mavlink_mission_item_t {
{ "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) }, \
{ "mission_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 37, offsetof(mavlink_mission_item_t, mission_type) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_MISSION_ITEM { \
"MISSION_ITEM", \
14, \
15, \
{ { "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) }, \
{ "seq", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_mission_item_t, seq) }, \
@ -70,6 +72,7 @@ typedef struct __mavlink_mission_item_t {
{ "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) }, \
{ "mission_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 37, offsetof(mavlink_mission_item_t, mission_type) }, \
} \
}
#endif
@ -94,10 +97,11 @@ typedef struct __mavlink_mission_item_t {
* @param x PARAM5 / local: X coordinate, global: latitude
* @param y PARAM6 / local: Y coordinate, global: longitude
* @param z PARAM7 / local: Z coordinate, global: altitude (relative or absolute, depending on frame).
* @param mission_type Mission type.
* @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)
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, uint8_t mission_type)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_MISSION_ITEM_LEN];
@ -115,6 +119,7 @@ static inline uint16_t mavlink_msg_mission_item_pack(uint8_t system_id, uint8_t
_mav_put_uint8_t(buf, 34, frame);
_mav_put_uint8_t(buf, 35, current);
_mav_put_uint8_t(buf, 36, autocontinue);
_mav_put_uint8_t(buf, 37, mission_type);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_ITEM_LEN);
#else
@ -133,6 +138,7 @@ static inline uint16_t mavlink_msg_mission_item_pack(uint8_t system_id, uint8_t
packet.frame = frame;
packet.current = current;
packet.autocontinue = autocontinue;
packet.mission_type = mission_type;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_ITEM_LEN);
#endif
@ -161,11 +167,12 @@ static inline uint16_t mavlink_msg_mission_item_pack(uint8_t system_id, uint8_t
* @param x PARAM5 / local: X coordinate, global: latitude
* @param y PARAM6 / local: Y coordinate, global: longitude
* @param z PARAM7 / local: Z coordinate, global: altitude (relative or absolute, depending on frame).
* @param mission_type Mission type.
* @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)
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,uint8_t mission_type)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_MISSION_ITEM_LEN];
@ -183,6 +190,7 @@ static inline uint16_t mavlink_msg_mission_item_pack_chan(uint8_t system_id, uin
_mav_put_uint8_t(buf, 34, frame);
_mav_put_uint8_t(buf, 35, current);
_mav_put_uint8_t(buf, 36, autocontinue);
_mav_put_uint8_t(buf, 37, mission_type);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_ITEM_LEN);
#else
@ -201,6 +209,7 @@ static inline uint16_t mavlink_msg_mission_item_pack_chan(uint8_t system_id, uin
packet.frame = frame;
packet.current = current;
packet.autocontinue = autocontinue;
packet.mission_type = mission_type;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_ITEM_LEN);
#endif
@ -219,7 +228,7 @@ static inline uint16_t mavlink_msg_mission_item_pack_chan(uint8_t system_id, uin
*/
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);
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, mission_item->mission_type);
}
/**
@ -233,7 +242,7 @@ static inline uint16_t mavlink_msg_mission_item_encode(uint8_t system_id, uint8_
*/
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);
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, mission_item->mission_type);
}
/**
@ -254,10 +263,11 @@ static inline uint16_t mavlink_msg_mission_item_encode_chan(uint8_t system_id, u
* @param x PARAM5 / local: X coordinate, global: latitude
* @param y PARAM6 / local: Y coordinate, global: longitude
* @param z PARAM7 / local: Z coordinate, global: altitude (relative or absolute, depending on frame).
* @param mission_type Mission type.
*/
#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)
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, uint8_t mission_type)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_MISSION_ITEM_LEN];
@ -275,6 +285,7 @@ static inline void mavlink_msg_mission_item_send(mavlink_channel_t chan, uint8_t
_mav_put_uint8_t(buf, 34, frame);
_mav_put_uint8_t(buf, 35, current);
_mav_put_uint8_t(buf, 36, autocontinue);
_mav_put_uint8_t(buf, 37, mission_type);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM, buf, MAVLINK_MSG_ID_MISSION_ITEM_MIN_LEN, MAVLINK_MSG_ID_MISSION_ITEM_LEN, MAVLINK_MSG_ID_MISSION_ITEM_CRC);
#else
@ -293,6 +304,7 @@ static inline void mavlink_msg_mission_item_send(mavlink_channel_t chan, uint8_t
packet.frame = frame;
packet.current = current;
packet.autocontinue = autocontinue;
packet.mission_type = mission_type;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM, (const char *)&packet, MAVLINK_MSG_ID_MISSION_ITEM_MIN_LEN, MAVLINK_MSG_ID_MISSION_ITEM_LEN, MAVLINK_MSG_ID_MISSION_ITEM_CRC);
#endif
@ -306,7 +318,7 @@ static inline void mavlink_msg_mission_item_send(mavlink_channel_t chan, uint8_t
static inline void mavlink_msg_mission_item_send_struct(mavlink_channel_t chan, const mavlink_mission_item_t* mission_item)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mavlink_msg_mission_item_send(chan, 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);
mavlink_msg_mission_item_send(chan, 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, mission_item->mission_type);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM, (const char *)mission_item, MAVLINK_MSG_ID_MISSION_ITEM_MIN_LEN, MAVLINK_MSG_ID_MISSION_ITEM_LEN, MAVLINK_MSG_ID_MISSION_ITEM_CRC);
#endif
@ -320,7 +332,7 @@ static inline void mavlink_msg_mission_item_send_struct(mavlink_channel_t chan,
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)
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, uint8_t mission_type)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
@ -338,6 +350,7 @@ static inline void mavlink_msg_mission_item_send_buf(mavlink_message_t *msgbuf,
_mav_put_uint8_t(buf, 34, frame);
_mav_put_uint8_t(buf, 35, current);
_mav_put_uint8_t(buf, 36, autocontinue);
_mav_put_uint8_t(buf, 37, mission_type);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM, buf, MAVLINK_MSG_ID_MISSION_ITEM_MIN_LEN, MAVLINK_MSG_ID_MISSION_ITEM_LEN, MAVLINK_MSG_ID_MISSION_ITEM_CRC);
#else
@ -356,6 +369,7 @@ static inline void mavlink_msg_mission_item_send_buf(mavlink_message_t *msgbuf,
packet->frame = frame;
packet->current = current;
packet->autocontinue = autocontinue;
packet->mission_type = mission_type;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM, (const char *)packet, MAVLINK_MSG_ID_MISSION_ITEM_MIN_LEN, MAVLINK_MSG_ID_MISSION_ITEM_LEN, MAVLINK_MSG_ID_MISSION_ITEM_CRC);
#endif
@ -507,6 +521,16 @@ static inline float mavlink_msg_mission_item_get_z(const mavlink_message_t* msg)
return _MAV_RETURN_float(msg, 24);
}
/**
* @brief Get field mission_type from mission_item message
*
* @return Mission type.
*/
static inline uint8_t mavlink_msg_mission_item_get_mission_type(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 37);
}
/**
* @brief Decode a mission_item message into a struct
*
@ -530,6 +554,7 @@ static inline void mavlink_msg_mission_item_decode(const mavlink_message_t* 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);
mission_item->mission_type = mavlink_msg_mission_item_get_mission_type(msg);
#else
uint8_t len = msg->len < MAVLINK_MSG_ID_MISSION_ITEM_LEN? msg->len : MAVLINK_MSG_ID_MISSION_ITEM_LEN;
memset(mission_item, 0, MAVLINK_MSG_ID_MISSION_ITEM_LEN);

View file

@ -19,11 +19,12 @@ typedef struct __mavlink_mission_item_int_t {
uint8_t frame; /*< The coordinate system of the waypoint.*/
uint8_t current; /*< false:0, true:1*/
uint8_t autocontinue; /*< Autocontinue to next waypoint*/
uint8_t mission_type; /*< Mission type.*/
} mavlink_mission_item_int_t;
#define MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN 37
#define MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN 38
#define MAVLINK_MSG_ID_MISSION_ITEM_INT_MIN_LEN 37
#define MAVLINK_MSG_ID_73_LEN 37
#define MAVLINK_MSG_ID_73_LEN 38
#define MAVLINK_MSG_ID_73_MIN_LEN 37
#define MAVLINK_MSG_ID_MISSION_ITEM_INT_CRC 38
@ -35,7 +36,7 @@ typedef struct __mavlink_mission_item_int_t {
#define MAVLINK_MESSAGE_INFO_MISSION_ITEM_INT { \
73, \
"MISSION_ITEM_INT", \
14, \
15, \
{ { "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) }, \
{ "seq", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_mission_item_int_t, seq) }, \
@ -50,12 +51,13 @@ typedef struct __mavlink_mission_item_int_t {
{ "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) }, \
{ "mission_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 37, offsetof(mavlink_mission_item_int_t, mission_type) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_MISSION_ITEM_INT { \
"MISSION_ITEM_INT", \
14, \
15, \
{ { "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) }, \
{ "seq", NULL, MAVLINK_TYPE_UINT16_T, 0, 28, offsetof(mavlink_mission_item_int_t, seq) }, \
@ -70,6 +72,7 @@ typedef struct __mavlink_mission_item_int_t {
{ "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) }, \
{ "mission_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 37, offsetof(mavlink_mission_item_int_t, mission_type) }, \
} \
}
#endif
@ -94,10 +97,11 @@ typedef struct __mavlink_mission_item_int_t {
* @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.
* @param mission_type Mission type.
* @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)
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, uint8_t mission_type)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN];
@ -115,6 +119,7 @@ static inline uint16_t mavlink_msg_mission_item_int_pack(uint8_t system_id, uint
_mav_put_uint8_t(buf, 34, frame);
_mav_put_uint8_t(buf, 35, current);
_mav_put_uint8_t(buf, 36, autocontinue);
_mav_put_uint8_t(buf, 37, mission_type);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN);
#else
@ -133,6 +138,7 @@ static inline uint16_t mavlink_msg_mission_item_int_pack(uint8_t system_id, uint
packet.frame = frame;
packet.current = current;
packet.autocontinue = autocontinue;
packet.mission_type = mission_type;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN);
#endif
@ -161,11 +167,12 @@ static inline uint16_t mavlink_msg_mission_item_int_pack(uint8_t system_id, uint
* @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.
* @param mission_type Mission type.
* @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)
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,uint8_t mission_type)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN];
@ -183,6 +190,7 @@ static inline uint16_t mavlink_msg_mission_item_int_pack_chan(uint8_t system_id,
_mav_put_uint8_t(buf, 34, frame);
_mav_put_uint8_t(buf, 35, current);
_mav_put_uint8_t(buf, 36, autocontinue);
_mav_put_uint8_t(buf, 37, mission_type);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN);
#else
@ -201,6 +209,7 @@ static inline uint16_t mavlink_msg_mission_item_int_pack_chan(uint8_t system_id,
packet.frame = frame;
packet.current = current;
packet.autocontinue = autocontinue;
packet.mission_type = mission_type;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN);
#endif
@ -219,7 +228,7 @@ static inline uint16_t mavlink_msg_mission_item_int_pack_chan(uint8_t system_id,
*/
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);
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, mission_item_int->mission_type);
}
/**
@ -233,7 +242,7 @@ static inline uint16_t mavlink_msg_mission_item_int_encode(uint8_t system_id, ui
*/
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);
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, mission_item_int->mission_type);
}
/**
@ -254,10 +263,11 @@ static inline uint16_t mavlink_msg_mission_item_int_encode_chan(uint8_t system_i
* @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.
* @param mission_type Mission type.
*/
#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)
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, uint8_t mission_type)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN];
@ -275,6 +285,7 @@ static inline void mavlink_msg_mission_item_int_send(mavlink_channel_t chan, uin
_mav_put_uint8_t(buf, 34, frame);
_mav_put_uint8_t(buf, 35, current);
_mav_put_uint8_t(buf, 36, autocontinue);
_mav_put_uint8_t(buf, 37, mission_type);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM_INT, buf, MAVLINK_MSG_ID_MISSION_ITEM_INT_MIN_LEN, MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN, MAVLINK_MSG_ID_MISSION_ITEM_INT_CRC);
#else
@ -293,6 +304,7 @@ static inline void mavlink_msg_mission_item_int_send(mavlink_channel_t chan, uin
packet.frame = frame;
packet.current = current;
packet.autocontinue = autocontinue;
packet.mission_type = mission_type;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM_INT, (const char *)&packet, MAVLINK_MSG_ID_MISSION_ITEM_INT_MIN_LEN, MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN, MAVLINK_MSG_ID_MISSION_ITEM_INT_CRC);
#endif
@ -306,7 +318,7 @@ static inline void mavlink_msg_mission_item_int_send(mavlink_channel_t chan, uin
static inline void mavlink_msg_mission_item_int_send_struct(mavlink_channel_t chan, const mavlink_mission_item_int_t* mission_item_int)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mavlink_msg_mission_item_int_send(chan, 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);
mavlink_msg_mission_item_int_send(chan, 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, mission_item_int->mission_type);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM_INT, (const char *)mission_item_int, MAVLINK_MSG_ID_MISSION_ITEM_INT_MIN_LEN, MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN, MAVLINK_MSG_ID_MISSION_ITEM_INT_CRC);
#endif
@ -320,7 +332,7 @@ static inline void mavlink_msg_mission_item_int_send_struct(mavlink_channel_t ch
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)
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, uint8_t mission_type)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
@ -338,6 +350,7 @@ static inline void mavlink_msg_mission_item_int_send_buf(mavlink_message_t *msgb
_mav_put_uint8_t(buf, 34, frame);
_mav_put_uint8_t(buf, 35, current);
_mav_put_uint8_t(buf, 36, autocontinue);
_mav_put_uint8_t(buf, 37, mission_type);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM_INT, buf, MAVLINK_MSG_ID_MISSION_ITEM_INT_MIN_LEN, MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN, MAVLINK_MSG_ID_MISSION_ITEM_INT_CRC);
#else
@ -356,6 +369,7 @@ static inline void mavlink_msg_mission_item_int_send_buf(mavlink_message_t *msgb
packet->frame = frame;
packet->current = current;
packet->autocontinue = autocontinue;
packet->mission_type = mission_type;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_ITEM_INT, (const char *)packet, MAVLINK_MSG_ID_MISSION_ITEM_INT_MIN_LEN, MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN, MAVLINK_MSG_ID_MISSION_ITEM_INT_CRC);
#endif
@ -507,6 +521,16 @@ static inline float mavlink_msg_mission_item_int_get_z(const mavlink_message_t*
return _MAV_RETURN_float(msg, 24);
}
/**
* @brief Get field mission_type from mission_item_int message
*
* @return Mission type.
*/
static inline uint8_t mavlink_msg_mission_item_int_get_mission_type(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 37);
}
/**
* @brief Decode a mission_item_int message into a struct
*
@ -530,6 +554,7 @@ static inline void mavlink_msg_mission_item_int_decode(const mavlink_message_t*
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);
mission_item_int->mission_type = mavlink_msg_mission_item_int_get_mission_type(msg);
#else
uint8_t len = msg->len < MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN? msg->len : MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN;
memset(mission_item_int, 0, MAVLINK_MSG_ID_MISSION_ITEM_INT_LEN);

View file

@ -8,11 +8,12 @@ typedef struct __mavlink_mission_request_t {
uint16_t seq; /*< Sequence*/
uint8_t target_system; /*< System ID*/
uint8_t target_component; /*< Component ID*/
uint8_t mission_type; /*< Mission type.*/
} mavlink_mission_request_t;
#define MAVLINK_MSG_ID_MISSION_REQUEST_LEN 4
#define MAVLINK_MSG_ID_MISSION_REQUEST_LEN 5
#define MAVLINK_MSG_ID_MISSION_REQUEST_MIN_LEN 4
#define MAVLINK_MSG_ID_40_LEN 4
#define MAVLINK_MSG_ID_40_LEN 5
#define MAVLINK_MSG_ID_40_MIN_LEN 4
#define MAVLINK_MSG_ID_MISSION_REQUEST_CRC 230
@ -24,19 +25,21 @@ typedef struct __mavlink_mission_request_t {
#define MAVLINK_MESSAGE_INFO_MISSION_REQUEST { \
40, \
"MISSION_REQUEST", \
3, \
4, \
{ { "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) }, \
{ "seq", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_mission_request_t, seq) }, \
{ "mission_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_mission_request_t, mission_type) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_MISSION_REQUEST { \
"MISSION_REQUEST", \
3, \
4, \
{ { "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) }, \
{ "seq", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_mission_request_t, seq) }, \
{ "mission_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_mission_request_t, mission_type) }, \
} \
}
#endif
@ -50,16 +53,18 @@ typedef struct __mavlink_mission_request_t {
* @param target_system System ID
* @param target_component Component ID
* @param seq Sequence
* @param mission_type Mission type.
* @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)
uint8_t target_system, uint8_t target_component, uint16_t seq, uint8_t mission_type)
{
#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);
_mav_put_uint8_t(buf, 4, mission_type);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_REQUEST_LEN);
#else
@ -67,6 +72,7 @@ static inline uint16_t mavlink_msg_mission_request_pack(uint8_t system_id, uint8
packet.seq = seq;
packet.target_system = target_system;
packet.target_component = target_component;
packet.mission_type = mission_type;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_REQUEST_LEN);
#endif
@ -84,17 +90,19 @@ static inline uint16_t mavlink_msg_mission_request_pack(uint8_t system_id, uint8
* @param target_system System ID
* @param target_component Component ID
* @param seq Sequence
* @param mission_type Mission type.
* @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)
uint8_t target_system,uint8_t target_component,uint16_t seq,uint8_t mission_type)
{
#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);
_mav_put_uint8_t(buf, 4, mission_type);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_REQUEST_LEN);
#else
@ -102,6 +110,7 @@ static inline uint16_t mavlink_msg_mission_request_pack_chan(uint8_t system_id,
packet.seq = seq;
packet.target_system = target_system;
packet.target_component = target_component;
packet.mission_type = mission_type;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_REQUEST_LEN);
#endif
@ -120,7 +129,7 @@ static inline uint16_t mavlink_msg_mission_request_pack_chan(uint8_t system_id,
*/
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);
return mavlink_msg_mission_request_pack(system_id, component_id, msg, mission_request->target_system, mission_request->target_component, mission_request->seq, mission_request->mission_type);
}
/**
@ -134,7 +143,7 @@ static inline uint16_t mavlink_msg_mission_request_encode(uint8_t system_id, uin
*/
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);
return mavlink_msg_mission_request_pack_chan(system_id, component_id, chan, msg, mission_request->target_system, mission_request->target_component, mission_request->seq, mission_request->mission_type);
}
/**
@ -144,16 +153,18 @@ static inline uint16_t mavlink_msg_mission_request_encode_chan(uint8_t system_id
* @param target_system System ID
* @param target_component Component ID
* @param seq Sequence
* @param mission_type Mission type.
*/
#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)
static inline void mavlink_msg_mission_request_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t seq, uint8_t mission_type)
{
#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);
_mav_put_uint8_t(buf, 4, mission_type);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST, buf, MAVLINK_MSG_ID_MISSION_REQUEST_MIN_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_CRC);
#else
@ -161,6 +172,7 @@ static inline void mavlink_msg_mission_request_send(mavlink_channel_t chan, uint
packet.seq = seq;
packet.target_system = target_system;
packet.target_component = target_component;
packet.mission_type = mission_type;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST, (const char *)&packet, MAVLINK_MSG_ID_MISSION_REQUEST_MIN_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_CRC);
#endif
@ -174,7 +186,7 @@ static inline void mavlink_msg_mission_request_send(mavlink_channel_t chan, uint
static inline void mavlink_msg_mission_request_send_struct(mavlink_channel_t chan, const mavlink_mission_request_t* mission_request)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mavlink_msg_mission_request_send(chan, mission_request->target_system, mission_request->target_component, mission_request->seq);
mavlink_msg_mission_request_send(chan, mission_request->target_system, mission_request->target_component, mission_request->seq, mission_request->mission_type);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST, (const char *)mission_request, MAVLINK_MSG_ID_MISSION_REQUEST_MIN_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_CRC);
#endif
@ -188,13 +200,14 @@ static inline void mavlink_msg_mission_request_send_struct(mavlink_channel_t cha
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)
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, uint8_t mission_type)
{
#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);
_mav_put_uint8_t(buf, 4, mission_type);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST, buf, MAVLINK_MSG_ID_MISSION_REQUEST_MIN_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_CRC);
#else
@ -202,6 +215,7 @@ static inline void mavlink_msg_mission_request_send_buf(mavlink_message_t *msgbu
packet->seq = seq;
packet->target_system = target_system;
packet->target_component = target_component;
packet->mission_type = mission_type;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST, (const char *)packet, MAVLINK_MSG_ID_MISSION_REQUEST_MIN_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_CRC);
#endif
@ -243,6 +257,16 @@ static inline uint16_t mavlink_msg_mission_request_get_seq(const mavlink_message
return _MAV_RETURN_uint16_t(msg, 0);
}
/**
* @brief Get field mission_type from mission_request message
*
* @return Mission type.
*/
static inline uint8_t mavlink_msg_mission_request_get_mission_type(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 4);
}
/**
* @brief Decode a mission_request message into a struct
*
@ -255,6 +279,7 @@ static inline void mavlink_msg_mission_request_decode(const mavlink_message_t* m
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);
mission_request->mission_type = mavlink_msg_mission_request_get_mission_type(msg);
#else
uint8_t len = msg->len < MAVLINK_MSG_ID_MISSION_REQUEST_LEN? msg->len : MAVLINK_MSG_ID_MISSION_REQUEST_LEN;
memset(mission_request, 0, MAVLINK_MSG_ID_MISSION_REQUEST_LEN);

View file

@ -8,11 +8,12 @@ typedef struct __mavlink_mission_request_int_t {
uint16_t seq; /*< Sequence*/
uint8_t target_system; /*< System ID*/
uint8_t target_component; /*< Component ID*/
uint8_t mission_type; /*< Mission type.*/
} mavlink_mission_request_int_t;
#define MAVLINK_MSG_ID_MISSION_REQUEST_INT_LEN 4
#define MAVLINK_MSG_ID_MISSION_REQUEST_INT_LEN 5
#define MAVLINK_MSG_ID_MISSION_REQUEST_INT_MIN_LEN 4
#define MAVLINK_MSG_ID_51_LEN 4
#define MAVLINK_MSG_ID_51_LEN 5
#define MAVLINK_MSG_ID_51_MIN_LEN 4
#define MAVLINK_MSG_ID_MISSION_REQUEST_INT_CRC 196
@ -24,19 +25,21 @@ typedef struct __mavlink_mission_request_int_t {
#define MAVLINK_MESSAGE_INFO_MISSION_REQUEST_INT { \
51, \
"MISSION_REQUEST_INT", \
3, \
4, \
{ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_mission_request_int_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_mission_request_int_t, target_component) }, \
{ "seq", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_mission_request_int_t, seq) }, \
{ "mission_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_mission_request_int_t, mission_type) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_MISSION_REQUEST_INT { \
"MISSION_REQUEST_INT", \
3, \
4, \
{ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_mission_request_int_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_mission_request_int_t, target_component) }, \
{ "seq", NULL, MAVLINK_TYPE_UINT16_T, 0, 0, offsetof(mavlink_mission_request_int_t, seq) }, \
{ "mission_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_mission_request_int_t, mission_type) }, \
} \
}
#endif
@ -50,16 +53,18 @@ typedef struct __mavlink_mission_request_int_t {
* @param target_system System ID
* @param target_component Component ID
* @param seq Sequence
* @param mission_type Mission type.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_mission_request_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 target_system, uint8_t target_component, uint16_t seq, uint8_t mission_type)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_MISSION_REQUEST_INT_LEN];
_mav_put_uint16_t(buf, 0, seq);
_mav_put_uint8_t(buf, 2, target_system);
_mav_put_uint8_t(buf, 3, target_component);
_mav_put_uint8_t(buf, 4, mission_type);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_REQUEST_INT_LEN);
#else
@ -67,6 +72,7 @@ static inline uint16_t mavlink_msg_mission_request_int_pack(uint8_t system_id, u
packet.seq = seq;
packet.target_system = target_system;
packet.target_component = target_component;
packet.mission_type = mission_type;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_REQUEST_INT_LEN);
#endif
@ -84,17 +90,19 @@ static inline uint16_t mavlink_msg_mission_request_int_pack(uint8_t system_id, u
* @param target_system System ID
* @param target_component Component ID
* @param seq Sequence
* @param mission_type Mission type.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_mission_request_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 target_system,uint8_t target_component,uint16_t seq,uint8_t mission_type)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_MISSION_REQUEST_INT_LEN];
_mav_put_uint16_t(buf, 0, seq);
_mav_put_uint8_t(buf, 2, target_system);
_mav_put_uint8_t(buf, 3, target_component);
_mav_put_uint8_t(buf, 4, mission_type);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_REQUEST_INT_LEN);
#else
@ -102,6 +110,7 @@ static inline uint16_t mavlink_msg_mission_request_int_pack_chan(uint8_t system_
packet.seq = seq;
packet.target_system = target_system;
packet.target_component = target_component;
packet.mission_type = mission_type;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_REQUEST_INT_LEN);
#endif
@ -120,7 +129,7 @@ static inline uint16_t mavlink_msg_mission_request_int_pack_chan(uint8_t system_
*/
static inline uint16_t mavlink_msg_mission_request_int_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mission_request_int_t* mission_request_int)
{
return mavlink_msg_mission_request_int_pack(system_id, component_id, msg, mission_request_int->target_system, mission_request_int->target_component, mission_request_int->seq);
return mavlink_msg_mission_request_int_pack(system_id, component_id, msg, mission_request_int->target_system, mission_request_int->target_component, mission_request_int->seq, mission_request_int->mission_type);
}
/**
@ -134,7 +143,7 @@ static inline uint16_t mavlink_msg_mission_request_int_encode(uint8_t system_id,
*/
static inline uint16_t mavlink_msg_mission_request_int_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_mission_request_int_t* mission_request_int)
{
return mavlink_msg_mission_request_int_pack_chan(system_id, component_id, chan, msg, mission_request_int->target_system, mission_request_int->target_component, mission_request_int->seq);
return mavlink_msg_mission_request_int_pack_chan(system_id, component_id, chan, msg, mission_request_int->target_system, mission_request_int->target_component, mission_request_int->seq, mission_request_int->mission_type);
}
/**
@ -144,16 +153,18 @@ static inline uint16_t mavlink_msg_mission_request_int_encode_chan(uint8_t syste
* @param target_system System ID
* @param target_component Component ID
* @param seq Sequence
* @param mission_type Mission type.
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_mission_request_int_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t seq)
static inline void mavlink_msg_mission_request_int_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t seq, uint8_t mission_type)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_MISSION_REQUEST_INT_LEN];
_mav_put_uint16_t(buf, 0, seq);
_mav_put_uint8_t(buf, 2, target_system);
_mav_put_uint8_t(buf, 3, target_component);
_mav_put_uint8_t(buf, 4, mission_type);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_INT, buf, MAVLINK_MSG_ID_MISSION_REQUEST_INT_MIN_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_INT_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_INT_CRC);
#else
@ -161,6 +172,7 @@ static inline void mavlink_msg_mission_request_int_send(mavlink_channel_t chan,
packet.seq = seq;
packet.target_system = target_system;
packet.target_component = target_component;
packet.mission_type = mission_type;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_INT, (const char *)&packet, MAVLINK_MSG_ID_MISSION_REQUEST_INT_MIN_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_INT_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_INT_CRC);
#endif
@ -174,7 +186,7 @@ static inline void mavlink_msg_mission_request_int_send(mavlink_channel_t chan,
static inline void mavlink_msg_mission_request_int_send_struct(mavlink_channel_t chan, const mavlink_mission_request_int_t* mission_request_int)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mavlink_msg_mission_request_int_send(chan, mission_request_int->target_system, mission_request_int->target_component, mission_request_int->seq);
mavlink_msg_mission_request_int_send(chan, mission_request_int->target_system, mission_request_int->target_component, mission_request_int->seq, mission_request_int->mission_type);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_INT, (const char *)mission_request_int, MAVLINK_MSG_ID_MISSION_REQUEST_INT_MIN_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_INT_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_INT_CRC);
#endif
@ -188,13 +200,14 @@ static inline void mavlink_msg_mission_request_int_send_struct(mavlink_channel_t
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_int_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t seq)
static inline void mavlink_msg_mission_request_int_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint16_t seq, uint8_t mission_type)
{
#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);
_mav_put_uint8_t(buf, 4, mission_type);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_INT, buf, MAVLINK_MSG_ID_MISSION_REQUEST_INT_MIN_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_INT_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_INT_CRC);
#else
@ -202,6 +215,7 @@ static inline void mavlink_msg_mission_request_int_send_buf(mavlink_message_t *m
packet->seq = seq;
packet->target_system = target_system;
packet->target_component = target_component;
packet->mission_type = mission_type;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_INT, (const char *)packet, MAVLINK_MSG_ID_MISSION_REQUEST_INT_MIN_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_INT_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_INT_CRC);
#endif
@ -243,6 +257,16 @@ static inline uint16_t mavlink_msg_mission_request_int_get_seq(const mavlink_mes
return _MAV_RETURN_uint16_t(msg, 0);
}
/**
* @brief Get field mission_type from mission_request_int message
*
* @return Mission type.
*/
static inline uint8_t mavlink_msg_mission_request_int_get_mission_type(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 4);
}
/**
* @brief Decode a mission_request_int message into a struct
*
@ -255,6 +279,7 @@ static inline void mavlink_msg_mission_request_int_decode(const mavlink_message_
mission_request_int->seq = mavlink_msg_mission_request_int_get_seq(msg);
mission_request_int->target_system = mavlink_msg_mission_request_int_get_target_system(msg);
mission_request_int->target_component = mavlink_msg_mission_request_int_get_target_component(msg);
mission_request_int->mission_type = mavlink_msg_mission_request_int_get_mission_type(msg);
#else
uint8_t len = msg->len < MAVLINK_MSG_ID_MISSION_REQUEST_INT_LEN? msg->len : MAVLINK_MSG_ID_MISSION_REQUEST_INT_LEN;
memset(mission_request_int, 0, MAVLINK_MSG_ID_MISSION_REQUEST_INT_LEN);

View file

@ -7,11 +7,12 @@
typedef struct __mavlink_mission_request_list_t {
uint8_t target_system; /*< System ID*/
uint8_t target_component; /*< Component ID*/
uint8_t mission_type; /*< Mission type.*/
} mavlink_mission_request_list_t;
#define MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN 2
#define MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN 3
#define MAVLINK_MSG_ID_MISSION_REQUEST_LIST_MIN_LEN 2
#define MAVLINK_MSG_ID_43_LEN 2
#define MAVLINK_MSG_ID_43_LEN 3
#define MAVLINK_MSG_ID_43_MIN_LEN 2
#define MAVLINK_MSG_ID_MISSION_REQUEST_LIST_CRC 132
@ -23,17 +24,19 @@ typedef struct __mavlink_mission_request_list_t {
#define MAVLINK_MESSAGE_INFO_MISSION_REQUEST_LIST { \
43, \
"MISSION_REQUEST_LIST", \
2, \
3, \
{ { "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) }, \
{ "mission_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_mission_request_list_t, mission_type) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_MISSION_REQUEST_LIST { \
"MISSION_REQUEST_LIST", \
2, \
3, \
{ { "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) }, \
{ "mission_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_mission_request_list_t, mission_type) }, \
} \
}
#endif
@ -46,21 +49,24 @@ typedef struct __mavlink_mission_request_list_t {
*
* @param target_system System ID
* @param target_component Component ID
* @param mission_type Mission type.
* @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)
uint8_t target_system, uint8_t target_component, uint8_t mission_type)
{
#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);
_mav_put_uint8_t(buf, 2, mission_type);
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;
packet.mission_type = mission_type;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN);
#endif
@ -77,22 +83,25 @@ static inline uint16_t mavlink_msg_mission_request_list_pack(uint8_t system_id,
* @param msg The MAVLink message to compress the data into
* @param target_system System ID
* @param target_component Component ID
* @param mission_type Mission type.
* @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)
uint8_t target_system,uint8_t target_component,uint8_t mission_type)
{
#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);
_mav_put_uint8_t(buf, 2, mission_type);
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;
packet.mission_type = mission_type;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN);
#endif
@ -111,7 +120,7 @@ static inline uint16_t mavlink_msg_mission_request_list_pack_chan(uint8_t system
*/
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);
return mavlink_msg_mission_request_list_pack(system_id, component_id, msg, mission_request_list->target_system, mission_request_list->target_component, mission_request_list->mission_type);
}
/**
@ -125,7 +134,7 @@ static inline uint16_t mavlink_msg_mission_request_list_encode(uint8_t system_id
*/
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);
return mavlink_msg_mission_request_list_pack_chan(system_id, component_id, chan, msg, mission_request_list->target_system, mission_request_list->target_component, mission_request_list->mission_type);
}
/**
@ -134,21 +143,24 @@ static inline uint16_t mavlink_msg_mission_request_list_encode_chan(uint8_t syst
*
* @param target_system System ID
* @param target_component Component ID
* @param mission_type Mission type.
*/
#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)
static inline void mavlink_msg_mission_request_list_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t mission_type)
{
#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);
_mav_put_uint8_t(buf, 2, mission_type);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_LIST, buf, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_MIN_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_CRC);
#else
mavlink_mission_request_list_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
packet.mission_type = mission_type;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_LIST, (const char *)&packet, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_MIN_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_CRC);
#endif
@ -162,7 +174,7 @@ static inline void mavlink_msg_mission_request_list_send(mavlink_channel_t chan,
static inline void mavlink_msg_mission_request_list_send_struct(mavlink_channel_t chan, const mavlink_mission_request_list_t* mission_request_list)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mavlink_msg_mission_request_list_send(chan, mission_request_list->target_system, mission_request_list->target_component);
mavlink_msg_mission_request_list_send(chan, mission_request_list->target_system, mission_request_list->target_component, mission_request_list->mission_type);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_LIST, (const char *)mission_request_list, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_MIN_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_CRC);
#endif
@ -176,18 +188,20 @@ static inline void mavlink_msg_mission_request_list_send_struct(mavlink_channel_
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)
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, uint8_t mission_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, mission_type);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_LIST, buf, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_MIN_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_CRC);
#else
mavlink_mission_request_list_t *packet = (mavlink_mission_request_list_t *)msgbuf;
packet->target_system = target_system;
packet->target_component = target_component;
packet->mission_type = mission_type;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_LIST, (const char *)packet, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_MIN_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_CRC);
#endif
@ -219,6 +233,16 @@ static inline uint8_t mavlink_msg_mission_request_list_get_target_component(cons
return _MAV_RETURN_uint8_t(msg, 1);
}
/**
* @brief Get field mission_type from mission_request_list message
*
* @return Mission type.
*/
static inline uint8_t mavlink_msg_mission_request_list_get_mission_type(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 2);
}
/**
* @brief Decode a mission_request_list message into a struct
*
@ -230,6 +254,7 @@ static inline void mavlink_msg_mission_request_list_decode(const mavlink_message
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
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);
mission_request_list->mission_type = mavlink_msg_mission_request_list_get_mission_type(msg);
#else
uint8_t len = msg->len < MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN? msg->len : MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN;
memset(mission_request_list, 0, MAVLINK_MSG_ID_MISSION_REQUEST_LIST_LEN);

View file

@ -9,11 +9,12 @@ typedef struct __mavlink_mission_request_partial_list_t {
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*/
uint8_t mission_type; /*< Mission type.*/
} mavlink_mission_request_partial_list_t;
#define MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN 6
#define MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN 7
#define MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_MIN_LEN 6
#define MAVLINK_MSG_ID_37_LEN 6
#define MAVLINK_MSG_ID_37_LEN 7
#define MAVLINK_MSG_ID_37_MIN_LEN 6
#define MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_CRC 212
@ -25,21 +26,23 @@ typedef struct __mavlink_mission_request_partial_list_t {
#define MAVLINK_MESSAGE_INFO_MISSION_REQUEST_PARTIAL_LIST { \
37, \
"MISSION_REQUEST_PARTIAL_LIST", \
4, \
5, \
{ { "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) }, \
{ "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) }, \
{ "mission_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_mission_request_partial_list_t, mission_type) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_MISSION_REQUEST_PARTIAL_LIST { \
"MISSION_REQUEST_PARTIAL_LIST", \
4, \
5, \
{ { "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) }, \
{ "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) }, \
{ "mission_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_mission_request_partial_list_t, mission_type) }, \
} \
}
#endif
@ -54,10 +57,11 @@ typedef struct __mavlink_mission_request_partial_list_t {
* @param target_component Component ID
* @param start_index Start index
* @param end_index End index, -1 by default (-1: send list to end). Else a valid index of the list
* @param mission_type Mission type.
* @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)
uint8_t target_system, uint8_t target_component, int16_t start_index, int16_t end_index, uint8_t mission_type)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN];
@ -65,6 +69,7 @@ static inline uint16_t mavlink_msg_mission_request_partial_list_pack(uint8_t sys
_mav_put_int16_t(buf, 2, end_index);
_mav_put_uint8_t(buf, 4, target_system);
_mav_put_uint8_t(buf, 5, target_component);
_mav_put_uint8_t(buf, 6, mission_type);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN);
#else
@ -73,6 +78,7 @@ static inline uint16_t mavlink_msg_mission_request_partial_list_pack(uint8_t sys
packet.end_index = end_index;
packet.target_system = target_system;
packet.target_component = target_component;
packet.mission_type = mission_type;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN);
#endif
@ -91,11 +97,12 @@ static inline uint16_t mavlink_msg_mission_request_partial_list_pack(uint8_t sys
* @param target_component Component ID
* @param start_index Start index
* @param end_index End index, -1 by default (-1: send list to end). Else a valid index of the list
* @param mission_type Mission type.
* @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)
uint8_t target_system,uint8_t target_component,int16_t start_index,int16_t end_index,uint8_t mission_type)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN];
@ -103,6 +110,7 @@ static inline uint16_t mavlink_msg_mission_request_partial_list_pack_chan(uint8_
_mav_put_int16_t(buf, 2, end_index);
_mav_put_uint8_t(buf, 4, target_system);
_mav_put_uint8_t(buf, 5, target_component);
_mav_put_uint8_t(buf, 6, mission_type);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN);
#else
@ -111,6 +119,7 @@ static inline uint16_t mavlink_msg_mission_request_partial_list_pack_chan(uint8_
packet.end_index = end_index;
packet.target_system = target_system;
packet.target_component = target_component;
packet.mission_type = mission_type;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN);
#endif
@ -129,7 +138,7 @@ static inline uint16_t mavlink_msg_mission_request_partial_list_pack_chan(uint8_
*/
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);
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, mission_request_partial_list->mission_type);
}
/**
@ -143,7 +152,7 @@ static inline uint16_t mavlink_msg_mission_request_partial_list_encode(uint8_t s
*/
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);
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, mission_request_partial_list->mission_type);
}
/**
@ -154,10 +163,11 @@ static inline uint16_t mavlink_msg_mission_request_partial_list_encode_chan(uint
* @param target_component Component ID
* @param start_index Start index
* @param end_index End index, -1 by default (-1: send list to end). Else a valid index of the list
* @param mission_type Mission type.
*/
#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)
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, uint8_t mission_type)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN];
@ -165,6 +175,7 @@ static inline void mavlink_msg_mission_request_partial_list_send(mavlink_channel
_mav_put_int16_t(buf, 2, end_index);
_mav_put_uint8_t(buf, 4, target_system);
_mav_put_uint8_t(buf, 5, target_component);
_mav_put_uint8_t(buf, 6, mission_type);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST, buf, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_MIN_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_CRC);
#else
@ -173,6 +184,7 @@ static inline void mavlink_msg_mission_request_partial_list_send(mavlink_channel
packet.end_index = end_index;
packet.target_system = target_system;
packet.target_component = target_component;
packet.mission_type = mission_type;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST, (const char *)&packet, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_MIN_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_CRC);
#endif
@ -186,7 +198,7 @@ static inline void mavlink_msg_mission_request_partial_list_send(mavlink_channel
static inline void mavlink_msg_mission_request_partial_list_send_struct(mavlink_channel_t chan, const mavlink_mission_request_partial_list_t* mission_request_partial_list)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mavlink_msg_mission_request_partial_list_send(chan, mission_request_partial_list->target_system, mission_request_partial_list->target_component, mission_request_partial_list->start_index, mission_request_partial_list->end_index);
mavlink_msg_mission_request_partial_list_send(chan, mission_request_partial_list->target_system, mission_request_partial_list->target_component, mission_request_partial_list->start_index, mission_request_partial_list->end_index, mission_request_partial_list->mission_type);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST, (const char *)mission_request_partial_list, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_MIN_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_CRC);
#endif
@ -200,7 +212,7 @@ static inline void mavlink_msg_mission_request_partial_list_send_struct(mavlink_
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)
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, uint8_t mission_type)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
@ -208,6 +220,7 @@ static inline void mavlink_msg_mission_request_partial_list_send_buf(mavlink_mes
_mav_put_int16_t(buf, 2, end_index);
_mav_put_uint8_t(buf, 4, target_system);
_mav_put_uint8_t(buf, 5, target_component);
_mav_put_uint8_t(buf, 6, mission_type);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST, buf, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_MIN_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_CRC);
#else
@ -216,6 +229,7 @@ static inline void mavlink_msg_mission_request_partial_list_send_buf(mavlink_mes
packet->end_index = end_index;
packet->target_system = target_system;
packet->target_component = target_component;
packet->mission_type = mission_type;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST, (const char *)packet, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_MIN_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_CRC);
#endif
@ -267,6 +281,16 @@ static inline int16_t mavlink_msg_mission_request_partial_list_get_end_index(con
return _MAV_RETURN_int16_t(msg, 2);
}
/**
* @brief Get field mission_type from mission_request_partial_list message
*
* @return Mission type.
*/
static inline uint8_t mavlink_msg_mission_request_partial_list_get_mission_type(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 6);
}
/**
* @brief Decode a mission_request_partial_list message into a struct
*
@ -280,6 +304,7 @@ static inline void mavlink_msg_mission_request_partial_list_decode(const mavlink
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);
mission_request_partial_list->mission_type = mavlink_msg_mission_request_partial_list_get_mission_type(msg);
#else
uint8_t len = msg->len < MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN? msg->len : MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN;
memset(mission_request_partial_list, 0, MAVLINK_MSG_ID_MISSION_REQUEST_PARTIAL_LIST_LEN);

View file

@ -9,11 +9,12 @@ typedef struct __mavlink_mission_write_partial_list_t {
int16_t end_index; /*< End index, equal or greater than start index.*/
uint8_t target_system; /*< System ID*/
uint8_t target_component; /*< Component ID*/
uint8_t mission_type; /*< Mission type.*/
} mavlink_mission_write_partial_list_t;
#define MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN 6
#define MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN 7
#define MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_MIN_LEN 6
#define MAVLINK_MSG_ID_38_LEN 6
#define MAVLINK_MSG_ID_38_LEN 7
#define MAVLINK_MSG_ID_38_MIN_LEN 6
#define MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_CRC 9
@ -25,21 +26,23 @@ typedef struct __mavlink_mission_write_partial_list_t {
#define MAVLINK_MESSAGE_INFO_MISSION_WRITE_PARTIAL_LIST { \
38, \
"MISSION_WRITE_PARTIAL_LIST", \
4, \
5, \
{ { "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) }, \
{ "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) }, \
{ "mission_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_mission_write_partial_list_t, mission_type) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_MISSION_WRITE_PARTIAL_LIST { \
"MISSION_WRITE_PARTIAL_LIST", \
4, \
5, \
{ { "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) }, \
{ "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) }, \
{ "mission_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 6, offsetof(mavlink_mission_write_partial_list_t, mission_type) }, \
} \
}
#endif
@ -54,10 +57,11 @@ typedef struct __mavlink_mission_write_partial_list_t {
* @param target_component Component ID
* @param start_index Start index. Must be smaller / equal to the largest index of the current onboard list.
* @param end_index End index, equal or greater than start index.
* @param mission_type Mission type.
* @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)
uint8_t target_system, uint8_t target_component, int16_t start_index, int16_t end_index, uint8_t mission_type)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN];
@ -65,6 +69,7 @@ static inline uint16_t mavlink_msg_mission_write_partial_list_pack(uint8_t syste
_mav_put_int16_t(buf, 2, end_index);
_mav_put_uint8_t(buf, 4, target_system);
_mav_put_uint8_t(buf, 5, target_component);
_mav_put_uint8_t(buf, 6, mission_type);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN);
#else
@ -73,6 +78,7 @@ static inline uint16_t mavlink_msg_mission_write_partial_list_pack(uint8_t syste
packet.end_index = end_index;
packet.target_system = target_system;
packet.target_component = target_component;
packet.mission_type = mission_type;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN);
#endif
@ -91,11 +97,12 @@ static inline uint16_t mavlink_msg_mission_write_partial_list_pack(uint8_t syste
* @param target_component Component ID
* @param start_index Start index. Must be smaller / equal to the largest index of the current onboard list.
* @param end_index End index, equal or greater than start index.
* @param mission_type Mission type.
* @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)
uint8_t target_system,uint8_t target_component,int16_t start_index,int16_t end_index,uint8_t mission_type)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN];
@ -103,6 +110,7 @@ static inline uint16_t mavlink_msg_mission_write_partial_list_pack_chan(uint8_t
_mav_put_int16_t(buf, 2, end_index);
_mav_put_uint8_t(buf, 4, target_system);
_mav_put_uint8_t(buf, 5, target_component);
_mav_put_uint8_t(buf, 6, mission_type);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN);
#else
@ -111,6 +119,7 @@ static inline uint16_t mavlink_msg_mission_write_partial_list_pack_chan(uint8_t
packet.end_index = end_index;
packet.target_system = target_system;
packet.target_component = target_component;
packet.mission_type = mission_type;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN);
#endif
@ -129,7 +138,7 @@ static inline uint16_t mavlink_msg_mission_write_partial_list_pack_chan(uint8_t
*/
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);
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, mission_write_partial_list->mission_type);
}
/**
@ -143,7 +152,7 @@ static inline uint16_t mavlink_msg_mission_write_partial_list_encode(uint8_t sys
*/
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);
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, mission_write_partial_list->mission_type);
}
/**
@ -154,10 +163,11 @@ static inline uint16_t mavlink_msg_mission_write_partial_list_encode_chan(uint8_
* @param target_component Component ID
* @param start_index Start index. Must be smaller / equal to the largest index of the current onboard list.
* @param end_index End index, equal or greater than start index.
* @param mission_type Mission type.
*/
#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)
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, uint8_t mission_type)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN];
@ -165,6 +175,7 @@ static inline void mavlink_msg_mission_write_partial_list_send(mavlink_channel_t
_mav_put_int16_t(buf, 2, end_index);
_mav_put_uint8_t(buf, 4, target_system);
_mav_put_uint8_t(buf, 5, target_component);
_mav_put_uint8_t(buf, 6, mission_type);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST, buf, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_MIN_LEN, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_CRC);
#else
@ -173,6 +184,7 @@ static inline void mavlink_msg_mission_write_partial_list_send(mavlink_channel_t
packet.end_index = end_index;
packet.target_system = target_system;
packet.target_component = target_component;
packet.mission_type = mission_type;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST, (const char *)&packet, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_MIN_LEN, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_CRC);
#endif
@ -186,7 +198,7 @@ static inline void mavlink_msg_mission_write_partial_list_send(mavlink_channel_t
static inline void mavlink_msg_mission_write_partial_list_send_struct(mavlink_channel_t chan, const mavlink_mission_write_partial_list_t* mission_write_partial_list)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mavlink_msg_mission_write_partial_list_send(chan, mission_write_partial_list->target_system, mission_write_partial_list->target_component, mission_write_partial_list->start_index, mission_write_partial_list->end_index);
mavlink_msg_mission_write_partial_list_send(chan, mission_write_partial_list->target_system, mission_write_partial_list->target_component, mission_write_partial_list->start_index, mission_write_partial_list->end_index, mission_write_partial_list->mission_type);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST, (const char *)mission_write_partial_list, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_MIN_LEN, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_CRC);
#endif
@ -200,7 +212,7 @@ static inline void mavlink_msg_mission_write_partial_list_send_struct(mavlink_ch
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)
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, uint8_t mission_type)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
@ -208,6 +220,7 @@ static inline void mavlink_msg_mission_write_partial_list_send_buf(mavlink_messa
_mav_put_int16_t(buf, 2, end_index);
_mav_put_uint8_t(buf, 4, target_system);
_mav_put_uint8_t(buf, 5, target_component);
_mav_put_uint8_t(buf, 6, mission_type);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST, buf, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_MIN_LEN, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_CRC);
#else
@ -216,6 +229,7 @@ static inline void mavlink_msg_mission_write_partial_list_send_buf(mavlink_messa
packet->end_index = end_index;
packet->target_system = target_system;
packet->target_component = target_component;
packet->mission_type = mission_type;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST, (const char *)packet, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_MIN_LEN, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_CRC);
#endif
@ -267,6 +281,16 @@ static inline int16_t mavlink_msg_mission_write_partial_list_get_end_index(const
return _MAV_RETURN_int16_t(msg, 2);
}
/**
* @brief Get field mission_type from mission_write_partial_list message
*
* @return Mission type.
*/
static inline uint8_t mavlink_msg_mission_write_partial_list_get_mission_type(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 6);
}
/**
* @brief Decode a mission_write_partial_list message into a struct
*
@ -280,6 +304,7 @@ static inline void mavlink_msg_mission_write_partial_list_decode(const mavlink_m
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);
mission_write_partial_list->mission_type = mavlink_msg_mission_write_partial_list_get_mission_type(msg);
#else
uint8_t len = msg->len < MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN? msg->len : MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN;
memset(mission_write_partial_list, 0, MAVLINK_MSG_ID_MISSION_WRITE_PARTIAL_LIST_LEN);

View file

@ -0,0 +1,313 @@
#pragma once
// MESSAGE MOUNT_ORIENTATION PACKING
#define MAVLINK_MSG_ID_MOUNT_ORIENTATION 265
typedef struct __mavlink_mount_orientation_t {
uint32_t time_boot_ms; /*< [ms] Timestamp (time since system boot).*/
float roll; /*< [deg] Roll in global frame (set to NaN for invalid).*/
float pitch; /*< [deg] Pitch in global frame (set to NaN for invalid).*/
float yaw; /*< [deg] Yaw relative to vehicle (set to NaN for invalid).*/
float yaw_absolute; /*< [deg] Yaw in absolute frame relative to Earth's North, north is 0 (set to NaN for invalid).*/
} mavlink_mount_orientation_t;
#define MAVLINK_MSG_ID_MOUNT_ORIENTATION_LEN 20
#define MAVLINK_MSG_ID_MOUNT_ORIENTATION_MIN_LEN 16
#define MAVLINK_MSG_ID_265_LEN 20
#define MAVLINK_MSG_ID_265_MIN_LEN 16
#define MAVLINK_MSG_ID_MOUNT_ORIENTATION_CRC 26
#define MAVLINK_MSG_ID_265_CRC 26
#if MAVLINK_COMMAND_24BIT
#define MAVLINK_MESSAGE_INFO_MOUNT_ORIENTATION { \
265, \
"MOUNT_ORIENTATION", \
5, \
{ { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_mount_orientation_t, time_boot_ms) }, \
{ "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_mount_orientation_t, roll) }, \
{ "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_mount_orientation_t, pitch) }, \
{ "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_mount_orientation_t, yaw) }, \
{ "yaw_absolute", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_mount_orientation_t, yaw_absolute) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_MOUNT_ORIENTATION { \
"MOUNT_ORIENTATION", \
5, \
{ { "time_boot_ms", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_mount_orientation_t, time_boot_ms) }, \
{ "roll", NULL, MAVLINK_TYPE_FLOAT, 0, 4, offsetof(mavlink_mount_orientation_t, roll) }, \
{ "pitch", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_mount_orientation_t, pitch) }, \
{ "yaw", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_mount_orientation_t, yaw) }, \
{ "yaw_absolute", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_mount_orientation_t, yaw_absolute) }, \
} \
}
#endif
/**
* @brief Pack a mount_orientation message
* @param system_id ID of this 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 [ms] Timestamp (time since system boot).
* @param roll [deg] Roll in global frame (set to NaN for invalid).
* @param pitch [deg] Pitch in global frame (set to NaN for invalid).
* @param yaw [deg] Yaw relative to vehicle (set to NaN for invalid).
* @param yaw_absolute [deg] Yaw in absolute frame relative to Earth's North, north is 0 (set to NaN for invalid).
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_mount_orientation_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 yaw_absolute)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_MOUNT_ORIENTATION_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, yaw_absolute);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MOUNT_ORIENTATION_LEN);
#else
mavlink_mount_orientation_t packet;
packet.time_boot_ms = time_boot_ms;
packet.roll = roll;
packet.pitch = pitch;
packet.yaw = yaw;
packet.yaw_absolute = yaw_absolute;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MOUNT_ORIENTATION_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_MOUNT_ORIENTATION;
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_MOUNT_ORIENTATION_MIN_LEN, MAVLINK_MSG_ID_MOUNT_ORIENTATION_LEN, MAVLINK_MSG_ID_MOUNT_ORIENTATION_CRC);
}
/**
* @brief Pack a mount_orientation message on a channel
* @param system_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 [ms] Timestamp (time since system boot).
* @param roll [deg] Roll in global frame (set to NaN for invalid).
* @param pitch [deg] Pitch in global frame (set to NaN for invalid).
* @param yaw [deg] Yaw relative to vehicle (set to NaN for invalid).
* @param yaw_absolute [deg] Yaw in absolute frame relative to Earth's North, north is 0 (set to NaN for invalid).
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_mount_orientation_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 yaw_absolute)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_MOUNT_ORIENTATION_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, yaw_absolute);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_MOUNT_ORIENTATION_LEN);
#else
mavlink_mount_orientation_t packet;
packet.time_boot_ms = time_boot_ms;
packet.roll = roll;
packet.pitch = pitch;
packet.yaw = yaw;
packet.yaw_absolute = yaw_absolute;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_MOUNT_ORIENTATION_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_MOUNT_ORIENTATION;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_MOUNT_ORIENTATION_MIN_LEN, MAVLINK_MSG_ID_MOUNT_ORIENTATION_LEN, MAVLINK_MSG_ID_MOUNT_ORIENTATION_CRC);
}
/**
* @brief Encode a mount_orientation 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 mount_orientation C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_mount_orientation_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_mount_orientation_t* mount_orientation)
{
return mavlink_msg_mount_orientation_pack(system_id, component_id, msg, mount_orientation->time_boot_ms, mount_orientation->roll, mount_orientation->pitch, mount_orientation->yaw, mount_orientation->yaw_absolute);
}
/**
* @brief Encode a mount_orientation 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 mount_orientation C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_mount_orientation_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_mount_orientation_t* mount_orientation)
{
return mavlink_msg_mount_orientation_pack_chan(system_id, component_id, chan, msg, mount_orientation->time_boot_ms, mount_orientation->roll, mount_orientation->pitch, mount_orientation->yaw, mount_orientation->yaw_absolute);
}
/**
* @brief Send a mount_orientation message
* @param chan MAVLink channel to send the message
*
* @param time_boot_ms [ms] Timestamp (time since system boot).
* @param roll [deg] Roll in global frame (set to NaN for invalid).
* @param pitch [deg] Pitch in global frame (set to NaN for invalid).
* @param yaw [deg] Yaw relative to vehicle (set to NaN for invalid).
* @param yaw_absolute [deg] Yaw in absolute frame relative to Earth's North, north is 0 (set to NaN for invalid).
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_mount_orientation_send(mavlink_channel_t chan, uint32_t time_boot_ms, float roll, float pitch, float yaw, float yaw_absolute)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_MOUNT_ORIENTATION_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, yaw_absolute);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MOUNT_ORIENTATION, buf, MAVLINK_MSG_ID_MOUNT_ORIENTATION_MIN_LEN, MAVLINK_MSG_ID_MOUNT_ORIENTATION_LEN, MAVLINK_MSG_ID_MOUNT_ORIENTATION_CRC);
#else
mavlink_mount_orientation_t packet;
packet.time_boot_ms = time_boot_ms;
packet.roll = roll;
packet.pitch = pitch;
packet.yaw = yaw;
packet.yaw_absolute = yaw_absolute;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MOUNT_ORIENTATION, (const char *)&packet, MAVLINK_MSG_ID_MOUNT_ORIENTATION_MIN_LEN, MAVLINK_MSG_ID_MOUNT_ORIENTATION_LEN, MAVLINK_MSG_ID_MOUNT_ORIENTATION_CRC);
#endif
}
/**
* @brief Send a mount_orientation message
* @param chan MAVLink channel to send the message
* @param struct The MAVLink struct to serialize
*/
static inline void mavlink_msg_mount_orientation_send_struct(mavlink_channel_t chan, const mavlink_mount_orientation_t* mount_orientation)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mavlink_msg_mount_orientation_send(chan, mount_orientation->time_boot_ms, mount_orientation->roll, mount_orientation->pitch, mount_orientation->yaw, mount_orientation->yaw_absolute);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MOUNT_ORIENTATION, (const char *)mount_orientation, MAVLINK_MSG_ID_MOUNT_ORIENTATION_MIN_LEN, MAVLINK_MSG_ID_MOUNT_ORIENTATION_LEN, MAVLINK_MSG_ID_MOUNT_ORIENTATION_CRC);
#endif
}
#if MAVLINK_MSG_ID_MOUNT_ORIENTATION_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_mount_orientation_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t time_boot_ms, float roll, float pitch, float yaw, float yaw_absolute)
{
#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, yaw_absolute);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MOUNT_ORIENTATION, buf, MAVLINK_MSG_ID_MOUNT_ORIENTATION_MIN_LEN, MAVLINK_MSG_ID_MOUNT_ORIENTATION_LEN, MAVLINK_MSG_ID_MOUNT_ORIENTATION_CRC);
#else
mavlink_mount_orientation_t *packet = (mavlink_mount_orientation_t *)msgbuf;
packet->time_boot_ms = time_boot_ms;
packet->roll = roll;
packet->pitch = pitch;
packet->yaw = yaw;
packet->yaw_absolute = yaw_absolute;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_MOUNT_ORIENTATION, (const char *)packet, MAVLINK_MSG_ID_MOUNT_ORIENTATION_MIN_LEN, MAVLINK_MSG_ID_MOUNT_ORIENTATION_LEN, MAVLINK_MSG_ID_MOUNT_ORIENTATION_CRC);
#endif
}
#endif
#endif
// MESSAGE MOUNT_ORIENTATION UNPACKING
/**
* @brief Get field time_boot_ms from mount_orientation message
*
* @return [ms] Timestamp (time since system boot).
*/
static inline uint32_t mavlink_msg_mount_orientation_get_time_boot_ms(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint32_t(msg, 0);
}
/**
* @brief Get field roll from mount_orientation message
*
* @return [deg] Roll in global frame (set to NaN for invalid).
*/
static inline float mavlink_msg_mount_orientation_get_roll(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 4);
}
/**
* @brief Get field pitch from mount_orientation message
*
* @return [deg] Pitch in global frame (set to NaN for invalid).
*/
static inline float mavlink_msg_mount_orientation_get_pitch(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 8);
}
/**
* @brief Get field yaw from mount_orientation message
*
* @return [deg] Yaw relative to vehicle (set to NaN for invalid).
*/
static inline float mavlink_msg_mount_orientation_get_yaw(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 12);
}
/**
* @brief Get field yaw_absolute from mount_orientation message
*
* @return [deg] Yaw in absolute frame relative to Earth's North, north is 0 (set to NaN for invalid).
*/
static inline float mavlink_msg_mount_orientation_get_yaw_absolute(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 16);
}
/**
* @brief Decode a mount_orientation message into a struct
*
* @param msg The message to decode
* @param mount_orientation C-struct to decode the message contents into
*/
static inline void mavlink_msg_mount_orientation_decode(const mavlink_message_t* msg, mavlink_mount_orientation_t* mount_orientation)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mount_orientation->time_boot_ms = mavlink_msg_mount_orientation_get_time_boot_ms(msg);
mount_orientation->roll = mavlink_msg_mount_orientation_get_roll(msg);
mount_orientation->pitch = mavlink_msg_mount_orientation_get_pitch(msg);
mount_orientation->yaw = mavlink_msg_mount_orientation_get_yaw(msg);
mount_orientation->yaw_absolute = mavlink_msg_mount_orientation_get_yaw_absolute(msg);
#else
uint8_t len = msg->len < MAVLINK_MSG_ID_MOUNT_ORIENTATION_LEN? msg->len : MAVLINK_MSG_ID_MOUNT_ORIENTATION_LEN;
memset(mount_orientation, 0, MAVLINK_MSG_ID_MOUNT_ORIENTATION_LEN);
memcpy(mount_orientation, _MAV_PAYLOAD(msg), len);
#endif
}

View file

@ -0,0 +1,405 @@
#pragma once
// MESSAGE OBSTACLE_DISTANCE PACKING
#define MAVLINK_MSG_ID_OBSTACLE_DISTANCE 330
MAVPACKED(
typedef struct __mavlink_obstacle_distance_t {
uint64_t time_usec; /*< [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.*/
uint16_t distances[72]; /*< [cm] Distance of obstacles around the vehicle with index 0 corresponding to north + angle_offset, unless otherwise specified in the frame. A value of 0 is valid and means that the obstacle is practically touching the sensor. A value of max_distance +1 means no obstacle is present. A value of UINT16_MAX for unknown/not used. In a array element, one unit corresponds to 1cm.*/
uint16_t min_distance; /*< [cm] Minimum distance the sensor can measure.*/
uint16_t max_distance; /*< [cm] Maximum distance the sensor can measure.*/
uint8_t sensor_type; /*< Class id of the distance sensor type.*/
uint8_t increment; /*< [deg] Angular width in degrees of each array element. Increment direction is clockwise. This field is ignored if increment_f is non-zero.*/
float increment_f; /*< [deg] Angular width in degrees of each array element as a float. If non-zero then this value is used instead of the uint8_t increment field. Positive is clockwise direction, negative is counter-clockwise.*/
float angle_offset; /*< [deg] Relative angle offset of the 0-index element in the distances array. Value of 0 corresponds to forward. Positive is clockwise direction, negative is counter-clockwise.*/
uint8_t frame; /*< Coordinate frame of reference for the yaw rotation and offset of the sensor data. Defaults to MAV_FRAME_GLOBAL, which is north aligned. For body-mounted sensors use MAV_FRAME_BODY_FRD, which is vehicle front aligned.*/
}) mavlink_obstacle_distance_t;
#define MAVLINK_MSG_ID_OBSTACLE_DISTANCE_LEN 167
#define MAVLINK_MSG_ID_OBSTACLE_DISTANCE_MIN_LEN 158
#define MAVLINK_MSG_ID_330_LEN 167
#define MAVLINK_MSG_ID_330_MIN_LEN 158
#define MAVLINK_MSG_ID_OBSTACLE_DISTANCE_CRC 23
#define MAVLINK_MSG_ID_330_CRC 23
#define MAVLINK_MSG_OBSTACLE_DISTANCE_FIELD_DISTANCES_LEN 72
#if MAVLINK_COMMAND_24BIT
#define MAVLINK_MESSAGE_INFO_OBSTACLE_DISTANCE { \
330, \
"OBSTACLE_DISTANCE", \
9, \
{ { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_obstacle_distance_t, time_usec) }, \
{ "sensor_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 156, offsetof(mavlink_obstacle_distance_t, sensor_type) }, \
{ "distances", NULL, MAVLINK_TYPE_UINT16_T, 72, 8, offsetof(mavlink_obstacle_distance_t, distances) }, \
{ "increment", NULL, MAVLINK_TYPE_UINT8_T, 0, 157, offsetof(mavlink_obstacle_distance_t, increment) }, \
{ "min_distance", NULL, MAVLINK_TYPE_UINT16_T, 0, 152, offsetof(mavlink_obstacle_distance_t, min_distance) }, \
{ "max_distance", NULL, MAVLINK_TYPE_UINT16_T, 0, 154, offsetof(mavlink_obstacle_distance_t, max_distance) }, \
{ "increment_f", NULL, MAVLINK_TYPE_FLOAT, 0, 158, offsetof(mavlink_obstacle_distance_t, increment_f) }, \
{ "angle_offset", NULL, MAVLINK_TYPE_FLOAT, 0, 162, offsetof(mavlink_obstacle_distance_t, angle_offset) }, \
{ "frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 166, offsetof(mavlink_obstacle_distance_t, frame) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_OBSTACLE_DISTANCE { \
"OBSTACLE_DISTANCE", \
9, \
{ { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_obstacle_distance_t, time_usec) }, \
{ "sensor_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 156, offsetof(mavlink_obstacle_distance_t, sensor_type) }, \
{ "distances", NULL, MAVLINK_TYPE_UINT16_T, 72, 8, offsetof(mavlink_obstacle_distance_t, distances) }, \
{ "increment", NULL, MAVLINK_TYPE_UINT8_T, 0, 157, offsetof(mavlink_obstacle_distance_t, increment) }, \
{ "min_distance", NULL, MAVLINK_TYPE_UINT16_T, 0, 152, offsetof(mavlink_obstacle_distance_t, min_distance) }, \
{ "max_distance", NULL, MAVLINK_TYPE_UINT16_T, 0, 154, offsetof(mavlink_obstacle_distance_t, max_distance) }, \
{ "increment_f", NULL, MAVLINK_TYPE_FLOAT, 0, 158, offsetof(mavlink_obstacle_distance_t, increment_f) }, \
{ "angle_offset", NULL, MAVLINK_TYPE_FLOAT, 0, 162, offsetof(mavlink_obstacle_distance_t, angle_offset) }, \
{ "frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 166, offsetof(mavlink_obstacle_distance_t, frame) }, \
} \
}
#endif
/**
* @brief Pack a obstacle_distance message
* @param system_id ID of this 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 [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
* @param sensor_type Class id of the distance sensor type.
* @param distances [cm] Distance of obstacles around the vehicle with index 0 corresponding to north + angle_offset, unless otherwise specified in the frame. A value of 0 is valid and means that the obstacle is practically touching the sensor. A value of max_distance +1 means no obstacle is present. A value of UINT16_MAX for unknown/not used. In a array element, one unit corresponds to 1cm.
* @param increment [deg] Angular width in degrees of each array element. Increment direction is clockwise. This field is ignored if increment_f is non-zero.
* @param min_distance [cm] Minimum distance the sensor can measure.
* @param max_distance [cm] Maximum distance the sensor can measure.
* @param increment_f [deg] Angular width in degrees of each array element as a float. If non-zero then this value is used instead of the uint8_t increment field. Positive is clockwise direction, negative is counter-clockwise.
* @param angle_offset [deg] Relative angle offset of the 0-index element in the distances array. Value of 0 corresponds to forward. Positive is clockwise direction, negative is counter-clockwise.
* @param frame Coordinate frame of reference for the yaw rotation and offset of the sensor data. Defaults to MAV_FRAME_GLOBAL, which is north aligned. For body-mounted sensors use MAV_FRAME_BODY_FRD, which is vehicle front aligned.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_obstacle_distance_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint64_t time_usec, uint8_t sensor_type, const uint16_t *distances, uint8_t increment, uint16_t min_distance, uint16_t max_distance, float increment_f, float angle_offset, uint8_t frame)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_OBSTACLE_DISTANCE_LEN];
_mav_put_uint64_t(buf, 0, time_usec);
_mav_put_uint16_t(buf, 152, min_distance);
_mav_put_uint16_t(buf, 154, max_distance);
_mav_put_uint8_t(buf, 156, sensor_type);
_mav_put_uint8_t(buf, 157, increment);
_mav_put_float(buf, 158, increment_f);
_mav_put_float(buf, 162, angle_offset);
_mav_put_uint8_t(buf, 166, frame);
_mav_put_uint16_t_array(buf, 8, distances, 72);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_OBSTACLE_DISTANCE_LEN);
#else
mavlink_obstacle_distance_t packet;
packet.time_usec = time_usec;
packet.min_distance = min_distance;
packet.max_distance = max_distance;
packet.sensor_type = sensor_type;
packet.increment = increment;
packet.increment_f = increment_f;
packet.angle_offset = angle_offset;
packet.frame = frame;
mav_array_memcpy(packet.distances, distances, sizeof(uint16_t)*72);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_OBSTACLE_DISTANCE_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_OBSTACLE_DISTANCE;
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_OBSTACLE_DISTANCE_MIN_LEN, MAVLINK_MSG_ID_OBSTACLE_DISTANCE_LEN, MAVLINK_MSG_ID_OBSTACLE_DISTANCE_CRC);
}
/**
* @brief Pack a obstacle_distance message on a channel
* @param system_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 [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
* @param sensor_type Class id of the distance sensor type.
* @param distances [cm] Distance of obstacles around the vehicle with index 0 corresponding to north + angle_offset, unless otherwise specified in the frame. A value of 0 is valid and means that the obstacle is practically touching the sensor. A value of max_distance +1 means no obstacle is present. A value of UINT16_MAX for unknown/not used. In a array element, one unit corresponds to 1cm.
* @param increment [deg] Angular width in degrees of each array element. Increment direction is clockwise. This field is ignored if increment_f is non-zero.
* @param min_distance [cm] Minimum distance the sensor can measure.
* @param max_distance [cm] Maximum distance the sensor can measure.
* @param increment_f [deg] Angular width in degrees of each array element as a float. If non-zero then this value is used instead of the uint8_t increment field. Positive is clockwise direction, negative is counter-clockwise.
* @param angle_offset [deg] Relative angle offset of the 0-index element in the distances array. Value of 0 corresponds to forward. Positive is clockwise direction, negative is counter-clockwise.
* @param frame Coordinate frame of reference for the yaw rotation and offset of the sensor data. Defaults to MAV_FRAME_GLOBAL, which is north aligned. For body-mounted sensors use MAV_FRAME_BODY_FRD, which is vehicle front aligned.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_obstacle_distance_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint64_t time_usec,uint8_t sensor_type,const uint16_t *distances,uint8_t increment,uint16_t min_distance,uint16_t max_distance,float increment_f,float angle_offset,uint8_t frame)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_OBSTACLE_DISTANCE_LEN];
_mav_put_uint64_t(buf, 0, time_usec);
_mav_put_uint16_t(buf, 152, min_distance);
_mav_put_uint16_t(buf, 154, max_distance);
_mav_put_uint8_t(buf, 156, sensor_type);
_mav_put_uint8_t(buf, 157, increment);
_mav_put_float(buf, 158, increment_f);
_mav_put_float(buf, 162, angle_offset);
_mav_put_uint8_t(buf, 166, frame);
_mav_put_uint16_t_array(buf, 8, distances, 72);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_OBSTACLE_DISTANCE_LEN);
#else
mavlink_obstacle_distance_t packet;
packet.time_usec = time_usec;
packet.min_distance = min_distance;
packet.max_distance = max_distance;
packet.sensor_type = sensor_type;
packet.increment = increment;
packet.increment_f = increment_f;
packet.angle_offset = angle_offset;
packet.frame = frame;
mav_array_memcpy(packet.distances, distances, sizeof(uint16_t)*72);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_OBSTACLE_DISTANCE_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_OBSTACLE_DISTANCE;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_OBSTACLE_DISTANCE_MIN_LEN, MAVLINK_MSG_ID_OBSTACLE_DISTANCE_LEN, MAVLINK_MSG_ID_OBSTACLE_DISTANCE_CRC);
}
/**
* @brief Encode a obstacle_distance 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 obstacle_distance C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_obstacle_distance_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_obstacle_distance_t* obstacle_distance)
{
return mavlink_msg_obstacle_distance_pack(system_id, component_id, msg, obstacle_distance->time_usec, obstacle_distance->sensor_type, obstacle_distance->distances, obstacle_distance->increment, obstacle_distance->min_distance, obstacle_distance->max_distance, obstacle_distance->increment_f, obstacle_distance->angle_offset, obstacle_distance->frame);
}
/**
* @brief Encode a obstacle_distance 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 obstacle_distance C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_obstacle_distance_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_obstacle_distance_t* obstacle_distance)
{
return mavlink_msg_obstacle_distance_pack_chan(system_id, component_id, chan, msg, obstacle_distance->time_usec, obstacle_distance->sensor_type, obstacle_distance->distances, obstacle_distance->increment, obstacle_distance->min_distance, obstacle_distance->max_distance, obstacle_distance->increment_f, obstacle_distance->angle_offset, obstacle_distance->frame);
}
/**
* @brief Send a obstacle_distance message
* @param chan MAVLink channel to send the message
*
* @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
* @param sensor_type Class id of the distance sensor type.
* @param distances [cm] Distance of obstacles around the vehicle with index 0 corresponding to north + angle_offset, unless otherwise specified in the frame. A value of 0 is valid and means that the obstacle is practically touching the sensor. A value of max_distance +1 means no obstacle is present. A value of UINT16_MAX for unknown/not used. In a array element, one unit corresponds to 1cm.
* @param increment [deg] Angular width in degrees of each array element. Increment direction is clockwise. This field is ignored if increment_f is non-zero.
* @param min_distance [cm] Minimum distance the sensor can measure.
* @param max_distance [cm] Maximum distance the sensor can measure.
* @param increment_f [deg] Angular width in degrees of each array element as a float. If non-zero then this value is used instead of the uint8_t increment field. Positive is clockwise direction, negative is counter-clockwise.
* @param angle_offset [deg] Relative angle offset of the 0-index element in the distances array. Value of 0 corresponds to forward. Positive is clockwise direction, negative is counter-clockwise.
* @param frame Coordinate frame of reference for the yaw rotation and offset of the sensor data. Defaults to MAV_FRAME_GLOBAL, which is north aligned. For body-mounted sensors use MAV_FRAME_BODY_FRD, which is vehicle front aligned.
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_obstacle_distance_send(mavlink_channel_t chan, uint64_t time_usec, uint8_t sensor_type, const uint16_t *distances, uint8_t increment, uint16_t min_distance, uint16_t max_distance, float increment_f, float angle_offset, uint8_t frame)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_OBSTACLE_DISTANCE_LEN];
_mav_put_uint64_t(buf, 0, time_usec);
_mav_put_uint16_t(buf, 152, min_distance);
_mav_put_uint16_t(buf, 154, max_distance);
_mav_put_uint8_t(buf, 156, sensor_type);
_mav_put_uint8_t(buf, 157, increment);
_mav_put_float(buf, 158, increment_f);
_mav_put_float(buf, 162, angle_offset);
_mav_put_uint8_t(buf, 166, frame);
_mav_put_uint16_t_array(buf, 8, distances, 72);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBSTACLE_DISTANCE, buf, MAVLINK_MSG_ID_OBSTACLE_DISTANCE_MIN_LEN, MAVLINK_MSG_ID_OBSTACLE_DISTANCE_LEN, MAVLINK_MSG_ID_OBSTACLE_DISTANCE_CRC);
#else
mavlink_obstacle_distance_t packet;
packet.time_usec = time_usec;
packet.min_distance = min_distance;
packet.max_distance = max_distance;
packet.sensor_type = sensor_type;
packet.increment = increment;
packet.increment_f = increment_f;
packet.angle_offset = angle_offset;
packet.frame = frame;
mav_array_memcpy(packet.distances, distances, sizeof(uint16_t)*72);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBSTACLE_DISTANCE, (const char *)&packet, MAVLINK_MSG_ID_OBSTACLE_DISTANCE_MIN_LEN, MAVLINK_MSG_ID_OBSTACLE_DISTANCE_LEN, MAVLINK_MSG_ID_OBSTACLE_DISTANCE_CRC);
#endif
}
/**
* @brief Send a obstacle_distance message
* @param chan MAVLink channel to send the message
* @param struct The MAVLink struct to serialize
*/
static inline void mavlink_msg_obstacle_distance_send_struct(mavlink_channel_t chan, const mavlink_obstacle_distance_t* obstacle_distance)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mavlink_msg_obstacle_distance_send(chan, obstacle_distance->time_usec, obstacle_distance->sensor_type, obstacle_distance->distances, obstacle_distance->increment, obstacle_distance->min_distance, obstacle_distance->max_distance, obstacle_distance->increment_f, obstacle_distance->angle_offset, obstacle_distance->frame);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBSTACLE_DISTANCE, (const char *)obstacle_distance, MAVLINK_MSG_ID_OBSTACLE_DISTANCE_MIN_LEN, MAVLINK_MSG_ID_OBSTACLE_DISTANCE_LEN, MAVLINK_MSG_ID_OBSTACLE_DISTANCE_CRC);
#endif
}
#if MAVLINK_MSG_ID_OBSTACLE_DISTANCE_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_obstacle_distance_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, uint8_t sensor_type, const uint16_t *distances, uint8_t increment, uint16_t min_distance, uint16_t max_distance, float increment_f, float angle_offset, uint8_t frame)
{
#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, 152, min_distance);
_mav_put_uint16_t(buf, 154, max_distance);
_mav_put_uint8_t(buf, 156, sensor_type);
_mav_put_uint8_t(buf, 157, increment);
_mav_put_float(buf, 158, increment_f);
_mav_put_float(buf, 162, angle_offset);
_mav_put_uint8_t(buf, 166, frame);
_mav_put_uint16_t_array(buf, 8, distances, 72);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBSTACLE_DISTANCE, buf, MAVLINK_MSG_ID_OBSTACLE_DISTANCE_MIN_LEN, MAVLINK_MSG_ID_OBSTACLE_DISTANCE_LEN, MAVLINK_MSG_ID_OBSTACLE_DISTANCE_CRC);
#else
mavlink_obstacle_distance_t *packet = (mavlink_obstacle_distance_t *)msgbuf;
packet->time_usec = time_usec;
packet->min_distance = min_distance;
packet->max_distance = max_distance;
packet->sensor_type = sensor_type;
packet->increment = increment;
packet->increment_f = increment_f;
packet->angle_offset = angle_offset;
packet->frame = frame;
mav_array_memcpy(packet->distances, distances, sizeof(uint16_t)*72);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OBSTACLE_DISTANCE, (const char *)packet, MAVLINK_MSG_ID_OBSTACLE_DISTANCE_MIN_LEN, MAVLINK_MSG_ID_OBSTACLE_DISTANCE_LEN, MAVLINK_MSG_ID_OBSTACLE_DISTANCE_CRC);
#endif
}
#endif
#endif
// MESSAGE OBSTACLE_DISTANCE UNPACKING
/**
* @brief Get field time_usec from obstacle_distance message
*
* @return [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
*/
static inline uint64_t mavlink_msg_obstacle_distance_get_time_usec(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint64_t(msg, 0);
}
/**
* @brief Get field sensor_type from obstacle_distance message
*
* @return Class id of the distance sensor type.
*/
static inline uint8_t mavlink_msg_obstacle_distance_get_sensor_type(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 156);
}
/**
* @brief Get field distances from obstacle_distance message
*
* @return [cm] Distance of obstacles around the vehicle with index 0 corresponding to north + angle_offset, unless otherwise specified in the frame. A value of 0 is valid and means that the obstacle is practically touching the sensor. A value of max_distance +1 means no obstacle is present. A value of UINT16_MAX for unknown/not used. In a array element, one unit corresponds to 1cm.
*/
static inline uint16_t mavlink_msg_obstacle_distance_get_distances(const mavlink_message_t* msg, uint16_t *distances)
{
return _MAV_RETURN_uint16_t_array(msg, distances, 72, 8);
}
/**
* @brief Get field increment from obstacle_distance message
*
* @return [deg] Angular width in degrees of each array element. Increment direction is clockwise. This field is ignored if increment_f is non-zero.
*/
static inline uint8_t mavlink_msg_obstacle_distance_get_increment(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 157);
}
/**
* @brief Get field min_distance from obstacle_distance message
*
* @return [cm] Minimum distance the sensor can measure.
*/
static inline uint16_t mavlink_msg_obstacle_distance_get_min_distance(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 152);
}
/**
* @brief Get field max_distance from obstacle_distance message
*
* @return [cm] Maximum distance the sensor can measure.
*/
static inline uint16_t mavlink_msg_obstacle_distance_get_max_distance(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 154);
}
/**
* @brief Get field increment_f from obstacle_distance message
*
* @return [deg] Angular width in degrees of each array element as a float. If non-zero then this value is used instead of the uint8_t increment field. Positive is clockwise direction, negative is counter-clockwise.
*/
static inline float mavlink_msg_obstacle_distance_get_increment_f(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 158);
}
/**
* @brief Get field angle_offset from obstacle_distance message
*
* @return [deg] Relative angle offset of the 0-index element in the distances array. Value of 0 corresponds to forward. Positive is clockwise direction, negative is counter-clockwise.
*/
static inline float mavlink_msg_obstacle_distance_get_angle_offset(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 162);
}
/**
* @brief Get field frame from obstacle_distance message
*
* @return Coordinate frame of reference for the yaw rotation and offset of the sensor data. Defaults to MAV_FRAME_GLOBAL, which is north aligned. For body-mounted sensors use MAV_FRAME_BODY_FRD, which is vehicle front aligned.
*/
static inline uint8_t mavlink_msg_obstacle_distance_get_frame(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 166);
}
/**
* @brief Decode a obstacle_distance message into a struct
*
* @param msg The message to decode
* @param obstacle_distance C-struct to decode the message contents into
*/
static inline void mavlink_msg_obstacle_distance_decode(const mavlink_message_t* msg, mavlink_obstacle_distance_t* obstacle_distance)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
obstacle_distance->time_usec = mavlink_msg_obstacle_distance_get_time_usec(msg);
mavlink_msg_obstacle_distance_get_distances(msg, obstacle_distance->distances);
obstacle_distance->min_distance = mavlink_msg_obstacle_distance_get_min_distance(msg);
obstacle_distance->max_distance = mavlink_msg_obstacle_distance_get_max_distance(msg);
obstacle_distance->sensor_type = mavlink_msg_obstacle_distance_get_sensor_type(msg);
obstacle_distance->increment = mavlink_msg_obstacle_distance_get_increment(msg);
obstacle_distance->increment_f = mavlink_msg_obstacle_distance_get_increment_f(msg);
obstacle_distance->angle_offset = mavlink_msg_obstacle_distance_get_angle_offset(msg);
obstacle_distance->frame = mavlink_msg_obstacle_distance_get_frame(msg);
#else
uint8_t len = msg->len < MAVLINK_MSG_ID_OBSTACLE_DISTANCE_LEN? msg->len : MAVLINK_MSG_ID_OBSTACLE_DISTANCE_LEN;
memset(obstacle_distance, 0, MAVLINK_MSG_ID_OBSTACLE_DISTANCE_LEN);
memcpy(obstacle_distance, _MAV_PAYLOAD(msg), len);
#endif
}

View file

@ -0,0 +1,607 @@
#pragma once
// MESSAGE ODOMETRY PACKING
#define MAVLINK_MSG_ID_ODOMETRY 331
typedef struct __mavlink_odometry_t {
uint64_t time_usec; /*< [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.*/
float x; /*< [m] X Position*/
float y; /*< [m] Y Position*/
float z; /*< [m] Z Position*/
float q[4]; /*< Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation)*/
float vx; /*< [m/s] X linear speed*/
float vy; /*< [m/s] Y linear speed*/
float vz; /*< [m/s] Z linear speed*/
float rollspeed; /*< [rad/s] Roll angular speed*/
float pitchspeed; /*< [rad/s] Pitch angular speed*/
float yawspeed; /*< [rad/s] Yaw angular speed*/
float pose_covariance[21]; /*< Row-major representation of a 6x6 pose cross-covariance matrix upper right triangle (states: x, y, z, roll, pitch, yaw; first six entries are the first ROW, next five entries are the second ROW, etc.). If unknown, assign NaN value to first element in the array.*/
float velocity_covariance[21]; /*< Row-major representation of a 6x6 velocity cross-covariance matrix upper right triangle (states: vx, vy, vz, rollspeed, pitchspeed, yawspeed; first six entries are the first ROW, next five entries are the second ROW, etc.). If unknown, assign NaN value to first element in the array.*/
uint8_t frame_id; /*< Coordinate frame of reference for the pose data.*/
uint8_t child_frame_id; /*< Coordinate frame of reference for the velocity in free space (twist) data.*/
uint8_t reset_counter; /*< Estimate reset counter. This should be incremented when the estimate resets in any of the dimensions (position, velocity, attitude, angular speed). This is designed to be used when e.g an external SLAM system detects a loop-closure and the estimate jumps.*/
uint8_t estimator_type; /*< Type of estimator that is providing the odometry.*/
} mavlink_odometry_t;
#define MAVLINK_MSG_ID_ODOMETRY_LEN 232
#define MAVLINK_MSG_ID_ODOMETRY_MIN_LEN 230
#define MAVLINK_MSG_ID_331_LEN 232
#define MAVLINK_MSG_ID_331_MIN_LEN 230
#define MAVLINK_MSG_ID_ODOMETRY_CRC 91
#define MAVLINK_MSG_ID_331_CRC 91
#define MAVLINK_MSG_ODOMETRY_FIELD_Q_LEN 4
#define MAVLINK_MSG_ODOMETRY_FIELD_POSE_COVARIANCE_LEN 21
#define MAVLINK_MSG_ODOMETRY_FIELD_VELOCITY_COVARIANCE_LEN 21
#if MAVLINK_COMMAND_24BIT
#define MAVLINK_MESSAGE_INFO_ODOMETRY { \
331, \
"ODOMETRY", \
17, \
{ { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_odometry_t, time_usec) }, \
{ "frame_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 228, offsetof(mavlink_odometry_t, frame_id) }, \
{ "child_frame_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 229, offsetof(mavlink_odometry_t, child_frame_id) }, \
{ "x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_odometry_t, x) }, \
{ "y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_odometry_t, y) }, \
{ "z", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_odometry_t, z) }, \
{ "q", NULL, MAVLINK_TYPE_FLOAT, 4, 20, offsetof(mavlink_odometry_t, q) }, \
{ "vx", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_odometry_t, vx) }, \
{ "vy", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_odometry_t, vy) }, \
{ "vz", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_odometry_t, vz) }, \
{ "rollspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_odometry_t, rollspeed) }, \
{ "pitchspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 52, offsetof(mavlink_odometry_t, pitchspeed) }, \
{ "yawspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 56, offsetof(mavlink_odometry_t, yawspeed) }, \
{ "pose_covariance", NULL, MAVLINK_TYPE_FLOAT, 21, 60, offsetof(mavlink_odometry_t, pose_covariance) }, \
{ "velocity_covariance", NULL, MAVLINK_TYPE_FLOAT, 21, 144, offsetof(mavlink_odometry_t, velocity_covariance) }, \
{ "reset_counter", NULL, MAVLINK_TYPE_UINT8_T, 0, 230, offsetof(mavlink_odometry_t, reset_counter) }, \
{ "estimator_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 231, offsetof(mavlink_odometry_t, estimator_type) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_ODOMETRY { \
"ODOMETRY", \
17, \
{ { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_odometry_t, time_usec) }, \
{ "frame_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 228, offsetof(mavlink_odometry_t, frame_id) }, \
{ "child_frame_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 229, offsetof(mavlink_odometry_t, child_frame_id) }, \
{ "x", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_odometry_t, x) }, \
{ "y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_odometry_t, y) }, \
{ "z", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_odometry_t, z) }, \
{ "q", NULL, MAVLINK_TYPE_FLOAT, 4, 20, offsetof(mavlink_odometry_t, q) }, \
{ "vx", NULL, MAVLINK_TYPE_FLOAT, 0, 36, offsetof(mavlink_odometry_t, vx) }, \
{ "vy", NULL, MAVLINK_TYPE_FLOAT, 0, 40, offsetof(mavlink_odometry_t, vy) }, \
{ "vz", NULL, MAVLINK_TYPE_FLOAT, 0, 44, offsetof(mavlink_odometry_t, vz) }, \
{ "rollspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 48, offsetof(mavlink_odometry_t, rollspeed) }, \
{ "pitchspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 52, offsetof(mavlink_odometry_t, pitchspeed) }, \
{ "yawspeed", NULL, MAVLINK_TYPE_FLOAT, 0, 56, offsetof(mavlink_odometry_t, yawspeed) }, \
{ "pose_covariance", NULL, MAVLINK_TYPE_FLOAT, 21, 60, offsetof(mavlink_odometry_t, pose_covariance) }, \
{ "velocity_covariance", NULL, MAVLINK_TYPE_FLOAT, 21, 144, offsetof(mavlink_odometry_t, velocity_covariance) }, \
{ "reset_counter", NULL, MAVLINK_TYPE_UINT8_T, 0, 230, offsetof(mavlink_odometry_t, reset_counter) }, \
{ "estimator_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 231, offsetof(mavlink_odometry_t, estimator_type) }, \
} \
}
#endif
/**
* @brief Pack a odometry message
* @param system_id ID of this 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 [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
* @param frame_id Coordinate frame of reference for the pose data.
* @param child_frame_id Coordinate frame of reference for the velocity in free space (twist) data.
* @param x [m] X Position
* @param y [m] Y Position
* @param z [m] Z Position
* @param q Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation)
* @param vx [m/s] X linear speed
* @param vy [m/s] Y linear speed
* @param vz [m/s] Z linear speed
* @param rollspeed [rad/s] Roll angular speed
* @param pitchspeed [rad/s] Pitch angular speed
* @param yawspeed [rad/s] Yaw angular speed
* @param pose_covariance Row-major representation of a 6x6 pose cross-covariance matrix upper right triangle (states: x, y, z, roll, pitch, yaw; first six entries are the first ROW, next five entries are the second ROW, etc.). If unknown, assign NaN value to first element in the array.
* @param velocity_covariance Row-major representation of a 6x6 velocity cross-covariance matrix upper right triangle (states: vx, vy, vz, rollspeed, pitchspeed, yawspeed; first six entries are the first ROW, next five entries are the second ROW, etc.). If unknown, assign NaN value to first element in the array.
* @param reset_counter Estimate reset counter. This should be incremented when the estimate resets in any of the dimensions (position, velocity, attitude, angular speed). This is designed to be used when e.g an external SLAM system detects a loop-closure and the estimate jumps.
* @param estimator_type Type of estimator that is providing the odometry.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_odometry_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint64_t time_usec, uint8_t frame_id, uint8_t child_frame_id, float x, float y, float z, const float *q, float vx, float vy, float vz, float rollspeed, float pitchspeed, float yawspeed, const float *pose_covariance, const float *velocity_covariance, uint8_t reset_counter, uint8_t estimator_type)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_ODOMETRY_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_float(buf, 36, vx);
_mav_put_float(buf, 40, vy);
_mav_put_float(buf, 44, vz);
_mav_put_float(buf, 48, rollspeed);
_mav_put_float(buf, 52, pitchspeed);
_mav_put_float(buf, 56, yawspeed);
_mav_put_uint8_t(buf, 228, frame_id);
_mav_put_uint8_t(buf, 229, child_frame_id);
_mav_put_uint8_t(buf, 230, reset_counter);
_mav_put_uint8_t(buf, 231, estimator_type);
_mav_put_float_array(buf, 20, q, 4);
_mav_put_float_array(buf, 60, pose_covariance, 21);
_mav_put_float_array(buf, 144, velocity_covariance, 21);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ODOMETRY_LEN);
#else
mavlink_odometry_t packet;
packet.time_usec = time_usec;
packet.x = x;
packet.y = y;
packet.z = z;
packet.vx = vx;
packet.vy = vy;
packet.vz = vz;
packet.rollspeed = rollspeed;
packet.pitchspeed = pitchspeed;
packet.yawspeed = yawspeed;
packet.frame_id = frame_id;
packet.child_frame_id = child_frame_id;
packet.reset_counter = reset_counter;
packet.estimator_type = estimator_type;
mav_array_memcpy(packet.q, q, sizeof(float)*4);
mav_array_memcpy(packet.pose_covariance, pose_covariance, sizeof(float)*21);
mav_array_memcpy(packet.velocity_covariance, velocity_covariance, sizeof(float)*21);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ODOMETRY_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_ODOMETRY;
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ODOMETRY_MIN_LEN, MAVLINK_MSG_ID_ODOMETRY_LEN, MAVLINK_MSG_ID_ODOMETRY_CRC);
}
/**
* @brief Pack a odometry message on a channel
* @param system_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 [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
* @param frame_id Coordinate frame of reference for the pose data.
* @param child_frame_id Coordinate frame of reference for the velocity in free space (twist) data.
* @param x [m] X Position
* @param y [m] Y Position
* @param z [m] Z Position
* @param q Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation)
* @param vx [m/s] X linear speed
* @param vy [m/s] Y linear speed
* @param vz [m/s] Z linear speed
* @param rollspeed [rad/s] Roll angular speed
* @param pitchspeed [rad/s] Pitch angular speed
* @param yawspeed [rad/s] Yaw angular speed
* @param pose_covariance Row-major representation of a 6x6 pose cross-covariance matrix upper right triangle (states: x, y, z, roll, pitch, yaw; first six entries are the first ROW, next five entries are the second ROW, etc.). If unknown, assign NaN value to first element in the array.
* @param velocity_covariance Row-major representation of a 6x6 velocity cross-covariance matrix upper right triangle (states: vx, vy, vz, rollspeed, pitchspeed, yawspeed; first six entries are the first ROW, next five entries are the second ROW, etc.). If unknown, assign NaN value to first element in the array.
* @param reset_counter Estimate reset counter. This should be incremented when the estimate resets in any of the dimensions (position, velocity, attitude, angular speed). This is designed to be used when e.g an external SLAM system detects a loop-closure and the estimate jumps.
* @param estimator_type Type of estimator that is providing the odometry.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_odometry_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint64_t time_usec,uint8_t frame_id,uint8_t child_frame_id,float x,float y,float z,const float *q,float vx,float vy,float vz,float rollspeed,float pitchspeed,float yawspeed,const float *pose_covariance,const float *velocity_covariance,uint8_t reset_counter,uint8_t estimator_type)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_ODOMETRY_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_float(buf, 36, vx);
_mav_put_float(buf, 40, vy);
_mav_put_float(buf, 44, vz);
_mav_put_float(buf, 48, rollspeed);
_mav_put_float(buf, 52, pitchspeed);
_mav_put_float(buf, 56, yawspeed);
_mav_put_uint8_t(buf, 228, frame_id);
_mav_put_uint8_t(buf, 229, child_frame_id);
_mav_put_uint8_t(buf, 230, reset_counter);
_mav_put_uint8_t(buf, 231, estimator_type);
_mav_put_float_array(buf, 20, q, 4);
_mav_put_float_array(buf, 60, pose_covariance, 21);
_mav_put_float_array(buf, 144, velocity_covariance, 21);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ODOMETRY_LEN);
#else
mavlink_odometry_t packet;
packet.time_usec = time_usec;
packet.x = x;
packet.y = y;
packet.z = z;
packet.vx = vx;
packet.vy = vy;
packet.vz = vz;
packet.rollspeed = rollspeed;
packet.pitchspeed = pitchspeed;
packet.yawspeed = yawspeed;
packet.frame_id = frame_id;
packet.child_frame_id = child_frame_id;
packet.reset_counter = reset_counter;
packet.estimator_type = estimator_type;
mav_array_memcpy(packet.q, q, sizeof(float)*4);
mav_array_memcpy(packet.pose_covariance, pose_covariance, sizeof(float)*21);
mav_array_memcpy(packet.velocity_covariance, velocity_covariance, sizeof(float)*21);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ODOMETRY_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_ODOMETRY;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ODOMETRY_MIN_LEN, MAVLINK_MSG_ID_ODOMETRY_LEN, MAVLINK_MSG_ID_ODOMETRY_CRC);
}
/**
* @brief Encode a odometry 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 odometry C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_odometry_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_odometry_t* odometry)
{
return mavlink_msg_odometry_pack(system_id, component_id, msg, odometry->time_usec, odometry->frame_id, odometry->child_frame_id, odometry->x, odometry->y, odometry->z, odometry->q, odometry->vx, odometry->vy, odometry->vz, odometry->rollspeed, odometry->pitchspeed, odometry->yawspeed, odometry->pose_covariance, odometry->velocity_covariance, odometry->reset_counter, odometry->estimator_type);
}
/**
* @brief Encode a odometry 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 odometry C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_odometry_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_odometry_t* odometry)
{
return mavlink_msg_odometry_pack_chan(system_id, component_id, chan, msg, odometry->time_usec, odometry->frame_id, odometry->child_frame_id, odometry->x, odometry->y, odometry->z, odometry->q, odometry->vx, odometry->vy, odometry->vz, odometry->rollspeed, odometry->pitchspeed, odometry->yawspeed, odometry->pose_covariance, odometry->velocity_covariance, odometry->reset_counter, odometry->estimator_type);
}
/**
* @brief Send a odometry message
* @param chan MAVLink channel to send the message
*
* @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
* @param frame_id Coordinate frame of reference for the pose data.
* @param child_frame_id Coordinate frame of reference for the velocity in free space (twist) data.
* @param x [m] X Position
* @param y [m] Y Position
* @param z [m] Z Position
* @param q Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation)
* @param vx [m/s] X linear speed
* @param vy [m/s] Y linear speed
* @param vz [m/s] Z linear speed
* @param rollspeed [rad/s] Roll angular speed
* @param pitchspeed [rad/s] Pitch angular speed
* @param yawspeed [rad/s] Yaw angular speed
* @param pose_covariance Row-major representation of a 6x6 pose cross-covariance matrix upper right triangle (states: x, y, z, roll, pitch, yaw; first six entries are the first ROW, next five entries are the second ROW, etc.). If unknown, assign NaN value to first element in the array.
* @param velocity_covariance Row-major representation of a 6x6 velocity cross-covariance matrix upper right triangle (states: vx, vy, vz, rollspeed, pitchspeed, yawspeed; first six entries are the first ROW, next five entries are the second ROW, etc.). If unknown, assign NaN value to first element in the array.
* @param reset_counter Estimate reset counter. This should be incremented when the estimate resets in any of the dimensions (position, velocity, attitude, angular speed). This is designed to be used when e.g an external SLAM system detects a loop-closure and the estimate jumps.
* @param estimator_type Type of estimator that is providing the odometry.
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_odometry_send(mavlink_channel_t chan, uint64_t time_usec, uint8_t frame_id, uint8_t child_frame_id, float x, float y, float z, const float *q, float vx, float vy, float vz, float rollspeed, float pitchspeed, float yawspeed, const float *pose_covariance, const float *velocity_covariance, uint8_t reset_counter, uint8_t estimator_type)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_ODOMETRY_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_float(buf, 36, vx);
_mav_put_float(buf, 40, vy);
_mav_put_float(buf, 44, vz);
_mav_put_float(buf, 48, rollspeed);
_mav_put_float(buf, 52, pitchspeed);
_mav_put_float(buf, 56, yawspeed);
_mav_put_uint8_t(buf, 228, frame_id);
_mav_put_uint8_t(buf, 229, child_frame_id);
_mav_put_uint8_t(buf, 230, reset_counter);
_mav_put_uint8_t(buf, 231, estimator_type);
_mav_put_float_array(buf, 20, q, 4);
_mav_put_float_array(buf, 60, pose_covariance, 21);
_mav_put_float_array(buf, 144, velocity_covariance, 21);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ODOMETRY, buf, MAVLINK_MSG_ID_ODOMETRY_MIN_LEN, MAVLINK_MSG_ID_ODOMETRY_LEN, MAVLINK_MSG_ID_ODOMETRY_CRC);
#else
mavlink_odometry_t packet;
packet.time_usec = time_usec;
packet.x = x;
packet.y = y;
packet.z = z;
packet.vx = vx;
packet.vy = vy;
packet.vz = vz;
packet.rollspeed = rollspeed;
packet.pitchspeed = pitchspeed;
packet.yawspeed = yawspeed;
packet.frame_id = frame_id;
packet.child_frame_id = child_frame_id;
packet.reset_counter = reset_counter;
packet.estimator_type = estimator_type;
mav_array_memcpy(packet.q, q, sizeof(float)*4);
mav_array_memcpy(packet.pose_covariance, pose_covariance, sizeof(float)*21);
mav_array_memcpy(packet.velocity_covariance, velocity_covariance, sizeof(float)*21);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ODOMETRY, (const char *)&packet, MAVLINK_MSG_ID_ODOMETRY_MIN_LEN, MAVLINK_MSG_ID_ODOMETRY_LEN, MAVLINK_MSG_ID_ODOMETRY_CRC);
#endif
}
/**
* @brief Send a odometry message
* @param chan MAVLink channel to send the message
* @param struct The MAVLink struct to serialize
*/
static inline void mavlink_msg_odometry_send_struct(mavlink_channel_t chan, const mavlink_odometry_t* odometry)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mavlink_msg_odometry_send(chan, odometry->time_usec, odometry->frame_id, odometry->child_frame_id, odometry->x, odometry->y, odometry->z, odometry->q, odometry->vx, odometry->vy, odometry->vz, odometry->rollspeed, odometry->pitchspeed, odometry->yawspeed, odometry->pose_covariance, odometry->velocity_covariance, odometry->reset_counter, odometry->estimator_type);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ODOMETRY, (const char *)odometry, MAVLINK_MSG_ID_ODOMETRY_MIN_LEN, MAVLINK_MSG_ID_ODOMETRY_LEN, MAVLINK_MSG_ID_ODOMETRY_CRC);
#endif
}
#if MAVLINK_MSG_ID_ODOMETRY_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_odometry_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, uint8_t frame_id, uint8_t child_frame_id, float x, float y, float z, const float *q, float vx, float vy, float vz, float rollspeed, float pitchspeed, float yawspeed, const float *pose_covariance, const float *velocity_covariance, uint8_t reset_counter, uint8_t estimator_type)
{
#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_float(buf, 36, vx);
_mav_put_float(buf, 40, vy);
_mav_put_float(buf, 44, vz);
_mav_put_float(buf, 48, rollspeed);
_mav_put_float(buf, 52, pitchspeed);
_mav_put_float(buf, 56, yawspeed);
_mav_put_uint8_t(buf, 228, frame_id);
_mav_put_uint8_t(buf, 229, child_frame_id);
_mav_put_uint8_t(buf, 230, reset_counter);
_mav_put_uint8_t(buf, 231, estimator_type);
_mav_put_float_array(buf, 20, q, 4);
_mav_put_float_array(buf, 60, pose_covariance, 21);
_mav_put_float_array(buf, 144, velocity_covariance, 21);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ODOMETRY, buf, MAVLINK_MSG_ID_ODOMETRY_MIN_LEN, MAVLINK_MSG_ID_ODOMETRY_LEN, MAVLINK_MSG_ID_ODOMETRY_CRC);
#else
mavlink_odometry_t *packet = (mavlink_odometry_t *)msgbuf;
packet->time_usec = time_usec;
packet->x = x;
packet->y = y;
packet->z = z;
packet->vx = vx;
packet->vy = vy;
packet->vz = vz;
packet->rollspeed = rollspeed;
packet->pitchspeed = pitchspeed;
packet->yawspeed = yawspeed;
packet->frame_id = frame_id;
packet->child_frame_id = child_frame_id;
packet->reset_counter = reset_counter;
packet->estimator_type = estimator_type;
mav_array_memcpy(packet->q, q, sizeof(float)*4);
mav_array_memcpy(packet->pose_covariance, pose_covariance, sizeof(float)*21);
mav_array_memcpy(packet->velocity_covariance, velocity_covariance, sizeof(float)*21);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ODOMETRY, (const char *)packet, MAVLINK_MSG_ID_ODOMETRY_MIN_LEN, MAVLINK_MSG_ID_ODOMETRY_LEN, MAVLINK_MSG_ID_ODOMETRY_CRC);
#endif
}
#endif
#endif
// MESSAGE ODOMETRY UNPACKING
/**
* @brief Get field time_usec from odometry message
*
* @return [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
*/
static inline uint64_t mavlink_msg_odometry_get_time_usec(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint64_t(msg, 0);
}
/**
* @brief Get field frame_id from odometry message
*
* @return Coordinate frame of reference for the pose data.
*/
static inline uint8_t mavlink_msg_odometry_get_frame_id(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 228);
}
/**
* @brief Get field child_frame_id from odometry message
*
* @return Coordinate frame of reference for the velocity in free space (twist) data.
*/
static inline uint8_t mavlink_msg_odometry_get_child_frame_id(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 229);
}
/**
* @brief Get field x from odometry message
*
* @return [m] X Position
*/
static inline float mavlink_msg_odometry_get_x(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 8);
}
/**
* @brief Get field y from odometry message
*
* @return [m] Y Position
*/
static inline float mavlink_msg_odometry_get_y(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 12);
}
/**
* @brief Get field z from odometry message
*
* @return [m] Z Position
*/
static inline float mavlink_msg_odometry_get_z(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 16);
}
/**
* @brief Get field q from odometry message
*
* @return Quaternion components, w, x, y, z (1 0 0 0 is the null-rotation)
*/
static inline uint16_t mavlink_msg_odometry_get_q(const mavlink_message_t* msg, float *q)
{
return _MAV_RETURN_float_array(msg, q, 4, 20);
}
/**
* @brief Get field vx from odometry message
*
* @return [m/s] X linear speed
*/
static inline float mavlink_msg_odometry_get_vx(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 36);
}
/**
* @brief Get field vy from odometry message
*
* @return [m/s] Y linear speed
*/
static inline float mavlink_msg_odometry_get_vy(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 40);
}
/**
* @brief Get field vz from odometry message
*
* @return [m/s] Z linear speed
*/
static inline float mavlink_msg_odometry_get_vz(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 44);
}
/**
* @brief Get field rollspeed from odometry message
*
* @return [rad/s] Roll angular speed
*/
static inline float mavlink_msg_odometry_get_rollspeed(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 48);
}
/**
* @brief Get field pitchspeed from odometry message
*
* @return [rad/s] Pitch angular speed
*/
static inline float mavlink_msg_odometry_get_pitchspeed(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 52);
}
/**
* @brief Get field yawspeed from odometry message
*
* @return [rad/s] Yaw angular speed
*/
static inline float mavlink_msg_odometry_get_yawspeed(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 56);
}
/**
* @brief Get field pose_covariance from odometry message
*
* @return Row-major representation of a 6x6 pose cross-covariance matrix upper right triangle (states: x, y, z, roll, pitch, yaw; first six entries are the first ROW, next five entries are the second ROW, etc.). If unknown, assign NaN value to first element in the array.
*/
static inline uint16_t mavlink_msg_odometry_get_pose_covariance(const mavlink_message_t* msg, float *pose_covariance)
{
return _MAV_RETURN_float_array(msg, pose_covariance, 21, 60);
}
/**
* @brief Get field velocity_covariance from odometry message
*
* @return Row-major representation of a 6x6 velocity cross-covariance matrix upper right triangle (states: vx, vy, vz, rollspeed, pitchspeed, yawspeed; first six entries are the first ROW, next five entries are the second ROW, etc.). If unknown, assign NaN value to first element in the array.
*/
static inline uint16_t mavlink_msg_odometry_get_velocity_covariance(const mavlink_message_t* msg, float *velocity_covariance)
{
return _MAV_RETURN_float_array(msg, velocity_covariance, 21, 144);
}
/**
* @brief Get field reset_counter from odometry message
*
* @return Estimate reset counter. This should be incremented when the estimate resets in any of the dimensions (position, velocity, attitude, angular speed). This is designed to be used when e.g an external SLAM system detects a loop-closure and the estimate jumps.
*/
static inline uint8_t mavlink_msg_odometry_get_reset_counter(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 230);
}
/**
* @brief Get field estimator_type from odometry message
*
* @return Type of estimator that is providing the odometry.
*/
static inline uint8_t mavlink_msg_odometry_get_estimator_type(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 231);
}
/**
* @brief Decode a odometry message into a struct
*
* @param msg The message to decode
* @param odometry C-struct to decode the message contents into
*/
static inline void mavlink_msg_odometry_decode(const mavlink_message_t* msg, mavlink_odometry_t* odometry)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
odometry->time_usec = mavlink_msg_odometry_get_time_usec(msg);
odometry->x = mavlink_msg_odometry_get_x(msg);
odometry->y = mavlink_msg_odometry_get_y(msg);
odometry->z = mavlink_msg_odometry_get_z(msg);
mavlink_msg_odometry_get_q(msg, odometry->q);
odometry->vx = mavlink_msg_odometry_get_vx(msg);
odometry->vy = mavlink_msg_odometry_get_vy(msg);
odometry->vz = mavlink_msg_odometry_get_vz(msg);
odometry->rollspeed = mavlink_msg_odometry_get_rollspeed(msg);
odometry->pitchspeed = mavlink_msg_odometry_get_pitchspeed(msg);
odometry->yawspeed = mavlink_msg_odometry_get_yawspeed(msg);
mavlink_msg_odometry_get_pose_covariance(msg, odometry->pose_covariance);
mavlink_msg_odometry_get_velocity_covariance(msg, odometry->velocity_covariance);
odometry->frame_id = mavlink_msg_odometry_get_frame_id(msg);
odometry->child_frame_id = mavlink_msg_odometry_get_child_frame_id(msg);
odometry->reset_counter = mavlink_msg_odometry_get_reset_counter(msg);
odometry->estimator_type = mavlink_msg_odometry_get_estimator_type(msg);
#else
uint8_t len = msg->len < MAVLINK_MSG_ID_ODOMETRY_LEN? msg->len : MAVLINK_MSG_ID_ODOMETRY_LEN;
memset(odometry, 0, MAVLINK_MSG_ID_ODOMETRY_LEN);
memcpy(odometry, _MAV_PAYLOAD(msg), len);
#endif
}

View file

@ -0,0 +1,693 @@
#pragma once
// MESSAGE ONBOARD_COMPUTER_STATUS PACKING
#define MAVLINK_MSG_ID_ONBOARD_COMPUTER_STATUS 390
typedef struct __mavlink_onboard_computer_status_t {
uint64_t time_usec; /*< [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.*/
uint32_t uptime; /*< [ms] Time since system boot.*/
uint32_t ram_usage; /*< [MiB] Amount of used RAM on the component system. A value of UINT32_MAX implies the field is unused.*/
uint32_t ram_total; /*< [MiB] Total amount of RAM on the component system. A value of UINT32_MAX implies the field is unused.*/
uint32_t storage_type[4]; /*< Storage type: 0: HDD, 1: SSD, 2: EMMC, 3: SD card (non-removable), 4: SD card (removable). A value of UINT32_MAX implies the field is unused.*/
uint32_t storage_usage[4]; /*< [MiB] Amount of used storage space on the component system. A value of UINT32_MAX implies the field is unused.*/
uint32_t storage_total[4]; /*< [MiB] Total amount of storage space on the component system. A value of UINT32_MAX implies the field is unused.*/
uint32_t link_type[6]; /*< Link type: 0-9: UART, 10-19: Wired network, 20-29: Wifi, 30-39: Point-to-point proprietary, 40-49: Mesh proprietary*/
uint32_t link_tx_rate[6]; /*< [KiB/s] Network traffic from the component system. A value of UINT32_MAX implies the field is unused.*/
uint32_t link_rx_rate[6]; /*< [KiB/s] Network traffic to the component system. A value of UINT32_MAX implies the field is unused.*/
uint32_t link_tx_max[6]; /*< [KiB/s] Network capacity from the component system. A value of UINT32_MAX implies the field is unused.*/
uint32_t link_rx_max[6]; /*< [KiB/s] Network capacity to the component system. A value of UINT32_MAX implies the field is unused.*/
int16_t fan_speed[4]; /*< [rpm] Fan speeds. A value of INT16_MAX implies the field is unused.*/
uint8_t type; /*< Type of the onboard computer: 0: Mission computer primary, 1: Mission computer backup 1, 2: Mission computer backup 2, 3: Compute node, 4-5: Compute spares, 6-9: Payload computers.*/
uint8_t cpu_cores[8]; /*< CPU usage on the component in percent (100 - idle). A value of UINT8_MAX implies the field is unused.*/
uint8_t cpu_combined[10]; /*< Combined CPU usage as the last 10 slices of 100 MS (a histogram). This allows to identify spikes in load that max out the system, but only for a short amount of time. A value of UINT8_MAX implies the field is unused.*/
uint8_t gpu_cores[4]; /*< GPU usage on the component in percent (100 - idle). A value of UINT8_MAX implies the field is unused.*/
uint8_t gpu_combined[10]; /*< Combined GPU usage as the last 10 slices of 100 MS (a histogram). This allows to identify spikes in load that max out the system, but only for a short amount of time. A value of UINT8_MAX implies the field is unused.*/
int8_t temperature_board; /*< [degC] Temperature of the board. A value of INT8_MAX implies the field is unused.*/
int8_t temperature_core[8]; /*< [degC] Temperature of the CPU core. A value of INT8_MAX implies the field is unused.*/
} mavlink_onboard_computer_status_t;
#define MAVLINK_MSG_ID_ONBOARD_COMPUTER_STATUS_LEN 238
#define MAVLINK_MSG_ID_ONBOARD_COMPUTER_STATUS_MIN_LEN 238
#define MAVLINK_MSG_ID_390_LEN 238
#define MAVLINK_MSG_ID_390_MIN_LEN 238
#define MAVLINK_MSG_ID_ONBOARD_COMPUTER_STATUS_CRC 156
#define MAVLINK_MSG_ID_390_CRC 156
#define MAVLINK_MSG_ONBOARD_COMPUTER_STATUS_FIELD_STORAGE_TYPE_LEN 4
#define MAVLINK_MSG_ONBOARD_COMPUTER_STATUS_FIELD_STORAGE_USAGE_LEN 4
#define MAVLINK_MSG_ONBOARD_COMPUTER_STATUS_FIELD_STORAGE_TOTAL_LEN 4
#define MAVLINK_MSG_ONBOARD_COMPUTER_STATUS_FIELD_LINK_TYPE_LEN 6
#define MAVLINK_MSG_ONBOARD_COMPUTER_STATUS_FIELD_LINK_TX_RATE_LEN 6
#define MAVLINK_MSG_ONBOARD_COMPUTER_STATUS_FIELD_LINK_RX_RATE_LEN 6
#define MAVLINK_MSG_ONBOARD_COMPUTER_STATUS_FIELD_LINK_TX_MAX_LEN 6
#define MAVLINK_MSG_ONBOARD_COMPUTER_STATUS_FIELD_LINK_RX_MAX_LEN 6
#define MAVLINK_MSG_ONBOARD_COMPUTER_STATUS_FIELD_FAN_SPEED_LEN 4
#define MAVLINK_MSG_ONBOARD_COMPUTER_STATUS_FIELD_CPU_CORES_LEN 8
#define MAVLINK_MSG_ONBOARD_COMPUTER_STATUS_FIELD_CPU_COMBINED_LEN 10
#define MAVLINK_MSG_ONBOARD_COMPUTER_STATUS_FIELD_GPU_CORES_LEN 4
#define MAVLINK_MSG_ONBOARD_COMPUTER_STATUS_FIELD_GPU_COMBINED_LEN 10
#define MAVLINK_MSG_ONBOARD_COMPUTER_STATUS_FIELD_TEMPERATURE_CORE_LEN 8
#if MAVLINK_COMMAND_24BIT
#define MAVLINK_MESSAGE_INFO_ONBOARD_COMPUTER_STATUS { \
390, \
"ONBOARD_COMPUTER_STATUS", \
20, \
{ { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_onboard_computer_status_t, time_usec) }, \
{ "uptime", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_onboard_computer_status_t, uptime) }, \
{ "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 196, offsetof(mavlink_onboard_computer_status_t, type) }, \
{ "cpu_cores", NULL, MAVLINK_TYPE_UINT8_T, 8, 197, offsetof(mavlink_onboard_computer_status_t, cpu_cores) }, \
{ "cpu_combined", NULL, MAVLINK_TYPE_UINT8_T, 10, 205, offsetof(mavlink_onboard_computer_status_t, cpu_combined) }, \
{ "gpu_cores", NULL, MAVLINK_TYPE_UINT8_T, 4, 215, offsetof(mavlink_onboard_computer_status_t, gpu_cores) }, \
{ "gpu_combined", NULL, MAVLINK_TYPE_UINT8_T, 10, 219, offsetof(mavlink_onboard_computer_status_t, gpu_combined) }, \
{ "temperature_board", NULL, MAVLINK_TYPE_INT8_T, 0, 229, offsetof(mavlink_onboard_computer_status_t, temperature_board) }, \
{ "temperature_core", NULL, MAVLINK_TYPE_INT8_T, 8, 230, offsetof(mavlink_onboard_computer_status_t, temperature_core) }, \
{ "fan_speed", NULL, MAVLINK_TYPE_INT16_T, 4, 188, offsetof(mavlink_onboard_computer_status_t, fan_speed) }, \
{ "ram_usage", NULL, MAVLINK_TYPE_UINT32_T, 0, 12, offsetof(mavlink_onboard_computer_status_t, ram_usage) }, \
{ "ram_total", NULL, MAVLINK_TYPE_UINT32_T, 0, 16, offsetof(mavlink_onboard_computer_status_t, ram_total) }, \
{ "storage_type", NULL, MAVLINK_TYPE_UINT32_T, 4, 20, offsetof(mavlink_onboard_computer_status_t, storage_type) }, \
{ "storage_usage", NULL, MAVLINK_TYPE_UINT32_T, 4, 36, offsetof(mavlink_onboard_computer_status_t, storage_usage) }, \
{ "storage_total", NULL, MAVLINK_TYPE_UINT32_T, 4, 52, offsetof(mavlink_onboard_computer_status_t, storage_total) }, \
{ "link_type", NULL, MAVLINK_TYPE_UINT32_T, 6, 68, offsetof(mavlink_onboard_computer_status_t, link_type) }, \
{ "link_tx_rate", NULL, MAVLINK_TYPE_UINT32_T, 6, 92, offsetof(mavlink_onboard_computer_status_t, link_tx_rate) }, \
{ "link_rx_rate", NULL, MAVLINK_TYPE_UINT32_T, 6, 116, offsetof(mavlink_onboard_computer_status_t, link_rx_rate) }, \
{ "link_tx_max", NULL, MAVLINK_TYPE_UINT32_T, 6, 140, offsetof(mavlink_onboard_computer_status_t, link_tx_max) }, \
{ "link_rx_max", NULL, MAVLINK_TYPE_UINT32_T, 6, 164, offsetof(mavlink_onboard_computer_status_t, link_rx_max) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_ONBOARD_COMPUTER_STATUS { \
"ONBOARD_COMPUTER_STATUS", \
20, \
{ { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_onboard_computer_status_t, time_usec) }, \
{ "uptime", NULL, MAVLINK_TYPE_UINT32_T, 0, 8, offsetof(mavlink_onboard_computer_status_t, uptime) }, \
{ "type", NULL, MAVLINK_TYPE_UINT8_T, 0, 196, offsetof(mavlink_onboard_computer_status_t, type) }, \
{ "cpu_cores", NULL, MAVLINK_TYPE_UINT8_T, 8, 197, offsetof(mavlink_onboard_computer_status_t, cpu_cores) }, \
{ "cpu_combined", NULL, MAVLINK_TYPE_UINT8_T, 10, 205, offsetof(mavlink_onboard_computer_status_t, cpu_combined) }, \
{ "gpu_cores", NULL, MAVLINK_TYPE_UINT8_T, 4, 215, offsetof(mavlink_onboard_computer_status_t, gpu_cores) }, \
{ "gpu_combined", NULL, MAVLINK_TYPE_UINT8_T, 10, 219, offsetof(mavlink_onboard_computer_status_t, gpu_combined) }, \
{ "temperature_board", NULL, MAVLINK_TYPE_INT8_T, 0, 229, offsetof(mavlink_onboard_computer_status_t, temperature_board) }, \
{ "temperature_core", NULL, MAVLINK_TYPE_INT8_T, 8, 230, offsetof(mavlink_onboard_computer_status_t, temperature_core) }, \
{ "fan_speed", NULL, MAVLINK_TYPE_INT16_T, 4, 188, offsetof(mavlink_onboard_computer_status_t, fan_speed) }, \
{ "ram_usage", NULL, MAVLINK_TYPE_UINT32_T, 0, 12, offsetof(mavlink_onboard_computer_status_t, ram_usage) }, \
{ "ram_total", NULL, MAVLINK_TYPE_UINT32_T, 0, 16, offsetof(mavlink_onboard_computer_status_t, ram_total) }, \
{ "storage_type", NULL, MAVLINK_TYPE_UINT32_T, 4, 20, offsetof(mavlink_onboard_computer_status_t, storage_type) }, \
{ "storage_usage", NULL, MAVLINK_TYPE_UINT32_T, 4, 36, offsetof(mavlink_onboard_computer_status_t, storage_usage) }, \
{ "storage_total", NULL, MAVLINK_TYPE_UINT32_T, 4, 52, offsetof(mavlink_onboard_computer_status_t, storage_total) }, \
{ "link_type", NULL, MAVLINK_TYPE_UINT32_T, 6, 68, offsetof(mavlink_onboard_computer_status_t, link_type) }, \
{ "link_tx_rate", NULL, MAVLINK_TYPE_UINT32_T, 6, 92, offsetof(mavlink_onboard_computer_status_t, link_tx_rate) }, \
{ "link_rx_rate", NULL, MAVLINK_TYPE_UINT32_T, 6, 116, offsetof(mavlink_onboard_computer_status_t, link_rx_rate) }, \
{ "link_tx_max", NULL, MAVLINK_TYPE_UINT32_T, 6, 140, offsetof(mavlink_onboard_computer_status_t, link_tx_max) }, \
{ "link_rx_max", NULL, MAVLINK_TYPE_UINT32_T, 6, 164, offsetof(mavlink_onboard_computer_status_t, link_rx_max) }, \
} \
}
#endif
/**
* @brief Pack a onboard_computer_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 time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
* @param uptime [ms] Time since system boot.
* @param type Type of the onboard computer: 0: Mission computer primary, 1: Mission computer backup 1, 2: Mission computer backup 2, 3: Compute node, 4-5: Compute spares, 6-9: Payload computers.
* @param cpu_cores CPU usage on the component in percent (100 - idle). A value of UINT8_MAX implies the field is unused.
* @param cpu_combined Combined CPU usage as the last 10 slices of 100 MS (a histogram). This allows to identify spikes in load that max out the system, but only for a short amount of time. A value of UINT8_MAX implies the field is unused.
* @param gpu_cores GPU usage on the component in percent (100 - idle). A value of UINT8_MAX implies the field is unused.
* @param gpu_combined Combined GPU usage as the last 10 slices of 100 MS (a histogram). This allows to identify spikes in load that max out the system, but only for a short amount of time. A value of UINT8_MAX implies the field is unused.
* @param temperature_board [degC] Temperature of the board. A value of INT8_MAX implies the field is unused.
* @param temperature_core [degC] Temperature of the CPU core. A value of INT8_MAX implies the field is unused.
* @param fan_speed [rpm] Fan speeds. A value of INT16_MAX implies the field is unused.
* @param ram_usage [MiB] Amount of used RAM on the component system. A value of UINT32_MAX implies the field is unused.
* @param ram_total [MiB] Total amount of RAM on the component system. A value of UINT32_MAX implies the field is unused.
* @param storage_type Storage type: 0: HDD, 1: SSD, 2: EMMC, 3: SD card (non-removable), 4: SD card (removable). A value of UINT32_MAX implies the field is unused.
* @param storage_usage [MiB] Amount of used storage space on the component system. A value of UINT32_MAX implies the field is unused.
* @param storage_total [MiB] Total amount of storage space on the component system. A value of UINT32_MAX implies the field is unused.
* @param link_type Link type: 0-9: UART, 10-19: Wired network, 20-29: Wifi, 30-39: Point-to-point proprietary, 40-49: Mesh proprietary
* @param link_tx_rate [KiB/s] Network traffic from the component system. A value of UINT32_MAX implies the field is unused.
* @param link_rx_rate [KiB/s] Network traffic to the component system. A value of UINT32_MAX implies the field is unused.
* @param link_tx_max [KiB/s] Network capacity from the component system. A value of UINT32_MAX implies the field is unused.
* @param link_rx_max [KiB/s] Network capacity to the component system. A value of UINT32_MAX implies the field is unused.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_onboard_computer_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint64_t time_usec, uint32_t uptime, uint8_t type, const uint8_t *cpu_cores, const uint8_t *cpu_combined, const uint8_t *gpu_cores, const uint8_t *gpu_combined, int8_t temperature_board, const int8_t *temperature_core, const int16_t *fan_speed, uint32_t ram_usage, uint32_t ram_total, const uint32_t *storage_type, const uint32_t *storage_usage, const uint32_t *storage_total, const uint32_t *link_type, const uint32_t *link_tx_rate, const uint32_t *link_rx_rate, const uint32_t *link_tx_max, const uint32_t *link_rx_max)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_ONBOARD_COMPUTER_STATUS_LEN];
_mav_put_uint64_t(buf, 0, time_usec);
_mav_put_uint32_t(buf, 8, uptime);
_mav_put_uint32_t(buf, 12, ram_usage);
_mav_put_uint32_t(buf, 16, ram_total);
_mav_put_uint8_t(buf, 196, type);
_mav_put_int8_t(buf, 229, temperature_board);
_mav_put_uint32_t_array(buf, 20, storage_type, 4);
_mav_put_uint32_t_array(buf, 36, storage_usage, 4);
_mav_put_uint32_t_array(buf, 52, storage_total, 4);
_mav_put_uint32_t_array(buf, 68, link_type, 6);
_mav_put_uint32_t_array(buf, 92, link_tx_rate, 6);
_mav_put_uint32_t_array(buf, 116, link_rx_rate, 6);
_mav_put_uint32_t_array(buf, 140, link_tx_max, 6);
_mav_put_uint32_t_array(buf, 164, link_rx_max, 6);
_mav_put_int16_t_array(buf, 188, fan_speed, 4);
_mav_put_uint8_t_array(buf, 197, cpu_cores, 8);
_mav_put_uint8_t_array(buf, 205, cpu_combined, 10);
_mav_put_uint8_t_array(buf, 215, gpu_cores, 4);
_mav_put_uint8_t_array(buf, 219, gpu_combined, 10);
_mav_put_int8_t_array(buf, 230, temperature_core, 8);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ONBOARD_COMPUTER_STATUS_LEN);
#else
mavlink_onboard_computer_status_t packet;
packet.time_usec = time_usec;
packet.uptime = uptime;
packet.ram_usage = ram_usage;
packet.ram_total = ram_total;
packet.type = type;
packet.temperature_board = temperature_board;
mav_array_memcpy(packet.storage_type, storage_type, sizeof(uint32_t)*4);
mav_array_memcpy(packet.storage_usage, storage_usage, sizeof(uint32_t)*4);
mav_array_memcpy(packet.storage_total, storage_total, sizeof(uint32_t)*4);
mav_array_memcpy(packet.link_type, link_type, sizeof(uint32_t)*6);
mav_array_memcpy(packet.link_tx_rate, link_tx_rate, sizeof(uint32_t)*6);
mav_array_memcpy(packet.link_rx_rate, link_rx_rate, sizeof(uint32_t)*6);
mav_array_memcpy(packet.link_tx_max, link_tx_max, sizeof(uint32_t)*6);
mav_array_memcpy(packet.link_rx_max, link_rx_max, sizeof(uint32_t)*6);
mav_array_memcpy(packet.fan_speed, fan_speed, sizeof(int16_t)*4);
mav_array_memcpy(packet.cpu_cores, cpu_cores, sizeof(uint8_t)*8);
mav_array_memcpy(packet.cpu_combined, cpu_combined, sizeof(uint8_t)*10);
mav_array_memcpy(packet.gpu_cores, gpu_cores, sizeof(uint8_t)*4);
mav_array_memcpy(packet.gpu_combined, gpu_combined, sizeof(uint8_t)*10);
mav_array_memcpy(packet.temperature_core, temperature_core, sizeof(int8_t)*8);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ONBOARD_COMPUTER_STATUS_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_ONBOARD_COMPUTER_STATUS;
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ONBOARD_COMPUTER_STATUS_MIN_LEN, MAVLINK_MSG_ID_ONBOARD_COMPUTER_STATUS_LEN, MAVLINK_MSG_ID_ONBOARD_COMPUTER_STATUS_CRC);
}
/**
* @brief Pack a onboard_computer_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 time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
* @param uptime [ms] Time since system boot.
* @param type Type of the onboard computer: 0: Mission computer primary, 1: Mission computer backup 1, 2: Mission computer backup 2, 3: Compute node, 4-5: Compute spares, 6-9: Payload computers.
* @param cpu_cores CPU usage on the component in percent (100 - idle). A value of UINT8_MAX implies the field is unused.
* @param cpu_combined Combined CPU usage as the last 10 slices of 100 MS (a histogram). This allows to identify spikes in load that max out the system, but only for a short amount of time. A value of UINT8_MAX implies the field is unused.
* @param gpu_cores GPU usage on the component in percent (100 - idle). A value of UINT8_MAX implies the field is unused.
* @param gpu_combined Combined GPU usage as the last 10 slices of 100 MS (a histogram). This allows to identify spikes in load that max out the system, but only for a short amount of time. A value of UINT8_MAX implies the field is unused.
* @param temperature_board [degC] Temperature of the board. A value of INT8_MAX implies the field is unused.
* @param temperature_core [degC] Temperature of the CPU core. A value of INT8_MAX implies the field is unused.
* @param fan_speed [rpm] Fan speeds. A value of INT16_MAX implies the field is unused.
* @param ram_usage [MiB] Amount of used RAM on the component system. A value of UINT32_MAX implies the field is unused.
* @param ram_total [MiB] Total amount of RAM on the component system. A value of UINT32_MAX implies the field is unused.
* @param storage_type Storage type: 0: HDD, 1: SSD, 2: EMMC, 3: SD card (non-removable), 4: SD card (removable). A value of UINT32_MAX implies the field is unused.
* @param storage_usage [MiB] Amount of used storage space on the component system. A value of UINT32_MAX implies the field is unused.
* @param storage_total [MiB] Total amount of storage space on the component system. A value of UINT32_MAX implies the field is unused.
* @param link_type Link type: 0-9: UART, 10-19: Wired network, 20-29: Wifi, 30-39: Point-to-point proprietary, 40-49: Mesh proprietary
* @param link_tx_rate [KiB/s] Network traffic from the component system. A value of UINT32_MAX implies the field is unused.
* @param link_rx_rate [KiB/s] Network traffic to the component system. A value of UINT32_MAX implies the field is unused.
* @param link_tx_max [KiB/s] Network capacity from the component system. A value of UINT32_MAX implies the field is unused.
* @param link_rx_max [KiB/s] Network capacity to the component system. A value of UINT32_MAX implies the field is unused.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_onboard_computer_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint64_t time_usec,uint32_t uptime,uint8_t type,const uint8_t *cpu_cores,const uint8_t *cpu_combined,const uint8_t *gpu_cores,const uint8_t *gpu_combined,int8_t temperature_board,const int8_t *temperature_core,const int16_t *fan_speed,uint32_t ram_usage,uint32_t ram_total,const uint32_t *storage_type,const uint32_t *storage_usage,const uint32_t *storage_total,const uint32_t *link_type,const uint32_t *link_tx_rate,const uint32_t *link_rx_rate,const uint32_t *link_tx_max,const uint32_t *link_rx_max)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_ONBOARD_COMPUTER_STATUS_LEN];
_mav_put_uint64_t(buf, 0, time_usec);
_mav_put_uint32_t(buf, 8, uptime);
_mav_put_uint32_t(buf, 12, ram_usage);
_mav_put_uint32_t(buf, 16, ram_total);
_mav_put_uint8_t(buf, 196, type);
_mav_put_int8_t(buf, 229, temperature_board);
_mav_put_uint32_t_array(buf, 20, storage_type, 4);
_mav_put_uint32_t_array(buf, 36, storage_usage, 4);
_mav_put_uint32_t_array(buf, 52, storage_total, 4);
_mav_put_uint32_t_array(buf, 68, link_type, 6);
_mav_put_uint32_t_array(buf, 92, link_tx_rate, 6);
_mav_put_uint32_t_array(buf, 116, link_rx_rate, 6);
_mav_put_uint32_t_array(buf, 140, link_tx_max, 6);
_mav_put_uint32_t_array(buf, 164, link_rx_max, 6);
_mav_put_int16_t_array(buf, 188, fan_speed, 4);
_mav_put_uint8_t_array(buf, 197, cpu_cores, 8);
_mav_put_uint8_t_array(buf, 205, cpu_combined, 10);
_mav_put_uint8_t_array(buf, 215, gpu_cores, 4);
_mav_put_uint8_t_array(buf, 219, gpu_combined, 10);
_mav_put_int8_t_array(buf, 230, temperature_core, 8);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ONBOARD_COMPUTER_STATUS_LEN);
#else
mavlink_onboard_computer_status_t packet;
packet.time_usec = time_usec;
packet.uptime = uptime;
packet.ram_usage = ram_usage;
packet.ram_total = ram_total;
packet.type = type;
packet.temperature_board = temperature_board;
mav_array_memcpy(packet.storage_type, storage_type, sizeof(uint32_t)*4);
mav_array_memcpy(packet.storage_usage, storage_usage, sizeof(uint32_t)*4);
mav_array_memcpy(packet.storage_total, storage_total, sizeof(uint32_t)*4);
mav_array_memcpy(packet.link_type, link_type, sizeof(uint32_t)*6);
mav_array_memcpy(packet.link_tx_rate, link_tx_rate, sizeof(uint32_t)*6);
mav_array_memcpy(packet.link_rx_rate, link_rx_rate, sizeof(uint32_t)*6);
mav_array_memcpy(packet.link_tx_max, link_tx_max, sizeof(uint32_t)*6);
mav_array_memcpy(packet.link_rx_max, link_rx_max, sizeof(uint32_t)*6);
mav_array_memcpy(packet.fan_speed, fan_speed, sizeof(int16_t)*4);
mav_array_memcpy(packet.cpu_cores, cpu_cores, sizeof(uint8_t)*8);
mav_array_memcpy(packet.cpu_combined, cpu_combined, sizeof(uint8_t)*10);
mav_array_memcpy(packet.gpu_cores, gpu_cores, sizeof(uint8_t)*4);
mav_array_memcpy(packet.gpu_combined, gpu_combined, sizeof(uint8_t)*10);
mav_array_memcpy(packet.temperature_core, temperature_core, sizeof(int8_t)*8);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ONBOARD_COMPUTER_STATUS_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_ONBOARD_COMPUTER_STATUS;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ONBOARD_COMPUTER_STATUS_MIN_LEN, MAVLINK_MSG_ID_ONBOARD_COMPUTER_STATUS_LEN, MAVLINK_MSG_ID_ONBOARD_COMPUTER_STATUS_CRC);
}
/**
* @brief Encode a onboard_computer_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 onboard_computer_status C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_onboard_computer_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_onboard_computer_status_t* onboard_computer_status)
{
return mavlink_msg_onboard_computer_status_pack(system_id, component_id, msg, onboard_computer_status->time_usec, onboard_computer_status->uptime, onboard_computer_status->type, onboard_computer_status->cpu_cores, onboard_computer_status->cpu_combined, onboard_computer_status->gpu_cores, onboard_computer_status->gpu_combined, onboard_computer_status->temperature_board, onboard_computer_status->temperature_core, onboard_computer_status->fan_speed, onboard_computer_status->ram_usage, onboard_computer_status->ram_total, onboard_computer_status->storage_type, onboard_computer_status->storage_usage, onboard_computer_status->storage_total, onboard_computer_status->link_type, onboard_computer_status->link_tx_rate, onboard_computer_status->link_rx_rate, onboard_computer_status->link_tx_max, onboard_computer_status->link_rx_max);
}
/**
* @brief Encode a onboard_computer_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 onboard_computer_status C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_onboard_computer_status_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_onboard_computer_status_t* onboard_computer_status)
{
return mavlink_msg_onboard_computer_status_pack_chan(system_id, component_id, chan, msg, onboard_computer_status->time_usec, onboard_computer_status->uptime, onboard_computer_status->type, onboard_computer_status->cpu_cores, onboard_computer_status->cpu_combined, onboard_computer_status->gpu_cores, onboard_computer_status->gpu_combined, onboard_computer_status->temperature_board, onboard_computer_status->temperature_core, onboard_computer_status->fan_speed, onboard_computer_status->ram_usage, onboard_computer_status->ram_total, onboard_computer_status->storage_type, onboard_computer_status->storage_usage, onboard_computer_status->storage_total, onboard_computer_status->link_type, onboard_computer_status->link_tx_rate, onboard_computer_status->link_rx_rate, onboard_computer_status->link_tx_max, onboard_computer_status->link_rx_max);
}
/**
* @brief Send a onboard_computer_status message
* @param chan MAVLink channel to send the message
*
* @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
* @param uptime [ms] Time since system boot.
* @param type Type of the onboard computer: 0: Mission computer primary, 1: Mission computer backup 1, 2: Mission computer backup 2, 3: Compute node, 4-5: Compute spares, 6-9: Payload computers.
* @param cpu_cores CPU usage on the component in percent (100 - idle). A value of UINT8_MAX implies the field is unused.
* @param cpu_combined Combined CPU usage as the last 10 slices of 100 MS (a histogram). This allows to identify spikes in load that max out the system, but only for a short amount of time. A value of UINT8_MAX implies the field is unused.
* @param gpu_cores GPU usage on the component in percent (100 - idle). A value of UINT8_MAX implies the field is unused.
* @param gpu_combined Combined GPU usage as the last 10 slices of 100 MS (a histogram). This allows to identify spikes in load that max out the system, but only for a short amount of time. A value of UINT8_MAX implies the field is unused.
* @param temperature_board [degC] Temperature of the board. A value of INT8_MAX implies the field is unused.
* @param temperature_core [degC] Temperature of the CPU core. A value of INT8_MAX implies the field is unused.
* @param fan_speed [rpm] Fan speeds. A value of INT16_MAX implies the field is unused.
* @param ram_usage [MiB] Amount of used RAM on the component system. A value of UINT32_MAX implies the field is unused.
* @param ram_total [MiB] Total amount of RAM on the component system. A value of UINT32_MAX implies the field is unused.
* @param storage_type Storage type: 0: HDD, 1: SSD, 2: EMMC, 3: SD card (non-removable), 4: SD card (removable). A value of UINT32_MAX implies the field is unused.
* @param storage_usage [MiB] Amount of used storage space on the component system. A value of UINT32_MAX implies the field is unused.
* @param storage_total [MiB] Total amount of storage space on the component system. A value of UINT32_MAX implies the field is unused.
* @param link_type Link type: 0-9: UART, 10-19: Wired network, 20-29: Wifi, 30-39: Point-to-point proprietary, 40-49: Mesh proprietary
* @param link_tx_rate [KiB/s] Network traffic from the component system. A value of UINT32_MAX implies the field is unused.
* @param link_rx_rate [KiB/s] Network traffic to the component system. A value of UINT32_MAX implies the field is unused.
* @param link_tx_max [KiB/s] Network capacity from the component system. A value of UINT32_MAX implies the field is unused.
* @param link_rx_max [KiB/s] Network capacity to the component system. A value of UINT32_MAX implies the field is unused.
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_onboard_computer_status_send(mavlink_channel_t chan, uint64_t time_usec, uint32_t uptime, uint8_t type, const uint8_t *cpu_cores, const uint8_t *cpu_combined, const uint8_t *gpu_cores, const uint8_t *gpu_combined, int8_t temperature_board, const int8_t *temperature_core, const int16_t *fan_speed, uint32_t ram_usage, uint32_t ram_total, const uint32_t *storage_type, const uint32_t *storage_usage, const uint32_t *storage_total, const uint32_t *link_type, const uint32_t *link_tx_rate, const uint32_t *link_rx_rate, const uint32_t *link_tx_max, const uint32_t *link_rx_max)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_ONBOARD_COMPUTER_STATUS_LEN];
_mav_put_uint64_t(buf, 0, time_usec);
_mav_put_uint32_t(buf, 8, uptime);
_mav_put_uint32_t(buf, 12, ram_usage);
_mav_put_uint32_t(buf, 16, ram_total);
_mav_put_uint8_t(buf, 196, type);
_mav_put_int8_t(buf, 229, temperature_board);
_mav_put_uint32_t_array(buf, 20, storage_type, 4);
_mav_put_uint32_t_array(buf, 36, storage_usage, 4);
_mav_put_uint32_t_array(buf, 52, storage_total, 4);
_mav_put_uint32_t_array(buf, 68, link_type, 6);
_mav_put_uint32_t_array(buf, 92, link_tx_rate, 6);
_mav_put_uint32_t_array(buf, 116, link_rx_rate, 6);
_mav_put_uint32_t_array(buf, 140, link_tx_max, 6);
_mav_put_uint32_t_array(buf, 164, link_rx_max, 6);
_mav_put_int16_t_array(buf, 188, fan_speed, 4);
_mav_put_uint8_t_array(buf, 197, cpu_cores, 8);
_mav_put_uint8_t_array(buf, 205, cpu_combined, 10);
_mav_put_uint8_t_array(buf, 215, gpu_cores, 4);
_mav_put_uint8_t_array(buf, 219, gpu_combined, 10);
_mav_put_int8_t_array(buf, 230, temperature_core, 8);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ONBOARD_COMPUTER_STATUS, buf, MAVLINK_MSG_ID_ONBOARD_COMPUTER_STATUS_MIN_LEN, MAVLINK_MSG_ID_ONBOARD_COMPUTER_STATUS_LEN, MAVLINK_MSG_ID_ONBOARD_COMPUTER_STATUS_CRC);
#else
mavlink_onboard_computer_status_t packet;
packet.time_usec = time_usec;
packet.uptime = uptime;
packet.ram_usage = ram_usage;
packet.ram_total = ram_total;
packet.type = type;
packet.temperature_board = temperature_board;
mav_array_memcpy(packet.storage_type, storage_type, sizeof(uint32_t)*4);
mav_array_memcpy(packet.storage_usage, storage_usage, sizeof(uint32_t)*4);
mav_array_memcpy(packet.storage_total, storage_total, sizeof(uint32_t)*4);
mav_array_memcpy(packet.link_type, link_type, sizeof(uint32_t)*6);
mav_array_memcpy(packet.link_tx_rate, link_tx_rate, sizeof(uint32_t)*6);
mav_array_memcpy(packet.link_rx_rate, link_rx_rate, sizeof(uint32_t)*6);
mav_array_memcpy(packet.link_tx_max, link_tx_max, sizeof(uint32_t)*6);
mav_array_memcpy(packet.link_rx_max, link_rx_max, sizeof(uint32_t)*6);
mav_array_memcpy(packet.fan_speed, fan_speed, sizeof(int16_t)*4);
mav_array_memcpy(packet.cpu_cores, cpu_cores, sizeof(uint8_t)*8);
mav_array_memcpy(packet.cpu_combined, cpu_combined, sizeof(uint8_t)*10);
mav_array_memcpy(packet.gpu_cores, gpu_cores, sizeof(uint8_t)*4);
mav_array_memcpy(packet.gpu_combined, gpu_combined, sizeof(uint8_t)*10);
mav_array_memcpy(packet.temperature_core, temperature_core, sizeof(int8_t)*8);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ONBOARD_COMPUTER_STATUS, (const char *)&packet, MAVLINK_MSG_ID_ONBOARD_COMPUTER_STATUS_MIN_LEN, MAVLINK_MSG_ID_ONBOARD_COMPUTER_STATUS_LEN, MAVLINK_MSG_ID_ONBOARD_COMPUTER_STATUS_CRC);
#endif
}
/**
* @brief Send a onboard_computer_status message
* @param chan MAVLink channel to send the message
* @param struct The MAVLink struct to serialize
*/
static inline void mavlink_msg_onboard_computer_status_send_struct(mavlink_channel_t chan, const mavlink_onboard_computer_status_t* onboard_computer_status)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mavlink_msg_onboard_computer_status_send(chan, onboard_computer_status->time_usec, onboard_computer_status->uptime, onboard_computer_status->type, onboard_computer_status->cpu_cores, onboard_computer_status->cpu_combined, onboard_computer_status->gpu_cores, onboard_computer_status->gpu_combined, onboard_computer_status->temperature_board, onboard_computer_status->temperature_core, onboard_computer_status->fan_speed, onboard_computer_status->ram_usage, onboard_computer_status->ram_total, onboard_computer_status->storage_type, onboard_computer_status->storage_usage, onboard_computer_status->storage_total, onboard_computer_status->link_type, onboard_computer_status->link_tx_rate, onboard_computer_status->link_rx_rate, onboard_computer_status->link_tx_max, onboard_computer_status->link_rx_max);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ONBOARD_COMPUTER_STATUS, (const char *)onboard_computer_status, MAVLINK_MSG_ID_ONBOARD_COMPUTER_STATUS_MIN_LEN, MAVLINK_MSG_ID_ONBOARD_COMPUTER_STATUS_LEN, MAVLINK_MSG_ID_ONBOARD_COMPUTER_STATUS_CRC);
#endif
}
#if MAVLINK_MSG_ID_ONBOARD_COMPUTER_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_onboard_computer_status_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, uint32_t uptime, uint8_t type, const uint8_t *cpu_cores, const uint8_t *cpu_combined, const uint8_t *gpu_cores, const uint8_t *gpu_combined, int8_t temperature_board, const int8_t *temperature_core, const int16_t *fan_speed, uint32_t ram_usage, uint32_t ram_total, const uint32_t *storage_type, const uint32_t *storage_usage, const uint32_t *storage_total, const uint32_t *link_type, const uint32_t *link_tx_rate, const uint32_t *link_rx_rate, const uint32_t *link_tx_max, const uint32_t *link_rx_max)
{
#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, uptime);
_mav_put_uint32_t(buf, 12, ram_usage);
_mav_put_uint32_t(buf, 16, ram_total);
_mav_put_uint8_t(buf, 196, type);
_mav_put_int8_t(buf, 229, temperature_board);
_mav_put_uint32_t_array(buf, 20, storage_type, 4);
_mav_put_uint32_t_array(buf, 36, storage_usage, 4);
_mav_put_uint32_t_array(buf, 52, storage_total, 4);
_mav_put_uint32_t_array(buf, 68, link_type, 6);
_mav_put_uint32_t_array(buf, 92, link_tx_rate, 6);
_mav_put_uint32_t_array(buf, 116, link_rx_rate, 6);
_mav_put_uint32_t_array(buf, 140, link_tx_max, 6);
_mav_put_uint32_t_array(buf, 164, link_rx_max, 6);
_mav_put_int16_t_array(buf, 188, fan_speed, 4);
_mav_put_uint8_t_array(buf, 197, cpu_cores, 8);
_mav_put_uint8_t_array(buf, 205, cpu_combined, 10);
_mav_put_uint8_t_array(buf, 215, gpu_cores, 4);
_mav_put_uint8_t_array(buf, 219, gpu_combined, 10);
_mav_put_int8_t_array(buf, 230, temperature_core, 8);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ONBOARD_COMPUTER_STATUS, buf, MAVLINK_MSG_ID_ONBOARD_COMPUTER_STATUS_MIN_LEN, MAVLINK_MSG_ID_ONBOARD_COMPUTER_STATUS_LEN, MAVLINK_MSG_ID_ONBOARD_COMPUTER_STATUS_CRC);
#else
mavlink_onboard_computer_status_t *packet = (mavlink_onboard_computer_status_t *)msgbuf;
packet->time_usec = time_usec;
packet->uptime = uptime;
packet->ram_usage = ram_usage;
packet->ram_total = ram_total;
packet->type = type;
packet->temperature_board = temperature_board;
mav_array_memcpy(packet->storage_type, storage_type, sizeof(uint32_t)*4);
mav_array_memcpy(packet->storage_usage, storage_usage, sizeof(uint32_t)*4);
mav_array_memcpy(packet->storage_total, storage_total, sizeof(uint32_t)*4);
mav_array_memcpy(packet->link_type, link_type, sizeof(uint32_t)*6);
mav_array_memcpy(packet->link_tx_rate, link_tx_rate, sizeof(uint32_t)*6);
mav_array_memcpy(packet->link_rx_rate, link_rx_rate, sizeof(uint32_t)*6);
mav_array_memcpy(packet->link_tx_max, link_tx_max, sizeof(uint32_t)*6);
mav_array_memcpy(packet->link_rx_max, link_rx_max, sizeof(uint32_t)*6);
mav_array_memcpy(packet->fan_speed, fan_speed, sizeof(int16_t)*4);
mav_array_memcpy(packet->cpu_cores, cpu_cores, sizeof(uint8_t)*8);
mav_array_memcpy(packet->cpu_combined, cpu_combined, sizeof(uint8_t)*10);
mav_array_memcpy(packet->gpu_cores, gpu_cores, sizeof(uint8_t)*4);
mav_array_memcpy(packet->gpu_combined, gpu_combined, sizeof(uint8_t)*10);
mav_array_memcpy(packet->temperature_core, temperature_core, sizeof(int8_t)*8);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ONBOARD_COMPUTER_STATUS, (const char *)packet, MAVLINK_MSG_ID_ONBOARD_COMPUTER_STATUS_MIN_LEN, MAVLINK_MSG_ID_ONBOARD_COMPUTER_STATUS_LEN, MAVLINK_MSG_ID_ONBOARD_COMPUTER_STATUS_CRC);
#endif
}
#endif
#endif
// MESSAGE ONBOARD_COMPUTER_STATUS UNPACKING
/**
* @brief Get field time_usec from onboard_computer_status message
*
* @return [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
*/
static inline uint64_t mavlink_msg_onboard_computer_status_get_time_usec(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint64_t(msg, 0);
}
/**
* @brief Get field uptime from onboard_computer_status message
*
* @return [ms] Time since system boot.
*/
static inline uint32_t mavlink_msg_onboard_computer_status_get_uptime(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint32_t(msg, 8);
}
/**
* @brief Get field type from onboard_computer_status message
*
* @return Type of the onboard computer: 0: Mission computer primary, 1: Mission computer backup 1, 2: Mission computer backup 2, 3: Compute node, 4-5: Compute spares, 6-9: Payload computers.
*/
static inline uint8_t mavlink_msg_onboard_computer_status_get_type(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 196);
}
/**
* @brief Get field cpu_cores from onboard_computer_status message
*
* @return CPU usage on the component in percent (100 - idle). A value of UINT8_MAX implies the field is unused.
*/
static inline uint16_t mavlink_msg_onboard_computer_status_get_cpu_cores(const mavlink_message_t* msg, uint8_t *cpu_cores)
{
return _MAV_RETURN_uint8_t_array(msg, cpu_cores, 8, 197);
}
/**
* @brief Get field cpu_combined from onboard_computer_status message
*
* @return Combined CPU usage as the last 10 slices of 100 MS (a histogram). This allows to identify spikes in load that max out the system, but only for a short amount of time. A value of UINT8_MAX implies the field is unused.
*/
static inline uint16_t mavlink_msg_onboard_computer_status_get_cpu_combined(const mavlink_message_t* msg, uint8_t *cpu_combined)
{
return _MAV_RETURN_uint8_t_array(msg, cpu_combined, 10, 205);
}
/**
* @brief Get field gpu_cores from onboard_computer_status message
*
* @return GPU usage on the component in percent (100 - idle). A value of UINT8_MAX implies the field is unused.
*/
static inline uint16_t mavlink_msg_onboard_computer_status_get_gpu_cores(const mavlink_message_t* msg, uint8_t *gpu_cores)
{
return _MAV_RETURN_uint8_t_array(msg, gpu_cores, 4, 215);
}
/**
* @brief Get field gpu_combined from onboard_computer_status message
*
* @return Combined GPU usage as the last 10 slices of 100 MS (a histogram). This allows to identify spikes in load that max out the system, but only for a short amount of time. A value of UINT8_MAX implies the field is unused.
*/
static inline uint16_t mavlink_msg_onboard_computer_status_get_gpu_combined(const mavlink_message_t* msg, uint8_t *gpu_combined)
{
return _MAV_RETURN_uint8_t_array(msg, gpu_combined, 10, 219);
}
/**
* @brief Get field temperature_board from onboard_computer_status message
*
* @return [degC] Temperature of the board. A value of INT8_MAX implies the field is unused.
*/
static inline int8_t mavlink_msg_onboard_computer_status_get_temperature_board(const mavlink_message_t* msg)
{
return _MAV_RETURN_int8_t(msg, 229);
}
/**
* @brief Get field temperature_core from onboard_computer_status message
*
* @return [degC] Temperature of the CPU core. A value of INT8_MAX implies the field is unused.
*/
static inline uint16_t mavlink_msg_onboard_computer_status_get_temperature_core(const mavlink_message_t* msg, int8_t *temperature_core)
{
return _MAV_RETURN_int8_t_array(msg, temperature_core, 8, 230);
}
/**
* @brief Get field fan_speed from onboard_computer_status message
*
* @return [rpm] Fan speeds. A value of INT16_MAX implies the field is unused.
*/
static inline uint16_t mavlink_msg_onboard_computer_status_get_fan_speed(const mavlink_message_t* msg, int16_t *fan_speed)
{
return _MAV_RETURN_int16_t_array(msg, fan_speed, 4, 188);
}
/**
* @brief Get field ram_usage from onboard_computer_status message
*
* @return [MiB] Amount of used RAM on the component system. A value of UINT32_MAX implies the field is unused.
*/
static inline uint32_t mavlink_msg_onboard_computer_status_get_ram_usage(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint32_t(msg, 12);
}
/**
* @brief Get field ram_total from onboard_computer_status message
*
* @return [MiB] Total amount of RAM on the component system. A value of UINT32_MAX implies the field is unused.
*/
static inline uint32_t mavlink_msg_onboard_computer_status_get_ram_total(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint32_t(msg, 16);
}
/**
* @brief Get field storage_type from onboard_computer_status message
*
* @return Storage type: 0: HDD, 1: SSD, 2: EMMC, 3: SD card (non-removable), 4: SD card (removable). A value of UINT32_MAX implies the field is unused.
*/
static inline uint16_t mavlink_msg_onboard_computer_status_get_storage_type(const mavlink_message_t* msg, uint32_t *storage_type)
{
return _MAV_RETURN_uint32_t_array(msg, storage_type, 4, 20);
}
/**
* @brief Get field storage_usage from onboard_computer_status message
*
* @return [MiB] Amount of used storage space on the component system. A value of UINT32_MAX implies the field is unused.
*/
static inline uint16_t mavlink_msg_onboard_computer_status_get_storage_usage(const mavlink_message_t* msg, uint32_t *storage_usage)
{
return _MAV_RETURN_uint32_t_array(msg, storage_usage, 4, 36);
}
/**
* @brief Get field storage_total from onboard_computer_status message
*
* @return [MiB] Total amount of storage space on the component system. A value of UINT32_MAX implies the field is unused.
*/
static inline uint16_t mavlink_msg_onboard_computer_status_get_storage_total(const mavlink_message_t* msg, uint32_t *storage_total)
{
return _MAV_RETURN_uint32_t_array(msg, storage_total, 4, 52);
}
/**
* @brief Get field link_type from onboard_computer_status message
*
* @return Link type: 0-9: UART, 10-19: Wired network, 20-29: Wifi, 30-39: Point-to-point proprietary, 40-49: Mesh proprietary
*/
static inline uint16_t mavlink_msg_onboard_computer_status_get_link_type(const mavlink_message_t* msg, uint32_t *link_type)
{
return _MAV_RETURN_uint32_t_array(msg, link_type, 6, 68);
}
/**
* @brief Get field link_tx_rate from onboard_computer_status message
*
* @return [KiB/s] Network traffic from the component system. A value of UINT32_MAX implies the field is unused.
*/
static inline uint16_t mavlink_msg_onboard_computer_status_get_link_tx_rate(const mavlink_message_t* msg, uint32_t *link_tx_rate)
{
return _MAV_RETURN_uint32_t_array(msg, link_tx_rate, 6, 92);
}
/**
* @brief Get field link_rx_rate from onboard_computer_status message
*
* @return [KiB/s] Network traffic to the component system. A value of UINT32_MAX implies the field is unused.
*/
static inline uint16_t mavlink_msg_onboard_computer_status_get_link_rx_rate(const mavlink_message_t* msg, uint32_t *link_rx_rate)
{
return _MAV_RETURN_uint32_t_array(msg, link_rx_rate, 6, 116);
}
/**
* @brief Get field link_tx_max from onboard_computer_status message
*
* @return [KiB/s] Network capacity from the component system. A value of UINT32_MAX implies the field is unused.
*/
static inline uint16_t mavlink_msg_onboard_computer_status_get_link_tx_max(const mavlink_message_t* msg, uint32_t *link_tx_max)
{
return _MAV_RETURN_uint32_t_array(msg, link_tx_max, 6, 140);
}
/**
* @brief Get field link_rx_max from onboard_computer_status message
*
* @return [KiB/s] Network capacity to the component system. A value of UINT32_MAX implies the field is unused.
*/
static inline uint16_t mavlink_msg_onboard_computer_status_get_link_rx_max(const mavlink_message_t* msg, uint32_t *link_rx_max)
{
return _MAV_RETURN_uint32_t_array(msg, link_rx_max, 6, 164);
}
/**
* @brief Decode a onboard_computer_status message into a struct
*
* @param msg The message to decode
* @param onboard_computer_status C-struct to decode the message contents into
*/
static inline void mavlink_msg_onboard_computer_status_decode(const mavlink_message_t* msg, mavlink_onboard_computer_status_t* onboard_computer_status)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
onboard_computer_status->time_usec = mavlink_msg_onboard_computer_status_get_time_usec(msg);
onboard_computer_status->uptime = mavlink_msg_onboard_computer_status_get_uptime(msg);
onboard_computer_status->ram_usage = mavlink_msg_onboard_computer_status_get_ram_usage(msg);
onboard_computer_status->ram_total = mavlink_msg_onboard_computer_status_get_ram_total(msg);
mavlink_msg_onboard_computer_status_get_storage_type(msg, onboard_computer_status->storage_type);
mavlink_msg_onboard_computer_status_get_storage_usage(msg, onboard_computer_status->storage_usage);
mavlink_msg_onboard_computer_status_get_storage_total(msg, onboard_computer_status->storage_total);
mavlink_msg_onboard_computer_status_get_link_type(msg, onboard_computer_status->link_type);
mavlink_msg_onboard_computer_status_get_link_tx_rate(msg, onboard_computer_status->link_tx_rate);
mavlink_msg_onboard_computer_status_get_link_rx_rate(msg, onboard_computer_status->link_rx_rate);
mavlink_msg_onboard_computer_status_get_link_tx_max(msg, onboard_computer_status->link_tx_max);
mavlink_msg_onboard_computer_status_get_link_rx_max(msg, onboard_computer_status->link_rx_max);
mavlink_msg_onboard_computer_status_get_fan_speed(msg, onboard_computer_status->fan_speed);
onboard_computer_status->type = mavlink_msg_onboard_computer_status_get_type(msg);
mavlink_msg_onboard_computer_status_get_cpu_cores(msg, onboard_computer_status->cpu_cores);
mavlink_msg_onboard_computer_status_get_cpu_combined(msg, onboard_computer_status->cpu_combined);
mavlink_msg_onboard_computer_status_get_gpu_cores(msg, onboard_computer_status->gpu_cores);
mavlink_msg_onboard_computer_status_get_gpu_combined(msg, onboard_computer_status->gpu_combined);
onboard_computer_status->temperature_board = mavlink_msg_onboard_computer_status_get_temperature_board(msg);
mavlink_msg_onboard_computer_status_get_temperature_core(msg, onboard_computer_status->temperature_core);
#else
uint8_t len = msg->len < MAVLINK_MSG_ID_ONBOARD_COMPUTER_STATUS_LEN? msg->len : MAVLINK_MSG_ID_ONBOARD_COMPUTER_STATUS_LEN;
memset(onboard_computer_status, 0, MAVLINK_MSG_ID_ONBOARD_COMPUTER_STATUS_LEN);
memcpy(onboard_computer_status, _MAV_PAYLOAD(msg), len);
#endif
}

View file

@ -0,0 +1,406 @@
#pragma once
// MESSAGE OPEN_DRONE_ID_AUTHENTICATION PACKING
#define MAVLINK_MSG_ID_OPEN_DRONE_ID_AUTHENTICATION 12902
typedef struct __mavlink_open_drone_id_authentication_t {
uint32_t timestamp; /*< [s] This field is only present for page 0. 32 bit Unix Timestamp in seconds since 00:00:00 01/01/2019.*/
uint8_t target_system; /*< System ID (0 for broadcast).*/
uint8_t target_component; /*< Component ID (0 for broadcast).*/
uint8_t id_or_mac[20]; /*< Only used for drone ID data received from other UAs. See detailed description at https://mavlink.io/en/services/opendroneid.html. */
uint8_t authentication_type; /*< Indicates the type of authentication.*/
uint8_t data_page; /*< Allowed range is 0 - 4.*/
uint8_t page_count; /*< This field is only present for page 0. Allowed range is 0 - 5.*/
uint8_t length; /*< [bytes] This field is only present for page 0. Total bytes of authentication_data from all data pages. Allowed range is 0 - 109 (17 + 23*4).*/
uint8_t authentication_data[23]; /*< Opaque authentication data. For page 0, the size is only 17 bytes. For other pages, the size is 23 bytes. Shall be filled with nulls in the unused portion of the field.*/
} mavlink_open_drone_id_authentication_t;
#define MAVLINK_MSG_ID_OPEN_DRONE_ID_AUTHENTICATION_LEN 53
#define MAVLINK_MSG_ID_OPEN_DRONE_ID_AUTHENTICATION_MIN_LEN 53
#define MAVLINK_MSG_ID_12902_LEN 53
#define MAVLINK_MSG_ID_12902_MIN_LEN 53
#define MAVLINK_MSG_ID_OPEN_DRONE_ID_AUTHENTICATION_CRC 49
#define MAVLINK_MSG_ID_12902_CRC 49
#define MAVLINK_MSG_OPEN_DRONE_ID_AUTHENTICATION_FIELD_ID_OR_MAC_LEN 20
#define MAVLINK_MSG_OPEN_DRONE_ID_AUTHENTICATION_FIELD_AUTHENTICATION_DATA_LEN 23
#if MAVLINK_COMMAND_24BIT
#define MAVLINK_MESSAGE_INFO_OPEN_DRONE_ID_AUTHENTICATION { \
12902, \
"OPEN_DRONE_ID_AUTHENTICATION", \
9, \
{ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_open_drone_id_authentication_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_open_drone_id_authentication_t, target_component) }, \
{ "id_or_mac", NULL, MAVLINK_TYPE_UINT8_T, 20, 6, offsetof(mavlink_open_drone_id_authentication_t, id_or_mac) }, \
{ "authentication_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 26, offsetof(mavlink_open_drone_id_authentication_t, authentication_type) }, \
{ "data_page", NULL, MAVLINK_TYPE_UINT8_T, 0, 27, offsetof(mavlink_open_drone_id_authentication_t, data_page) }, \
{ "page_count", NULL, MAVLINK_TYPE_UINT8_T, 0, 28, offsetof(mavlink_open_drone_id_authentication_t, page_count) }, \
{ "length", NULL, MAVLINK_TYPE_UINT8_T, 0, 29, offsetof(mavlink_open_drone_id_authentication_t, length) }, \
{ "timestamp", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_open_drone_id_authentication_t, timestamp) }, \
{ "authentication_data", NULL, MAVLINK_TYPE_UINT8_T, 23, 30, offsetof(mavlink_open_drone_id_authentication_t, authentication_data) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_OPEN_DRONE_ID_AUTHENTICATION { \
"OPEN_DRONE_ID_AUTHENTICATION", \
9, \
{ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 4, offsetof(mavlink_open_drone_id_authentication_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 5, offsetof(mavlink_open_drone_id_authentication_t, target_component) }, \
{ "id_or_mac", NULL, MAVLINK_TYPE_UINT8_T, 20, 6, offsetof(mavlink_open_drone_id_authentication_t, id_or_mac) }, \
{ "authentication_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 26, offsetof(mavlink_open_drone_id_authentication_t, authentication_type) }, \
{ "data_page", NULL, MAVLINK_TYPE_UINT8_T, 0, 27, offsetof(mavlink_open_drone_id_authentication_t, data_page) }, \
{ "page_count", NULL, MAVLINK_TYPE_UINT8_T, 0, 28, offsetof(mavlink_open_drone_id_authentication_t, page_count) }, \
{ "length", NULL, MAVLINK_TYPE_UINT8_T, 0, 29, offsetof(mavlink_open_drone_id_authentication_t, length) }, \
{ "timestamp", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_open_drone_id_authentication_t, timestamp) }, \
{ "authentication_data", NULL, MAVLINK_TYPE_UINT8_T, 23, 30, offsetof(mavlink_open_drone_id_authentication_t, authentication_data) }, \
} \
}
#endif
/**
* @brief Pack a open_drone_id_authentication message
* @param system_id ID of this 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 (0 for broadcast).
* @param target_component Component ID (0 for broadcast).
* @param id_or_mac Only used for drone ID data received from other UAs. See detailed description at https://mavlink.io/en/services/opendroneid.html.
* @param authentication_type Indicates the type of authentication.
* @param data_page Allowed range is 0 - 4.
* @param page_count This field is only present for page 0. Allowed range is 0 - 5.
* @param length [bytes] This field is only present for page 0. Total bytes of authentication_data from all data pages. Allowed range is 0 - 109 (17 + 23*4).
* @param timestamp [s] This field is only present for page 0. 32 bit Unix Timestamp in seconds since 00:00:00 01/01/2019.
* @param authentication_data Opaque authentication data. For page 0, the size is only 17 bytes. For other pages, the size is 23 bytes. Shall be filled with nulls in the unused portion of the field.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_open_drone_id_authentication_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t target_system, uint8_t target_component, const uint8_t *id_or_mac, uint8_t authentication_type, uint8_t data_page, uint8_t page_count, uint8_t length, uint32_t timestamp, const uint8_t *authentication_data)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_OPEN_DRONE_ID_AUTHENTICATION_LEN];
_mav_put_uint32_t(buf, 0, timestamp);
_mav_put_uint8_t(buf, 4, target_system);
_mav_put_uint8_t(buf, 5, target_component);
_mav_put_uint8_t(buf, 26, authentication_type);
_mav_put_uint8_t(buf, 27, data_page);
_mav_put_uint8_t(buf, 28, page_count);
_mav_put_uint8_t(buf, 29, length);
_mav_put_uint8_t_array(buf, 6, id_or_mac, 20);
_mav_put_uint8_t_array(buf, 30, authentication_data, 23);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_OPEN_DRONE_ID_AUTHENTICATION_LEN);
#else
mavlink_open_drone_id_authentication_t packet;
packet.timestamp = timestamp;
packet.target_system = target_system;
packet.target_component = target_component;
packet.authentication_type = authentication_type;
packet.data_page = data_page;
packet.page_count = page_count;
packet.length = length;
mav_array_memcpy(packet.id_or_mac, id_or_mac, sizeof(uint8_t)*20);
mav_array_memcpy(packet.authentication_data, authentication_data, sizeof(uint8_t)*23);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_OPEN_DRONE_ID_AUTHENTICATION_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_OPEN_DRONE_ID_AUTHENTICATION;
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_OPEN_DRONE_ID_AUTHENTICATION_MIN_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_AUTHENTICATION_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_AUTHENTICATION_CRC);
}
/**
* @brief Pack a open_drone_id_authentication message on a channel
* @param system_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 (0 for broadcast).
* @param target_component Component ID (0 for broadcast).
* @param id_or_mac Only used for drone ID data received from other UAs. See detailed description at https://mavlink.io/en/services/opendroneid.html.
* @param authentication_type Indicates the type of authentication.
* @param data_page Allowed range is 0 - 4.
* @param page_count This field is only present for page 0. Allowed range is 0 - 5.
* @param length [bytes] This field is only present for page 0. Total bytes of authentication_data from all data pages. Allowed range is 0 - 109 (17 + 23*4).
* @param timestamp [s] This field is only present for page 0. 32 bit Unix Timestamp in seconds since 00:00:00 01/01/2019.
* @param authentication_data Opaque authentication data. For page 0, the size is only 17 bytes. For other pages, the size is 23 bytes. Shall be filled with nulls in the unused portion of the field.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_open_drone_id_authentication_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 uint8_t *id_or_mac,uint8_t authentication_type,uint8_t data_page,uint8_t page_count,uint8_t length,uint32_t timestamp,const uint8_t *authentication_data)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_OPEN_DRONE_ID_AUTHENTICATION_LEN];
_mav_put_uint32_t(buf, 0, timestamp);
_mav_put_uint8_t(buf, 4, target_system);
_mav_put_uint8_t(buf, 5, target_component);
_mav_put_uint8_t(buf, 26, authentication_type);
_mav_put_uint8_t(buf, 27, data_page);
_mav_put_uint8_t(buf, 28, page_count);
_mav_put_uint8_t(buf, 29, length);
_mav_put_uint8_t_array(buf, 6, id_or_mac, 20);
_mav_put_uint8_t_array(buf, 30, authentication_data, 23);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_OPEN_DRONE_ID_AUTHENTICATION_LEN);
#else
mavlink_open_drone_id_authentication_t packet;
packet.timestamp = timestamp;
packet.target_system = target_system;
packet.target_component = target_component;
packet.authentication_type = authentication_type;
packet.data_page = data_page;
packet.page_count = page_count;
packet.length = length;
mav_array_memcpy(packet.id_or_mac, id_or_mac, sizeof(uint8_t)*20);
mav_array_memcpy(packet.authentication_data, authentication_data, sizeof(uint8_t)*23);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_OPEN_DRONE_ID_AUTHENTICATION_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_OPEN_DRONE_ID_AUTHENTICATION;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_OPEN_DRONE_ID_AUTHENTICATION_MIN_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_AUTHENTICATION_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_AUTHENTICATION_CRC);
}
/**
* @brief Encode a open_drone_id_authentication 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 open_drone_id_authentication C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_open_drone_id_authentication_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_open_drone_id_authentication_t* open_drone_id_authentication)
{
return mavlink_msg_open_drone_id_authentication_pack(system_id, component_id, msg, open_drone_id_authentication->target_system, open_drone_id_authentication->target_component, open_drone_id_authentication->id_or_mac, open_drone_id_authentication->authentication_type, open_drone_id_authentication->data_page, open_drone_id_authentication->page_count, open_drone_id_authentication->length, open_drone_id_authentication->timestamp, open_drone_id_authentication->authentication_data);
}
/**
* @brief Encode a open_drone_id_authentication 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 open_drone_id_authentication C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_open_drone_id_authentication_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_open_drone_id_authentication_t* open_drone_id_authentication)
{
return mavlink_msg_open_drone_id_authentication_pack_chan(system_id, component_id, chan, msg, open_drone_id_authentication->target_system, open_drone_id_authentication->target_component, open_drone_id_authentication->id_or_mac, open_drone_id_authentication->authentication_type, open_drone_id_authentication->data_page, open_drone_id_authentication->page_count, open_drone_id_authentication->length, open_drone_id_authentication->timestamp, open_drone_id_authentication->authentication_data);
}
/**
* @brief Send a open_drone_id_authentication message
* @param chan MAVLink channel to send the message
*
* @param target_system System ID (0 for broadcast).
* @param target_component Component ID (0 for broadcast).
* @param id_or_mac Only used for drone ID data received from other UAs. See detailed description at https://mavlink.io/en/services/opendroneid.html.
* @param authentication_type Indicates the type of authentication.
* @param data_page Allowed range is 0 - 4.
* @param page_count This field is only present for page 0. Allowed range is 0 - 5.
* @param length [bytes] This field is only present for page 0. Total bytes of authentication_data from all data pages. Allowed range is 0 - 109 (17 + 23*4).
* @param timestamp [s] This field is only present for page 0. 32 bit Unix Timestamp in seconds since 00:00:00 01/01/2019.
* @param authentication_data Opaque authentication data. For page 0, the size is only 17 bytes. For other pages, the size is 23 bytes. Shall be filled with nulls in the unused portion of the field.
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_open_drone_id_authentication_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, const uint8_t *id_or_mac, uint8_t authentication_type, uint8_t data_page, uint8_t page_count, uint8_t length, uint32_t timestamp, const uint8_t *authentication_data)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_OPEN_DRONE_ID_AUTHENTICATION_LEN];
_mav_put_uint32_t(buf, 0, timestamp);
_mav_put_uint8_t(buf, 4, target_system);
_mav_put_uint8_t(buf, 5, target_component);
_mav_put_uint8_t(buf, 26, authentication_type);
_mav_put_uint8_t(buf, 27, data_page);
_mav_put_uint8_t(buf, 28, page_count);
_mav_put_uint8_t(buf, 29, length);
_mav_put_uint8_t_array(buf, 6, id_or_mac, 20);
_mav_put_uint8_t_array(buf, 30, authentication_data, 23);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPEN_DRONE_ID_AUTHENTICATION, buf, MAVLINK_MSG_ID_OPEN_DRONE_ID_AUTHENTICATION_MIN_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_AUTHENTICATION_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_AUTHENTICATION_CRC);
#else
mavlink_open_drone_id_authentication_t packet;
packet.timestamp = timestamp;
packet.target_system = target_system;
packet.target_component = target_component;
packet.authentication_type = authentication_type;
packet.data_page = data_page;
packet.page_count = page_count;
packet.length = length;
mav_array_memcpy(packet.id_or_mac, id_or_mac, sizeof(uint8_t)*20);
mav_array_memcpy(packet.authentication_data, authentication_data, sizeof(uint8_t)*23);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPEN_DRONE_ID_AUTHENTICATION, (const char *)&packet, MAVLINK_MSG_ID_OPEN_DRONE_ID_AUTHENTICATION_MIN_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_AUTHENTICATION_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_AUTHENTICATION_CRC);
#endif
}
/**
* @brief Send a open_drone_id_authentication message
* @param chan MAVLink channel to send the message
* @param struct The MAVLink struct to serialize
*/
static inline void mavlink_msg_open_drone_id_authentication_send_struct(mavlink_channel_t chan, const mavlink_open_drone_id_authentication_t* open_drone_id_authentication)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mavlink_msg_open_drone_id_authentication_send(chan, open_drone_id_authentication->target_system, open_drone_id_authentication->target_component, open_drone_id_authentication->id_or_mac, open_drone_id_authentication->authentication_type, open_drone_id_authentication->data_page, open_drone_id_authentication->page_count, open_drone_id_authentication->length, open_drone_id_authentication->timestamp, open_drone_id_authentication->authentication_data);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPEN_DRONE_ID_AUTHENTICATION, (const char *)open_drone_id_authentication, MAVLINK_MSG_ID_OPEN_DRONE_ID_AUTHENTICATION_MIN_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_AUTHENTICATION_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_AUTHENTICATION_CRC);
#endif
}
#if MAVLINK_MSG_ID_OPEN_DRONE_ID_AUTHENTICATION_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_open_drone_id_authentication_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, const uint8_t *id_or_mac, uint8_t authentication_type, uint8_t data_page, uint8_t page_count, uint8_t length, uint32_t timestamp, const uint8_t *authentication_data)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
_mav_put_uint32_t(buf, 0, timestamp);
_mav_put_uint8_t(buf, 4, target_system);
_mav_put_uint8_t(buf, 5, target_component);
_mav_put_uint8_t(buf, 26, authentication_type);
_mav_put_uint8_t(buf, 27, data_page);
_mav_put_uint8_t(buf, 28, page_count);
_mav_put_uint8_t(buf, 29, length);
_mav_put_uint8_t_array(buf, 6, id_or_mac, 20);
_mav_put_uint8_t_array(buf, 30, authentication_data, 23);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPEN_DRONE_ID_AUTHENTICATION, buf, MAVLINK_MSG_ID_OPEN_DRONE_ID_AUTHENTICATION_MIN_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_AUTHENTICATION_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_AUTHENTICATION_CRC);
#else
mavlink_open_drone_id_authentication_t *packet = (mavlink_open_drone_id_authentication_t *)msgbuf;
packet->timestamp = timestamp;
packet->target_system = target_system;
packet->target_component = target_component;
packet->authentication_type = authentication_type;
packet->data_page = data_page;
packet->page_count = page_count;
packet->length = length;
mav_array_memcpy(packet->id_or_mac, id_or_mac, sizeof(uint8_t)*20);
mav_array_memcpy(packet->authentication_data, authentication_data, sizeof(uint8_t)*23);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPEN_DRONE_ID_AUTHENTICATION, (const char *)packet, MAVLINK_MSG_ID_OPEN_DRONE_ID_AUTHENTICATION_MIN_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_AUTHENTICATION_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_AUTHENTICATION_CRC);
#endif
}
#endif
#endif
// MESSAGE OPEN_DRONE_ID_AUTHENTICATION UNPACKING
/**
* @brief Get field target_system from open_drone_id_authentication message
*
* @return System ID (0 for broadcast).
*/
static inline uint8_t mavlink_msg_open_drone_id_authentication_get_target_system(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 4);
}
/**
* @brief Get field target_component from open_drone_id_authentication message
*
* @return Component ID (0 for broadcast).
*/
static inline uint8_t mavlink_msg_open_drone_id_authentication_get_target_component(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 5);
}
/**
* @brief Get field id_or_mac from open_drone_id_authentication message
*
* @return Only used for drone ID data received from other UAs. See detailed description at https://mavlink.io/en/services/opendroneid.html.
*/
static inline uint16_t mavlink_msg_open_drone_id_authentication_get_id_or_mac(const mavlink_message_t* msg, uint8_t *id_or_mac)
{
return _MAV_RETURN_uint8_t_array(msg, id_or_mac, 20, 6);
}
/**
* @brief Get field authentication_type from open_drone_id_authentication message
*
* @return Indicates the type of authentication.
*/
static inline uint8_t mavlink_msg_open_drone_id_authentication_get_authentication_type(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 26);
}
/**
* @brief Get field data_page from open_drone_id_authentication message
*
* @return Allowed range is 0 - 4.
*/
static inline uint8_t mavlink_msg_open_drone_id_authentication_get_data_page(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 27);
}
/**
* @brief Get field page_count from open_drone_id_authentication message
*
* @return This field is only present for page 0. Allowed range is 0 - 5.
*/
static inline uint8_t mavlink_msg_open_drone_id_authentication_get_page_count(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 28);
}
/**
* @brief Get field length from open_drone_id_authentication message
*
* @return [bytes] This field is only present for page 0. Total bytes of authentication_data from all data pages. Allowed range is 0 - 109 (17 + 23*4).
*/
static inline uint8_t mavlink_msg_open_drone_id_authentication_get_length(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 29);
}
/**
* @brief Get field timestamp from open_drone_id_authentication message
*
* @return [s] This field is only present for page 0. 32 bit Unix Timestamp in seconds since 00:00:00 01/01/2019.
*/
static inline uint32_t mavlink_msg_open_drone_id_authentication_get_timestamp(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint32_t(msg, 0);
}
/**
* @brief Get field authentication_data from open_drone_id_authentication message
*
* @return Opaque authentication data. For page 0, the size is only 17 bytes. For other pages, the size is 23 bytes. Shall be filled with nulls in the unused portion of the field.
*/
static inline uint16_t mavlink_msg_open_drone_id_authentication_get_authentication_data(const mavlink_message_t* msg, uint8_t *authentication_data)
{
return _MAV_RETURN_uint8_t_array(msg, authentication_data, 23, 30);
}
/**
* @brief Decode a open_drone_id_authentication message into a struct
*
* @param msg The message to decode
* @param open_drone_id_authentication C-struct to decode the message contents into
*/
static inline void mavlink_msg_open_drone_id_authentication_decode(const mavlink_message_t* msg, mavlink_open_drone_id_authentication_t* open_drone_id_authentication)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
open_drone_id_authentication->timestamp = mavlink_msg_open_drone_id_authentication_get_timestamp(msg);
open_drone_id_authentication->target_system = mavlink_msg_open_drone_id_authentication_get_target_system(msg);
open_drone_id_authentication->target_component = mavlink_msg_open_drone_id_authentication_get_target_component(msg);
mavlink_msg_open_drone_id_authentication_get_id_or_mac(msg, open_drone_id_authentication->id_or_mac);
open_drone_id_authentication->authentication_type = mavlink_msg_open_drone_id_authentication_get_authentication_type(msg);
open_drone_id_authentication->data_page = mavlink_msg_open_drone_id_authentication_get_data_page(msg);
open_drone_id_authentication->page_count = mavlink_msg_open_drone_id_authentication_get_page_count(msg);
open_drone_id_authentication->length = mavlink_msg_open_drone_id_authentication_get_length(msg);
mavlink_msg_open_drone_id_authentication_get_authentication_data(msg, open_drone_id_authentication->authentication_data);
#else
uint8_t len = msg->len < MAVLINK_MSG_ID_OPEN_DRONE_ID_AUTHENTICATION_LEN? msg->len : MAVLINK_MSG_ID_OPEN_DRONE_ID_AUTHENTICATION_LEN;
memset(open_drone_id_authentication, 0, MAVLINK_MSG_ID_OPEN_DRONE_ID_AUTHENTICATION_LEN);
memcpy(open_drone_id_authentication, _MAV_PAYLOAD(msg), len);
#endif
}

View file

@ -0,0 +1,331 @@
#pragma once
// MESSAGE OPEN_DRONE_ID_BASIC_ID PACKING
#define MAVLINK_MSG_ID_OPEN_DRONE_ID_BASIC_ID 12900
typedef struct __mavlink_open_drone_id_basic_id_t {
uint8_t target_system; /*< System ID (0 for broadcast).*/
uint8_t target_component; /*< Component ID (0 for broadcast).*/
uint8_t id_or_mac[20]; /*< Only used for drone ID data received from other UAs. See detailed description at https://mavlink.io/en/services/opendroneid.html. */
uint8_t id_type; /*< Indicates the format for the uas_id field of this message.*/
uint8_t ua_type; /*< Indicates the type of UA (Unmanned Aircraft).*/
uint8_t uas_id[20]; /*< UAS (Unmanned Aircraft System) ID following the format specified by id_type. Shall be filled with nulls in the unused portion of the field.*/
} mavlink_open_drone_id_basic_id_t;
#define MAVLINK_MSG_ID_OPEN_DRONE_ID_BASIC_ID_LEN 44
#define MAVLINK_MSG_ID_OPEN_DRONE_ID_BASIC_ID_MIN_LEN 44
#define MAVLINK_MSG_ID_12900_LEN 44
#define MAVLINK_MSG_ID_12900_MIN_LEN 44
#define MAVLINK_MSG_ID_OPEN_DRONE_ID_BASIC_ID_CRC 114
#define MAVLINK_MSG_ID_12900_CRC 114
#define MAVLINK_MSG_OPEN_DRONE_ID_BASIC_ID_FIELD_ID_OR_MAC_LEN 20
#define MAVLINK_MSG_OPEN_DRONE_ID_BASIC_ID_FIELD_UAS_ID_LEN 20
#if MAVLINK_COMMAND_24BIT
#define MAVLINK_MESSAGE_INFO_OPEN_DRONE_ID_BASIC_ID { \
12900, \
"OPEN_DRONE_ID_BASIC_ID", \
6, \
{ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_open_drone_id_basic_id_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_open_drone_id_basic_id_t, target_component) }, \
{ "id_or_mac", NULL, MAVLINK_TYPE_UINT8_T, 20, 2, offsetof(mavlink_open_drone_id_basic_id_t, id_or_mac) }, \
{ "id_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 22, offsetof(mavlink_open_drone_id_basic_id_t, id_type) }, \
{ "ua_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 23, offsetof(mavlink_open_drone_id_basic_id_t, ua_type) }, \
{ "uas_id", NULL, MAVLINK_TYPE_UINT8_T, 20, 24, offsetof(mavlink_open_drone_id_basic_id_t, uas_id) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_OPEN_DRONE_ID_BASIC_ID { \
"OPEN_DRONE_ID_BASIC_ID", \
6, \
{ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_open_drone_id_basic_id_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_open_drone_id_basic_id_t, target_component) }, \
{ "id_or_mac", NULL, MAVLINK_TYPE_UINT8_T, 20, 2, offsetof(mavlink_open_drone_id_basic_id_t, id_or_mac) }, \
{ "id_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 22, offsetof(mavlink_open_drone_id_basic_id_t, id_type) }, \
{ "ua_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 23, offsetof(mavlink_open_drone_id_basic_id_t, ua_type) }, \
{ "uas_id", NULL, MAVLINK_TYPE_UINT8_T, 20, 24, offsetof(mavlink_open_drone_id_basic_id_t, uas_id) }, \
} \
}
#endif
/**
* @brief Pack a open_drone_id_basic_id message
* @param system_id ID of this 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 (0 for broadcast).
* @param target_component Component ID (0 for broadcast).
* @param id_or_mac Only used for drone ID data received from other UAs. See detailed description at https://mavlink.io/en/services/opendroneid.html.
* @param id_type Indicates the format for the uas_id field of this message.
* @param ua_type Indicates the type of UA (Unmanned Aircraft).
* @param uas_id UAS (Unmanned Aircraft System) ID following the format specified by id_type. Shall be filled with nulls in the unused portion of the field.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_open_drone_id_basic_id_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t target_system, uint8_t target_component, const uint8_t *id_or_mac, uint8_t id_type, uint8_t ua_type, const uint8_t *uas_id)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_OPEN_DRONE_ID_BASIC_ID_LEN];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
_mav_put_uint8_t(buf, 22, id_type);
_mav_put_uint8_t(buf, 23, ua_type);
_mav_put_uint8_t_array(buf, 2, id_or_mac, 20);
_mav_put_uint8_t_array(buf, 24, uas_id, 20);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_OPEN_DRONE_ID_BASIC_ID_LEN);
#else
mavlink_open_drone_id_basic_id_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
packet.id_type = id_type;
packet.ua_type = ua_type;
mav_array_memcpy(packet.id_or_mac, id_or_mac, sizeof(uint8_t)*20);
mav_array_memcpy(packet.uas_id, uas_id, sizeof(uint8_t)*20);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_OPEN_DRONE_ID_BASIC_ID_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_OPEN_DRONE_ID_BASIC_ID;
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_OPEN_DRONE_ID_BASIC_ID_MIN_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_BASIC_ID_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_BASIC_ID_CRC);
}
/**
* @brief Pack a open_drone_id_basic_id message on a channel
* @param system_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 (0 for broadcast).
* @param target_component Component ID (0 for broadcast).
* @param id_or_mac Only used for drone ID data received from other UAs. See detailed description at https://mavlink.io/en/services/opendroneid.html.
* @param id_type Indicates the format for the uas_id field of this message.
* @param ua_type Indicates the type of UA (Unmanned Aircraft).
* @param uas_id UAS (Unmanned Aircraft System) ID following the format specified by id_type. Shall be filled with nulls in the unused portion of the field.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_open_drone_id_basic_id_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 uint8_t *id_or_mac,uint8_t id_type,uint8_t ua_type,const uint8_t *uas_id)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_OPEN_DRONE_ID_BASIC_ID_LEN];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
_mav_put_uint8_t(buf, 22, id_type);
_mav_put_uint8_t(buf, 23, ua_type);
_mav_put_uint8_t_array(buf, 2, id_or_mac, 20);
_mav_put_uint8_t_array(buf, 24, uas_id, 20);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_OPEN_DRONE_ID_BASIC_ID_LEN);
#else
mavlink_open_drone_id_basic_id_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
packet.id_type = id_type;
packet.ua_type = ua_type;
mav_array_memcpy(packet.id_or_mac, id_or_mac, sizeof(uint8_t)*20);
mav_array_memcpy(packet.uas_id, uas_id, sizeof(uint8_t)*20);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_OPEN_DRONE_ID_BASIC_ID_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_OPEN_DRONE_ID_BASIC_ID;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_OPEN_DRONE_ID_BASIC_ID_MIN_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_BASIC_ID_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_BASIC_ID_CRC);
}
/**
* @brief Encode a open_drone_id_basic_id 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 open_drone_id_basic_id C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_open_drone_id_basic_id_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_open_drone_id_basic_id_t* open_drone_id_basic_id)
{
return mavlink_msg_open_drone_id_basic_id_pack(system_id, component_id, msg, open_drone_id_basic_id->target_system, open_drone_id_basic_id->target_component, open_drone_id_basic_id->id_or_mac, open_drone_id_basic_id->id_type, open_drone_id_basic_id->ua_type, open_drone_id_basic_id->uas_id);
}
/**
* @brief Encode a open_drone_id_basic_id 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 open_drone_id_basic_id C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_open_drone_id_basic_id_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_open_drone_id_basic_id_t* open_drone_id_basic_id)
{
return mavlink_msg_open_drone_id_basic_id_pack_chan(system_id, component_id, chan, msg, open_drone_id_basic_id->target_system, open_drone_id_basic_id->target_component, open_drone_id_basic_id->id_or_mac, open_drone_id_basic_id->id_type, open_drone_id_basic_id->ua_type, open_drone_id_basic_id->uas_id);
}
/**
* @brief Send a open_drone_id_basic_id message
* @param chan MAVLink channel to send the message
*
* @param target_system System ID (0 for broadcast).
* @param target_component Component ID (0 for broadcast).
* @param id_or_mac Only used for drone ID data received from other UAs. See detailed description at https://mavlink.io/en/services/opendroneid.html.
* @param id_type Indicates the format for the uas_id field of this message.
* @param ua_type Indicates the type of UA (Unmanned Aircraft).
* @param uas_id UAS (Unmanned Aircraft System) ID following the format specified by id_type. Shall be filled with nulls in the unused portion of the field.
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_open_drone_id_basic_id_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, const uint8_t *id_or_mac, uint8_t id_type, uint8_t ua_type, const uint8_t *uas_id)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_OPEN_DRONE_ID_BASIC_ID_LEN];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
_mav_put_uint8_t(buf, 22, id_type);
_mav_put_uint8_t(buf, 23, ua_type);
_mav_put_uint8_t_array(buf, 2, id_or_mac, 20);
_mav_put_uint8_t_array(buf, 24, uas_id, 20);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPEN_DRONE_ID_BASIC_ID, buf, MAVLINK_MSG_ID_OPEN_DRONE_ID_BASIC_ID_MIN_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_BASIC_ID_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_BASIC_ID_CRC);
#else
mavlink_open_drone_id_basic_id_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
packet.id_type = id_type;
packet.ua_type = ua_type;
mav_array_memcpy(packet.id_or_mac, id_or_mac, sizeof(uint8_t)*20);
mav_array_memcpy(packet.uas_id, uas_id, sizeof(uint8_t)*20);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPEN_DRONE_ID_BASIC_ID, (const char *)&packet, MAVLINK_MSG_ID_OPEN_DRONE_ID_BASIC_ID_MIN_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_BASIC_ID_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_BASIC_ID_CRC);
#endif
}
/**
* @brief Send a open_drone_id_basic_id message
* @param chan MAVLink channel to send the message
* @param struct The MAVLink struct to serialize
*/
static inline void mavlink_msg_open_drone_id_basic_id_send_struct(mavlink_channel_t chan, const mavlink_open_drone_id_basic_id_t* open_drone_id_basic_id)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mavlink_msg_open_drone_id_basic_id_send(chan, open_drone_id_basic_id->target_system, open_drone_id_basic_id->target_component, open_drone_id_basic_id->id_or_mac, open_drone_id_basic_id->id_type, open_drone_id_basic_id->ua_type, open_drone_id_basic_id->uas_id);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPEN_DRONE_ID_BASIC_ID, (const char *)open_drone_id_basic_id, MAVLINK_MSG_ID_OPEN_DRONE_ID_BASIC_ID_MIN_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_BASIC_ID_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_BASIC_ID_CRC);
#endif
}
#if MAVLINK_MSG_ID_OPEN_DRONE_ID_BASIC_ID_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_open_drone_id_basic_id_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, const uint8_t *id_or_mac, uint8_t id_type, uint8_t ua_type, const uint8_t *uas_id)
{
#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, 22, id_type);
_mav_put_uint8_t(buf, 23, ua_type);
_mav_put_uint8_t_array(buf, 2, id_or_mac, 20);
_mav_put_uint8_t_array(buf, 24, uas_id, 20);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPEN_DRONE_ID_BASIC_ID, buf, MAVLINK_MSG_ID_OPEN_DRONE_ID_BASIC_ID_MIN_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_BASIC_ID_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_BASIC_ID_CRC);
#else
mavlink_open_drone_id_basic_id_t *packet = (mavlink_open_drone_id_basic_id_t *)msgbuf;
packet->target_system = target_system;
packet->target_component = target_component;
packet->id_type = id_type;
packet->ua_type = ua_type;
mav_array_memcpy(packet->id_or_mac, id_or_mac, sizeof(uint8_t)*20);
mav_array_memcpy(packet->uas_id, uas_id, sizeof(uint8_t)*20);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPEN_DRONE_ID_BASIC_ID, (const char *)packet, MAVLINK_MSG_ID_OPEN_DRONE_ID_BASIC_ID_MIN_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_BASIC_ID_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_BASIC_ID_CRC);
#endif
}
#endif
#endif
// MESSAGE OPEN_DRONE_ID_BASIC_ID UNPACKING
/**
* @brief Get field target_system from open_drone_id_basic_id message
*
* @return System ID (0 for broadcast).
*/
static inline uint8_t mavlink_msg_open_drone_id_basic_id_get_target_system(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 0);
}
/**
* @brief Get field target_component from open_drone_id_basic_id message
*
* @return Component ID (0 for broadcast).
*/
static inline uint8_t mavlink_msg_open_drone_id_basic_id_get_target_component(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 1);
}
/**
* @brief Get field id_or_mac from open_drone_id_basic_id message
*
* @return Only used for drone ID data received from other UAs. See detailed description at https://mavlink.io/en/services/opendroneid.html.
*/
static inline uint16_t mavlink_msg_open_drone_id_basic_id_get_id_or_mac(const mavlink_message_t* msg, uint8_t *id_or_mac)
{
return _MAV_RETURN_uint8_t_array(msg, id_or_mac, 20, 2);
}
/**
* @brief Get field id_type from open_drone_id_basic_id message
*
* @return Indicates the format for the uas_id field of this message.
*/
static inline uint8_t mavlink_msg_open_drone_id_basic_id_get_id_type(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 22);
}
/**
* @brief Get field ua_type from open_drone_id_basic_id message
*
* @return Indicates the type of UA (Unmanned Aircraft).
*/
static inline uint8_t mavlink_msg_open_drone_id_basic_id_get_ua_type(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 23);
}
/**
* @brief Get field uas_id from open_drone_id_basic_id message
*
* @return UAS (Unmanned Aircraft System) ID following the format specified by id_type. Shall be filled with nulls in the unused portion of the field.
*/
static inline uint16_t mavlink_msg_open_drone_id_basic_id_get_uas_id(const mavlink_message_t* msg, uint8_t *uas_id)
{
return _MAV_RETURN_uint8_t_array(msg, uas_id, 20, 24);
}
/**
* @brief Decode a open_drone_id_basic_id message into a struct
*
* @param msg The message to decode
* @param open_drone_id_basic_id C-struct to decode the message contents into
*/
static inline void mavlink_msg_open_drone_id_basic_id_decode(const mavlink_message_t* msg, mavlink_open_drone_id_basic_id_t* open_drone_id_basic_id)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
open_drone_id_basic_id->target_system = mavlink_msg_open_drone_id_basic_id_get_target_system(msg);
open_drone_id_basic_id->target_component = mavlink_msg_open_drone_id_basic_id_get_target_component(msg);
mavlink_msg_open_drone_id_basic_id_get_id_or_mac(msg, open_drone_id_basic_id->id_or_mac);
open_drone_id_basic_id->id_type = mavlink_msg_open_drone_id_basic_id_get_id_type(msg);
open_drone_id_basic_id->ua_type = mavlink_msg_open_drone_id_basic_id_get_ua_type(msg);
mavlink_msg_open_drone_id_basic_id_get_uas_id(msg, open_drone_id_basic_id->uas_id);
#else
uint8_t len = msg->len < MAVLINK_MSG_ID_OPEN_DRONE_ID_BASIC_ID_LEN? msg->len : MAVLINK_MSG_ID_OPEN_DRONE_ID_BASIC_ID_LEN;
memset(open_drone_id_basic_id, 0, MAVLINK_MSG_ID_OPEN_DRONE_ID_BASIC_ID_LEN);
memcpy(open_drone_id_basic_id, _MAV_PAYLOAD(msg), len);
#endif
}

View file

@ -0,0 +1,655 @@
#pragma once
// MESSAGE OPEN_DRONE_ID_LOCATION PACKING
#define MAVLINK_MSG_ID_OPEN_DRONE_ID_LOCATION 12901
typedef struct __mavlink_open_drone_id_location_t {
int32_t latitude; /*< [degE7] Current latitude of the unmanned aircraft. If unknown: 0 (both Lat/Lon).*/
int32_t longitude; /*< [degE7] Current longitude of the unmanned aircraft. If unknown: 0 (both Lat/Lon).*/
float altitude_barometric; /*< [m] The altitude calculated from the barometric pressue. Reference is against 29.92inHg or 1013.2mb. If unknown: -1000 m.*/
float altitude_geodetic; /*< [m] The geodetic altitude as defined by WGS84. If unknown: -1000 m.*/
float height; /*< [m] The current height of the unmanned aircraft above the take-off location or the ground as indicated by height_reference. If unknown: -1000 m.*/
float timestamp; /*< [s] Seconds after the full hour with reference to UTC time. Typically the GPS outputs a time-of-week value in milliseconds. First convert that to UTC and then convert for this field using ((float) (time_week_ms % (60*60*1000))) / 1000.*/
uint16_t direction; /*< [cdeg] Direction over ground (not heading, but direction of movement) measured clockwise from true North: 0 - 35999 centi-degrees. If unknown: 36100 centi-degrees.*/
uint16_t speed_horizontal; /*< [cm/s] Ground speed. Positive only. If unknown: 25500 cm/s. If speed is larger than 25425 cm/s, use 25425 cm/s.*/
int16_t speed_vertical; /*< [cm/s] The vertical speed. Up is positive. If unknown: 6300 cm/s. If speed is larger than 6200 cm/s, use 6200 cm/s. If lower than -6200 cm/s, use -6200 cm/s.*/
uint8_t target_system; /*< System ID (0 for broadcast).*/
uint8_t target_component; /*< Component ID (0 for broadcast).*/
uint8_t id_or_mac[20]; /*< Only used for drone ID data received from other UAs. See detailed description at https://mavlink.io/en/services/opendroneid.html. */
uint8_t status; /*< Indicates whether the unmanned aircraft is on the ground or in the air.*/
uint8_t height_reference; /*< Indicates the reference point for the height field.*/
uint8_t horizontal_accuracy; /*< The accuracy of the horizontal position.*/
uint8_t vertical_accuracy; /*< The accuracy of the vertical position.*/
uint8_t barometer_accuracy; /*< The accuracy of the barometric altitude.*/
uint8_t speed_accuracy; /*< The accuracy of the horizontal and vertical speed.*/
uint8_t timestamp_accuracy; /*< The accuracy of the timestamps.*/
} mavlink_open_drone_id_location_t;
#define MAVLINK_MSG_ID_OPEN_DRONE_ID_LOCATION_LEN 59
#define MAVLINK_MSG_ID_OPEN_DRONE_ID_LOCATION_MIN_LEN 59
#define MAVLINK_MSG_ID_12901_LEN 59
#define MAVLINK_MSG_ID_12901_MIN_LEN 59
#define MAVLINK_MSG_ID_OPEN_DRONE_ID_LOCATION_CRC 254
#define MAVLINK_MSG_ID_12901_CRC 254
#define MAVLINK_MSG_OPEN_DRONE_ID_LOCATION_FIELD_ID_OR_MAC_LEN 20
#if MAVLINK_COMMAND_24BIT
#define MAVLINK_MESSAGE_INFO_OPEN_DRONE_ID_LOCATION { \
12901, \
"OPEN_DRONE_ID_LOCATION", \
19, \
{ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 30, offsetof(mavlink_open_drone_id_location_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 31, offsetof(mavlink_open_drone_id_location_t, target_component) }, \
{ "id_or_mac", NULL, MAVLINK_TYPE_UINT8_T, 20, 32, offsetof(mavlink_open_drone_id_location_t, id_or_mac) }, \
{ "status", NULL, MAVLINK_TYPE_UINT8_T, 0, 52, offsetof(mavlink_open_drone_id_location_t, status) }, \
{ "direction", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_open_drone_id_location_t, direction) }, \
{ "speed_horizontal", NULL, MAVLINK_TYPE_UINT16_T, 0, 26, offsetof(mavlink_open_drone_id_location_t, speed_horizontal) }, \
{ "speed_vertical", NULL, MAVLINK_TYPE_INT16_T, 0, 28, offsetof(mavlink_open_drone_id_location_t, speed_vertical) }, \
{ "latitude", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_open_drone_id_location_t, latitude) }, \
{ "longitude", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_open_drone_id_location_t, longitude) }, \
{ "altitude_barometric", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_open_drone_id_location_t, altitude_barometric) }, \
{ "altitude_geodetic", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_open_drone_id_location_t, altitude_geodetic) }, \
{ "height_reference", NULL, MAVLINK_TYPE_UINT8_T, 0, 53, offsetof(mavlink_open_drone_id_location_t, height_reference) }, \
{ "height", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_open_drone_id_location_t, height) }, \
{ "horizontal_accuracy", NULL, MAVLINK_TYPE_UINT8_T, 0, 54, offsetof(mavlink_open_drone_id_location_t, horizontal_accuracy) }, \
{ "vertical_accuracy", NULL, MAVLINK_TYPE_UINT8_T, 0, 55, offsetof(mavlink_open_drone_id_location_t, vertical_accuracy) }, \
{ "barometer_accuracy", NULL, MAVLINK_TYPE_UINT8_T, 0, 56, offsetof(mavlink_open_drone_id_location_t, barometer_accuracy) }, \
{ "speed_accuracy", NULL, MAVLINK_TYPE_UINT8_T, 0, 57, offsetof(mavlink_open_drone_id_location_t, speed_accuracy) }, \
{ "timestamp", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_open_drone_id_location_t, timestamp) }, \
{ "timestamp_accuracy", NULL, MAVLINK_TYPE_UINT8_T, 0, 58, offsetof(mavlink_open_drone_id_location_t, timestamp_accuracy) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_OPEN_DRONE_ID_LOCATION { \
"OPEN_DRONE_ID_LOCATION", \
19, \
{ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 30, offsetof(mavlink_open_drone_id_location_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 31, offsetof(mavlink_open_drone_id_location_t, target_component) }, \
{ "id_or_mac", NULL, MAVLINK_TYPE_UINT8_T, 20, 32, offsetof(mavlink_open_drone_id_location_t, id_or_mac) }, \
{ "status", NULL, MAVLINK_TYPE_UINT8_T, 0, 52, offsetof(mavlink_open_drone_id_location_t, status) }, \
{ "direction", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_open_drone_id_location_t, direction) }, \
{ "speed_horizontal", NULL, MAVLINK_TYPE_UINT16_T, 0, 26, offsetof(mavlink_open_drone_id_location_t, speed_horizontal) }, \
{ "speed_vertical", NULL, MAVLINK_TYPE_INT16_T, 0, 28, offsetof(mavlink_open_drone_id_location_t, speed_vertical) }, \
{ "latitude", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_open_drone_id_location_t, latitude) }, \
{ "longitude", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_open_drone_id_location_t, longitude) }, \
{ "altitude_barometric", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_open_drone_id_location_t, altitude_barometric) }, \
{ "altitude_geodetic", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_open_drone_id_location_t, altitude_geodetic) }, \
{ "height_reference", NULL, MAVLINK_TYPE_UINT8_T, 0, 53, offsetof(mavlink_open_drone_id_location_t, height_reference) }, \
{ "height", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_open_drone_id_location_t, height) }, \
{ "horizontal_accuracy", NULL, MAVLINK_TYPE_UINT8_T, 0, 54, offsetof(mavlink_open_drone_id_location_t, horizontal_accuracy) }, \
{ "vertical_accuracy", NULL, MAVLINK_TYPE_UINT8_T, 0, 55, offsetof(mavlink_open_drone_id_location_t, vertical_accuracy) }, \
{ "barometer_accuracy", NULL, MAVLINK_TYPE_UINT8_T, 0, 56, offsetof(mavlink_open_drone_id_location_t, barometer_accuracy) }, \
{ "speed_accuracy", NULL, MAVLINK_TYPE_UINT8_T, 0, 57, offsetof(mavlink_open_drone_id_location_t, speed_accuracy) }, \
{ "timestamp", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_open_drone_id_location_t, timestamp) }, \
{ "timestamp_accuracy", NULL, MAVLINK_TYPE_UINT8_T, 0, 58, offsetof(mavlink_open_drone_id_location_t, timestamp_accuracy) }, \
} \
}
#endif
/**
* @brief Pack a open_drone_id_location message
* @param system_id ID of this 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 (0 for broadcast).
* @param target_component Component ID (0 for broadcast).
* @param id_or_mac Only used for drone ID data received from other UAs. See detailed description at https://mavlink.io/en/services/opendroneid.html.
* @param status Indicates whether the unmanned aircraft is on the ground or in the air.
* @param direction [cdeg] Direction over ground (not heading, but direction of movement) measured clockwise from true North: 0 - 35999 centi-degrees. If unknown: 36100 centi-degrees.
* @param speed_horizontal [cm/s] Ground speed. Positive only. If unknown: 25500 cm/s. If speed is larger than 25425 cm/s, use 25425 cm/s.
* @param speed_vertical [cm/s] The vertical speed. Up is positive. If unknown: 6300 cm/s. If speed is larger than 6200 cm/s, use 6200 cm/s. If lower than -6200 cm/s, use -6200 cm/s.
* @param latitude [degE7] Current latitude of the unmanned aircraft. If unknown: 0 (both Lat/Lon).
* @param longitude [degE7] Current longitude of the unmanned aircraft. If unknown: 0 (both Lat/Lon).
* @param altitude_barometric [m] The altitude calculated from the barometric pressue. Reference is against 29.92inHg or 1013.2mb. If unknown: -1000 m.
* @param altitude_geodetic [m] The geodetic altitude as defined by WGS84. If unknown: -1000 m.
* @param height_reference Indicates the reference point for the height field.
* @param height [m] The current height of the unmanned aircraft above the take-off location or the ground as indicated by height_reference. If unknown: -1000 m.
* @param horizontal_accuracy The accuracy of the horizontal position.
* @param vertical_accuracy The accuracy of the vertical position.
* @param barometer_accuracy The accuracy of the barometric altitude.
* @param speed_accuracy The accuracy of the horizontal and vertical speed.
* @param timestamp [s] Seconds after the full hour with reference to UTC time. Typically the GPS outputs a time-of-week value in milliseconds. First convert that to UTC and then convert for this field using ((float) (time_week_ms % (60*60*1000))) / 1000.
* @param timestamp_accuracy The accuracy of the timestamps.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_open_drone_id_location_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t target_system, uint8_t target_component, const uint8_t *id_or_mac, uint8_t status, uint16_t direction, uint16_t speed_horizontal, int16_t speed_vertical, int32_t latitude, int32_t longitude, float altitude_barometric, float altitude_geodetic, uint8_t height_reference, float height, uint8_t horizontal_accuracy, uint8_t vertical_accuracy, uint8_t barometer_accuracy, uint8_t speed_accuracy, float timestamp, uint8_t timestamp_accuracy)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_OPEN_DRONE_ID_LOCATION_LEN];
_mav_put_int32_t(buf, 0, latitude);
_mav_put_int32_t(buf, 4, longitude);
_mav_put_float(buf, 8, altitude_barometric);
_mav_put_float(buf, 12, altitude_geodetic);
_mav_put_float(buf, 16, height);
_mav_put_float(buf, 20, timestamp);
_mav_put_uint16_t(buf, 24, direction);
_mav_put_uint16_t(buf, 26, speed_horizontal);
_mav_put_int16_t(buf, 28, speed_vertical);
_mav_put_uint8_t(buf, 30, target_system);
_mav_put_uint8_t(buf, 31, target_component);
_mav_put_uint8_t(buf, 52, status);
_mav_put_uint8_t(buf, 53, height_reference);
_mav_put_uint8_t(buf, 54, horizontal_accuracy);
_mav_put_uint8_t(buf, 55, vertical_accuracy);
_mav_put_uint8_t(buf, 56, barometer_accuracy);
_mav_put_uint8_t(buf, 57, speed_accuracy);
_mav_put_uint8_t(buf, 58, timestamp_accuracy);
_mav_put_uint8_t_array(buf, 32, id_or_mac, 20);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_OPEN_DRONE_ID_LOCATION_LEN);
#else
mavlink_open_drone_id_location_t packet;
packet.latitude = latitude;
packet.longitude = longitude;
packet.altitude_barometric = altitude_barometric;
packet.altitude_geodetic = altitude_geodetic;
packet.height = height;
packet.timestamp = timestamp;
packet.direction = direction;
packet.speed_horizontal = speed_horizontal;
packet.speed_vertical = speed_vertical;
packet.target_system = target_system;
packet.target_component = target_component;
packet.status = status;
packet.height_reference = height_reference;
packet.horizontal_accuracy = horizontal_accuracy;
packet.vertical_accuracy = vertical_accuracy;
packet.barometer_accuracy = barometer_accuracy;
packet.speed_accuracy = speed_accuracy;
packet.timestamp_accuracy = timestamp_accuracy;
mav_array_memcpy(packet.id_or_mac, id_or_mac, sizeof(uint8_t)*20);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_OPEN_DRONE_ID_LOCATION_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_OPEN_DRONE_ID_LOCATION;
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_OPEN_DRONE_ID_LOCATION_MIN_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_LOCATION_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_LOCATION_CRC);
}
/**
* @brief Pack a open_drone_id_location message on a channel
* @param system_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 (0 for broadcast).
* @param target_component Component ID (0 for broadcast).
* @param id_or_mac Only used for drone ID data received from other UAs. See detailed description at https://mavlink.io/en/services/opendroneid.html.
* @param status Indicates whether the unmanned aircraft is on the ground or in the air.
* @param direction [cdeg] Direction over ground (not heading, but direction of movement) measured clockwise from true North: 0 - 35999 centi-degrees. If unknown: 36100 centi-degrees.
* @param speed_horizontal [cm/s] Ground speed. Positive only. If unknown: 25500 cm/s. If speed is larger than 25425 cm/s, use 25425 cm/s.
* @param speed_vertical [cm/s] The vertical speed. Up is positive. If unknown: 6300 cm/s. If speed is larger than 6200 cm/s, use 6200 cm/s. If lower than -6200 cm/s, use -6200 cm/s.
* @param latitude [degE7] Current latitude of the unmanned aircraft. If unknown: 0 (both Lat/Lon).
* @param longitude [degE7] Current longitude of the unmanned aircraft. If unknown: 0 (both Lat/Lon).
* @param altitude_barometric [m] The altitude calculated from the barometric pressue. Reference is against 29.92inHg or 1013.2mb. If unknown: -1000 m.
* @param altitude_geodetic [m] The geodetic altitude as defined by WGS84. If unknown: -1000 m.
* @param height_reference Indicates the reference point for the height field.
* @param height [m] The current height of the unmanned aircraft above the take-off location or the ground as indicated by height_reference. If unknown: -1000 m.
* @param horizontal_accuracy The accuracy of the horizontal position.
* @param vertical_accuracy The accuracy of the vertical position.
* @param barometer_accuracy The accuracy of the barometric altitude.
* @param speed_accuracy The accuracy of the horizontal and vertical speed.
* @param timestamp [s] Seconds after the full hour with reference to UTC time. Typically the GPS outputs a time-of-week value in milliseconds. First convert that to UTC and then convert for this field using ((float) (time_week_ms % (60*60*1000))) / 1000.
* @param timestamp_accuracy The accuracy of the timestamps.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_open_drone_id_location_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 uint8_t *id_or_mac,uint8_t status,uint16_t direction,uint16_t speed_horizontal,int16_t speed_vertical,int32_t latitude,int32_t longitude,float altitude_barometric,float altitude_geodetic,uint8_t height_reference,float height,uint8_t horizontal_accuracy,uint8_t vertical_accuracy,uint8_t barometer_accuracy,uint8_t speed_accuracy,float timestamp,uint8_t timestamp_accuracy)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_OPEN_DRONE_ID_LOCATION_LEN];
_mav_put_int32_t(buf, 0, latitude);
_mav_put_int32_t(buf, 4, longitude);
_mav_put_float(buf, 8, altitude_barometric);
_mav_put_float(buf, 12, altitude_geodetic);
_mav_put_float(buf, 16, height);
_mav_put_float(buf, 20, timestamp);
_mav_put_uint16_t(buf, 24, direction);
_mav_put_uint16_t(buf, 26, speed_horizontal);
_mav_put_int16_t(buf, 28, speed_vertical);
_mav_put_uint8_t(buf, 30, target_system);
_mav_put_uint8_t(buf, 31, target_component);
_mav_put_uint8_t(buf, 52, status);
_mav_put_uint8_t(buf, 53, height_reference);
_mav_put_uint8_t(buf, 54, horizontal_accuracy);
_mav_put_uint8_t(buf, 55, vertical_accuracy);
_mav_put_uint8_t(buf, 56, barometer_accuracy);
_mav_put_uint8_t(buf, 57, speed_accuracy);
_mav_put_uint8_t(buf, 58, timestamp_accuracy);
_mav_put_uint8_t_array(buf, 32, id_or_mac, 20);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_OPEN_DRONE_ID_LOCATION_LEN);
#else
mavlink_open_drone_id_location_t packet;
packet.latitude = latitude;
packet.longitude = longitude;
packet.altitude_barometric = altitude_barometric;
packet.altitude_geodetic = altitude_geodetic;
packet.height = height;
packet.timestamp = timestamp;
packet.direction = direction;
packet.speed_horizontal = speed_horizontal;
packet.speed_vertical = speed_vertical;
packet.target_system = target_system;
packet.target_component = target_component;
packet.status = status;
packet.height_reference = height_reference;
packet.horizontal_accuracy = horizontal_accuracy;
packet.vertical_accuracy = vertical_accuracy;
packet.barometer_accuracy = barometer_accuracy;
packet.speed_accuracy = speed_accuracy;
packet.timestamp_accuracy = timestamp_accuracy;
mav_array_memcpy(packet.id_or_mac, id_or_mac, sizeof(uint8_t)*20);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_OPEN_DRONE_ID_LOCATION_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_OPEN_DRONE_ID_LOCATION;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_OPEN_DRONE_ID_LOCATION_MIN_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_LOCATION_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_LOCATION_CRC);
}
/**
* @brief Encode a open_drone_id_location 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 open_drone_id_location C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_open_drone_id_location_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_open_drone_id_location_t* open_drone_id_location)
{
return mavlink_msg_open_drone_id_location_pack(system_id, component_id, msg, open_drone_id_location->target_system, open_drone_id_location->target_component, open_drone_id_location->id_or_mac, open_drone_id_location->status, open_drone_id_location->direction, open_drone_id_location->speed_horizontal, open_drone_id_location->speed_vertical, open_drone_id_location->latitude, open_drone_id_location->longitude, open_drone_id_location->altitude_barometric, open_drone_id_location->altitude_geodetic, open_drone_id_location->height_reference, open_drone_id_location->height, open_drone_id_location->horizontal_accuracy, open_drone_id_location->vertical_accuracy, open_drone_id_location->barometer_accuracy, open_drone_id_location->speed_accuracy, open_drone_id_location->timestamp, open_drone_id_location->timestamp_accuracy);
}
/**
* @brief Encode a open_drone_id_location 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 open_drone_id_location C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_open_drone_id_location_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_open_drone_id_location_t* open_drone_id_location)
{
return mavlink_msg_open_drone_id_location_pack_chan(system_id, component_id, chan, msg, open_drone_id_location->target_system, open_drone_id_location->target_component, open_drone_id_location->id_or_mac, open_drone_id_location->status, open_drone_id_location->direction, open_drone_id_location->speed_horizontal, open_drone_id_location->speed_vertical, open_drone_id_location->latitude, open_drone_id_location->longitude, open_drone_id_location->altitude_barometric, open_drone_id_location->altitude_geodetic, open_drone_id_location->height_reference, open_drone_id_location->height, open_drone_id_location->horizontal_accuracy, open_drone_id_location->vertical_accuracy, open_drone_id_location->barometer_accuracy, open_drone_id_location->speed_accuracy, open_drone_id_location->timestamp, open_drone_id_location->timestamp_accuracy);
}
/**
* @brief Send a open_drone_id_location message
* @param chan MAVLink channel to send the message
*
* @param target_system System ID (0 for broadcast).
* @param target_component Component ID (0 for broadcast).
* @param id_or_mac Only used for drone ID data received from other UAs. See detailed description at https://mavlink.io/en/services/opendroneid.html.
* @param status Indicates whether the unmanned aircraft is on the ground or in the air.
* @param direction [cdeg] Direction over ground (not heading, but direction of movement) measured clockwise from true North: 0 - 35999 centi-degrees. If unknown: 36100 centi-degrees.
* @param speed_horizontal [cm/s] Ground speed. Positive only. If unknown: 25500 cm/s. If speed is larger than 25425 cm/s, use 25425 cm/s.
* @param speed_vertical [cm/s] The vertical speed. Up is positive. If unknown: 6300 cm/s. If speed is larger than 6200 cm/s, use 6200 cm/s. If lower than -6200 cm/s, use -6200 cm/s.
* @param latitude [degE7] Current latitude of the unmanned aircraft. If unknown: 0 (both Lat/Lon).
* @param longitude [degE7] Current longitude of the unmanned aircraft. If unknown: 0 (both Lat/Lon).
* @param altitude_barometric [m] The altitude calculated from the barometric pressue. Reference is against 29.92inHg or 1013.2mb. If unknown: -1000 m.
* @param altitude_geodetic [m] The geodetic altitude as defined by WGS84. If unknown: -1000 m.
* @param height_reference Indicates the reference point for the height field.
* @param height [m] The current height of the unmanned aircraft above the take-off location or the ground as indicated by height_reference. If unknown: -1000 m.
* @param horizontal_accuracy The accuracy of the horizontal position.
* @param vertical_accuracy The accuracy of the vertical position.
* @param barometer_accuracy The accuracy of the barometric altitude.
* @param speed_accuracy The accuracy of the horizontal and vertical speed.
* @param timestamp [s] Seconds after the full hour with reference to UTC time. Typically the GPS outputs a time-of-week value in milliseconds. First convert that to UTC and then convert for this field using ((float) (time_week_ms % (60*60*1000))) / 1000.
* @param timestamp_accuracy The accuracy of the timestamps.
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_open_drone_id_location_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, const uint8_t *id_or_mac, uint8_t status, uint16_t direction, uint16_t speed_horizontal, int16_t speed_vertical, int32_t latitude, int32_t longitude, float altitude_barometric, float altitude_geodetic, uint8_t height_reference, float height, uint8_t horizontal_accuracy, uint8_t vertical_accuracy, uint8_t barometer_accuracy, uint8_t speed_accuracy, float timestamp, uint8_t timestamp_accuracy)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_OPEN_DRONE_ID_LOCATION_LEN];
_mav_put_int32_t(buf, 0, latitude);
_mav_put_int32_t(buf, 4, longitude);
_mav_put_float(buf, 8, altitude_barometric);
_mav_put_float(buf, 12, altitude_geodetic);
_mav_put_float(buf, 16, height);
_mav_put_float(buf, 20, timestamp);
_mav_put_uint16_t(buf, 24, direction);
_mav_put_uint16_t(buf, 26, speed_horizontal);
_mav_put_int16_t(buf, 28, speed_vertical);
_mav_put_uint8_t(buf, 30, target_system);
_mav_put_uint8_t(buf, 31, target_component);
_mav_put_uint8_t(buf, 52, status);
_mav_put_uint8_t(buf, 53, height_reference);
_mav_put_uint8_t(buf, 54, horizontal_accuracy);
_mav_put_uint8_t(buf, 55, vertical_accuracy);
_mav_put_uint8_t(buf, 56, barometer_accuracy);
_mav_put_uint8_t(buf, 57, speed_accuracy);
_mav_put_uint8_t(buf, 58, timestamp_accuracy);
_mav_put_uint8_t_array(buf, 32, id_or_mac, 20);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPEN_DRONE_ID_LOCATION, buf, MAVLINK_MSG_ID_OPEN_DRONE_ID_LOCATION_MIN_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_LOCATION_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_LOCATION_CRC);
#else
mavlink_open_drone_id_location_t packet;
packet.latitude = latitude;
packet.longitude = longitude;
packet.altitude_barometric = altitude_barometric;
packet.altitude_geodetic = altitude_geodetic;
packet.height = height;
packet.timestamp = timestamp;
packet.direction = direction;
packet.speed_horizontal = speed_horizontal;
packet.speed_vertical = speed_vertical;
packet.target_system = target_system;
packet.target_component = target_component;
packet.status = status;
packet.height_reference = height_reference;
packet.horizontal_accuracy = horizontal_accuracy;
packet.vertical_accuracy = vertical_accuracy;
packet.barometer_accuracy = barometer_accuracy;
packet.speed_accuracy = speed_accuracy;
packet.timestamp_accuracy = timestamp_accuracy;
mav_array_memcpy(packet.id_or_mac, id_or_mac, sizeof(uint8_t)*20);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPEN_DRONE_ID_LOCATION, (const char *)&packet, MAVLINK_MSG_ID_OPEN_DRONE_ID_LOCATION_MIN_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_LOCATION_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_LOCATION_CRC);
#endif
}
/**
* @brief Send a open_drone_id_location message
* @param chan MAVLink channel to send the message
* @param struct The MAVLink struct to serialize
*/
static inline void mavlink_msg_open_drone_id_location_send_struct(mavlink_channel_t chan, const mavlink_open_drone_id_location_t* open_drone_id_location)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mavlink_msg_open_drone_id_location_send(chan, open_drone_id_location->target_system, open_drone_id_location->target_component, open_drone_id_location->id_or_mac, open_drone_id_location->status, open_drone_id_location->direction, open_drone_id_location->speed_horizontal, open_drone_id_location->speed_vertical, open_drone_id_location->latitude, open_drone_id_location->longitude, open_drone_id_location->altitude_barometric, open_drone_id_location->altitude_geodetic, open_drone_id_location->height_reference, open_drone_id_location->height, open_drone_id_location->horizontal_accuracy, open_drone_id_location->vertical_accuracy, open_drone_id_location->barometer_accuracy, open_drone_id_location->speed_accuracy, open_drone_id_location->timestamp, open_drone_id_location->timestamp_accuracy);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPEN_DRONE_ID_LOCATION, (const char *)open_drone_id_location, MAVLINK_MSG_ID_OPEN_DRONE_ID_LOCATION_MIN_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_LOCATION_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_LOCATION_CRC);
#endif
}
#if MAVLINK_MSG_ID_OPEN_DRONE_ID_LOCATION_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_open_drone_id_location_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, const uint8_t *id_or_mac, uint8_t status, uint16_t direction, uint16_t speed_horizontal, int16_t speed_vertical, int32_t latitude, int32_t longitude, float altitude_barometric, float altitude_geodetic, uint8_t height_reference, float height, uint8_t horizontal_accuracy, uint8_t vertical_accuracy, uint8_t barometer_accuracy, uint8_t speed_accuracy, float timestamp, uint8_t timestamp_accuracy)
{
#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_float(buf, 8, altitude_barometric);
_mav_put_float(buf, 12, altitude_geodetic);
_mav_put_float(buf, 16, height);
_mav_put_float(buf, 20, timestamp);
_mav_put_uint16_t(buf, 24, direction);
_mav_put_uint16_t(buf, 26, speed_horizontal);
_mav_put_int16_t(buf, 28, speed_vertical);
_mav_put_uint8_t(buf, 30, target_system);
_mav_put_uint8_t(buf, 31, target_component);
_mav_put_uint8_t(buf, 52, status);
_mav_put_uint8_t(buf, 53, height_reference);
_mav_put_uint8_t(buf, 54, horizontal_accuracy);
_mav_put_uint8_t(buf, 55, vertical_accuracy);
_mav_put_uint8_t(buf, 56, barometer_accuracy);
_mav_put_uint8_t(buf, 57, speed_accuracy);
_mav_put_uint8_t(buf, 58, timestamp_accuracy);
_mav_put_uint8_t_array(buf, 32, id_or_mac, 20);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPEN_DRONE_ID_LOCATION, buf, MAVLINK_MSG_ID_OPEN_DRONE_ID_LOCATION_MIN_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_LOCATION_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_LOCATION_CRC);
#else
mavlink_open_drone_id_location_t *packet = (mavlink_open_drone_id_location_t *)msgbuf;
packet->latitude = latitude;
packet->longitude = longitude;
packet->altitude_barometric = altitude_barometric;
packet->altitude_geodetic = altitude_geodetic;
packet->height = height;
packet->timestamp = timestamp;
packet->direction = direction;
packet->speed_horizontal = speed_horizontal;
packet->speed_vertical = speed_vertical;
packet->target_system = target_system;
packet->target_component = target_component;
packet->status = status;
packet->height_reference = height_reference;
packet->horizontal_accuracy = horizontal_accuracy;
packet->vertical_accuracy = vertical_accuracy;
packet->barometer_accuracy = barometer_accuracy;
packet->speed_accuracy = speed_accuracy;
packet->timestamp_accuracy = timestamp_accuracy;
mav_array_memcpy(packet->id_or_mac, id_or_mac, sizeof(uint8_t)*20);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPEN_DRONE_ID_LOCATION, (const char *)packet, MAVLINK_MSG_ID_OPEN_DRONE_ID_LOCATION_MIN_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_LOCATION_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_LOCATION_CRC);
#endif
}
#endif
#endif
// MESSAGE OPEN_DRONE_ID_LOCATION UNPACKING
/**
* @brief Get field target_system from open_drone_id_location message
*
* @return System ID (0 for broadcast).
*/
static inline uint8_t mavlink_msg_open_drone_id_location_get_target_system(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 30);
}
/**
* @brief Get field target_component from open_drone_id_location message
*
* @return Component ID (0 for broadcast).
*/
static inline uint8_t mavlink_msg_open_drone_id_location_get_target_component(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 31);
}
/**
* @brief Get field id_or_mac from open_drone_id_location message
*
* @return Only used for drone ID data received from other UAs. See detailed description at https://mavlink.io/en/services/opendroneid.html.
*/
static inline uint16_t mavlink_msg_open_drone_id_location_get_id_or_mac(const mavlink_message_t* msg, uint8_t *id_or_mac)
{
return _MAV_RETURN_uint8_t_array(msg, id_or_mac, 20, 32);
}
/**
* @brief Get field status from open_drone_id_location message
*
* @return Indicates whether the unmanned aircraft is on the ground or in the air.
*/
static inline uint8_t mavlink_msg_open_drone_id_location_get_status(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 52);
}
/**
* @brief Get field direction from open_drone_id_location message
*
* @return [cdeg] Direction over ground (not heading, but direction of movement) measured clockwise from true North: 0 - 35999 centi-degrees. If unknown: 36100 centi-degrees.
*/
static inline uint16_t mavlink_msg_open_drone_id_location_get_direction(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 24);
}
/**
* @brief Get field speed_horizontal from open_drone_id_location message
*
* @return [cm/s] Ground speed. Positive only. If unknown: 25500 cm/s. If speed is larger than 25425 cm/s, use 25425 cm/s.
*/
static inline uint16_t mavlink_msg_open_drone_id_location_get_speed_horizontal(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 26);
}
/**
* @brief Get field speed_vertical from open_drone_id_location message
*
* @return [cm/s] The vertical speed. Up is positive. If unknown: 6300 cm/s. If speed is larger than 6200 cm/s, use 6200 cm/s. If lower than -6200 cm/s, use -6200 cm/s.
*/
static inline int16_t mavlink_msg_open_drone_id_location_get_speed_vertical(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 28);
}
/**
* @brief Get field latitude from open_drone_id_location message
*
* @return [degE7] Current latitude of the unmanned aircraft. If unknown: 0 (both Lat/Lon).
*/
static inline int32_t mavlink_msg_open_drone_id_location_get_latitude(const mavlink_message_t* msg)
{
return _MAV_RETURN_int32_t(msg, 0);
}
/**
* @brief Get field longitude from open_drone_id_location message
*
* @return [degE7] Current longitude of the unmanned aircraft. If unknown: 0 (both Lat/Lon).
*/
static inline int32_t mavlink_msg_open_drone_id_location_get_longitude(const mavlink_message_t* msg)
{
return _MAV_RETURN_int32_t(msg, 4);
}
/**
* @brief Get field altitude_barometric from open_drone_id_location message
*
* @return [m] The altitude calculated from the barometric pressue. Reference is against 29.92inHg or 1013.2mb. If unknown: -1000 m.
*/
static inline float mavlink_msg_open_drone_id_location_get_altitude_barometric(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 8);
}
/**
* @brief Get field altitude_geodetic from open_drone_id_location message
*
* @return [m] The geodetic altitude as defined by WGS84. If unknown: -1000 m.
*/
static inline float mavlink_msg_open_drone_id_location_get_altitude_geodetic(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 12);
}
/**
* @brief Get field height_reference from open_drone_id_location message
*
* @return Indicates the reference point for the height field.
*/
static inline uint8_t mavlink_msg_open_drone_id_location_get_height_reference(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 53);
}
/**
* @brief Get field height from open_drone_id_location message
*
* @return [m] The current height of the unmanned aircraft above the take-off location or the ground as indicated by height_reference. If unknown: -1000 m.
*/
static inline float mavlink_msg_open_drone_id_location_get_height(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 16);
}
/**
* @brief Get field horizontal_accuracy from open_drone_id_location message
*
* @return The accuracy of the horizontal position.
*/
static inline uint8_t mavlink_msg_open_drone_id_location_get_horizontal_accuracy(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 54);
}
/**
* @brief Get field vertical_accuracy from open_drone_id_location message
*
* @return The accuracy of the vertical position.
*/
static inline uint8_t mavlink_msg_open_drone_id_location_get_vertical_accuracy(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 55);
}
/**
* @brief Get field barometer_accuracy from open_drone_id_location message
*
* @return The accuracy of the barometric altitude.
*/
static inline uint8_t mavlink_msg_open_drone_id_location_get_barometer_accuracy(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 56);
}
/**
* @brief Get field speed_accuracy from open_drone_id_location message
*
* @return The accuracy of the horizontal and vertical speed.
*/
static inline uint8_t mavlink_msg_open_drone_id_location_get_speed_accuracy(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 57);
}
/**
* @brief Get field timestamp from open_drone_id_location message
*
* @return [s] Seconds after the full hour with reference to UTC time. Typically the GPS outputs a time-of-week value in milliseconds. First convert that to UTC and then convert for this field using ((float) (time_week_ms % (60*60*1000))) / 1000.
*/
static inline float mavlink_msg_open_drone_id_location_get_timestamp(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 20);
}
/**
* @brief Get field timestamp_accuracy from open_drone_id_location message
*
* @return The accuracy of the timestamps.
*/
static inline uint8_t mavlink_msg_open_drone_id_location_get_timestamp_accuracy(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 58);
}
/**
* @brief Decode a open_drone_id_location message into a struct
*
* @param msg The message to decode
* @param open_drone_id_location C-struct to decode the message contents into
*/
static inline void mavlink_msg_open_drone_id_location_decode(const mavlink_message_t* msg, mavlink_open_drone_id_location_t* open_drone_id_location)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
open_drone_id_location->latitude = mavlink_msg_open_drone_id_location_get_latitude(msg);
open_drone_id_location->longitude = mavlink_msg_open_drone_id_location_get_longitude(msg);
open_drone_id_location->altitude_barometric = mavlink_msg_open_drone_id_location_get_altitude_barometric(msg);
open_drone_id_location->altitude_geodetic = mavlink_msg_open_drone_id_location_get_altitude_geodetic(msg);
open_drone_id_location->height = mavlink_msg_open_drone_id_location_get_height(msg);
open_drone_id_location->timestamp = mavlink_msg_open_drone_id_location_get_timestamp(msg);
open_drone_id_location->direction = mavlink_msg_open_drone_id_location_get_direction(msg);
open_drone_id_location->speed_horizontal = mavlink_msg_open_drone_id_location_get_speed_horizontal(msg);
open_drone_id_location->speed_vertical = mavlink_msg_open_drone_id_location_get_speed_vertical(msg);
open_drone_id_location->target_system = mavlink_msg_open_drone_id_location_get_target_system(msg);
open_drone_id_location->target_component = mavlink_msg_open_drone_id_location_get_target_component(msg);
mavlink_msg_open_drone_id_location_get_id_or_mac(msg, open_drone_id_location->id_or_mac);
open_drone_id_location->status = mavlink_msg_open_drone_id_location_get_status(msg);
open_drone_id_location->height_reference = mavlink_msg_open_drone_id_location_get_height_reference(msg);
open_drone_id_location->horizontal_accuracy = mavlink_msg_open_drone_id_location_get_horizontal_accuracy(msg);
open_drone_id_location->vertical_accuracy = mavlink_msg_open_drone_id_location_get_vertical_accuracy(msg);
open_drone_id_location->barometer_accuracy = mavlink_msg_open_drone_id_location_get_barometer_accuracy(msg);
open_drone_id_location->speed_accuracy = mavlink_msg_open_drone_id_location_get_speed_accuracy(msg);
open_drone_id_location->timestamp_accuracy = mavlink_msg_open_drone_id_location_get_timestamp_accuracy(msg);
#else
uint8_t len = msg->len < MAVLINK_MSG_ID_OPEN_DRONE_ID_LOCATION_LEN? msg->len : MAVLINK_MSG_ID_OPEN_DRONE_ID_LOCATION_LEN;
memset(open_drone_id_location, 0, MAVLINK_MSG_ID_OPEN_DRONE_ID_LOCATION_LEN);
memcpy(open_drone_id_location, _MAV_PAYLOAD(msg), len);
#endif
}

View file

@ -0,0 +1,305 @@
#pragma once
// MESSAGE OPEN_DRONE_ID_MESSAGE_PACK PACKING
#define MAVLINK_MSG_ID_OPEN_DRONE_ID_MESSAGE_PACK 12915
typedef struct __mavlink_open_drone_id_message_pack_t {
uint8_t target_system; /*< System ID (0 for broadcast).*/
uint8_t target_component; /*< Component ID (0 for broadcast).*/
uint8_t single_message_size; /*< [bytes] This field must currently always be equal to 25 (bytes), since all encoded OpenDroneID messages are specificed to have this length.*/
uint8_t msg_pack_size; /*< Number of encoded messages in the pack (not the number of bytes). Allowed range is 1 - 10.*/
uint8_t messages[250]; /*< Concatenation of encoded OpenDroneID messages. Shall be filled with nulls in the unused portion of the field.*/
} mavlink_open_drone_id_message_pack_t;
#define MAVLINK_MSG_ID_OPEN_DRONE_ID_MESSAGE_PACK_LEN 254
#define MAVLINK_MSG_ID_OPEN_DRONE_ID_MESSAGE_PACK_MIN_LEN 254
#define MAVLINK_MSG_ID_12915_LEN 254
#define MAVLINK_MSG_ID_12915_MIN_LEN 254
#define MAVLINK_MSG_ID_OPEN_DRONE_ID_MESSAGE_PACK_CRC 62
#define MAVLINK_MSG_ID_12915_CRC 62
#define MAVLINK_MSG_OPEN_DRONE_ID_MESSAGE_PACK_FIELD_MESSAGES_LEN 250
#if MAVLINK_COMMAND_24BIT
#define MAVLINK_MESSAGE_INFO_OPEN_DRONE_ID_MESSAGE_PACK { \
12915, \
"OPEN_DRONE_ID_MESSAGE_PACK", \
5, \
{ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_open_drone_id_message_pack_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_open_drone_id_message_pack_t, target_component) }, \
{ "single_message_size", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_open_drone_id_message_pack_t, single_message_size) }, \
{ "msg_pack_size", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_open_drone_id_message_pack_t, msg_pack_size) }, \
{ "messages", NULL, MAVLINK_TYPE_UINT8_T, 250, 4, offsetof(mavlink_open_drone_id_message_pack_t, messages) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_OPEN_DRONE_ID_MESSAGE_PACK { \
"OPEN_DRONE_ID_MESSAGE_PACK", \
5, \
{ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_open_drone_id_message_pack_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_open_drone_id_message_pack_t, target_component) }, \
{ "single_message_size", NULL, MAVLINK_TYPE_UINT8_T, 0, 2, offsetof(mavlink_open_drone_id_message_pack_t, single_message_size) }, \
{ "msg_pack_size", NULL, MAVLINK_TYPE_UINT8_T, 0, 3, offsetof(mavlink_open_drone_id_message_pack_t, msg_pack_size) }, \
{ "messages", NULL, MAVLINK_TYPE_UINT8_T, 250, 4, offsetof(mavlink_open_drone_id_message_pack_t, messages) }, \
} \
}
#endif
/**
* @brief Pack a open_drone_id_message_pack message
* @param system_id ID of this 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 (0 for broadcast).
* @param target_component Component ID (0 for broadcast).
* @param single_message_size [bytes] This field must currently always be equal to 25 (bytes), since all encoded OpenDroneID messages are specificed to have this length.
* @param msg_pack_size Number of encoded messages in the pack (not the number of bytes). Allowed range is 1 - 10.
* @param messages Concatenation of encoded OpenDroneID messages. Shall be filled with nulls in the unused portion of the field.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_open_drone_id_message_pack_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t target_system, uint8_t target_component, uint8_t single_message_size, uint8_t msg_pack_size, const uint8_t *messages)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_OPEN_DRONE_ID_MESSAGE_PACK_LEN];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
_mav_put_uint8_t(buf, 2, single_message_size);
_mav_put_uint8_t(buf, 3, msg_pack_size);
_mav_put_uint8_t_array(buf, 4, messages, 250);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_OPEN_DRONE_ID_MESSAGE_PACK_LEN);
#else
mavlink_open_drone_id_message_pack_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
packet.single_message_size = single_message_size;
packet.msg_pack_size = msg_pack_size;
mav_array_memcpy(packet.messages, messages, sizeof(uint8_t)*250);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_OPEN_DRONE_ID_MESSAGE_PACK_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_OPEN_DRONE_ID_MESSAGE_PACK;
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_OPEN_DRONE_ID_MESSAGE_PACK_MIN_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_MESSAGE_PACK_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_MESSAGE_PACK_CRC);
}
/**
* @brief Pack a open_drone_id_message_pack message on a channel
* @param system_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 (0 for broadcast).
* @param target_component Component ID (0 for broadcast).
* @param single_message_size [bytes] This field must currently always be equal to 25 (bytes), since all encoded OpenDroneID messages are specificed to have this length.
* @param msg_pack_size Number of encoded messages in the pack (not the number of bytes). Allowed range is 1 - 10.
* @param messages Concatenation of encoded OpenDroneID messages. Shall be filled with nulls in the unused portion of the field.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_open_drone_id_message_pack_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 single_message_size,uint8_t msg_pack_size,const uint8_t *messages)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_OPEN_DRONE_ID_MESSAGE_PACK_LEN];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
_mav_put_uint8_t(buf, 2, single_message_size);
_mav_put_uint8_t(buf, 3, msg_pack_size);
_mav_put_uint8_t_array(buf, 4, messages, 250);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_OPEN_DRONE_ID_MESSAGE_PACK_LEN);
#else
mavlink_open_drone_id_message_pack_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
packet.single_message_size = single_message_size;
packet.msg_pack_size = msg_pack_size;
mav_array_memcpy(packet.messages, messages, sizeof(uint8_t)*250);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_OPEN_DRONE_ID_MESSAGE_PACK_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_OPEN_DRONE_ID_MESSAGE_PACK;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_OPEN_DRONE_ID_MESSAGE_PACK_MIN_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_MESSAGE_PACK_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_MESSAGE_PACK_CRC);
}
/**
* @brief Encode a open_drone_id_message_pack 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 open_drone_id_message_pack C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_open_drone_id_message_pack_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_open_drone_id_message_pack_t* open_drone_id_message_pack)
{
return mavlink_msg_open_drone_id_message_pack_pack(system_id, component_id, msg, open_drone_id_message_pack->target_system, open_drone_id_message_pack->target_component, open_drone_id_message_pack->single_message_size, open_drone_id_message_pack->msg_pack_size, open_drone_id_message_pack->messages);
}
/**
* @brief Encode a open_drone_id_message_pack 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 open_drone_id_message_pack C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_open_drone_id_message_pack_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_open_drone_id_message_pack_t* open_drone_id_message_pack)
{
return mavlink_msg_open_drone_id_message_pack_pack_chan(system_id, component_id, chan, msg, open_drone_id_message_pack->target_system, open_drone_id_message_pack->target_component, open_drone_id_message_pack->single_message_size, open_drone_id_message_pack->msg_pack_size, open_drone_id_message_pack->messages);
}
/**
* @brief Send a open_drone_id_message_pack message
* @param chan MAVLink channel to send the message
*
* @param target_system System ID (0 for broadcast).
* @param target_component Component ID (0 for broadcast).
* @param single_message_size [bytes] This field must currently always be equal to 25 (bytes), since all encoded OpenDroneID messages are specificed to have this length.
* @param msg_pack_size Number of encoded messages in the pack (not the number of bytes). Allowed range is 1 - 10.
* @param messages Concatenation of encoded OpenDroneID messages. Shall be filled with nulls in the unused portion of the field.
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_open_drone_id_message_pack_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t single_message_size, uint8_t msg_pack_size, const uint8_t *messages)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_OPEN_DRONE_ID_MESSAGE_PACK_LEN];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
_mav_put_uint8_t(buf, 2, single_message_size);
_mav_put_uint8_t(buf, 3, msg_pack_size);
_mav_put_uint8_t_array(buf, 4, messages, 250);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPEN_DRONE_ID_MESSAGE_PACK, buf, MAVLINK_MSG_ID_OPEN_DRONE_ID_MESSAGE_PACK_MIN_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_MESSAGE_PACK_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_MESSAGE_PACK_CRC);
#else
mavlink_open_drone_id_message_pack_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
packet.single_message_size = single_message_size;
packet.msg_pack_size = msg_pack_size;
mav_array_memcpy(packet.messages, messages, sizeof(uint8_t)*250);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPEN_DRONE_ID_MESSAGE_PACK, (const char *)&packet, MAVLINK_MSG_ID_OPEN_DRONE_ID_MESSAGE_PACK_MIN_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_MESSAGE_PACK_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_MESSAGE_PACK_CRC);
#endif
}
/**
* @brief Send a open_drone_id_message_pack message
* @param chan MAVLink channel to send the message
* @param struct The MAVLink struct to serialize
*/
static inline void mavlink_msg_open_drone_id_message_pack_send_struct(mavlink_channel_t chan, const mavlink_open_drone_id_message_pack_t* open_drone_id_message_pack)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mavlink_msg_open_drone_id_message_pack_send(chan, open_drone_id_message_pack->target_system, open_drone_id_message_pack->target_component, open_drone_id_message_pack->single_message_size, open_drone_id_message_pack->msg_pack_size, open_drone_id_message_pack->messages);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPEN_DRONE_ID_MESSAGE_PACK, (const char *)open_drone_id_message_pack, MAVLINK_MSG_ID_OPEN_DRONE_ID_MESSAGE_PACK_MIN_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_MESSAGE_PACK_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_MESSAGE_PACK_CRC);
#endif
}
#if MAVLINK_MSG_ID_OPEN_DRONE_ID_MESSAGE_PACK_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_open_drone_id_message_pack_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, uint8_t single_message_size, uint8_t msg_pack_size, const uint8_t *messages)
{
#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, single_message_size);
_mav_put_uint8_t(buf, 3, msg_pack_size);
_mav_put_uint8_t_array(buf, 4, messages, 250);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPEN_DRONE_ID_MESSAGE_PACK, buf, MAVLINK_MSG_ID_OPEN_DRONE_ID_MESSAGE_PACK_MIN_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_MESSAGE_PACK_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_MESSAGE_PACK_CRC);
#else
mavlink_open_drone_id_message_pack_t *packet = (mavlink_open_drone_id_message_pack_t *)msgbuf;
packet->target_system = target_system;
packet->target_component = target_component;
packet->single_message_size = single_message_size;
packet->msg_pack_size = msg_pack_size;
mav_array_memcpy(packet->messages, messages, sizeof(uint8_t)*250);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPEN_DRONE_ID_MESSAGE_PACK, (const char *)packet, MAVLINK_MSG_ID_OPEN_DRONE_ID_MESSAGE_PACK_MIN_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_MESSAGE_PACK_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_MESSAGE_PACK_CRC);
#endif
}
#endif
#endif
// MESSAGE OPEN_DRONE_ID_MESSAGE_PACK UNPACKING
/**
* @brief Get field target_system from open_drone_id_message_pack message
*
* @return System ID (0 for broadcast).
*/
static inline uint8_t mavlink_msg_open_drone_id_message_pack_get_target_system(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 0);
}
/**
* @brief Get field target_component from open_drone_id_message_pack message
*
* @return Component ID (0 for broadcast).
*/
static inline uint8_t mavlink_msg_open_drone_id_message_pack_get_target_component(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 1);
}
/**
* @brief Get field single_message_size from open_drone_id_message_pack message
*
* @return [bytes] This field must currently always be equal to 25 (bytes), since all encoded OpenDroneID messages are specificed to have this length.
*/
static inline uint8_t mavlink_msg_open_drone_id_message_pack_get_single_message_size(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 2);
}
/**
* @brief Get field msg_pack_size from open_drone_id_message_pack message
*
* @return Number of encoded messages in the pack (not the number of bytes). Allowed range is 1 - 10.
*/
static inline uint8_t mavlink_msg_open_drone_id_message_pack_get_msg_pack_size(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 3);
}
/**
* @brief Get field messages from open_drone_id_message_pack message
*
* @return Concatenation of encoded OpenDroneID messages. Shall be filled with nulls in the unused portion of the field.
*/
static inline uint16_t mavlink_msg_open_drone_id_message_pack_get_messages(const mavlink_message_t* msg, uint8_t *messages)
{
return _MAV_RETURN_uint8_t_array(msg, messages, 250, 4);
}
/**
* @brief Decode a open_drone_id_message_pack message into a struct
*
* @param msg The message to decode
* @param open_drone_id_message_pack C-struct to decode the message contents into
*/
static inline void mavlink_msg_open_drone_id_message_pack_decode(const mavlink_message_t* msg, mavlink_open_drone_id_message_pack_t* open_drone_id_message_pack)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
open_drone_id_message_pack->target_system = mavlink_msg_open_drone_id_message_pack_get_target_system(msg);
open_drone_id_message_pack->target_component = mavlink_msg_open_drone_id_message_pack_get_target_component(msg);
open_drone_id_message_pack->single_message_size = mavlink_msg_open_drone_id_message_pack_get_single_message_size(msg);
open_drone_id_message_pack->msg_pack_size = mavlink_msg_open_drone_id_message_pack_get_msg_pack_size(msg);
mavlink_msg_open_drone_id_message_pack_get_messages(msg, open_drone_id_message_pack->messages);
#else
uint8_t len = msg->len < MAVLINK_MSG_ID_OPEN_DRONE_ID_MESSAGE_PACK_LEN? msg->len : MAVLINK_MSG_ID_OPEN_DRONE_ID_MESSAGE_PACK_LEN;
memset(open_drone_id_message_pack, 0, MAVLINK_MSG_ID_OPEN_DRONE_ID_MESSAGE_PACK_LEN);
memcpy(open_drone_id_message_pack, _MAV_PAYLOAD(msg), len);
#endif
}

View file

@ -0,0 +1,306 @@
#pragma once
// MESSAGE OPEN_DRONE_ID_OPERATOR_ID PACKING
#define MAVLINK_MSG_ID_OPEN_DRONE_ID_OPERATOR_ID 12905
typedef struct __mavlink_open_drone_id_operator_id_t {
uint8_t target_system; /*< System ID (0 for broadcast).*/
uint8_t target_component; /*< Component ID (0 for broadcast).*/
uint8_t id_or_mac[20]; /*< Only used for drone ID data received from other UAs. See detailed description at https://mavlink.io/en/services/opendroneid.html. */
uint8_t operator_id_type; /*< Indicates the type of the operator_id field.*/
char operator_id[20]; /*< Text description or numeric value expressed as ASCII characters. Shall be filled with nulls in the unused portion of the field.*/
} mavlink_open_drone_id_operator_id_t;
#define MAVLINK_MSG_ID_OPEN_DRONE_ID_OPERATOR_ID_LEN 43
#define MAVLINK_MSG_ID_OPEN_DRONE_ID_OPERATOR_ID_MIN_LEN 43
#define MAVLINK_MSG_ID_12905_LEN 43
#define MAVLINK_MSG_ID_12905_MIN_LEN 43
#define MAVLINK_MSG_ID_OPEN_DRONE_ID_OPERATOR_ID_CRC 49
#define MAVLINK_MSG_ID_12905_CRC 49
#define MAVLINK_MSG_OPEN_DRONE_ID_OPERATOR_ID_FIELD_ID_OR_MAC_LEN 20
#define MAVLINK_MSG_OPEN_DRONE_ID_OPERATOR_ID_FIELD_OPERATOR_ID_LEN 20
#if MAVLINK_COMMAND_24BIT
#define MAVLINK_MESSAGE_INFO_OPEN_DRONE_ID_OPERATOR_ID { \
12905, \
"OPEN_DRONE_ID_OPERATOR_ID", \
5, \
{ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_open_drone_id_operator_id_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_open_drone_id_operator_id_t, target_component) }, \
{ "id_or_mac", NULL, MAVLINK_TYPE_UINT8_T, 20, 2, offsetof(mavlink_open_drone_id_operator_id_t, id_or_mac) }, \
{ "operator_id_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 22, offsetof(mavlink_open_drone_id_operator_id_t, operator_id_type) }, \
{ "operator_id", NULL, MAVLINK_TYPE_CHAR, 20, 23, offsetof(mavlink_open_drone_id_operator_id_t, operator_id) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_OPEN_DRONE_ID_OPERATOR_ID { \
"OPEN_DRONE_ID_OPERATOR_ID", \
5, \
{ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_open_drone_id_operator_id_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_open_drone_id_operator_id_t, target_component) }, \
{ "id_or_mac", NULL, MAVLINK_TYPE_UINT8_T, 20, 2, offsetof(mavlink_open_drone_id_operator_id_t, id_or_mac) }, \
{ "operator_id_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 22, offsetof(mavlink_open_drone_id_operator_id_t, operator_id_type) }, \
{ "operator_id", NULL, MAVLINK_TYPE_CHAR, 20, 23, offsetof(mavlink_open_drone_id_operator_id_t, operator_id) }, \
} \
}
#endif
/**
* @brief Pack a open_drone_id_operator_id message
* @param system_id ID of this 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 (0 for broadcast).
* @param target_component Component ID (0 for broadcast).
* @param id_or_mac Only used for drone ID data received from other UAs. See detailed description at https://mavlink.io/en/services/opendroneid.html.
* @param operator_id_type Indicates the type of the operator_id field.
* @param operator_id Text description or numeric value expressed as ASCII characters. Shall be filled with nulls in the unused portion of the field.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_open_drone_id_operator_id_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t target_system, uint8_t target_component, const uint8_t *id_or_mac, uint8_t operator_id_type, const char *operator_id)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_OPEN_DRONE_ID_OPERATOR_ID_LEN];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
_mav_put_uint8_t(buf, 22, operator_id_type);
_mav_put_uint8_t_array(buf, 2, id_or_mac, 20);
_mav_put_char_array(buf, 23, operator_id, 20);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_OPEN_DRONE_ID_OPERATOR_ID_LEN);
#else
mavlink_open_drone_id_operator_id_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
packet.operator_id_type = operator_id_type;
mav_array_memcpy(packet.id_or_mac, id_or_mac, sizeof(uint8_t)*20);
mav_array_memcpy(packet.operator_id, operator_id, sizeof(char)*20);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_OPEN_DRONE_ID_OPERATOR_ID_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_OPEN_DRONE_ID_OPERATOR_ID;
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_OPEN_DRONE_ID_OPERATOR_ID_MIN_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_OPERATOR_ID_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_OPERATOR_ID_CRC);
}
/**
* @brief Pack a open_drone_id_operator_id message on a channel
* @param system_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 (0 for broadcast).
* @param target_component Component ID (0 for broadcast).
* @param id_or_mac Only used for drone ID data received from other UAs. See detailed description at https://mavlink.io/en/services/opendroneid.html.
* @param operator_id_type Indicates the type of the operator_id field.
* @param operator_id Text description or numeric value expressed as ASCII characters. Shall be filled with nulls in the unused portion of the field.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_open_drone_id_operator_id_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 uint8_t *id_or_mac,uint8_t operator_id_type,const char *operator_id)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_OPEN_DRONE_ID_OPERATOR_ID_LEN];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
_mav_put_uint8_t(buf, 22, operator_id_type);
_mav_put_uint8_t_array(buf, 2, id_or_mac, 20);
_mav_put_char_array(buf, 23, operator_id, 20);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_OPEN_DRONE_ID_OPERATOR_ID_LEN);
#else
mavlink_open_drone_id_operator_id_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
packet.operator_id_type = operator_id_type;
mav_array_memcpy(packet.id_or_mac, id_or_mac, sizeof(uint8_t)*20);
mav_array_memcpy(packet.operator_id, operator_id, sizeof(char)*20);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_OPEN_DRONE_ID_OPERATOR_ID_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_OPEN_DRONE_ID_OPERATOR_ID;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_OPEN_DRONE_ID_OPERATOR_ID_MIN_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_OPERATOR_ID_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_OPERATOR_ID_CRC);
}
/**
* @brief Encode a open_drone_id_operator_id 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 open_drone_id_operator_id C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_open_drone_id_operator_id_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_open_drone_id_operator_id_t* open_drone_id_operator_id)
{
return mavlink_msg_open_drone_id_operator_id_pack(system_id, component_id, msg, open_drone_id_operator_id->target_system, open_drone_id_operator_id->target_component, open_drone_id_operator_id->id_or_mac, open_drone_id_operator_id->operator_id_type, open_drone_id_operator_id->operator_id);
}
/**
* @brief Encode a open_drone_id_operator_id 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 open_drone_id_operator_id C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_open_drone_id_operator_id_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_open_drone_id_operator_id_t* open_drone_id_operator_id)
{
return mavlink_msg_open_drone_id_operator_id_pack_chan(system_id, component_id, chan, msg, open_drone_id_operator_id->target_system, open_drone_id_operator_id->target_component, open_drone_id_operator_id->id_or_mac, open_drone_id_operator_id->operator_id_type, open_drone_id_operator_id->operator_id);
}
/**
* @brief Send a open_drone_id_operator_id message
* @param chan MAVLink channel to send the message
*
* @param target_system System ID (0 for broadcast).
* @param target_component Component ID (0 for broadcast).
* @param id_or_mac Only used for drone ID data received from other UAs. See detailed description at https://mavlink.io/en/services/opendroneid.html.
* @param operator_id_type Indicates the type of the operator_id field.
* @param operator_id Text description or numeric value expressed as ASCII characters. Shall be filled with nulls in the unused portion of the field.
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_open_drone_id_operator_id_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, const uint8_t *id_or_mac, uint8_t operator_id_type, const char *operator_id)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_OPEN_DRONE_ID_OPERATOR_ID_LEN];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
_mav_put_uint8_t(buf, 22, operator_id_type);
_mav_put_uint8_t_array(buf, 2, id_or_mac, 20);
_mav_put_char_array(buf, 23, operator_id, 20);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPEN_DRONE_ID_OPERATOR_ID, buf, MAVLINK_MSG_ID_OPEN_DRONE_ID_OPERATOR_ID_MIN_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_OPERATOR_ID_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_OPERATOR_ID_CRC);
#else
mavlink_open_drone_id_operator_id_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
packet.operator_id_type = operator_id_type;
mav_array_memcpy(packet.id_or_mac, id_or_mac, sizeof(uint8_t)*20);
mav_array_memcpy(packet.operator_id, operator_id, sizeof(char)*20);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPEN_DRONE_ID_OPERATOR_ID, (const char *)&packet, MAVLINK_MSG_ID_OPEN_DRONE_ID_OPERATOR_ID_MIN_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_OPERATOR_ID_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_OPERATOR_ID_CRC);
#endif
}
/**
* @brief Send a open_drone_id_operator_id message
* @param chan MAVLink channel to send the message
* @param struct The MAVLink struct to serialize
*/
static inline void mavlink_msg_open_drone_id_operator_id_send_struct(mavlink_channel_t chan, const mavlink_open_drone_id_operator_id_t* open_drone_id_operator_id)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mavlink_msg_open_drone_id_operator_id_send(chan, open_drone_id_operator_id->target_system, open_drone_id_operator_id->target_component, open_drone_id_operator_id->id_or_mac, open_drone_id_operator_id->operator_id_type, open_drone_id_operator_id->operator_id);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPEN_DRONE_ID_OPERATOR_ID, (const char *)open_drone_id_operator_id, MAVLINK_MSG_ID_OPEN_DRONE_ID_OPERATOR_ID_MIN_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_OPERATOR_ID_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_OPERATOR_ID_CRC);
#endif
}
#if MAVLINK_MSG_ID_OPEN_DRONE_ID_OPERATOR_ID_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_open_drone_id_operator_id_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, const uint8_t *id_or_mac, uint8_t operator_id_type, const char *operator_id)
{
#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, 22, operator_id_type);
_mav_put_uint8_t_array(buf, 2, id_or_mac, 20);
_mav_put_char_array(buf, 23, operator_id, 20);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPEN_DRONE_ID_OPERATOR_ID, buf, MAVLINK_MSG_ID_OPEN_DRONE_ID_OPERATOR_ID_MIN_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_OPERATOR_ID_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_OPERATOR_ID_CRC);
#else
mavlink_open_drone_id_operator_id_t *packet = (mavlink_open_drone_id_operator_id_t *)msgbuf;
packet->target_system = target_system;
packet->target_component = target_component;
packet->operator_id_type = operator_id_type;
mav_array_memcpy(packet->id_or_mac, id_or_mac, sizeof(uint8_t)*20);
mav_array_memcpy(packet->operator_id, operator_id, sizeof(char)*20);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPEN_DRONE_ID_OPERATOR_ID, (const char *)packet, MAVLINK_MSG_ID_OPEN_DRONE_ID_OPERATOR_ID_MIN_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_OPERATOR_ID_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_OPERATOR_ID_CRC);
#endif
}
#endif
#endif
// MESSAGE OPEN_DRONE_ID_OPERATOR_ID UNPACKING
/**
* @brief Get field target_system from open_drone_id_operator_id message
*
* @return System ID (0 for broadcast).
*/
static inline uint8_t mavlink_msg_open_drone_id_operator_id_get_target_system(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 0);
}
/**
* @brief Get field target_component from open_drone_id_operator_id message
*
* @return Component ID (0 for broadcast).
*/
static inline uint8_t mavlink_msg_open_drone_id_operator_id_get_target_component(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 1);
}
/**
* @brief Get field id_or_mac from open_drone_id_operator_id message
*
* @return Only used for drone ID data received from other UAs. See detailed description at https://mavlink.io/en/services/opendroneid.html.
*/
static inline uint16_t mavlink_msg_open_drone_id_operator_id_get_id_or_mac(const mavlink_message_t* msg, uint8_t *id_or_mac)
{
return _MAV_RETURN_uint8_t_array(msg, id_or_mac, 20, 2);
}
/**
* @brief Get field operator_id_type from open_drone_id_operator_id message
*
* @return Indicates the type of the operator_id field.
*/
static inline uint8_t mavlink_msg_open_drone_id_operator_id_get_operator_id_type(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 22);
}
/**
* @brief Get field operator_id from open_drone_id_operator_id message
*
* @return Text description or numeric value expressed as ASCII characters. Shall be filled with nulls in the unused portion of the field.
*/
static inline uint16_t mavlink_msg_open_drone_id_operator_id_get_operator_id(const mavlink_message_t* msg, char *operator_id)
{
return _MAV_RETURN_char_array(msg, operator_id, 20, 23);
}
/**
* @brief Decode a open_drone_id_operator_id message into a struct
*
* @param msg The message to decode
* @param open_drone_id_operator_id C-struct to decode the message contents into
*/
static inline void mavlink_msg_open_drone_id_operator_id_decode(const mavlink_message_t* msg, mavlink_open_drone_id_operator_id_t* open_drone_id_operator_id)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
open_drone_id_operator_id->target_system = mavlink_msg_open_drone_id_operator_id_get_target_system(msg);
open_drone_id_operator_id->target_component = mavlink_msg_open_drone_id_operator_id_get_target_component(msg);
mavlink_msg_open_drone_id_operator_id_get_id_or_mac(msg, open_drone_id_operator_id->id_or_mac);
open_drone_id_operator_id->operator_id_type = mavlink_msg_open_drone_id_operator_id_get_operator_id_type(msg);
mavlink_msg_open_drone_id_operator_id_get_operator_id(msg, open_drone_id_operator_id->operator_id);
#else
uint8_t len = msg->len < MAVLINK_MSG_ID_OPEN_DRONE_ID_OPERATOR_ID_LEN? msg->len : MAVLINK_MSG_ID_OPEN_DRONE_ID_OPERATOR_ID_LEN;
memset(open_drone_id_operator_id, 0, MAVLINK_MSG_ID_OPEN_DRONE_ID_OPERATOR_ID_LEN);
memcpy(open_drone_id_operator_id, _MAV_PAYLOAD(msg), len);
#endif
}

View file

@ -0,0 +1,306 @@
#pragma once
// MESSAGE OPEN_DRONE_ID_SELF_ID PACKING
#define MAVLINK_MSG_ID_OPEN_DRONE_ID_SELF_ID 12903
typedef struct __mavlink_open_drone_id_self_id_t {
uint8_t target_system; /*< System ID (0 for broadcast).*/
uint8_t target_component; /*< Component ID (0 for broadcast).*/
uint8_t id_or_mac[20]; /*< Only used for drone ID data received from other UAs. See detailed description at https://mavlink.io/en/services/opendroneid.html. */
uint8_t description_type; /*< Indicates the type of the description field.*/
char description[23]; /*< Text description or numeric value expressed as ASCII characters. Shall be filled with nulls in the unused portion of the field.*/
} mavlink_open_drone_id_self_id_t;
#define MAVLINK_MSG_ID_OPEN_DRONE_ID_SELF_ID_LEN 46
#define MAVLINK_MSG_ID_OPEN_DRONE_ID_SELF_ID_MIN_LEN 46
#define MAVLINK_MSG_ID_12903_LEN 46
#define MAVLINK_MSG_ID_12903_MIN_LEN 46
#define MAVLINK_MSG_ID_OPEN_DRONE_ID_SELF_ID_CRC 249
#define MAVLINK_MSG_ID_12903_CRC 249
#define MAVLINK_MSG_OPEN_DRONE_ID_SELF_ID_FIELD_ID_OR_MAC_LEN 20
#define MAVLINK_MSG_OPEN_DRONE_ID_SELF_ID_FIELD_DESCRIPTION_LEN 23
#if MAVLINK_COMMAND_24BIT
#define MAVLINK_MESSAGE_INFO_OPEN_DRONE_ID_SELF_ID { \
12903, \
"OPEN_DRONE_ID_SELF_ID", \
5, \
{ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_open_drone_id_self_id_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_open_drone_id_self_id_t, target_component) }, \
{ "id_or_mac", NULL, MAVLINK_TYPE_UINT8_T, 20, 2, offsetof(mavlink_open_drone_id_self_id_t, id_or_mac) }, \
{ "description_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 22, offsetof(mavlink_open_drone_id_self_id_t, description_type) }, \
{ "description", NULL, MAVLINK_TYPE_CHAR, 23, 23, offsetof(mavlink_open_drone_id_self_id_t, description) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_OPEN_DRONE_ID_SELF_ID { \
"OPEN_DRONE_ID_SELF_ID", \
5, \
{ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_open_drone_id_self_id_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_open_drone_id_self_id_t, target_component) }, \
{ "id_or_mac", NULL, MAVLINK_TYPE_UINT8_T, 20, 2, offsetof(mavlink_open_drone_id_self_id_t, id_or_mac) }, \
{ "description_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 22, offsetof(mavlink_open_drone_id_self_id_t, description_type) }, \
{ "description", NULL, MAVLINK_TYPE_CHAR, 23, 23, offsetof(mavlink_open_drone_id_self_id_t, description) }, \
} \
}
#endif
/**
* @brief Pack a open_drone_id_self_id message
* @param system_id ID of this 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 (0 for broadcast).
* @param target_component Component ID (0 for broadcast).
* @param id_or_mac Only used for drone ID data received from other UAs. See detailed description at https://mavlink.io/en/services/opendroneid.html.
* @param description_type Indicates the type of the description field.
* @param description Text description or numeric value expressed as ASCII characters. Shall be filled with nulls in the unused portion of the field.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_open_drone_id_self_id_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t target_system, uint8_t target_component, const uint8_t *id_or_mac, uint8_t description_type, const char *description)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_OPEN_DRONE_ID_SELF_ID_LEN];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
_mav_put_uint8_t(buf, 22, description_type);
_mav_put_uint8_t_array(buf, 2, id_or_mac, 20);
_mav_put_char_array(buf, 23, description, 23);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_OPEN_DRONE_ID_SELF_ID_LEN);
#else
mavlink_open_drone_id_self_id_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
packet.description_type = description_type;
mav_array_memcpy(packet.id_or_mac, id_or_mac, sizeof(uint8_t)*20);
mav_array_memcpy(packet.description, description, sizeof(char)*23);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_OPEN_DRONE_ID_SELF_ID_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_OPEN_DRONE_ID_SELF_ID;
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_OPEN_DRONE_ID_SELF_ID_MIN_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_SELF_ID_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_SELF_ID_CRC);
}
/**
* @brief Pack a open_drone_id_self_id message on a channel
* @param system_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 (0 for broadcast).
* @param target_component Component ID (0 for broadcast).
* @param id_or_mac Only used for drone ID data received from other UAs. See detailed description at https://mavlink.io/en/services/opendroneid.html.
* @param description_type Indicates the type of the description field.
* @param description Text description or numeric value expressed as ASCII characters. Shall be filled with nulls in the unused portion of the field.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_open_drone_id_self_id_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 uint8_t *id_or_mac,uint8_t description_type,const char *description)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_OPEN_DRONE_ID_SELF_ID_LEN];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
_mav_put_uint8_t(buf, 22, description_type);
_mav_put_uint8_t_array(buf, 2, id_or_mac, 20);
_mav_put_char_array(buf, 23, description, 23);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_OPEN_DRONE_ID_SELF_ID_LEN);
#else
mavlink_open_drone_id_self_id_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
packet.description_type = description_type;
mav_array_memcpy(packet.id_or_mac, id_or_mac, sizeof(uint8_t)*20);
mav_array_memcpy(packet.description, description, sizeof(char)*23);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_OPEN_DRONE_ID_SELF_ID_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_OPEN_DRONE_ID_SELF_ID;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_OPEN_DRONE_ID_SELF_ID_MIN_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_SELF_ID_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_SELF_ID_CRC);
}
/**
* @brief Encode a open_drone_id_self_id 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 open_drone_id_self_id C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_open_drone_id_self_id_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_open_drone_id_self_id_t* open_drone_id_self_id)
{
return mavlink_msg_open_drone_id_self_id_pack(system_id, component_id, msg, open_drone_id_self_id->target_system, open_drone_id_self_id->target_component, open_drone_id_self_id->id_or_mac, open_drone_id_self_id->description_type, open_drone_id_self_id->description);
}
/**
* @brief Encode a open_drone_id_self_id 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 open_drone_id_self_id C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_open_drone_id_self_id_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_open_drone_id_self_id_t* open_drone_id_self_id)
{
return mavlink_msg_open_drone_id_self_id_pack_chan(system_id, component_id, chan, msg, open_drone_id_self_id->target_system, open_drone_id_self_id->target_component, open_drone_id_self_id->id_or_mac, open_drone_id_self_id->description_type, open_drone_id_self_id->description);
}
/**
* @brief Send a open_drone_id_self_id message
* @param chan MAVLink channel to send the message
*
* @param target_system System ID (0 for broadcast).
* @param target_component Component ID (0 for broadcast).
* @param id_or_mac Only used for drone ID data received from other UAs. See detailed description at https://mavlink.io/en/services/opendroneid.html.
* @param description_type Indicates the type of the description field.
* @param description Text description or numeric value expressed as ASCII characters. Shall be filled with nulls in the unused portion of the field.
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_open_drone_id_self_id_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, const uint8_t *id_or_mac, uint8_t description_type, const char *description)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_OPEN_DRONE_ID_SELF_ID_LEN];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
_mav_put_uint8_t(buf, 22, description_type);
_mav_put_uint8_t_array(buf, 2, id_or_mac, 20);
_mav_put_char_array(buf, 23, description, 23);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPEN_DRONE_ID_SELF_ID, buf, MAVLINK_MSG_ID_OPEN_DRONE_ID_SELF_ID_MIN_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_SELF_ID_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_SELF_ID_CRC);
#else
mavlink_open_drone_id_self_id_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
packet.description_type = description_type;
mav_array_memcpy(packet.id_or_mac, id_or_mac, sizeof(uint8_t)*20);
mav_array_memcpy(packet.description, description, sizeof(char)*23);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPEN_DRONE_ID_SELF_ID, (const char *)&packet, MAVLINK_MSG_ID_OPEN_DRONE_ID_SELF_ID_MIN_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_SELF_ID_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_SELF_ID_CRC);
#endif
}
/**
* @brief Send a open_drone_id_self_id message
* @param chan MAVLink channel to send the message
* @param struct The MAVLink struct to serialize
*/
static inline void mavlink_msg_open_drone_id_self_id_send_struct(mavlink_channel_t chan, const mavlink_open_drone_id_self_id_t* open_drone_id_self_id)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mavlink_msg_open_drone_id_self_id_send(chan, open_drone_id_self_id->target_system, open_drone_id_self_id->target_component, open_drone_id_self_id->id_or_mac, open_drone_id_self_id->description_type, open_drone_id_self_id->description);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPEN_DRONE_ID_SELF_ID, (const char *)open_drone_id_self_id, MAVLINK_MSG_ID_OPEN_DRONE_ID_SELF_ID_MIN_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_SELF_ID_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_SELF_ID_CRC);
#endif
}
#if MAVLINK_MSG_ID_OPEN_DRONE_ID_SELF_ID_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_open_drone_id_self_id_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, const uint8_t *id_or_mac, uint8_t description_type, const char *description)
{
#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, 22, description_type);
_mav_put_uint8_t_array(buf, 2, id_or_mac, 20);
_mav_put_char_array(buf, 23, description, 23);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPEN_DRONE_ID_SELF_ID, buf, MAVLINK_MSG_ID_OPEN_DRONE_ID_SELF_ID_MIN_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_SELF_ID_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_SELF_ID_CRC);
#else
mavlink_open_drone_id_self_id_t *packet = (mavlink_open_drone_id_self_id_t *)msgbuf;
packet->target_system = target_system;
packet->target_component = target_component;
packet->description_type = description_type;
mav_array_memcpy(packet->id_or_mac, id_or_mac, sizeof(uint8_t)*20);
mav_array_memcpy(packet->description, description, sizeof(char)*23);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPEN_DRONE_ID_SELF_ID, (const char *)packet, MAVLINK_MSG_ID_OPEN_DRONE_ID_SELF_ID_MIN_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_SELF_ID_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_SELF_ID_CRC);
#endif
}
#endif
#endif
// MESSAGE OPEN_DRONE_ID_SELF_ID UNPACKING
/**
* @brief Get field target_system from open_drone_id_self_id message
*
* @return System ID (0 for broadcast).
*/
static inline uint8_t mavlink_msg_open_drone_id_self_id_get_target_system(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 0);
}
/**
* @brief Get field target_component from open_drone_id_self_id message
*
* @return Component ID (0 for broadcast).
*/
static inline uint8_t mavlink_msg_open_drone_id_self_id_get_target_component(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 1);
}
/**
* @brief Get field id_or_mac from open_drone_id_self_id message
*
* @return Only used for drone ID data received from other UAs. See detailed description at https://mavlink.io/en/services/opendroneid.html.
*/
static inline uint16_t mavlink_msg_open_drone_id_self_id_get_id_or_mac(const mavlink_message_t* msg, uint8_t *id_or_mac)
{
return _MAV_RETURN_uint8_t_array(msg, id_or_mac, 20, 2);
}
/**
* @brief Get field description_type from open_drone_id_self_id message
*
* @return Indicates the type of the description field.
*/
static inline uint8_t mavlink_msg_open_drone_id_self_id_get_description_type(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 22);
}
/**
* @brief Get field description from open_drone_id_self_id message
*
* @return Text description or numeric value expressed as ASCII characters. Shall be filled with nulls in the unused portion of the field.
*/
static inline uint16_t mavlink_msg_open_drone_id_self_id_get_description(const mavlink_message_t* msg, char *description)
{
return _MAV_RETURN_char_array(msg, description, 23, 23);
}
/**
* @brief Decode a open_drone_id_self_id message into a struct
*
* @param msg The message to decode
* @param open_drone_id_self_id C-struct to decode the message contents into
*/
static inline void mavlink_msg_open_drone_id_self_id_decode(const mavlink_message_t* msg, mavlink_open_drone_id_self_id_t* open_drone_id_self_id)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
open_drone_id_self_id->target_system = mavlink_msg_open_drone_id_self_id_get_target_system(msg);
open_drone_id_self_id->target_component = mavlink_msg_open_drone_id_self_id_get_target_component(msg);
mavlink_msg_open_drone_id_self_id_get_id_or_mac(msg, open_drone_id_self_id->id_or_mac);
open_drone_id_self_id->description_type = mavlink_msg_open_drone_id_self_id_get_description_type(msg);
mavlink_msg_open_drone_id_self_id_get_description(msg, open_drone_id_self_id->description);
#else
uint8_t len = msg->len < MAVLINK_MSG_ID_OPEN_DRONE_ID_SELF_ID_LEN? msg->len : MAVLINK_MSG_ID_OPEN_DRONE_ID_SELF_ID_LEN;
memset(open_drone_id_self_id, 0, MAVLINK_MSG_ID_OPEN_DRONE_ID_SELF_ID_LEN);
memcpy(open_drone_id_self_id, _MAV_PAYLOAD(msg), len);
#endif
}

View file

@ -0,0 +1,505 @@
#pragma once
// MESSAGE OPEN_DRONE_ID_SYSTEM PACKING
#define MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM 12904
typedef struct __mavlink_open_drone_id_system_t {
int32_t operator_latitude; /*< [degE7] Latitude of the operator. If unknown: 0 (both Lat/Lon).*/
int32_t operator_longitude; /*< [degE7] Longitude of the operator. If unknown: 0 (both Lat/Lon).*/
float area_ceiling; /*< [m] Area Operations Ceiling relative to WGS84. If unknown: -1000 m.*/
float area_floor; /*< [m] Area Operations Floor relative to WGS84. If unknown: -1000 m.*/
uint16_t area_count; /*< Number of aircraft in the area, group or formation (default 1).*/
uint16_t area_radius; /*< [m] Radius of the cylindrical area of the group or formation (default 0).*/
uint8_t target_system; /*< System ID (0 for broadcast).*/
uint8_t target_component; /*< Component ID (0 for broadcast).*/
uint8_t id_or_mac[20]; /*< Only used for drone ID data received from other UAs. See detailed description at https://mavlink.io/en/services/opendroneid.html. */
uint8_t operator_location_type; /*< Specifies the operator location type.*/
uint8_t classification_type; /*< Specifies the classification type of the UA.*/
uint8_t category_eu; /*< When classification_type is MAV_ODID_CLASSIFICATION_TYPE_EU, specifies the category of the UA.*/
uint8_t class_eu; /*< When classification_type is MAV_ODID_CLASSIFICATION_TYPE_EU, specifies the class of the UA.*/
} mavlink_open_drone_id_system_t;
#define MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_LEN 46
#define MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_MIN_LEN 46
#define MAVLINK_MSG_ID_12904_LEN 46
#define MAVLINK_MSG_ID_12904_MIN_LEN 46
#define MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_CRC 203
#define MAVLINK_MSG_ID_12904_CRC 203
#define MAVLINK_MSG_OPEN_DRONE_ID_SYSTEM_FIELD_ID_OR_MAC_LEN 20
#if MAVLINK_COMMAND_24BIT
#define MAVLINK_MESSAGE_INFO_OPEN_DRONE_ID_SYSTEM { \
12904, \
"OPEN_DRONE_ID_SYSTEM", \
13, \
{ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 20, offsetof(mavlink_open_drone_id_system_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 21, offsetof(mavlink_open_drone_id_system_t, target_component) }, \
{ "id_or_mac", NULL, MAVLINK_TYPE_UINT8_T, 20, 22, offsetof(mavlink_open_drone_id_system_t, id_or_mac) }, \
{ "operator_location_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 42, offsetof(mavlink_open_drone_id_system_t, operator_location_type) }, \
{ "classification_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 43, offsetof(mavlink_open_drone_id_system_t, classification_type) }, \
{ "operator_latitude", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_open_drone_id_system_t, operator_latitude) }, \
{ "operator_longitude", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_open_drone_id_system_t, operator_longitude) }, \
{ "area_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_open_drone_id_system_t, area_count) }, \
{ "area_radius", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_open_drone_id_system_t, area_radius) }, \
{ "area_ceiling", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_open_drone_id_system_t, area_ceiling) }, \
{ "area_floor", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_open_drone_id_system_t, area_floor) }, \
{ "category_eu", NULL, MAVLINK_TYPE_UINT8_T, 0, 44, offsetof(mavlink_open_drone_id_system_t, category_eu) }, \
{ "class_eu", NULL, MAVLINK_TYPE_UINT8_T, 0, 45, offsetof(mavlink_open_drone_id_system_t, class_eu) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_OPEN_DRONE_ID_SYSTEM { \
"OPEN_DRONE_ID_SYSTEM", \
13, \
{ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 20, offsetof(mavlink_open_drone_id_system_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 21, offsetof(mavlink_open_drone_id_system_t, target_component) }, \
{ "id_or_mac", NULL, MAVLINK_TYPE_UINT8_T, 20, 22, offsetof(mavlink_open_drone_id_system_t, id_or_mac) }, \
{ "operator_location_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 42, offsetof(mavlink_open_drone_id_system_t, operator_location_type) }, \
{ "classification_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 43, offsetof(mavlink_open_drone_id_system_t, classification_type) }, \
{ "operator_latitude", NULL, MAVLINK_TYPE_INT32_T, 0, 0, offsetof(mavlink_open_drone_id_system_t, operator_latitude) }, \
{ "operator_longitude", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_open_drone_id_system_t, operator_longitude) }, \
{ "area_count", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_open_drone_id_system_t, area_count) }, \
{ "area_radius", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_open_drone_id_system_t, area_radius) }, \
{ "area_ceiling", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_open_drone_id_system_t, area_ceiling) }, \
{ "area_floor", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_open_drone_id_system_t, area_floor) }, \
{ "category_eu", NULL, MAVLINK_TYPE_UINT8_T, 0, 44, offsetof(mavlink_open_drone_id_system_t, category_eu) }, \
{ "class_eu", NULL, MAVLINK_TYPE_UINT8_T, 0, 45, offsetof(mavlink_open_drone_id_system_t, class_eu) }, \
} \
}
#endif
/**
* @brief Pack a open_drone_id_system message
* @param system_id ID of this 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 (0 for broadcast).
* @param target_component Component ID (0 for broadcast).
* @param id_or_mac Only used for drone ID data received from other UAs. See detailed description at https://mavlink.io/en/services/opendroneid.html.
* @param operator_location_type Specifies the operator location type.
* @param classification_type Specifies the classification type of the UA.
* @param operator_latitude [degE7] Latitude of the operator. If unknown: 0 (both Lat/Lon).
* @param operator_longitude [degE7] Longitude of the operator. If unknown: 0 (both Lat/Lon).
* @param area_count Number of aircraft in the area, group or formation (default 1).
* @param area_radius [m] Radius of the cylindrical area of the group or formation (default 0).
* @param area_ceiling [m] Area Operations Ceiling relative to WGS84. If unknown: -1000 m.
* @param area_floor [m] Area Operations Floor relative to WGS84. If unknown: -1000 m.
* @param category_eu When classification_type is MAV_ODID_CLASSIFICATION_TYPE_EU, specifies the category of the UA.
* @param class_eu When classification_type is MAV_ODID_CLASSIFICATION_TYPE_EU, specifies the class of the UA.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_open_drone_id_system_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint8_t target_system, uint8_t target_component, const uint8_t *id_or_mac, uint8_t operator_location_type, uint8_t classification_type, int32_t operator_latitude, int32_t operator_longitude, uint16_t area_count, uint16_t area_radius, float area_ceiling, float area_floor, uint8_t category_eu, uint8_t class_eu)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_LEN];
_mav_put_int32_t(buf, 0, operator_latitude);
_mav_put_int32_t(buf, 4, operator_longitude);
_mav_put_float(buf, 8, area_ceiling);
_mav_put_float(buf, 12, area_floor);
_mav_put_uint16_t(buf, 16, area_count);
_mav_put_uint16_t(buf, 18, area_radius);
_mav_put_uint8_t(buf, 20, target_system);
_mav_put_uint8_t(buf, 21, target_component);
_mav_put_uint8_t(buf, 42, operator_location_type);
_mav_put_uint8_t(buf, 43, classification_type);
_mav_put_uint8_t(buf, 44, category_eu);
_mav_put_uint8_t(buf, 45, class_eu);
_mav_put_uint8_t_array(buf, 22, id_or_mac, 20);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_LEN);
#else
mavlink_open_drone_id_system_t packet;
packet.operator_latitude = operator_latitude;
packet.operator_longitude = operator_longitude;
packet.area_ceiling = area_ceiling;
packet.area_floor = area_floor;
packet.area_count = area_count;
packet.area_radius = area_radius;
packet.target_system = target_system;
packet.target_component = target_component;
packet.operator_location_type = operator_location_type;
packet.classification_type = classification_type;
packet.category_eu = category_eu;
packet.class_eu = class_eu;
mav_array_memcpy(packet.id_or_mac, id_or_mac, sizeof(uint8_t)*20);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM;
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_MIN_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_CRC);
}
/**
* @brief Pack a open_drone_id_system message on a channel
* @param system_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 (0 for broadcast).
* @param target_component Component ID (0 for broadcast).
* @param id_or_mac Only used for drone ID data received from other UAs. See detailed description at https://mavlink.io/en/services/opendroneid.html.
* @param operator_location_type Specifies the operator location type.
* @param classification_type Specifies the classification type of the UA.
* @param operator_latitude [degE7] Latitude of the operator. If unknown: 0 (both Lat/Lon).
* @param operator_longitude [degE7] Longitude of the operator. If unknown: 0 (both Lat/Lon).
* @param area_count Number of aircraft in the area, group or formation (default 1).
* @param area_radius [m] Radius of the cylindrical area of the group or formation (default 0).
* @param area_ceiling [m] Area Operations Ceiling relative to WGS84. If unknown: -1000 m.
* @param area_floor [m] Area Operations Floor relative to WGS84. If unknown: -1000 m.
* @param category_eu When classification_type is MAV_ODID_CLASSIFICATION_TYPE_EU, specifies the category of the UA.
* @param class_eu When classification_type is MAV_ODID_CLASSIFICATION_TYPE_EU, specifies the class of the UA.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_open_drone_id_system_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 uint8_t *id_or_mac,uint8_t operator_location_type,uint8_t classification_type,int32_t operator_latitude,int32_t operator_longitude,uint16_t area_count,uint16_t area_radius,float area_ceiling,float area_floor,uint8_t category_eu,uint8_t class_eu)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_LEN];
_mav_put_int32_t(buf, 0, operator_latitude);
_mav_put_int32_t(buf, 4, operator_longitude);
_mav_put_float(buf, 8, area_ceiling);
_mav_put_float(buf, 12, area_floor);
_mav_put_uint16_t(buf, 16, area_count);
_mav_put_uint16_t(buf, 18, area_radius);
_mav_put_uint8_t(buf, 20, target_system);
_mav_put_uint8_t(buf, 21, target_component);
_mav_put_uint8_t(buf, 42, operator_location_type);
_mav_put_uint8_t(buf, 43, classification_type);
_mav_put_uint8_t(buf, 44, category_eu);
_mav_put_uint8_t(buf, 45, class_eu);
_mav_put_uint8_t_array(buf, 22, id_or_mac, 20);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_LEN);
#else
mavlink_open_drone_id_system_t packet;
packet.operator_latitude = operator_latitude;
packet.operator_longitude = operator_longitude;
packet.area_ceiling = area_ceiling;
packet.area_floor = area_floor;
packet.area_count = area_count;
packet.area_radius = area_radius;
packet.target_system = target_system;
packet.target_component = target_component;
packet.operator_location_type = operator_location_type;
packet.classification_type = classification_type;
packet.category_eu = category_eu;
packet.class_eu = class_eu;
mav_array_memcpy(packet.id_or_mac, id_or_mac, sizeof(uint8_t)*20);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_MIN_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_CRC);
}
/**
* @brief Encode a open_drone_id_system 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 open_drone_id_system C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_open_drone_id_system_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_open_drone_id_system_t* open_drone_id_system)
{
return mavlink_msg_open_drone_id_system_pack(system_id, component_id, msg, open_drone_id_system->target_system, open_drone_id_system->target_component, open_drone_id_system->id_or_mac, open_drone_id_system->operator_location_type, open_drone_id_system->classification_type, open_drone_id_system->operator_latitude, open_drone_id_system->operator_longitude, open_drone_id_system->area_count, open_drone_id_system->area_radius, open_drone_id_system->area_ceiling, open_drone_id_system->area_floor, open_drone_id_system->category_eu, open_drone_id_system->class_eu);
}
/**
* @brief Encode a open_drone_id_system 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 open_drone_id_system C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_open_drone_id_system_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_open_drone_id_system_t* open_drone_id_system)
{
return mavlink_msg_open_drone_id_system_pack_chan(system_id, component_id, chan, msg, open_drone_id_system->target_system, open_drone_id_system->target_component, open_drone_id_system->id_or_mac, open_drone_id_system->operator_location_type, open_drone_id_system->classification_type, open_drone_id_system->operator_latitude, open_drone_id_system->operator_longitude, open_drone_id_system->area_count, open_drone_id_system->area_radius, open_drone_id_system->area_ceiling, open_drone_id_system->area_floor, open_drone_id_system->category_eu, open_drone_id_system->class_eu);
}
/**
* @brief Send a open_drone_id_system message
* @param chan MAVLink channel to send the message
*
* @param target_system System ID (0 for broadcast).
* @param target_component Component ID (0 for broadcast).
* @param id_or_mac Only used for drone ID data received from other UAs. See detailed description at https://mavlink.io/en/services/opendroneid.html.
* @param operator_location_type Specifies the operator location type.
* @param classification_type Specifies the classification type of the UA.
* @param operator_latitude [degE7] Latitude of the operator. If unknown: 0 (both Lat/Lon).
* @param operator_longitude [degE7] Longitude of the operator. If unknown: 0 (both Lat/Lon).
* @param area_count Number of aircraft in the area, group or formation (default 1).
* @param area_radius [m] Radius of the cylindrical area of the group or formation (default 0).
* @param area_ceiling [m] Area Operations Ceiling relative to WGS84. If unknown: -1000 m.
* @param area_floor [m] Area Operations Floor relative to WGS84. If unknown: -1000 m.
* @param category_eu When classification_type is MAV_ODID_CLASSIFICATION_TYPE_EU, specifies the category of the UA.
* @param class_eu When classification_type is MAV_ODID_CLASSIFICATION_TYPE_EU, specifies the class of the UA.
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_open_drone_id_system_send(mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, const uint8_t *id_or_mac, uint8_t operator_location_type, uint8_t classification_type, int32_t operator_latitude, int32_t operator_longitude, uint16_t area_count, uint16_t area_radius, float area_ceiling, float area_floor, uint8_t category_eu, uint8_t class_eu)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_LEN];
_mav_put_int32_t(buf, 0, operator_latitude);
_mav_put_int32_t(buf, 4, operator_longitude);
_mav_put_float(buf, 8, area_ceiling);
_mav_put_float(buf, 12, area_floor);
_mav_put_uint16_t(buf, 16, area_count);
_mav_put_uint16_t(buf, 18, area_radius);
_mav_put_uint8_t(buf, 20, target_system);
_mav_put_uint8_t(buf, 21, target_component);
_mav_put_uint8_t(buf, 42, operator_location_type);
_mav_put_uint8_t(buf, 43, classification_type);
_mav_put_uint8_t(buf, 44, category_eu);
_mav_put_uint8_t(buf, 45, class_eu);
_mav_put_uint8_t_array(buf, 22, id_or_mac, 20);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM, buf, MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_MIN_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_CRC);
#else
mavlink_open_drone_id_system_t packet;
packet.operator_latitude = operator_latitude;
packet.operator_longitude = operator_longitude;
packet.area_ceiling = area_ceiling;
packet.area_floor = area_floor;
packet.area_count = area_count;
packet.area_radius = area_radius;
packet.target_system = target_system;
packet.target_component = target_component;
packet.operator_location_type = operator_location_type;
packet.classification_type = classification_type;
packet.category_eu = category_eu;
packet.class_eu = class_eu;
mav_array_memcpy(packet.id_or_mac, id_or_mac, sizeof(uint8_t)*20);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM, (const char *)&packet, MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_MIN_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_CRC);
#endif
}
/**
* @brief Send a open_drone_id_system message
* @param chan MAVLink channel to send the message
* @param struct The MAVLink struct to serialize
*/
static inline void mavlink_msg_open_drone_id_system_send_struct(mavlink_channel_t chan, const mavlink_open_drone_id_system_t* open_drone_id_system)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mavlink_msg_open_drone_id_system_send(chan, open_drone_id_system->target_system, open_drone_id_system->target_component, open_drone_id_system->id_or_mac, open_drone_id_system->operator_location_type, open_drone_id_system->classification_type, open_drone_id_system->operator_latitude, open_drone_id_system->operator_longitude, open_drone_id_system->area_count, open_drone_id_system->area_radius, open_drone_id_system->area_ceiling, open_drone_id_system->area_floor, open_drone_id_system->category_eu, open_drone_id_system->class_eu);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM, (const char *)open_drone_id_system, MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_MIN_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_CRC);
#endif
}
#if MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_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_open_drone_id_system_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint8_t target_system, uint8_t target_component, const uint8_t *id_or_mac, uint8_t operator_location_type, uint8_t classification_type, int32_t operator_latitude, int32_t operator_longitude, uint16_t area_count, uint16_t area_radius, float area_ceiling, float area_floor, uint8_t category_eu, uint8_t class_eu)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
_mav_put_int32_t(buf, 0, operator_latitude);
_mav_put_int32_t(buf, 4, operator_longitude);
_mav_put_float(buf, 8, area_ceiling);
_mav_put_float(buf, 12, area_floor);
_mav_put_uint16_t(buf, 16, area_count);
_mav_put_uint16_t(buf, 18, area_radius);
_mav_put_uint8_t(buf, 20, target_system);
_mav_put_uint8_t(buf, 21, target_component);
_mav_put_uint8_t(buf, 42, operator_location_type);
_mav_put_uint8_t(buf, 43, classification_type);
_mav_put_uint8_t(buf, 44, category_eu);
_mav_put_uint8_t(buf, 45, class_eu);
_mav_put_uint8_t_array(buf, 22, id_or_mac, 20);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM, buf, MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_MIN_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_CRC);
#else
mavlink_open_drone_id_system_t *packet = (mavlink_open_drone_id_system_t *)msgbuf;
packet->operator_latitude = operator_latitude;
packet->operator_longitude = operator_longitude;
packet->area_ceiling = area_ceiling;
packet->area_floor = area_floor;
packet->area_count = area_count;
packet->area_radius = area_radius;
packet->target_system = target_system;
packet->target_component = target_component;
packet->operator_location_type = operator_location_type;
packet->classification_type = classification_type;
packet->category_eu = category_eu;
packet->class_eu = class_eu;
mav_array_memcpy(packet->id_or_mac, id_or_mac, sizeof(uint8_t)*20);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM, (const char *)packet, MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_MIN_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_LEN, MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_CRC);
#endif
}
#endif
#endif
// MESSAGE OPEN_DRONE_ID_SYSTEM UNPACKING
/**
* @brief Get field target_system from open_drone_id_system message
*
* @return System ID (0 for broadcast).
*/
static inline uint8_t mavlink_msg_open_drone_id_system_get_target_system(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 20);
}
/**
* @brief Get field target_component from open_drone_id_system message
*
* @return Component ID (0 for broadcast).
*/
static inline uint8_t mavlink_msg_open_drone_id_system_get_target_component(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 21);
}
/**
* @brief Get field id_or_mac from open_drone_id_system message
*
* @return Only used for drone ID data received from other UAs. See detailed description at https://mavlink.io/en/services/opendroneid.html.
*/
static inline uint16_t mavlink_msg_open_drone_id_system_get_id_or_mac(const mavlink_message_t* msg, uint8_t *id_or_mac)
{
return _MAV_RETURN_uint8_t_array(msg, id_or_mac, 20, 22);
}
/**
* @brief Get field operator_location_type from open_drone_id_system message
*
* @return Specifies the operator location type.
*/
static inline uint8_t mavlink_msg_open_drone_id_system_get_operator_location_type(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 42);
}
/**
* @brief Get field classification_type from open_drone_id_system message
*
* @return Specifies the classification type of the UA.
*/
static inline uint8_t mavlink_msg_open_drone_id_system_get_classification_type(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 43);
}
/**
* @brief Get field operator_latitude from open_drone_id_system message
*
* @return [degE7] Latitude of the operator. If unknown: 0 (both Lat/Lon).
*/
static inline int32_t mavlink_msg_open_drone_id_system_get_operator_latitude(const mavlink_message_t* msg)
{
return _MAV_RETURN_int32_t(msg, 0);
}
/**
* @brief Get field operator_longitude from open_drone_id_system message
*
* @return [degE7] Longitude of the operator. If unknown: 0 (both Lat/Lon).
*/
static inline int32_t mavlink_msg_open_drone_id_system_get_operator_longitude(const mavlink_message_t* msg)
{
return _MAV_RETURN_int32_t(msg, 4);
}
/**
* @brief Get field area_count from open_drone_id_system message
*
* @return Number of aircraft in the area, group or formation (default 1).
*/
static inline uint16_t mavlink_msg_open_drone_id_system_get_area_count(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 16);
}
/**
* @brief Get field area_radius from open_drone_id_system message
*
* @return [m] Radius of the cylindrical area of the group or formation (default 0).
*/
static inline uint16_t mavlink_msg_open_drone_id_system_get_area_radius(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 18);
}
/**
* @brief Get field area_ceiling from open_drone_id_system message
*
* @return [m] Area Operations Ceiling relative to WGS84. If unknown: -1000 m.
*/
static inline float mavlink_msg_open_drone_id_system_get_area_ceiling(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 8);
}
/**
* @brief Get field area_floor from open_drone_id_system message
*
* @return [m] Area Operations Floor relative to WGS84. If unknown: -1000 m.
*/
static inline float mavlink_msg_open_drone_id_system_get_area_floor(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 12);
}
/**
* @brief Get field category_eu from open_drone_id_system message
*
* @return When classification_type is MAV_ODID_CLASSIFICATION_TYPE_EU, specifies the category of the UA.
*/
static inline uint8_t mavlink_msg_open_drone_id_system_get_category_eu(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 44);
}
/**
* @brief Get field class_eu from open_drone_id_system message
*
* @return When classification_type is MAV_ODID_CLASSIFICATION_TYPE_EU, specifies the class of the UA.
*/
static inline uint8_t mavlink_msg_open_drone_id_system_get_class_eu(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 45);
}
/**
* @brief Decode a open_drone_id_system message into a struct
*
* @param msg The message to decode
* @param open_drone_id_system C-struct to decode the message contents into
*/
static inline void mavlink_msg_open_drone_id_system_decode(const mavlink_message_t* msg, mavlink_open_drone_id_system_t* open_drone_id_system)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
open_drone_id_system->operator_latitude = mavlink_msg_open_drone_id_system_get_operator_latitude(msg);
open_drone_id_system->operator_longitude = mavlink_msg_open_drone_id_system_get_operator_longitude(msg);
open_drone_id_system->area_ceiling = mavlink_msg_open_drone_id_system_get_area_ceiling(msg);
open_drone_id_system->area_floor = mavlink_msg_open_drone_id_system_get_area_floor(msg);
open_drone_id_system->area_count = mavlink_msg_open_drone_id_system_get_area_count(msg);
open_drone_id_system->area_radius = mavlink_msg_open_drone_id_system_get_area_radius(msg);
open_drone_id_system->target_system = mavlink_msg_open_drone_id_system_get_target_system(msg);
open_drone_id_system->target_component = mavlink_msg_open_drone_id_system_get_target_component(msg);
mavlink_msg_open_drone_id_system_get_id_or_mac(msg, open_drone_id_system->id_or_mac);
open_drone_id_system->operator_location_type = mavlink_msg_open_drone_id_system_get_operator_location_type(msg);
open_drone_id_system->classification_type = mavlink_msg_open_drone_id_system_get_classification_type(msg);
open_drone_id_system->category_eu = mavlink_msg_open_drone_id_system_get_category_eu(msg);
open_drone_id_system->class_eu = mavlink_msg_open_drone_id_system_get_class_eu(msg);
#else
uint8_t len = msg->len < MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_LEN? msg->len : MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_LEN;
memset(open_drone_id_system, 0, MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM_LEN);
memcpy(open_drone_id_system, _MAV_PAYLOAD(msg), len);
#endif
}

View file

@ -3,7 +3,7 @@
#define MAVLINK_MSG_ID_OPTICAL_FLOW 100
MAVPACKED(
typedef struct __mavlink_optical_flow_t {
uint64_t time_usec; /*< [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.*/
float flow_comp_m_x; /*< [m/s] Flow in x-sensor direction, angular-speed compensated*/
@ -13,11 +13,13 @@ typedef struct __mavlink_optical_flow_t {
int16_t flow_y; /*< [dpix] Flow in y-sensor direction*/
uint8_t sensor_id; /*< Sensor ID*/
uint8_t quality; /*< Optical flow quality / confidence. 0: bad, 255: maximum quality*/
} mavlink_optical_flow_t;
float flow_rate_x; /*< [rad/s] Flow rate about X axis*/
float flow_rate_y; /*< [rad/s] Flow rate about Y axis*/
}) mavlink_optical_flow_t;
#define MAVLINK_MSG_ID_OPTICAL_FLOW_LEN 26
#define MAVLINK_MSG_ID_OPTICAL_FLOW_LEN 34
#define MAVLINK_MSG_ID_OPTICAL_FLOW_MIN_LEN 26
#define MAVLINK_MSG_ID_100_LEN 26
#define MAVLINK_MSG_ID_100_LEN 34
#define MAVLINK_MSG_ID_100_MIN_LEN 26
#define MAVLINK_MSG_ID_OPTICAL_FLOW_CRC 175
@ -29,7 +31,7 @@ typedef struct __mavlink_optical_flow_t {
#define MAVLINK_MESSAGE_INFO_OPTICAL_FLOW { \
100, \
"OPTICAL_FLOW", \
8, \
10, \
{ { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_optical_flow_t, time_usec) }, \
{ "sensor_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 24, offsetof(mavlink_optical_flow_t, sensor_id) }, \
{ "flow_x", NULL, MAVLINK_TYPE_INT16_T, 0, 20, offsetof(mavlink_optical_flow_t, flow_x) }, \
@ -38,12 +40,14 @@ typedef struct __mavlink_optical_flow_t {
{ "flow_comp_m_y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_optical_flow_t, flow_comp_m_y) }, \
{ "quality", NULL, MAVLINK_TYPE_UINT8_T, 0, 25, offsetof(mavlink_optical_flow_t, quality) }, \
{ "ground_distance", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_optical_flow_t, ground_distance) }, \
{ "flow_rate_x", NULL, MAVLINK_TYPE_FLOAT, 0, 26, offsetof(mavlink_optical_flow_t, flow_rate_x) }, \
{ "flow_rate_y", NULL, MAVLINK_TYPE_FLOAT, 0, 30, offsetof(mavlink_optical_flow_t, flow_rate_y) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_OPTICAL_FLOW { \
"OPTICAL_FLOW", \
8, \
10, \
{ { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_optical_flow_t, time_usec) }, \
{ "sensor_id", NULL, MAVLINK_TYPE_UINT8_T, 0, 24, offsetof(mavlink_optical_flow_t, sensor_id) }, \
{ "flow_x", NULL, MAVLINK_TYPE_INT16_T, 0, 20, offsetof(mavlink_optical_flow_t, flow_x) }, \
@ -52,6 +56,8 @@ typedef struct __mavlink_optical_flow_t {
{ "flow_comp_m_y", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_optical_flow_t, flow_comp_m_y) }, \
{ "quality", NULL, MAVLINK_TYPE_UINT8_T, 0, 25, offsetof(mavlink_optical_flow_t, quality) }, \
{ "ground_distance", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_optical_flow_t, ground_distance) }, \
{ "flow_rate_x", NULL, MAVLINK_TYPE_FLOAT, 0, 26, offsetof(mavlink_optical_flow_t, flow_rate_x) }, \
{ "flow_rate_y", NULL, MAVLINK_TYPE_FLOAT, 0, 30, offsetof(mavlink_optical_flow_t, flow_rate_y) }, \
} \
}
#endif
@ -70,10 +76,12 @@ typedef struct __mavlink_optical_flow_t {
* @param flow_comp_m_y [m/s] Flow in y-sensor direction, angular-speed compensated
* @param quality Optical flow quality / confidence. 0: bad, 255: maximum quality
* @param ground_distance [m] Ground distance. Positive value: distance known. Negative value: Unknown distance
* @param flow_rate_x [rad/s] Flow rate about X axis
* @param flow_rate_y [rad/s] Flow rate about Y axis
* @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)
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, float flow_rate_x, float flow_rate_y)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_OPTICAL_FLOW_LEN];
@ -85,6 +93,8 @@ static inline uint16_t mavlink_msg_optical_flow_pack(uint8_t system_id, uint8_t
_mav_put_int16_t(buf, 22, flow_y);
_mav_put_uint8_t(buf, 24, sensor_id);
_mav_put_uint8_t(buf, 25, quality);
_mav_put_float(buf, 26, flow_rate_x);
_mav_put_float(buf, 30, flow_rate_y);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_OPTICAL_FLOW_LEN);
#else
@ -97,6 +107,8 @@ static inline uint16_t mavlink_msg_optical_flow_pack(uint8_t system_id, uint8_t
packet.flow_y = flow_y;
packet.sensor_id = sensor_id;
packet.quality = quality;
packet.flow_rate_x = flow_rate_x;
packet.flow_rate_y = flow_rate_y;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_OPTICAL_FLOW_LEN);
#endif
@ -119,11 +131,13 @@ static inline uint16_t mavlink_msg_optical_flow_pack(uint8_t system_id, uint8_t
* @param flow_comp_m_y [m/s] Flow in y-sensor direction, angular-speed compensated
* @param quality Optical flow quality / confidence. 0: bad, 255: maximum quality
* @param ground_distance [m] Ground distance. Positive value: distance known. Negative value: Unknown distance
* @param flow_rate_x [rad/s] Flow rate about X axis
* @param flow_rate_y [rad/s] Flow rate about Y axis
* @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)
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,float flow_rate_x,float flow_rate_y)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_OPTICAL_FLOW_LEN];
@ -135,6 +149,8 @@ static inline uint16_t mavlink_msg_optical_flow_pack_chan(uint8_t system_id, uin
_mav_put_int16_t(buf, 22, flow_y);
_mav_put_uint8_t(buf, 24, sensor_id);
_mav_put_uint8_t(buf, 25, quality);
_mav_put_float(buf, 26, flow_rate_x);
_mav_put_float(buf, 30, flow_rate_y);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_OPTICAL_FLOW_LEN);
#else
@ -147,6 +163,8 @@ static inline uint16_t mavlink_msg_optical_flow_pack_chan(uint8_t system_id, uin
packet.flow_y = flow_y;
packet.sensor_id = sensor_id;
packet.quality = quality;
packet.flow_rate_x = flow_rate_x;
packet.flow_rate_y = flow_rate_y;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_OPTICAL_FLOW_LEN);
#endif
@ -165,7 +183,7 @@ static inline uint16_t mavlink_msg_optical_flow_pack_chan(uint8_t system_id, uin
*/
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);
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, optical_flow->flow_rate_x, optical_flow->flow_rate_y);
}
/**
@ -179,7 +197,7 @@ static inline uint16_t mavlink_msg_optical_flow_encode(uint8_t system_id, uint8_
*/
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);
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, optical_flow->flow_rate_x, optical_flow->flow_rate_y);
}
/**
@ -194,10 +212,12 @@ static inline uint16_t mavlink_msg_optical_flow_encode_chan(uint8_t system_id, u
* @param flow_comp_m_y [m/s] Flow in y-sensor direction, angular-speed compensated
* @param quality Optical flow quality / confidence. 0: bad, 255: maximum quality
* @param ground_distance [m] Ground distance. Positive value: distance known. Negative value: Unknown distance
* @param flow_rate_x [rad/s] Flow rate about X axis
* @param flow_rate_y [rad/s] Flow rate about Y axis
*/
#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)
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, float flow_rate_x, float flow_rate_y)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_OPTICAL_FLOW_LEN];
@ -209,6 +229,8 @@ static inline void mavlink_msg_optical_flow_send(mavlink_channel_t chan, uint64_
_mav_put_int16_t(buf, 22, flow_y);
_mav_put_uint8_t(buf, 24, sensor_id);
_mav_put_uint8_t(buf, 25, quality);
_mav_put_float(buf, 26, flow_rate_x);
_mav_put_float(buf, 30, flow_rate_y);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPTICAL_FLOW, buf, MAVLINK_MSG_ID_OPTICAL_FLOW_MIN_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_CRC);
#else
@ -221,6 +243,8 @@ static inline void mavlink_msg_optical_flow_send(mavlink_channel_t chan, uint64_
packet.flow_y = flow_y;
packet.sensor_id = sensor_id;
packet.quality = quality;
packet.flow_rate_x = flow_rate_x;
packet.flow_rate_y = flow_rate_y;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPTICAL_FLOW, (const char *)&packet, MAVLINK_MSG_ID_OPTICAL_FLOW_MIN_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_CRC);
#endif
@ -234,7 +258,7 @@ static inline void mavlink_msg_optical_flow_send(mavlink_channel_t chan, uint64_
static inline void mavlink_msg_optical_flow_send_struct(mavlink_channel_t chan, const mavlink_optical_flow_t* optical_flow)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mavlink_msg_optical_flow_send(chan, 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);
mavlink_msg_optical_flow_send(chan, 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, optical_flow->flow_rate_x, optical_flow->flow_rate_y);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPTICAL_FLOW, (const char *)optical_flow, MAVLINK_MSG_ID_OPTICAL_FLOW_MIN_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_CRC);
#endif
@ -248,7 +272,7 @@ static inline void mavlink_msg_optical_flow_send_struct(mavlink_channel_t chan,
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)
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, float flow_rate_x, float flow_rate_y)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
@ -260,6 +284,8 @@ static inline void mavlink_msg_optical_flow_send_buf(mavlink_message_t *msgbuf,
_mav_put_int16_t(buf, 22, flow_y);
_mav_put_uint8_t(buf, 24, sensor_id);
_mav_put_uint8_t(buf, 25, quality);
_mav_put_float(buf, 26, flow_rate_x);
_mav_put_float(buf, 30, flow_rate_y);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPTICAL_FLOW, buf, MAVLINK_MSG_ID_OPTICAL_FLOW_MIN_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_CRC);
#else
@ -272,6 +298,8 @@ static inline void mavlink_msg_optical_flow_send_buf(mavlink_message_t *msgbuf,
packet->flow_y = flow_y;
packet->sensor_id = sensor_id;
packet->quality = quality;
packet->flow_rate_x = flow_rate_x;
packet->flow_rate_y = flow_rate_y;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_OPTICAL_FLOW, (const char *)packet, MAVLINK_MSG_ID_OPTICAL_FLOW_MIN_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_LEN, MAVLINK_MSG_ID_OPTICAL_FLOW_CRC);
#endif
@ -363,6 +391,26 @@ static inline float mavlink_msg_optical_flow_get_ground_distance(const mavlink_m
return _MAV_RETURN_float(msg, 16);
}
/**
* @brief Get field flow_rate_x from optical_flow message
*
* @return [rad/s] Flow rate about X axis
*/
static inline float mavlink_msg_optical_flow_get_flow_rate_x(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 26);
}
/**
* @brief Get field flow_rate_y from optical_flow message
*
* @return [rad/s] Flow rate about Y axis
*/
static inline float mavlink_msg_optical_flow_get_flow_rate_y(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 30);
}
/**
* @brief Decode a optical_flow message into a struct
*
@ -380,6 +428,8 @@ static inline void mavlink_msg_optical_flow_decode(const mavlink_message_t* 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);
optical_flow->flow_rate_x = mavlink_msg_optical_flow_get_flow_rate_x(msg);
optical_flow->flow_rate_y = mavlink_msg_optical_flow_get_flow_rate_y(msg);
#else
uint8_t len = msg->len < MAVLINK_MSG_ID_OPTICAL_FLOW_LEN? msg->len : MAVLINK_MSG_ID_OPTICAL_FLOW_LEN;
memset(optical_flow, 0, MAVLINK_MSG_ID_OPTICAL_FLOW_LEN);

View file

@ -0,0 +1,338 @@
#pragma once
// MESSAGE ORBIT_EXECUTION_STATUS PACKING
#define MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS 360
typedef struct __mavlink_orbit_execution_status_t {
uint64_t time_usec; /*< [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.*/
float radius; /*< [m] Radius of the orbit circle. Positive values orbit clockwise, negative values orbit counter-clockwise.*/
int32_t x; /*< X coordinate of center point. Coordinate system depends on frame field: local = x position in meters * 1e4, global = latitude in degrees * 1e7.*/
int32_t y; /*< Y coordinate of center point. Coordinate system depends on frame field: local = x position in meters * 1e4, global = latitude in degrees * 1e7.*/
float z; /*< [m] Altitude of center point. Coordinate system depends on frame field.*/
uint8_t frame; /*< The coordinate system of the fields: x, y, z.*/
} mavlink_orbit_execution_status_t;
#define MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS_LEN 25
#define MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS_MIN_LEN 25
#define MAVLINK_MSG_ID_360_LEN 25
#define MAVLINK_MSG_ID_360_MIN_LEN 25
#define MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS_CRC 11
#define MAVLINK_MSG_ID_360_CRC 11
#if MAVLINK_COMMAND_24BIT
#define MAVLINK_MESSAGE_INFO_ORBIT_EXECUTION_STATUS { \
360, \
"ORBIT_EXECUTION_STATUS", \
6, \
{ { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_orbit_execution_status_t, time_usec) }, \
{ "radius", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_orbit_execution_status_t, radius) }, \
{ "frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 24, offsetof(mavlink_orbit_execution_status_t, frame) }, \
{ "x", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_orbit_execution_status_t, x) }, \
{ "y", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_orbit_execution_status_t, y) }, \
{ "z", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_orbit_execution_status_t, z) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_ORBIT_EXECUTION_STATUS { \
"ORBIT_EXECUTION_STATUS", \
6, \
{ { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_orbit_execution_status_t, time_usec) }, \
{ "radius", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_orbit_execution_status_t, radius) }, \
{ "frame", NULL, MAVLINK_TYPE_UINT8_T, 0, 24, offsetof(mavlink_orbit_execution_status_t, frame) }, \
{ "x", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_orbit_execution_status_t, x) }, \
{ "y", NULL, MAVLINK_TYPE_INT32_T, 0, 16, offsetof(mavlink_orbit_execution_status_t, y) }, \
{ "z", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_orbit_execution_status_t, z) }, \
} \
}
#endif
/**
* @brief Pack a orbit_execution_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 time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
* @param radius [m] Radius of the orbit circle. Positive values orbit clockwise, negative values orbit counter-clockwise.
* @param frame The coordinate system of the fields: x, y, z.
* @param x X coordinate of center point. Coordinate system depends on frame field: local = x position in meters * 1e4, global = latitude in degrees * 1e7.
* @param y Y coordinate of center point. Coordinate system depends on frame field: local = x position in meters * 1e4, global = latitude in degrees * 1e7.
* @param z [m] Altitude of center point. Coordinate system depends on frame field.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_orbit_execution_status_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint64_t time_usec, float radius, uint8_t frame, int32_t x, int32_t y, float z)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS_LEN];
_mav_put_uint64_t(buf, 0, time_usec);
_mav_put_float(buf, 8, radius);
_mav_put_int32_t(buf, 12, x);
_mav_put_int32_t(buf, 16, y);
_mav_put_float(buf, 20, z);
_mav_put_uint8_t(buf, 24, frame);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS_LEN);
#else
mavlink_orbit_execution_status_t packet;
packet.time_usec = time_usec;
packet.radius = radius;
packet.x = x;
packet.y = y;
packet.z = z;
packet.frame = frame;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS;
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS_MIN_LEN, MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS_LEN, MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS_CRC);
}
/**
* @brief Pack a orbit_execution_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 time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
* @param radius [m] Radius of the orbit circle. Positive values orbit clockwise, negative values orbit counter-clockwise.
* @param frame The coordinate system of the fields: x, y, z.
* @param x X coordinate of center point. Coordinate system depends on frame field: local = x position in meters * 1e4, global = latitude in degrees * 1e7.
* @param y Y coordinate of center point. Coordinate system depends on frame field: local = x position in meters * 1e4, global = latitude in degrees * 1e7.
* @param z [m] Altitude of center point. Coordinate system depends on frame field.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_orbit_execution_status_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint64_t time_usec,float radius,uint8_t frame,int32_t x,int32_t y,float z)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS_LEN];
_mav_put_uint64_t(buf, 0, time_usec);
_mav_put_float(buf, 8, radius);
_mav_put_int32_t(buf, 12, x);
_mav_put_int32_t(buf, 16, y);
_mav_put_float(buf, 20, z);
_mav_put_uint8_t(buf, 24, frame);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS_LEN);
#else
mavlink_orbit_execution_status_t packet;
packet.time_usec = time_usec;
packet.radius = radius;
packet.x = x;
packet.y = y;
packet.z = z;
packet.frame = frame;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS_MIN_LEN, MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS_LEN, MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS_CRC);
}
/**
* @brief Encode a orbit_execution_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 orbit_execution_status C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_orbit_execution_status_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_orbit_execution_status_t* orbit_execution_status)
{
return mavlink_msg_orbit_execution_status_pack(system_id, component_id, msg, orbit_execution_status->time_usec, orbit_execution_status->radius, orbit_execution_status->frame, orbit_execution_status->x, orbit_execution_status->y, orbit_execution_status->z);
}
/**
* @brief Encode a orbit_execution_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 orbit_execution_status C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_orbit_execution_status_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_orbit_execution_status_t* orbit_execution_status)
{
return mavlink_msg_orbit_execution_status_pack_chan(system_id, component_id, chan, msg, orbit_execution_status->time_usec, orbit_execution_status->radius, orbit_execution_status->frame, orbit_execution_status->x, orbit_execution_status->y, orbit_execution_status->z);
}
/**
* @brief Send a orbit_execution_status message
* @param chan MAVLink channel to send the message
*
* @param time_usec [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
* @param radius [m] Radius of the orbit circle. Positive values orbit clockwise, negative values orbit counter-clockwise.
* @param frame The coordinate system of the fields: x, y, z.
* @param x X coordinate of center point. Coordinate system depends on frame field: local = x position in meters * 1e4, global = latitude in degrees * 1e7.
* @param y Y coordinate of center point. Coordinate system depends on frame field: local = x position in meters * 1e4, global = latitude in degrees * 1e7.
* @param z [m] Altitude of center point. Coordinate system depends on frame field.
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_orbit_execution_status_send(mavlink_channel_t chan, uint64_t time_usec, float radius, uint8_t frame, int32_t x, int32_t y, float z)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS_LEN];
_mav_put_uint64_t(buf, 0, time_usec);
_mav_put_float(buf, 8, radius);
_mav_put_int32_t(buf, 12, x);
_mav_put_int32_t(buf, 16, y);
_mav_put_float(buf, 20, z);
_mav_put_uint8_t(buf, 24, frame);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS, buf, MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS_MIN_LEN, MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS_LEN, MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS_CRC);
#else
mavlink_orbit_execution_status_t packet;
packet.time_usec = time_usec;
packet.radius = radius;
packet.x = x;
packet.y = y;
packet.z = z;
packet.frame = frame;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS, (const char *)&packet, MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS_MIN_LEN, MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS_LEN, MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS_CRC);
#endif
}
/**
* @brief Send a orbit_execution_status message
* @param chan MAVLink channel to send the message
* @param struct The MAVLink struct to serialize
*/
static inline void mavlink_msg_orbit_execution_status_send_struct(mavlink_channel_t chan, const mavlink_orbit_execution_status_t* orbit_execution_status)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mavlink_msg_orbit_execution_status_send(chan, orbit_execution_status->time_usec, orbit_execution_status->radius, orbit_execution_status->frame, orbit_execution_status->x, orbit_execution_status->y, orbit_execution_status->z);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS, (const char *)orbit_execution_status, MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS_MIN_LEN, MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS_LEN, MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS_CRC);
#endif
}
#if MAVLINK_MSG_ID_ORBIT_EXECUTION_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_orbit_execution_status_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, float radius, uint8_t frame, int32_t x, int32_t 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, radius);
_mav_put_int32_t(buf, 12, x);
_mav_put_int32_t(buf, 16, y);
_mav_put_float(buf, 20, z);
_mav_put_uint8_t(buf, 24, frame);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS, buf, MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS_MIN_LEN, MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS_LEN, MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS_CRC);
#else
mavlink_orbit_execution_status_t *packet = (mavlink_orbit_execution_status_t *)msgbuf;
packet->time_usec = time_usec;
packet->radius = radius;
packet->x = x;
packet->y = y;
packet->z = z;
packet->frame = frame;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS, (const char *)packet, MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS_MIN_LEN, MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS_LEN, MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS_CRC);
#endif
}
#endif
#endif
// MESSAGE ORBIT_EXECUTION_STATUS UNPACKING
/**
* @brief Get field time_usec from orbit_execution_status message
*
* @return [us] Timestamp (UNIX Epoch time or time since system boot). The receiving end can infer timestamp format (since 1.1.1970 or since system boot) by checking for the magnitude of the number.
*/
static inline uint64_t mavlink_msg_orbit_execution_status_get_time_usec(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint64_t(msg, 0);
}
/**
* @brief Get field radius from orbit_execution_status message
*
* @return [m] Radius of the orbit circle. Positive values orbit clockwise, negative values orbit counter-clockwise.
*/
static inline float mavlink_msg_orbit_execution_status_get_radius(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 8);
}
/**
* @brief Get field frame from orbit_execution_status message
*
* @return The coordinate system of the fields: x, y, z.
*/
static inline uint8_t mavlink_msg_orbit_execution_status_get_frame(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 24);
}
/**
* @brief Get field x from orbit_execution_status message
*
* @return X coordinate of center point. Coordinate system depends on frame field: local = x position in meters * 1e4, global = latitude in degrees * 1e7.
*/
static inline int32_t mavlink_msg_orbit_execution_status_get_x(const mavlink_message_t* msg)
{
return _MAV_RETURN_int32_t(msg, 12);
}
/**
* @brief Get field y from orbit_execution_status message
*
* @return Y coordinate of center point. Coordinate system depends on frame field: local = x position in meters * 1e4, global = latitude in degrees * 1e7.
*/
static inline int32_t mavlink_msg_orbit_execution_status_get_y(const mavlink_message_t* msg)
{
return _MAV_RETURN_int32_t(msg, 16);
}
/**
* @brief Get field z from orbit_execution_status message
*
* @return [m] Altitude of center point. Coordinate system depends on frame field.
*/
static inline float mavlink_msg_orbit_execution_status_get_z(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 20);
}
/**
* @brief Decode a orbit_execution_status message into a struct
*
* @param msg The message to decode
* @param orbit_execution_status C-struct to decode the message contents into
*/
static inline void mavlink_msg_orbit_execution_status_decode(const mavlink_message_t* msg, mavlink_orbit_execution_status_t* orbit_execution_status)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
orbit_execution_status->time_usec = mavlink_msg_orbit_execution_status_get_time_usec(msg);
orbit_execution_status->radius = mavlink_msg_orbit_execution_status_get_radius(msg);
orbit_execution_status->x = mavlink_msg_orbit_execution_status_get_x(msg);
orbit_execution_status->y = mavlink_msg_orbit_execution_status_get_y(msg);
orbit_execution_status->z = mavlink_msg_orbit_execution_status_get_z(msg);
orbit_execution_status->frame = mavlink_msg_orbit_execution_status_get_frame(msg);
#else
uint8_t len = msg->len < MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS_LEN? msg->len : MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS_LEN;
memset(orbit_execution_status, 0, MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS_LEN);
memcpy(orbit_execution_status, _MAV_PAYLOAD(msg), len);
#endif
}

View file

@ -0,0 +1,281 @@
#pragma once
// MESSAGE PARAM_EXT_ACK PACKING
#define MAVLINK_MSG_ID_PARAM_EXT_ACK 324
typedef struct __mavlink_param_ext_ack_t {
char param_id[16]; /*< 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*/
char param_value[128]; /*< Parameter value (new value if PARAM_ACK_ACCEPTED, current value otherwise)*/
uint8_t param_type; /*< Parameter type.*/
uint8_t param_result; /*< Result code.*/
} mavlink_param_ext_ack_t;
#define MAVLINK_MSG_ID_PARAM_EXT_ACK_LEN 146
#define MAVLINK_MSG_ID_PARAM_EXT_ACK_MIN_LEN 146
#define MAVLINK_MSG_ID_324_LEN 146
#define MAVLINK_MSG_ID_324_MIN_LEN 146
#define MAVLINK_MSG_ID_PARAM_EXT_ACK_CRC 132
#define MAVLINK_MSG_ID_324_CRC 132
#define MAVLINK_MSG_PARAM_EXT_ACK_FIELD_PARAM_ID_LEN 16
#define MAVLINK_MSG_PARAM_EXT_ACK_FIELD_PARAM_VALUE_LEN 128
#if MAVLINK_COMMAND_24BIT
#define MAVLINK_MESSAGE_INFO_PARAM_EXT_ACK { \
324, \
"PARAM_EXT_ACK", \
4, \
{ { "param_id", NULL, MAVLINK_TYPE_CHAR, 16, 0, offsetof(mavlink_param_ext_ack_t, param_id) }, \
{ "param_value", NULL, MAVLINK_TYPE_CHAR, 128, 16, offsetof(mavlink_param_ext_ack_t, param_value) }, \
{ "param_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 144, offsetof(mavlink_param_ext_ack_t, param_type) }, \
{ "param_result", NULL, MAVLINK_TYPE_UINT8_T, 0, 145, offsetof(mavlink_param_ext_ack_t, param_result) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_PARAM_EXT_ACK { \
"PARAM_EXT_ACK", \
4, \
{ { "param_id", NULL, MAVLINK_TYPE_CHAR, 16, 0, offsetof(mavlink_param_ext_ack_t, param_id) }, \
{ "param_value", NULL, MAVLINK_TYPE_CHAR, 128, 16, offsetof(mavlink_param_ext_ack_t, param_value) }, \
{ "param_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 144, offsetof(mavlink_param_ext_ack_t, param_type) }, \
{ "param_result", NULL, MAVLINK_TYPE_UINT8_T, 0, 145, offsetof(mavlink_param_ext_ack_t, param_result) }, \
} \
}
#endif
/**
* @brief Pack a param_ext_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 param_id 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 Parameter value (new value if PARAM_ACK_ACCEPTED, current value otherwise)
* @param param_type Parameter type.
* @param param_result Result code.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_param_ext_ack_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
const char *param_id, const char *param_value, uint8_t param_type, uint8_t param_result)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_PARAM_EXT_ACK_LEN];
_mav_put_uint8_t(buf, 144, param_type);
_mav_put_uint8_t(buf, 145, param_result);
_mav_put_char_array(buf, 0, param_id, 16);
_mav_put_char_array(buf, 16, param_value, 128);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PARAM_EXT_ACK_LEN);
#else
mavlink_param_ext_ack_t packet;
packet.param_type = param_type;
packet.param_result = param_result;
mav_array_memcpy(packet.param_id, param_id, sizeof(char)*16);
mav_array_memcpy(packet.param_value, param_value, sizeof(char)*128);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PARAM_EXT_ACK_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_PARAM_EXT_ACK;
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_PARAM_EXT_ACK_MIN_LEN, MAVLINK_MSG_ID_PARAM_EXT_ACK_LEN, MAVLINK_MSG_ID_PARAM_EXT_ACK_CRC);
}
/**
* @brief Pack a param_ext_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 param_id 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 Parameter value (new value if PARAM_ACK_ACCEPTED, current value otherwise)
* @param param_type Parameter type.
* @param param_result Result code.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_param_ext_ack_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
const char *param_id,const char *param_value,uint8_t param_type,uint8_t param_result)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_PARAM_EXT_ACK_LEN];
_mav_put_uint8_t(buf, 144, param_type);
_mav_put_uint8_t(buf, 145, param_result);
_mav_put_char_array(buf, 0, param_id, 16);
_mav_put_char_array(buf, 16, param_value, 128);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_PARAM_EXT_ACK_LEN);
#else
mavlink_param_ext_ack_t packet;
packet.param_type = param_type;
packet.param_result = param_result;
mav_array_memcpy(packet.param_id, param_id, sizeof(char)*16);
mav_array_memcpy(packet.param_value, param_value, sizeof(char)*128);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_PARAM_EXT_ACK_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_PARAM_EXT_ACK;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_PARAM_EXT_ACK_MIN_LEN, MAVLINK_MSG_ID_PARAM_EXT_ACK_LEN, MAVLINK_MSG_ID_PARAM_EXT_ACK_CRC);
}
/**
* @brief Encode a param_ext_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 param_ext_ack C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_param_ext_ack_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_param_ext_ack_t* param_ext_ack)
{
return mavlink_msg_param_ext_ack_pack(system_id, component_id, msg, param_ext_ack->param_id, param_ext_ack->param_value, param_ext_ack->param_type, param_ext_ack->param_result);
}
/**
* @brief Encode a param_ext_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 param_ext_ack C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_param_ext_ack_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_param_ext_ack_t* param_ext_ack)
{
return mavlink_msg_param_ext_ack_pack_chan(system_id, component_id, chan, msg, param_ext_ack->param_id, param_ext_ack->param_value, param_ext_ack->param_type, param_ext_ack->param_result);
}
/**
* @brief Send a param_ext_ack message
* @param chan MAVLink channel to send the message
*
* @param param_id 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 Parameter value (new value if PARAM_ACK_ACCEPTED, current value otherwise)
* @param param_type Parameter type.
* @param param_result Result code.
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_param_ext_ack_send(mavlink_channel_t chan, const char *param_id, const char *param_value, uint8_t param_type, uint8_t param_result)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_PARAM_EXT_ACK_LEN];
_mav_put_uint8_t(buf, 144, param_type);
_mav_put_uint8_t(buf, 145, param_result);
_mav_put_char_array(buf, 0, param_id, 16);
_mav_put_char_array(buf, 16, param_value, 128);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_EXT_ACK, buf, MAVLINK_MSG_ID_PARAM_EXT_ACK_MIN_LEN, MAVLINK_MSG_ID_PARAM_EXT_ACK_LEN, MAVLINK_MSG_ID_PARAM_EXT_ACK_CRC);
#else
mavlink_param_ext_ack_t packet;
packet.param_type = param_type;
packet.param_result = param_result;
mav_array_memcpy(packet.param_id, param_id, sizeof(char)*16);
mav_array_memcpy(packet.param_value, param_value, sizeof(char)*128);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_EXT_ACK, (const char *)&packet, MAVLINK_MSG_ID_PARAM_EXT_ACK_MIN_LEN, MAVLINK_MSG_ID_PARAM_EXT_ACK_LEN, MAVLINK_MSG_ID_PARAM_EXT_ACK_CRC);
#endif
}
/**
* @brief Send a param_ext_ack message
* @param chan MAVLink channel to send the message
* @param struct The MAVLink struct to serialize
*/
static inline void mavlink_msg_param_ext_ack_send_struct(mavlink_channel_t chan, const mavlink_param_ext_ack_t* param_ext_ack)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mavlink_msg_param_ext_ack_send(chan, param_ext_ack->param_id, param_ext_ack->param_value, param_ext_ack->param_type, param_ext_ack->param_result);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_EXT_ACK, (const char *)param_ext_ack, MAVLINK_MSG_ID_PARAM_EXT_ACK_MIN_LEN, MAVLINK_MSG_ID_PARAM_EXT_ACK_LEN, MAVLINK_MSG_ID_PARAM_EXT_ACK_CRC);
#endif
}
#if MAVLINK_MSG_ID_PARAM_EXT_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_param_ext_ack_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, const char *param_id, const char *param_value, uint8_t param_type, uint8_t param_result)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
_mav_put_uint8_t(buf, 144, param_type);
_mav_put_uint8_t(buf, 145, param_result);
_mav_put_char_array(buf, 0, param_id, 16);
_mav_put_char_array(buf, 16, param_value, 128);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_EXT_ACK, buf, MAVLINK_MSG_ID_PARAM_EXT_ACK_MIN_LEN, MAVLINK_MSG_ID_PARAM_EXT_ACK_LEN, MAVLINK_MSG_ID_PARAM_EXT_ACK_CRC);
#else
mavlink_param_ext_ack_t *packet = (mavlink_param_ext_ack_t *)msgbuf;
packet->param_type = param_type;
packet->param_result = param_result;
mav_array_memcpy(packet->param_id, param_id, sizeof(char)*16);
mav_array_memcpy(packet->param_value, param_value, sizeof(char)*128);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_EXT_ACK, (const char *)packet, MAVLINK_MSG_ID_PARAM_EXT_ACK_MIN_LEN, MAVLINK_MSG_ID_PARAM_EXT_ACK_LEN, MAVLINK_MSG_ID_PARAM_EXT_ACK_CRC);
#endif
}
#endif
#endif
// MESSAGE PARAM_EXT_ACK UNPACKING
/**
* @brief Get field param_id from param_ext_ack message
*
* @return 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_ext_ack_get_param_id(const mavlink_message_t* msg, char *param_id)
{
return _MAV_RETURN_char_array(msg, param_id, 16, 0);
}
/**
* @brief Get field param_value from param_ext_ack message
*
* @return Parameter value (new value if PARAM_ACK_ACCEPTED, current value otherwise)
*/
static inline uint16_t mavlink_msg_param_ext_ack_get_param_value(const mavlink_message_t* msg, char *param_value)
{
return _MAV_RETURN_char_array(msg, param_value, 128, 16);
}
/**
* @brief Get field param_type from param_ext_ack message
*
* @return Parameter type.
*/
static inline uint8_t mavlink_msg_param_ext_ack_get_param_type(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 144);
}
/**
* @brief Get field param_result from param_ext_ack message
*
* @return Result code.
*/
static inline uint8_t mavlink_msg_param_ext_ack_get_param_result(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 145);
}
/**
* @brief Decode a param_ext_ack message into a struct
*
* @param msg The message to decode
* @param param_ext_ack C-struct to decode the message contents into
*/
static inline void mavlink_msg_param_ext_ack_decode(const mavlink_message_t* msg, mavlink_param_ext_ack_t* param_ext_ack)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mavlink_msg_param_ext_ack_get_param_id(msg, param_ext_ack->param_id);
mavlink_msg_param_ext_ack_get_param_value(msg, param_ext_ack->param_value);
param_ext_ack->param_type = mavlink_msg_param_ext_ack_get_param_type(msg);
param_ext_ack->param_result = mavlink_msg_param_ext_ack_get_param_result(msg);
#else
uint8_t len = msg->len < MAVLINK_MSG_ID_PARAM_EXT_ACK_LEN? msg->len : MAVLINK_MSG_ID_PARAM_EXT_ACK_LEN;
memset(param_ext_ack, 0, MAVLINK_MSG_ID_PARAM_EXT_ACK_LEN);
memcpy(param_ext_ack, _MAV_PAYLOAD(msg), len);
#endif
}

View file

@ -0,0 +1,238 @@
#pragma once
// MESSAGE PARAM_EXT_REQUEST_LIST PACKING
#define MAVLINK_MSG_ID_PARAM_EXT_REQUEST_LIST 321
typedef struct __mavlink_param_ext_request_list_t {
uint8_t target_system; /*< System ID*/
uint8_t target_component; /*< Component ID*/
} mavlink_param_ext_request_list_t;
#define MAVLINK_MSG_ID_PARAM_EXT_REQUEST_LIST_LEN 2
#define MAVLINK_MSG_ID_PARAM_EXT_REQUEST_LIST_MIN_LEN 2
#define MAVLINK_MSG_ID_321_LEN 2
#define MAVLINK_MSG_ID_321_MIN_LEN 2
#define MAVLINK_MSG_ID_PARAM_EXT_REQUEST_LIST_CRC 88
#define MAVLINK_MSG_ID_321_CRC 88
#if MAVLINK_COMMAND_24BIT
#define MAVLINK_MESSAGE_INFO_PARAM_EXT_REQUEST_LIST { \
321, \
"PARAM_EXT_REQUEST_LIST", \
2, \
{ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_param_ext_request_list_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_param_ext_request_list_t, target_component) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_PARAM_EXT_REQUEST_LIST { \
"PARAM_EXT_REQUEST_LIST", \
2, \
{ { "target_system", NULL, MAVLINK_TYPE_UINT8_T, 0, 0, offsetof(mavlink_param_ext_request_list_t, target_system) }, \
{ "target_component", NULL, MAVLINK_TYPE_UINT8_T, 0, 1, offsetof(mavlink_param_ext_request_list_t, target_component) }, \
} \
}
#endif
/**
* @brief Pack a param_ext_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_ext_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_EXT_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_EXT_REQUEST_LIST_LEN);
#else
mavlink_param_ext_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_EXT_REQUEST_LIST_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_PARAM_EXT_REQUEST_LIST;
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_PARAM_EXT_REQUEST_LIST_MIN_LEN, MAVLINK_MSG_ID_PARAM_EXT_REQUEST_LIST_LEN, MAVLINK_MSG_ID_PARAM_EXT_REQUEST_LIST_CRC);
}
/**
* @brief Pack a param_ext_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_ext_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_EXT_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_EXT_REQUEST_LIST_LEN);
#else
mavlink_param_ext_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_EXT_REQUEST_LIST_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_PARAM_EXT_REQUEST_LIST;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_PARAM_EXT_REQUEST_LIST_MIN_LEN, MAVLINK_MSG_ID_PARAM_EXT_REQUEST_LIST_LEN, MAVLINK_MSG_ID_PARAM_EXT_REQUEST_LIST_CRC);
}
/**
* @brief Encode a param_ext_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_ext_request_list C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_param_ext_request_list_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_param_ext_request_list_t* param_ext_request_list)
{
return mavlink_msg_param_ext_request_list_pack(system_id, component_id, msg, param_ext_request_list->target_system, param_ext_request_list->target_component);
}
/**
* @brief Encode a param_ext_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_ext_request_list C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_param_ext_request_list_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_param_ext_request_list_t* param_ext_request_list)
{
return mavlink_msg_param_ext_request_list_pack_chan(system_id, component_id, chan, msg, param_ext_request_list->target_system, param_ext_request_list->target_component);
}
/**
* @brief Send a param_ext_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_ext_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_EXT_REQUEST_LIST_LEN];
_mav_put_uint8_t(buf, 0, target_system);
_mav_put_uint8_t(buf, 1, target_component);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_EXT_REQUEST_LIST, buf, MAVLINK_MSG_ID_PARAM_EXT_REQUEST_LIST_MIN_LEN, MAVLINK_MSG_ID_PARAM_EXT_REQUEST_LIST_LEN, MAVLINK_MSG_ID_PARAM_EXT_REQUEST_LIST_CRC);
#else
mavlink_param_ext_request_list_t packet;
packet.target_system = target_system;
packet.target_component = target_component;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_EXT_REQUEST_LIST, (const char *)&packet, MAVLINK_MSG_ID_PARAM_EXT_REQUEST_LIST_MIN_LEN, MAVLINK_MSG_ID_PARAM_EXT_REQUEST_LIST_LEN, MAVLINK_MSG_ID_PARAM_EXT_REQUEST_LIST_CRC);
#endif
}
/**
* @brief Send a param_ext_request_list message
* @param chan MAVLink channel to send the message
* @param struct The MAVLink struct to serialize
*/
static inline void mavlink_msg_param_ext_request_list_send_struct(mavlink_channel_t chan, const mavlink_param_ext_request_list_t* param_ext_request_list)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mavlink_msg_param_ext_request_list_send(chan, param_ext_request_list->target_system, param_ext_request_list->target_component);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_EXT_REQUEST_LIST, (const char *)param_ext_request_list, MAVLINK_MSG_ID_PARAM_EXT_REQUEST_LIST_MIN_LEN, MAVLINK_MSG_ID_PARAM_EXT_REQUEST_LIST_LEN, MAVLINK_MSG_ID_PARAM_EXT_REQUEST_LIST_CRC);
#endif
}
#if MAVLINK_MSG_ID_PARAM_EXT_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_ext_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);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_EXT_REQUEST_LIST, buf, MAVLINK_MSG_ID_PARAM_EXT_REQUEST_LIST_MIN_LEN, MAVLINK_MSG_ID_PARAM_EXT_REQUEST_LIST_LEN, MAVLINK_MSG_ID_PARAM_EXT_REQUEST_LIST_CRC);
#else
mavlink_param_ext_request_list_t *packet = (mavlink_param_ext_request_list_t *)msgbuf;
packet->target_system = target_system;
packet->target_component = target_component;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_PARAM_EXT_REQUEST_LIST, (const char *)packet, MAVLINK_MSG_ID_PARAM_EXT_REQUEST_LIST_MIN_LEN, MAVLINK_MSG_ID_PARAM_EXT_REQUEST_LIST_LEN, MAVLINK_MSG_ID_PARAM_EXT_REQUEST_LIST_CRC);
#endif
}
#endif
#endif
// MESSAGE PARAM_EXT_REQUEST_LIST UNPACKING
/**
* @brief Get field target_system from param_ext_request_list message
*
* @return System ID
*/
static inline uint8_t mavlink_msg_param_ext_request_list_get_target_system(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 0);
}
/**
* @brief Get field target_component from param_ext_request_list message
*
* @return Component ID
*/
static inline uint8_t mavlink_msg_param_ext_request_list_get_target_component(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 1);
}
/**
* @brief Decode a param_ext_request_list message into a struct
*
* @param msg The message to decode
* @param param_ext_request_list C-struct to decode the message contents into
*/
static inline void mavlink_msg_param_ext_request_list_decode(const mavlink_message_t* msg, mavlink_param_ext_request_list_t* param_ext_request_list)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
param_ext_request_list->target_system = mavlink_msg_param_ext_request_list_get_target_system(msg);
param_ext_request_list->target_component = mavlink_msg_param_ext_request_list_get_target_component(msg);
#else
uint8_t len = msg->len < MAVLINK_MSG_ID_PARAM_EXT_REQUEST_LIST_LEN? msg->len : MAVLINK_MSG_ID_PARAM_EXT_REQUEST_LIST_LEN;
memset(param_ext_request_list, 0, MAVLINK_MSG_ID_PARAM_EXT_REQUEST_LIST_LEN);
memcpy(param_ext_request_list, _MAV_PAYLOAD(msg), len);
#endif
}

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