pull/431/merge
JohhnGoblin 2025-04-27 22:28:05 +03:00 committed by GitHub
commit 1a87b270fc
No known key found for this signature in database
GPG Key ID: B5690EEEBB952194
388 changed files with 116596 additions and 0 deletions

View File

@ -0,0 +1,114 @@
# sandbox-fpv
Sandbox for FPV experiments. Telegram-group: `https://t.me/+BMyMoolVOpkzNWUy` | [link](https://t.me/+BMyMoolVOpkzNWUy)
## News
* `26.07.2023` - FPV link setup via 4G modem .
* `01.07.2023` - A short note about the imx335 gk7205v300 camera . About baud for telemetry .
* `22.06.2023` - Finally, the problem with the picture being jerky at 30fps was resolved .
* `06.04.2023` - Added coupler firmware for ivg-g2s with u-boot on board.
* `05.04.2023` - Added functionality to rcjoystick for displaying packet losses (link quality) in rssi.
* `04.04.2023` - OpenIPC has added the majestic streamer, now the ivg-g2s camera runs h265 cbr (constant bitrate). This gave a cleaner picture and a significant reduction in noise. At the same time, changes were made to the link launch process. The main service is now S98datalinkwith the config /etc/datalink.conf, and wfb is now launched via /usr/bin/wifibroadcast. The articles have been corrected to accommodate this innovation.
* `01.04.2023` - Due to certain circumstances, wfb-ng was replaced in my camera and recorder with an alternative from OpenHD . Here is the package for assembly in buildroot OpenIPC. The shell wrappers take into account both options, due to the presence of a parameter link_idthat is not required in the OpenHD implementation. Archive with binaries of both options.
## Notes
* [Notes on setting up the link on the gk7205v200 camera and hi3536ev100 (dv100) recorder](notes_link_gk7205v200_hi3536ev100.md)
* [Notes on camera firmware gk7205v200 on OpenIPC](notes_start_ivg-g2s.md)
* [Notes on firmware for hi3536ev100 recorder on OpenIPC](notes_start_hi3536ev100.md)
* [A note about the imx335 gk7205v300 camera](notes_imx335_gk7205v300.md)
* [Adding smoothness to video on goke/hisilicon cameras](gkrcparams.md)
* [A note about controlling the camera via RC channels from the ground](notes_cam_control.md)
* [Switch between two cameras in the air](note-two-cameras-switched.md)
* [Loader for telemetry for gk7502v200, which does not hang the camera upon reboot](gk7205v200_u-boot-7502v200-for-telemetry.md)
* [Controlling buttons from the front panel on the recorder](nvr_gpio.md)
* [Connecting and setting up a tablet or smartphone for video and OSD via USB](usb-tethering.md)
* [Connecting the tablet to the recorder via wifi via the tablet's AP](note-nvr-tab-ap.md)
* [Connecting the tablet to the recorder via ethernet-usb-device](usb-eth-modem.md)
* [Using the hardware as a joystick to transmit RC channels via mavlink](rcjoystick.md)
* [About the analogue of RSSI](rcjoystick.md#rssi)
* [SBUS-to-USB joystick for using any equipment with an sbus receiver](sbus-to-usb-joystick)
* [FPV link setup via 4G modem](lte-fpv.md)
* [Installing usb_modeswitch on a camera with fpv, lite firmware](usb-modeswitch.md)
#### Miscellaneous
* [mavfwd for inav (one way msp) for camera](user_TipoMan/mavfwd_mavlink2.tar?raw=true)
* [Displaying video on windows and MP](gstlaunch_on_windows.md)
* [Disabling watchdog on the hi3536dv100 recorder](note_nvr_wdt.md)
* [Different from 115200 baud on camera uart for telemetry](note_telemetry_baud.md)
## Road map
* ~~Starting video with transfer from the recorder to the PC.~~
* ~~Launch one- and two-way telemetry.~~
* ~~Starting video transfer via usb tethering to an Android tablet.~~
* ~~Building and testing LTE firmware on e3372h + zerotier~~
* ~~Starting telemetry routing via mavlink-router.~~
* ~~Finding ways to control the camera through mavlink.~~.
* Finding ways to output video and osd via hdmi.
* ~~~Switching between several cameras, where one is the master with wfb-ng, and the rest are slaves.~~~
* Development of expansion board for camera: bec 5v/3.3v; usb hub, uart, wifi/modem power transistor, microSD.
* Development of a zoom lens control board and a method for controlling commercially available boards.
* Development of a stabilizing gimbal controlled from the ground via wfb-ng.
## Russians:
## Новое
* `26.07.2023` - Настройка FPV-линка [через 4G модем](lte-fpv.md).
* `01.07.2023` - Короткая заметка о камере [imx335 gk7205v300](notes_imx335_gk7205v300.md). О [baud для телеметрии](note_telemetry_baud.md).
* `22.06.2023` - Наконец [решилась](gkrcparams.md) проблема с дерганностью картинки на 30fps.
* `06.04.2023` - Добавлена [прошивка coupler](notes_start_ivg-g2s.md#L33) для ivg-g2s с u-boot на борту.
* `05.04.2023` - В rcjoystick [добавлен](rcjoystick.md#rssi) функционал для целей отображения потерь пакетов (качества линка) в rssi.
* `04.04.2023` - В OpenIPC "допилили" стример majestic, теперь на камере ivg-g2s работает h265 cbr (постоянный битрейт). Это дало более чистую картинку и значительное уменьшение шума. Вместе с этим были внесены изменения в процесс запуска линка. Основным сервисом теперь является `S98datalink` с конфигом `/etc/datalink.conf`, а запуск wfb теперь производится через `/usr/bin/wifibroadcast`. Статьи были исправлены под это нововведение.
* `01.04.2023` - В связи с некоторыми обстоятельствами, wfb-ng был заменен в моих камере и регистраторе на альтернативу от [OpenHD](https://github.com/OpenHD/wifibroadcast/). [Тут](wfbopenhd.zip) пакет для сборки в buildroot OpenIPC. В шелл-обертках учтены оба варианта, по наличию параметра `link_id` который не требуется в реализации от OpenHD. [Архив](https://github.com/OpenIPC/sandbox-fpv/blob/master/wfb.zip) с бинарниками обоих вариантов.
## Заметки
* [Заметки о настройке линка на камере gk7205v200 и регистраторе hi3536ev100 (dv100)](notes_link_gk7205v200_hi3536ev100.md)
* [Заметки о прошивке камеры gk7205v200 на OpenIPC](notes_start_ivg-g2s.md)
* [Заметки о прошивке регистратора hi3536ev100 на OpenIPC](notes_start_hi3536ev100.md)
* [Заметка о камере imx335 gk7205v300](notes_imx335_gk7205v300.md)
* [Добавляем плавности видео на goke/hisilicon камерах](gkrcparams.md)
* [Заметка о управлении камерой через RC каналы с наземки](notes_cam_control.md)
* [Переключение между двумя камерами в воздухе](note-two-cameras-switched.md)
* [Загрузчик под телеметрию для gk7502v200, который не вешает камеру при ребуте](gk7205v200_u-boot-7502v200-for-telemetry.md)
* [Управление кнопками с front panel на регистраторе](nvr_gpio.md)
* [Подключение и настройка планшета или смартфона для видео и OSD по USB](usb-tethering.md)
* [Подключение планшета к регистратору по wifi через AP планшета](note-nvr-tab-ap.md)
* [Подключение планшета к регистратору через ethernet-usb-device](usb-eth-modem.md)
* [Использование аппаратуры как джойстика для передачи каналов RC через mavlink](rcjoystick.md)
* [Про аналог RSSI](rcjoystick.md#rssi)
* [SBUS-to-USB joystick для использования любой аппаратуры с sbus приемником](sbus-to-usb-joystick)
* [Настройка FPV-линка через 4G модем](lte-fpv.md)
* [Установка usb_modeswitch на камеру с прошивкой fpv, lite](usb-modeswitch.md)
#### Разное
* [mavfwd для inav (односторонний msp) для камеры](user_TipoMan/mavfwd_mavlink2.tar?raw=true)
* [Отображение видео на windows и в MP](gstlaunch_on_windows.md)
* [Отключение watchdog на регистраторе hi3536dv100](note_nvr_wdt.md)
* [Отличный от 115200 baud на uartе камеры для телеметрии](note_telemetry_baud.md)
## Дорожная карта
* ~~Запуск видео с передачей с регистратора на пк.~~
* ~~Запуск одно-и двусторонней телеметрии.~~
* ~~Запуск передачи видео через usb tethering на android-планшет.~~
* ~~Сборка и тестирование прошивки LTE на e3372h + zerotier~~
* ~~Запуск маршрутизации телеметрии через mavlink-router.~~
* ~~Поиск путей управления камерой сквозь mavlink~~.
* Поиск способов вывода видео и osd через hdmi.
* ~~~Переключение между несколькими камерами, где одна ведущая с wfb-ng, а остальные ведомые.~~~
* Разработка платы расширения для камеры: bec 5v/3.3v; usb hub, uart, транзистор питания wifi/modem, microSD.
* Разработка платы управления зум-объективом и способа управления имеющимися в продаже платами.
* Разработка стабилизирующего подвеса, управляемого с земли сквозь wfb-ng.

View File

@ -0,0 +1,56 @@
### Notes on NVR hi3536ev100 firmware on OpenIPC for FPV purposes
[RU](notes_start_hi3536ev100.md)
<details>
<summary>How memory works</summary>
To begin with, you need to figure out how the memory of the recorder (and the camera too) works and what needs to be flashed. Data is stored on spi-flash 16mb in the form of mtd blocks:
```
cat /proc/cmdline
mem=150M console=ttyAMA0,115200 panic=20 root=/dev/mtdblock3 rootfstype=squashfs init=/init mtdparts=hi_sfc:256k(boot),64k(env),2048k(kernel),8192k(rootfs),-(rootfs_data)
ls /dev/mtdb*
/dev/mtdblock0 /dev/mtdblock1 /dev/mtdblock2 /dev/mtdblock3 /dev/mtdblock4
```
As follows from the output, block zero is the u-boot bootloader; Next comes a block for storing environment variables (`printenv`, `setenv` commands are written to RAM, and `saveenv` saves it in this block); next is the uImage core; then rootfs.squashfs (immutable file system image); and finally rootfs_data or also overlay - a changeable part where differences from rootfs are written if you change any files. Thus, by clearing the overlay, we will reset the file system to default:
```
sf probe 0 #select a device
sf erase 0xA50000 0x500000 #we clean
reset #reboot nvr
```
It's even easier to reset the firmware to factory defaults using the `firstboot` command.
An address calculator for commands is available [here](https://openipc.org/tools/firmware-partitions-calculation). In our case, the rootfs partition: 8192kB, which means the start address of the overlay will be 0xA50000. For a camera with a flash of 8mB and a rootfs size of 5120kB, the addresses will be different, including environment variables!
</details>
The bootloader of this recorder does not have a password, and you can access it via uart/115200 baud by pressing Ctrl+C several times at startup while connected to the debug-uart port of the recorder via a usb-uart 3v3 adapter (ftdi, ch340). Debug uart is located opposite the VGA connector on the opposite edge of the board and is labeled gnd/tx/rx. We don't need to flash the bootloader, we don't need burn. Our ENVs (environment variables) are different from the factory ones, but they are easier to install directly from the bootloader line by line:
```
setenv ipaddr '192.168.0.222' #here is the ip in your subnet from the free ones
setenv serverip '192.168.0.107' #PC address with tftp server
setenv netmask '255.255.255.0'
setenv bootcmd 'sf probe 0; sf read 0x82000000 0x50000 0x200000; bootm 0x82000000'
setenv uk 'mw.b 0x82000000 ff 1000000;tftp 0x82000000 uImage.${soc}; sf probe 0; sf erase 0x50000 0x200000; sf write 0x82000000 0x50000 ${filesize}'
setenv ur 'mw.b 0x82000000 ff 1000000;tftp 0x82000000 rootfs.squashfs.${soc}; sf probe 0; sf erase 0x250000 0x800000; sf write 0x82000000 0x250000 ${filesize}'
setenv bootargs 'mem=192M console=ttyAMA0,115200 panic=20 root=/dev/mtdblock3 rootfstype=squashfs init=/init mtdparts=hi_sfc:256k(boot),64k(env),2048k(kernel),8192k(rootfs) ,-(rootfs_data)'
setenv osmem '192M'
setenv totalmem '256M'
setenv soc 'hi3536dv100'
#here we clear variables that are no longer needed
setenvda; setenv du; setenv dr; setenv dw; setenv dl; setenv dc; setenv up; setenv tk; setenvdd; setenv de; setenv jpeg_addr; setenv jpeg_size; setenv vobuf; setenv loadlogo; setenv appVideoStandard; setenv appSystemLanguage; setenv appCloudExAbility
saveenv #save the new variable environment
printenv #see if everything is ok
```
The original env and full dump of the chip (16mb backup of factory firmware in case of recovery) are available [here](https://github.com/OpenIPC/sandbox-fpv/tree/master/hi3536dv100/original_firmware).
As you may have noticed, the uk and ur variables store macros for the uImage and rootfs downloading them from [tftp server](https://pjo2.github.io/tftpd64/) specified in serverip variable. All addresses correspond to the bootargs variable, the contents of which specify the file system layout for the kernel at boot. The layout is different from the usual for goke/hisilicone cameras, our core is the same as lite/fpv, 2MB in size, but the file system is 8MB in size, like ultimate. The remaining ~5MB are used by the overlay (your changes to the files relative to the original rootfs). For firmware, use official builds from the releases page [openipc/firmware](https://github.com/OpenIPC/firmware/releases/download/latest/openipc.hi3536dv100-nor-fpv.tgz). The archive contains the kernel and file system.
So, after setting the variables, you can start flashing the remaining part. Start the tftpd server, put uImage.hi3536dv100 and rootfs.squashfs.hi3536dv100 in its root, select the appropriate network interface and run the macro in the bootloader: `run uk`. A series of commands must be executed, the output of which should indicate that the uImage file has been downloaded and flashed into flash. Similarly, run `run ur` to flash rootfs. If the addresses are set correctly, but the download is stuck at "Downloading", change the registrar address to a nearby free one: `setenv ipaddr '192.168.0.223'`.
If everything went without errors, do a `reset` and boot into the operating system, login root, password 12345.
The configs from the hi3536dv100 catalog are not relevant, but they may be of interest regarding connecting the tablet via usb/wifi/ethernet hotspot; you can transfer them, by analogy, to the configs of the official firmware or use separate bash scripts. Usually the essence of these changes is to determine the address of the connected tablet (which is the gateway for the registrar in cases where the tablet has a dhcp server) and specifying this address in an additional instance of wfb_rx for the video stream and for telemetry streams.
The firmware is updated via the Internet using the command `sysupgrade -r -k -n`.
<details>
<summary>Update without internet from /tmp</summary>
In the future, you can update the recorder's firmware by uploading the kernel and rootfs into the `/tmp` directory via WinSCP and running `sysupgrade --kernel=/tmp/uImage.hi3536dv100 --rootfs=/tmp/rootfs.squashfs.hi3536dv100 -z` . The `-z` parameter is needed if you do not have an Internet connection (does not update the sysupgrade script), `-n` will clear the user fs (overlay).
</details>

View File

@ -0,0 +1,84 @@
#!/bin/sh
DAEMON="majestic"
PIDFILE="/var/run/$DAEMON.pid"
DAEMON_ARGS="-s"
# shellcheck source=/dev/null
[ -r "/etc/default/$DAEMON" ] && . "/etc/default/$DAEMON"
load_majestic() {
printf 'Starting %s: ' "$DAEMON"
[ -f /usr/bin/$DAEMON ] || echo -en "DISABLED, "
# shellcheck disable=SC2086 # we need the word splitting
[ -f /etc/coredump.conf ] && . /etc/coredump.conf
if [ "$coredump_enabled" ]; then
[ "$(cli -g .watchdog.timeout)" -lt "30" ] && cli -s .watchdog.timeout 30
ulimit -c unlimited && echo "|/usr/sbin/sendcoredump.sh" >/proc/sys/kernel/core_pattern
fi
cli -s .isp.sensorConfig /etc/sensors/imx307_i2c_2l_1080p.ini
cli -s .video0.size 1920x1080
cli -s .video0.fps 30
start-stop-daemon -b -m -S -q -p "$PIDFILE" -x "/usr/bin/$DAEMON" -- $DAEMON_ARGS
sleep .5
cli -s .isp.sensorConfig /etc/sensors/imx307_i2c_2l_720p_50fps.ini
cli -s .video0.size 1280x720
cli -s .video0.fps 50
killall -1 majestic
sleep 1
gkrcparams --MaxQp 30 --MaxI 2
status=$?
if [ "$status" -eq 0 ]; then
echo "OK"
else
echo "FAIL"
fi
return "$status"
}
# The daemon does not create a pidfile, and use "-m" to instruct start-stop-daemon to create one.
start() {
logger -s -p daemon.info -t $(ipcinfo -v) "Loading video system has started..."
export SENSOR=$(fw_printenv -n sensor)
load_majestic
}
stop() {
printf 'Stopping %s: ' "$DAEMON"
[ -f /usr/bin/$DAEMON ] || echo -en "DISABLED, "
start-stop-daemon -K -q -p "$PIDFILE"
status=$?
if [ "$status" -eq 0 ]; then
rm -f "$PIDFILE"
echo "OK"
else
echo "FAIL"
fi
return "$status"
}
restart() {
stop
sleep 1
reload
}
reload() {
load_majestic
}
case "$1" in
start|stop|restart|reload)
"$1";;
*)
echo "Usage: $0 {start|stop|restart|reload}"
exit 1
esac

View File

@ -0,0 +1,77 @@
#!/bin/sh
#
# Start fpv datalink
#
. /etc/datalink.conf
chip=$(ipcinfo -c)
fw=$(grep "BUILD_OPTION" "/etc/os-release" | cut -d= -f2)
start() {
if ! [ -f /etc/system.ok ]; then
killall majestic
tweaksys ${chip}
fi
echo "Starting FPV datalink..."
if ! [ -f /etc/servicemode ]; then
echo "Start wlan0 in Service Mode (connect to your AP)"
rm -f /etc/servicemode
wpa_passphrase "ssid" "password" >/tmp/wpa_supplicant.conf
sed -i '2i \\tscan_ssid=1' /tmp/wpa_supplicant.conf
sleep 3
wpa_supplicant -B -D nl80211 -i wlan0 -c /tmp/wpa_supplicant.conf
ifconfig wlan0 up
udhcpc -x hostname:openipc-servicemode -T 1 -t 5 -R -b -O search -i wlan0
else
if [ ${fw} = "lte" ]; then
if [ ${usb_modem} = "true" ]; then
echo "Starting lte modem configuration..."
echo "ToDo: Running usb_modeswitch or other shit here..."
fi
# for the future
#cli -s .outgoing.url1 udp://${gs_ipaddr}:${gs_port}
if [ ${use_zt} = "true" ]; then
echo "Starting ZeroTier-One daemon..."
/usr/sbin/zerotier-one -d &
if [ ! -f /var/lib/zerotier-one/networks.d/${zt_netid}.conf ]; then
sleep 8
zerotier-cli join ${zt_netid} &> /dev/null
echo "Don't forget authorize in the my.zerotier.com!"
fi
fi
if [ ${telemetry} = "true" ]; then
/usr/bin/telemetry start
fi
else
echo "Starting wifibroadcast service..."
/usr/bin/wifibroadcast start
fi
fi
}
stop() {
echo "Stopping all services..."
kill -9 $(pidof wfb_tx)
kill -9 $(pidof telemetry_rx)
kill -9 $(pidof telemetry_tx)
kill -9 $(pidof mavlink-routerd)
kill -9 $(pidof mavfwd)
}
case "$1" in
start)
start
;;
stop)
stop
;;
restart)
stop
start
;;
*)
echo "Usage: $0 {start|stop|restart}"
exit 1
esac

View File

@ -0,0 +1,65 @@
system:
webAdmin: disabled
buffer: 1024
image:
mirror: false
flip: false
rotate: none
contrast: 50
hue: 50
saturation: 50
luminance: 50
osd:
enabled: false
template: "%a %e %B %Y %H:%M:%S %Z"
nightMode:
enabled: false
records:
enabled: false
path: /mnt/mmc/%Y/%m/%d/%H.mp4
maxUsage: 95
video0:
enabled: true
bitrate: 6144
codec: h265
rcMode: cbr
gopSize: 1.0
size: 1280x720
fps: 50
video1:
enabled: false
jpeg:
enabled: false
mjpeg:
size: 640x360
fps: 5
bitrate: 1024
audio:
enabled: false
volume: auto
srate: 8000
rtsp:
enabled: false
port: 554
hls:
enabled: false
youtube:
enabled: false
motionDetect:
enabled: false
visualize: true
debug: true
ipeye:
enabled: false
watchdog:
enabled: true
timeout: 10
isp:
slowShutter: disabled
drc: 350
lowDelay: true
sensorConfig: /etc/sensors/imx307_i2c_2l_720p_50fps.ini
netip:
enabled: false
outgoing:
- udp://127.0.0.1:5600

View File

@ -0,0 +1,131 @@
[sensor]
Sensor_type =stSnsImx307_2l_Obj ;sensor name
Mode =0 ;WDR_MODE_NONE = 0
;WDR_MODE_BUILT_IN = 1
;WDR_MODE_QUDRA = 2
;WDR_MODE_2To1_LINE = 3
;WDR_MODE_2To1_FRAME = 4
;WDR_MODE_2To1_FRAME_FULL_RATE = 5
;WDR_MODE_3To1_LINE = 6
;WDR_MODE_3To1_FRAME = 7
;WDR_MODE_3To1_FRAME_FULL_RATE = 8
;WDR_MODE_4To1_LINE = 9
;WDR_MODE_4To1_FRAME = 10
;WDR_MODE_4To1_FRAME_FULL_RATE = 11
DllFile = /usr/lib/sensors/libsns_imx307_2l_720p_50fps.so ;sensor lib path
[mode]
input_mode =0 ;INPUT_MODE_MIPI = 0
;INPUT_MODE_SUBLVDS = 1
;INPUT_MODE_LVDS = 2 ...etc
raw_bitness = 10
[mipi]
;----------only for mipi_dev---------
data_type = DATA_TYPE_RAW_10BIT
lane_id = 0|2|-1|-1|-1|-1|-1|-1| ;lane_id: -1 - disable
[isp_image]
Isp_x =0
Isp_y =0
Isp_W =1280
Isp_H =720
Isp_FrameRate=60
Isp_Bayer =0 ;BAYER_RGGB=0, BAYER_GRBG=1, BAYER_GBRG=2, BAYER_BGGR=3
[vi_dev]
Input_mod = 6
; VI_MODE_BT656 = 0, /* ITU-R BT.656 YUV4:2:2 */
; VI_MODE_BT656_PACKED_YUV, /* ITU-R BT.656 packed YUV4:2:2 */
; VI_MODE_BT601, /* ITU-R BT.601 YUV4:2:2 */
; VI_MODE_DIGITAL_CAMERA, /* digatal camera mode */
; VI_MODE_BT1120_STANDARD, /* BT.1120 progressive mode */
; VI_MODE_BT1120_INTERLEAVED, /* BT.1120 interstage mode */
; VI_MODE_MIPI, /* MIPI RAW mode */
; VI_MODE_MIPI_YUV420_NORMAL, /* MIPI YUV420 normal mode */
; VI_MODE_MIPI_YUV420_LEGACY, /* MIPI YUV420 legacy mode */
; VI_MODE_MIPI_YUV422, /* MIPI YUV422 mode */
; VI_MODE_LVDS, /* LVDS mode */
; VI_MODE_HISPI, /* HiSPi mode */
; VI_MODE_SLVS, /* SLVS mode */
Work_mod =0 ;VI_WORK_MODE_1Multiplex = 0
;VI_WORK_MODE_2Multiplex,
;VI_WORK_MODE_4Multiplex
Combine_mode =0 ;Y/C composite or separation mode
;VI_COMBINE_COMPOSITE = 0 /*Composite mode */
;VI_COMBINE_SEPARATE, /*Separate mode */
Comp_mode =0 ;Component mode (single-component or dual-component)
;VI_COMP_MODE_SINGLE = 0, /*single component mode */
;VI_COMP_MODE_DOUBLE = 1, /*double component mode */
Clock_edge =1 ;Clock edge mode (sampling on the rising or falling edge)
;VI_CLK_EDGE_SINGLE_UP=0, /*rising edge */
;VI_CLK_EDGE_SINGLE_DOWN, /*falling edge */
Mask_num =2 ;Component mask
Mask_0 =0xFFF00000
Mask_1 =0x0
Scan_mode = 1;VI_SCAN_INTERLACED = 0
;VI_SCAN_PROGRESSIVE,
Data_seq =2 ;data sequence (ONLY for YUV format)
;----2th component U/V sequence in bt1120
; VI_INPUT_DATA_VUVU = 0,
; VI_INPUT_DATA_UVUV,
;----input sequence for yuv
; VI_INPUT_DATA_UYVY = 0,
; VI_INPUT_DATA_VYUY,
; VI_INPUT_DATA_YUYV,
; VI_INPUT_DATA_YVYU
Vsync =1 ; vertical synchronization signal
;VI_VSYNC_FIELD = 0,
;VI_VSYNC_PULSE,
VsyncNeg=1 ;Polarity of the vertical synchronization signal
;VI_VSYNC_NEG_HIGH = 0,
;VI_VSYNC_NEG_LOW /*if VIU_VSYNC_E
Hsync =0 ;Attribute of the horizontal synchronization signal
;VI_HSYNC_VALID_SINGNAL = 0,
;VI_HSYNC_PULSE,
HsyncNeg =0 ;Polarity of the horizontal synchronization signal
;VI_HSYNC_NEG_HIGH = 0,
;VI_HSYNC_NEG_LOW
VsyncValid =1 ;Attribute of the valid vertical synchronization signal
;VI_VSYNC_NORM_PULSE = 0,
;VI_VSYNC_VALID_SINGAL,
VsyncValidNeg =0;Polarity of the valid vertical synchronization signal
;VI_VSYNC_VALID_NEG_HIGH = 0,
;VI_VSYNC_VALID_NEG_LOW
Timingblank_HsyncHfb =0 ;Horizontal front blanking width
Timingblank_HsyncAct =1280 ;Horizontal effetive width
Timingblank_HsyncHbb =0 ;Horizontal back blanking width
Timingblank_VsyncVfb =0 ;Vertical front blanking height
Timingblank_VsyncVact =720 ;Vertical effetive width
Timingblank_VsyncVbb=0 ;Vertical back blanking height
Timingblank_VsyncVbfb =0 ;Even-field vertical front blanking height(interlace, invalid progressive)
Timingblank_VsyncVbact=0 ;Even-field vertical effetive width(interlace, invalid progressive)
Timingblank_VsyncVbbb =0 ;Even-field vertical back blanking height(interlace, invalid progressive)
;----- only for bt656 ----------
FixCode =0 ;BT656_FIXCODE_1 = 0,
;BT656_FIXCODE_0
FieldPolar=0 ;BT656_FIELD_POLAR_STD = 0
;BT656_FIELD_POLAR_NSTD
DataPath =1 ;ISP enable or bypass
;VI_PATH_BYPASS = 0,/* ISP bypass */
;VI_PATH_ISP = 1,/* ISP enable */
;VI_PATH_RAW = 2,/* Capture raw data, for debug */
InputDataType=1 ;VI_DATA_TYPE_YUV = 0,VI_DATA_TYPE_RGB = 1,
DataRev =FALSE ;Data reverse. FALSE = 0; TRUE = 1
DevRect_x=200 ;
DevRect_y=20 ;
DevRect_w=1280 ;
DevRect_h=720 ;
FullLinesStd=750
[vi_chn]
CapRect_X =320
CapRect_Y =180
CapRect_Width=1280
CapRect_Height=720
DestSize_Width=1280
DestSize_Height=720

View File

@ -0,0 +1,18 @@
wlan=wlan0
region=BO
# By default used channel number, but, you may set freq instead. For ex: 2387M
channel=44
#frequency=5220M
txpower=20
driver_txpower_override=16
bandwidth=20
stbc=1
ldpc=1
mcs_index=1
stream=0
link_id=7669206
udp_port=5600
fec_k=8
fec_n=12
fec_timeout=0
guard_interval=long

View File

@ -0,0 +1,8 @@
#yaml-cli -s .isp.sensorConfig /etc/sensors/imx307_i2c_2l_1080p.ini #use this for imx307
yaml-cli -s .isp.sensorConfig /etc/sensors/imx415.bin
yaml-cli -s .isp.exposure 10
yaml-cli -s .video0.size 1920x1080
yaml-cli -s .video0.fps 30
yaml-cli -s .video0.crop 0x0x1920x1080
sleep .2
/root/kill.sh

View File

@ -0,0 +1,7 @@
yaml-cli -s .video0.size 1920x1080
yaml-cli -s .video0.crop 0x0x1920x1080
yaml-cli -s .video0.fps 60
yaml-cli -s .isp.sensorConfig /etc/sensors/imx415f.bin
yaml-cli -s .isp.exposure 20
sleep .2
/root/kill.sh

View File

@ -0,0 +1,7 @@
yaml-cli -s .video0.size 1920x1080
yaml-cli -s .video0.crop 0x0x1920x1080
yaml-cli -s .video0.fps 90
yaml-cli -s .isp.sensorConfig /etc/sensors/imx415f.bin
yaml-cli -s .isp.exposure 30
sleep .2
/root/kill.sh

View File

@ -0,0 +1,7 @@
yaml-cli -s .video0.size 3200x1800
yaml-cli -s .video0.crop 250x150x2560x1440
yaml-cli -s .video0.fps 30
yaml-cli -s .isp.sensorConfig /etc/sensors/imx415.bin
yaml-cli -s .isp.exposure 10
sleep .2
/root/kill.sh

View File

@ -0,0 +1,7 @@
yaml-cli -s .video0.size 3840x2160
yaml-cli -s .video0.crop 575x330x2560x1440
yaml-cli -s .video0.fps 20
yaml-cli -s .isp.sensorConfig /etc/sensors/imx415.bin
yaml-cli -s .isp.exposure 10
sleep .2
/root/kill.sh

View File

@ -0,0 +1,9 @@
#yaml-cli -s .isp.sensorConfig /etc/sensors/720p30_imx307_50.ini #use this for imx307
#yaml-cli -s .video0.fps 50 #use thise for imx307
yaml-cli -s .video0.size 1280x720
yaml-cli -s .video0.fps 30
yaml-cli -s .isp.sensorConfig /etc/sensors/imx415.bin
yaml-cli -s .isp.exposure 10
yaml-cli -s .video0.crop 0x0x1280x720
sleep .2
/root/kill.sh

View File

@ -0,0 +1,7 @@
yaml-cli -s .video0.size 1280x720
yaml-cli -s .video0.crop 0x0x1280x720
yaml-cli -s .video0.fps 60
yaml-cli -s .isp.sensorConfig /etc/sensors/imx415f.bin
yaml-cli -s .isp.exposure 20
sleep .2
/root/kill.sh

View File

@ -0,0 +1,7 @@
yaml-cli -s .video0.size 1280x720
yaml-cli -s .video0.crop 0x0x1280x720
yaml-cli -s .video0.fps 90
yaml-cli -s .isp.sensorConfig /etc/sensors/imx415f.bin
yaml-cli -s .isp.exposure 30
sleep .2
/root/kill.sh

View File

@ -0,0 +1,7 @@
yaml-cli -s .video0.size 1280x720
yaml-cli -s .video0.crop 0x0x1280x720
yaml-cli -s .video0.fps 120
yaml-cli -s .isp.sensorConfig /etc/sensors/imx415f.bin
yaml-cli -s .isp.exposure 30
sleep .2
/root/kill.sh

View File

@ -0,0 +1,92 @@
echo $1 $2 >>/tmp/channels.log
#channel 5
if [ $1 -eq 5 ]; then
if [ $2 -gt 1600 ]; then
CURRENT_SIZE=`yaml-cli -g .video0.size`
if [ $CURRENT_SIZE == '1280x720' ]; then
/root/1080.sh
sleep 3
else
/root/720.sh
sleep 3
fi
fi
fi
#channel 6
#if [ $1 -eq 6 ]; then
# if [ $2 -lt 1600 ]; then
# /root/ircut.sh off
# else
# /root/ircut.sh on
# fi
#fi
if [ $1 -eq 6 ]; then
if [ $2 -gt 1600 ]; then
CURRENT_SIZE=`yaml-cli -g .video0.size`
CURRENT_FPS=`yaml-cli -g .video0.fps`
if [ $CURRENT_SIZE == '1280x720' ] && [ $CURRENT_FPS == '30' ] ; then
/root/720b.sh
sleep 3
elif [ $CURRENT_SIZE == '1280x720' ] && [ $CURRENT_FPS == '60' ] ; then
/root/720c.sh
sleep 3
elif [ $CURRENT_SIZE == '1280x720' ] && [ $CURRENT_FPS == '90' ] ; then
/root/720d.sh
sleep 3
elif [ $CURRENT_SIZE == '1280x720' ] && [ $CURRENT_FPS == '120' ] ; then
/root/1080.sh
sleep 3
elif [ $CURRENT_SIZE == '1920x1080' ] && [ $CURRENT_FPS == '30' ] ; then
/root/1080b.sh
sleep 3
elif [ $CURRENT_SIZE == '1920x1080' ] && [ $CURRENT_FPS == '60' ] ; then
/root/1080c.sh
sleep 3
elif [ $CURRENT_SIZE == '1920x1080' ] && [ $CURRENT_FPS == '90' ] ; then
/root/3K.sh
sleep 3
elif [ $CURRENT_SIZE == '3200x1800' ]; then
/root/4K.sh
sleep 3
else
/root/720.sh
sleep 3
fi
fi
fi
#channel 7
if [ $1 -eq 7 ]; then
if [ $2 -lt 1400 ]; then
yaml-cli -s .image.luminance 50
killall -1 majestic
elif [ $2 -gt 1400 ] && [ $2 -lt 1600 ]; then
yaml-cli -s .image.luminance 90
killall -1 majestic
else
yaml-cli -s .image.luminance 30
killall -1 majestic
fi
fi
#channel 8
if [ $1 -eq 8 ]; then
if [ $2 -gt 1600 ]; then
CURRENT_BITRATE=`yaml-cli -g .video0.bitrate`
if [ $CURRENT_BITRATE -lt 7168 ]; then
NEW_BITRATE="$(($CURRENT_BITRATE+1024))"
else
NEW_BITRATE="1024"
sleep 2
fi
yaml-cli -s .video0.bitrate $NEW_BITRATE
sleep .2
/root/kill.sh
fi
sleep 3
fi
exit 1

View File

@ -0,0 +1,19 @@
if [ $1 -eq 7 ]; then
if [ $2 -gt 1600 ]; then
/root/ircut.sh on
elif [ $2 -gt 1400 ] && [ $2 -lt 1600 ]; then
/root/ircut.sh off
fi
fi
if [ $1 -eq 8 ]; then
if [ $2 -gt 1600 ]; then
killall venc
venc -p 5600 -f 30 -r 12288 -c 265cbr -v 200_imx307F -d frame --low-delay &
elif [ $2 -gt 1400 ] && [ $2 -lt 1600 ]; then
killall venc
venc -p 5600 -f 50 -r 12288 -c 265cbr -v 200_imx307B -d frame &
fi
fi
exit 1

View File

@ -0,0 +1,32 @@
#use: ./ircut.sh on | off
function gpio_setup {
if [ ! -e /sys/class/gpio/gpio$1 ]; then
echo $1 > /sys/class/gpio/export
fi
echo $2 > /sys/class/gpio/gpio$1/direction
}
function set_gpio {
echo $2 > /sys/class/gpio/gpio$1/value
}
function ircut_on {
set_gpio 8 0
set_gpio 9 1
sleep 0.1
set_gpio 8 0
}
function ircut_off {
set_gpio 8 1
set_gpio 9 0
sleep 0.1
set_gpio 8 0
}
gpio_setup 8 out
gpio_setup 9 out
ircut_$1

View File

@ -0,0 +1,5 @@
killall majestic
sleep 1
majestic
sleep 5
gkrcparams --MaxQp 30 --MaxI 2

View File

@ -0,0 +1,57 @@
#!/bin/sh
#
# Start telemetry
#
. /etc/datalink.conf
. /etc/telemetry.conf
keydir="/etc"
fw=$(grep "BUILD_OPTION" "/etc/os-release" | cut -d= -f2)
start_telemetry() {
if [ ! -f /usr/bin/telemetry_rx -a ! -f /usr/bin/telemetry_tx ]; then
ln -s /usr/bin/wfb_rx /usr/bin/telemetry_rx ; chmod +x /usr/bin/telemetry_rx
ln -s /usr/bin/wfb_tx /usr/bin/telemetry_tx ; chmod +x /usr/bin/telemetry_tx
else
if [ ${one_way} = "false" ]; then
if [ -z "${link_id}" ]; then
telemetry2_rx -r ${stream_rx} -u ${port_rx} -K ${keydir}/drone.key ${wlan} >/dev/null &
else
telemetry_rx -p ${stream_rx} -u ${port_rx} -K ${keydir}/drone.key -i ${link_id} ${wlan} >/dev/null &
fi
fi
if [ -z "${link_id}" ]; then
telemetry2_tx -r ${stream_tx} -u ${port_tx} -K ${keydir}/drone.key -B ${bandwidth} -M ${mcs_index} -S ${stbc} -L ${ldpc} -G ${guard_interval} -k ${fec_k} -p ${fec_p} ${wlan} >/dev/null &
else
telemetry_tx -p ${stream_tx} -u ${port_tx} -K ${keydir}/drone.key -B ${bandwidth} -M ${mcs_index} -S ${stbc} -L ${ldpc} -G ${guard_interval} -k ${fec_k} -n ${fec_n} -T ${fec_timeout} -i ${link_id} ${wlan} >/dev/null &
fi
fi
}
case "$1" in
start)
echo "Loading MAVLink telemetry service..."
if [ ${router} -eq 1 ] || [ ${fw} = "lte" ]; then
/usr/bin/mavlink-routerd &
else
mavfwd --master ${serial} --baudrate ${baud} --out 127.0.0.1:${port_tx} --in 127.0.0.1:${port_rx} &
fi
if [ ${fw} = "fpv" ]; then
start_telemetry
fi
echo "Done."
;;
stop)
echo "Stopping telemetry services..."
kill -9 $(pidof telemetry_rx)
kill -9 $(pidof telemetry_tx)
kill -9 $(pidof mavlink-routerd)
kill -9 $(pidof mavfwd)
;;
*)
echo "Usage: $0 {start|stop}"
exit 1
esac

Binary file not shown.

View File

@ -0,0 +1,156 @@
#!/bin/sh
#
# Start wifibroadcast
#
. /etc/datalink.conf
. /etc/wfb.conf
keydir="/etc"
chip=$(ipcinfo -c)
vendor=$(ipcinfo -v)
driver=""
set_mcs() {
if [ ${vendor} = "ingenic" ]; then
mcs=$(ls -l /lib/firmware | grep "htc_9271" | awk {'print $11'} | cut -d "." -f3)
else
mcs=$(ls -l /lib/firmware/ath9k_htc | grep "htc_9271-1.4.0.fw" | cut -d "." -f6)
fi
if [ -z "${mcs}" ]; then
setmcs ${mcs_index}
fi
if [ ${mcs_index} -eq 1 ] || [ ${mcs_index} -eq 3 ]; then
if [ ! ${mcs_index} -eq ${mcs} ]; then
setmcs ${mcs_index}
sleep 3
fi
fi
}
# "0bda:8813" -> (8814) -> 8814au
# "0846:9052" -> (8811) -> 8821au
detect_wifi_card() {
echo "Detecting wifi card vendor..."
devices=$(lsusb | cut -d ' ' -f6 | sort | uniq)
for card in ${devices}
do
case "${card}" in
"0bda:8812" | "0bda:881a" | "0b05:17d2" | "2357:0101")
driver="realtek"
modprobe 88XXau rtw_tx_pwr_idx_override=${driver_txpower_override}
;;
"0cf3:9271" | "040d:3801")
driver="atheros"
set_mcs
modprobe mac80211
modprobe ath9k_htc
;;
esac
done
if [ -z "${driver}" ]; then
echo "No usb wifi card detected. Check wifi stick connection, usb power or possible bad soldering."
exit
else
echo "Detected:" ${driver}
fi
echo "Awaiting interface ${wlan} in system..."
local n=0
while ! $(ifconfig -a | grep -q ${wlan})
do
if [ ${n} -ge 5 ]; then
echo "No interface ${wlan}. Check wifi stick connection, usb power or possible bad soldering."
exit
fi
sleep 0.5
n=$(expr ${n} + 1)
done
}
load_modules() {
modprobe cfg80211
detect_wifi_card
}
load_interface() {
if [ ${driver} = "realtek" ]; then
ifconfig ${wlan} up
iwconfig ${wlan} mode monitor
elif [ ${driver} = "atheros" ]; then
iwconfig ${wlan} mode monitor
ifconfig ${wlan} up
fi
iw reg set ${region}
if [ ! -z "${frequency}" ]; then
iwconfig ${wlan} freq ${frequency}
else
iwconfig ${wlan} channel ${channel}
fi
# dirty fix crash if txpower set. setting txpower disabled because patched driver always set txpower level 58
# iw dev ${wlan} set txpower fixed $((${txpower} * 100))
}
start_wfb() {
if [ -z "${link_id}" ]; then
wfb2_tx -r ${stream} -u ${udp_port} -K ${keydir}/drone.key -B ${bandwidth} -M ${mcs_index} -S ${stbc} -L ${ldpc} -G ${guard_interval} -k ${fec_k} -p ${fec_p} ${wlan} >/dev/null &
else
wfb_tx -p ${stream} -u ${udp_port} -K ${keydir}/drone.key -B ${bandwidth} -M ${mcs_index} -S ${stbc} -L ${ldpc} -G ${guard_interval} -k ${fec_k} -n ${fec_n} -T ${fec_timeout} -i ${link_id} ${wlan} &
fi
}
case "$1" in
start)
if [ ${daemon} -eq 1 ]; then
echo "Loading modules and wifi card driver..."
load_modules
echo "Preparing interface wlan..."
load_interface
if ! cat ${keydir}/drone.key > /dev/null 2>&1; then
echo "Generating drone & ground station keys..."
cd ${keydir} ; wfb_keygen
else
echo "Drone key exist..."
fi
echo "Starting Wifibroadcast service..."
start_wfb
echo "Done."
if [ ${telemetry} = "true" ]; then
if [ ${chip} = "gk7205v200" ]; then
# UART2_RX mux
devmem 0x120c0010 32 0x1e04
fi
/usr/bin/telemetry start
fi
else
echo "Wifibroadcast service disabled in wfb.conf..."
fi
;;
stop)
echo "Stopping all services..."
kill -9 $(pidof wfb_tx)
kill -9 $(pidof telemetry_rx)
kill -9 $(pidof telemetry_tx)
kill -9 $(pidof mavlink-routerd)
kill -9 $(pidof mavfwd)
;;
*)
echo "Usage: $0 {start|stop}"
exit 1
esac

View File

@ -0,0 +1,17 @@
## U-Boot для телеметрии
#### только для gk7502v200!
загрузчик внесён разработчиками в релизы, и если вы прошиваетесь с инструкций на openipc.net, то этого уже делать не надо, только установить bootdelay 0.
Чтобы поток телеметрии не прерывал загрузку камеры, когда u-boot считает телеметрию "нажатием любой кнопки для входа в консоль загрузчика", нужно залить этот загрузчик
[(ССЫЛКА)](https://github.com/OpenIPC/sandbox-fpv/raw/master/gk7205v200/u-boot-gk7205v200-universal.bin):
```
# закачайте файл u-boot-gk7205v200-universal.bin в /tmp камеры через winscp ИЛИ выполните команду и УБЕДИТЕСЬ ЧТО ФАЙЛ СКАЧАЛСЯ!!!#curl -o /tmp/u-boot-gk7205v200-universal.bin http://fpv.openipc.net/u-boot-gk7205v200-universal.bin
flashcp -v /tmp/u-boot-gk7205v200-universal.bin /dev/mtd0
```
и установите нулевую задержку загрузки командой `fw_setenv bootdelay 0`.
При первой прошивке просто используйте этот файл вместо указанного на странице инструкций. Только для gk7502v200!
Данный загрузчик прерывается по комбинации клавиш Ctrl+C, а не любой. Будьте осторожны! Завалите загрузчик - придется паять и шить программатором.

View File

@ -0,0 +1,69 @@
system:
webAdmin: disabled
buffer: 1024
image:
mirror: false
flip: false
rotate: none
contrast: 50
hue: 50
saturation: 50
luminance: 50
osd:
enabled: false
template: "%a %e %B %Y %H:%M:%S %Z"
nightMode:
enabled: false
records:
enabled: false
path: /mnt/mmcblk0p1/%Y-%m-%d-%H.mp4
maxUsage: 95
video0:
enabled: true
bitrate: 5192
codec: h265
rcMode: cbr
gopSize: 0.2
size: 1920x1080
fps: 30
#crop: 320x180x1280x720
video1:
enabled: false
jpeg:
enabled: false
mjpeg:
size: 640x360
fps: 5
bitrate: 1024
audio:
enabled: false
volume: auto
srate: 8000
rtsp:
enabled: false
port: 554
hls:
enabled: false
youtube:
enabled: false
motionDetect:
enabled: false
visualize: true
debug: true
ipeye:
enabled: false
watchdog:
enabled: false
timeout: 10
isp:
sensorConfig: /etc/sensors/smtsec_imx307_i2c_4l_1080p.ini
slowShutter: disabled
drc: 420
lowDelay: true
#rawMode: none
blkCnt: 12
#dis: true
netip:
enabled: false
outgoing:
- udp://127.0.0.1:5600

View File

@ -0,0 +1,20 @@
serial=/dev/ttyAMA0
baud=115200
### router: use simple mavfwd (0) or classic mavlink-routerd (1)
router=0
wlan=wlan0
bandwidth=20
stbc=1
ldpc=1
mcs_index=1
stream_rx=144
stream_tx=16
link_id=7669206
port_rx=14551
port_tx=14550
fec_k=1
fec_n=2
fec_timeout=0
guard_interval=long
one_way=false

View File

@ -0,0 +1,18 @@
wlan=wlan0
region=BO
# By default used channel number, but, you may set freq instead. For ex: 2387M
channel=44
frequency=
txpower=20
driver_txpower_override=20
bandwidth=20
stbc=1
ldpc=1
mcs_index=1
stream=0
link_id=7669206
udp_port=5600
fec_k=8
fec_n=12
fec_timeout=0
guard_interval=long

View File

@ -0,0 +1,32 @@
#use: ./ircut.sh on | off
function gpio_setup {
if [ ! -e /sys/class/gpio/gpio$1 ]; then
echo $1 > /sys/class/gpio/export
fi
echo $2 > /sys/class/gpio/gpio$1/direction
}
function set_gpio {
echo $2 > /sys/class/gpio/gpio$1/value
}
function ircut_on {
set_gpio 11 0
set_gpio 10 1
sleep 0.1
set_gpio 11 0
}
function ircut_off {
set_gpio 11 1
set_gpio 10 0
sleep 0.1
set_gpio 11 0
}
gpio_setup 11 out
gpio_setup 10 out
ircut_$1

View File

@ -0,0 +1,26 @@
## Добавляем плавности видео
На режимах 1080p@30fps заметно легкое подергивание видео, а при замедленной съемке таймера видно что картинка замирает на какое то время и далее обновляется. Это происходит из за неравномерности потока, который резко возрастает на ключевых кадрах.
Исправить это можно, перенастроив на камере два параметра энкодера.
Спасибо за проделанную работу TipoMan и widgetii!
Нам нужно положить файл [gkrcparams](https://github.com/OpenIPC/sandbox-fpv/raw/master/user_TipoMan/gkrcparams) в /usr/sbin, дать права на выполнение `chmod +x /usr/sbin/gkrcparams` и вставить запуск его после старта majestic в /etc/init.d/S95majestic:
```
start-stop-daemon -b -m -S -q -p "$PIDFILE" -x "/usr/bin/$DAEMON" -- $DAEMON_ARGS
sleep 1 <=== ЭТО ВСТАВИТЬ
gkrcparams --MaxQp 30 --MaxI 2 <=== ЭТО ВСТАВИТЬ
status=$?
```
После перезапуска картинка должна стать плавной. Прочие настройки в majestic.yaml для режима mcs1:
```
video0:
enabled: true
bitrate: 7168
codec: h265
rcMode: cbr
gopSize: 1.0
size: 1920x1080
```
Если же картинка все равно иногда подергивается, придется изменить mcs на 3 в `/etc/wfb.conf` потеряв в дальности либо уменьшать битрейт.

View File

@ -0,0 +1,14 @@
## Прием и отображение видео на windows
В "классическом режиме" (на камере стримит majestic, а NVR пересылает видеопоток на ПК, не забываем указать IP адрес ПК в wfb.conf регистратора) видео можно принимать в QGroundControl, Mission Planner и можно просто вывести в отдельном окне
без привязки к программам. Для этого нужно установить [GStreamer](https://gstreamer.freedesktop.org/download/) и запускать его на прием с некими параметрами, например:
```
C:\gstreamer\1.0\msvc_x86_64\bin\gst-launch-1.0.exe -v udpsrc port=5600 buffer-size=32768 ! application/x-rtp ! rtph265depay ! queue max-size-buffers=5 ! avdec_h265 ! videoconvert ! videoscale ! video/x-raw,width=1280,height=720,format=BGRA ! autovideosink sync=false
```
В данном примере размер видео изменяется до 1280x720. Для запуска видео с разрешением оригинального потока убираем из строки `videoscale ! ` и `width=1280,height=720,`.
![preview](https://github.com/OpenIPC/sandbox-fpv/raw/master/notes_files/Screenshot_2.png)
Для воспроизведения видео в окне Mission Planner нужно кликнуть правой кнопкой мыши по его окну с горизонтом и выбрать `Video > Set GStreamer source`, внести строку параметров: `udpsrc port=5600 buffer-size=32768 ! application/x-rtp ! rtph265depay ! queue max-size-buffers=5 ! avdec_h265 ! videoconvert ! video/x-raw,format=BGRA ! appsink name=outsink`, нажать Ok. Строка сохранится для будущий применений.

View File

@ -0,0 +1,18 @@
#!/bin/sh
#
# Start gpio monitor
#
case "$1" in
start)
echo "Starting gpio_monitor daemon..."
/root/gpio_monitor.sh &
;;
stop)
echo "Stopping gpio_monitor daemon..."
kill -9 $(pidof {exe} ash /root/gpio_monitor.sh)
;;
*)
echo "Usage: $0 {start|stop}"
exit 1
esac

View File

@ -0,0 +1,23 @@
#!/bin/sh
start() {
/usr/bin/rcjoystick -t 25 -c 16 -i wlan0 &
}
stop() {
killall rcjoystick
}
restart() {
stop
sleep 1
start
}
case "$1" in
start|stop|restart)
"$1";;
*)
echo "Usage: $0 {start|stop|restart}"
exit 1
esac

View File

@ -0,0 +1,21 @@
[General]
TcpServerPort = 0
DebugLogLevel = error
[UdpEndpoint qgroundcontrol]
Mode = Server
Address = 0.0.0.0
Port = 14550
[UdpEndpoint telemetry_tx]
Group=wfb
Mode = Normal
Address = 127.0.0.1
Port = 14650
[UdpEndpoint telemetry_rx]
Group=wfb
Mode = Server
Address = 127.0.0.1
Port = 14651

View File

@ -0,0 +1,20 @@
serial=/dev/ttyAMA0
baud=115200
### router: use simple mavfwd (0) or classic mavlink-routerd (1)
router=1
wlan=wlan0
bandwidth=20
stbc=1
ldpc=1
mcs_index=1
stream_rx=16
stream_tx=144
link_id=7669206
port_rx=14651
port_tx=14650
fec_k=1
fec_n=2
fec_timeout=0
guard_interval=long
one_way=false

File diff suppressed because it is too large Load Diff

View File

@ -0,0 +1,138 @@
# Architecture
BR2_arm=y
BR2_cortex_a7=y
BR2_ARM_EABI=y
BR2_ARM_FPU_NEON_VFPV4=y
BR2_ARM_INSTRUCTIONS_THUMB2=y
BR2_KERNEL_HEADERS_VERSION=y
BR2_DEFAULT_KERNEL_VERSION="4.9.37"
BR2_PACKAGE_HOST_LINUX_HEADERS_CUSTOM_4_9=y
# Toolchain
BR2_PER_PACKAGE_DIRECTORIES=y
BR2_GCC_VERSION_8_X=y
# BR2_TOOLCHAIN_USES_UCLIBC is not set
# BR2_TOOLCHAIN_BUILDROOT_UCLIBC is not set
# BR2_TOOLCHAIN_BUILDROOT_LIBC="uclibc"
# BR2_TOOLCHAIN_USES_MUSL is not set
# BR2_TOOLCHAIN_BUILDROOT_MUSL is not set
# BR2_TOOLCHAIN_BUILDROOT_LIBC="musl"
BR2_TOOLCHAIN_USES_GLIBC=y
BR2_TOOLCHAIN_BUILDROOT_GLIBC=y
BR2_TOOLCHAIN_BUILDROOT_LIBC="glibc"
BR2_PACKAGE_GLIBC_UTILS=y
BR2_TOOLCHAIN_BUILDROOT_CXX=y
# BR2_TOOLCHAIN_BUILDROOT_LOCALE is not set
BR2_TOOLCHAIN_BUILDROOT_USE_SSP=y
BR2_PIC_PIE=y
BR2_GCC_ENABLE_LTO=y
BR2_INSTALL_LIBSTDCPP=y
# Kernel
BR2_LINUX_KERNEL=y
BR2_LINUX_KERNEL_CUSTOM_VERSION=y
BR2_LINUX_KERNEL_CUSTOM_VERSION_VALUE="4.9.37"
BR2_LINUX_KERNEL_USE_CUSTOM_CONFIG=y
BR2_LINUX_KERNEL_CUSTOM_CONFIG_FILE="$(BR2_EXTERNAL_HISILICON_PATH)/board/hi3536dv100/kernel/hi3536dv100.generic.config"
BR2_LINUX_KERNEL_UIMAGE=y
BR2_LINUX_KERNEL_UIMAGE_LOADADDR="0x80008000"
BR2_LINUX_KERNEL_XZ=y
BR2_LINUX_KERNEL_EXT_HISI_PATCHER=y
BR2_LINUX_KERNEL_EXT_HISI_PATCHER_LIST="$(BR2_EXTERNAL_HISILICON_PATH)/board/hi3536dv100/kernel/patches/ $(BR2_EXTERNAL_HISILICON_PATH)/board/hi3536dv100/kernel/overlay"
# Filesystem
# BR2_TARGET_TZ_INFO is not set
# BR2_TARGET_ROOTFS_CPIO is not set
BR2_TARGET_ROOTFS_SQUASHFS=y
BR2_TARGET_ROOTFS_SQUASHFS4_XZ=y
BR2_ROOTFS_OVERLAY="$(TOPDIR)/../general/overlay"
BR2_ROOTFS_POST_BUILD_SCRIPT="$(TOPDIR)/../scripts/executing_commands_for_$(BR2_TOOLCHAIN_BUILDROOT_LIBC).sh"
# OpenIPC configuration
BR2_TOOLCHAIN_BUILDROOT_VENDOR="openipc"
BR2_TARGET_GENERIC_ISSUE="Welcome to OpenIPC"
BR2_TARGET_GENERIC_HOSTNAME="openipc-hi3536dv100"
BR2_GLOBAL_PATCH_DIR="$(TOPDIR)/../general/package/all-patches"
# OpenIPC packages
BR2_PACKAGE_HISILICON_OSDRV_HI3536DV100=y
BR2_PACKAGE_BUSYBOX_CONFIG="$(TOPDIR)/../general/package/busybox/busybox.config"
BR2_PACKAGE_DROPBEAR_OPENIPC=y
# BR2_PACKAGE_FDK_AAC_OPENIPC is not set
BR2_PACKAGE_FWPRINTENV_OPENIPC=y
# BR2_PACKAGE_HASERL is not set
# BR2_PACKAGE_HISI_GPIO is not set
BR2_PACKAGE_IPCTOOL=y
# BR2_PACKAGE_JSON_C is not set
# BR2_PACKAGE_JSONFILTER is not set
# BR2_PACKAGE_LAME_OPENIPC is not set
BR2_PACKAGE_LIBCURL_OPENIPC=y
BR2_PACKAGE_LIBCURL_OPENIPC_CURL=y
# BR2_PACKAGE_LIBCURL_OPENIPC_VERBOSE is not set
# BR2_PACKAGE_LIBCURL_OPENIPC_PROXY_SUPPORT is not set
# BR2_PACKAGE_LIBCURL_OPENIPC_COOKIES_SUPPORT is not set
# BR2_PACKAGE_LIBCURL_OPENIPC_EXTRA_PROTOCOLS_FEATURES is not set
BR2_PACKAGE_LIBCURL_OPENIPC_MBEDTLS=y
# BR2_PACKAGE_LIBEVENT_OPENIPC is not set
# BR2_PACKAGE_LIBEVENT_OPENIPC_REMOVE_PYSCRIPT is not set
# BR2_PACKAGE_LIBOGG_OPENIPC is not set
# BR2_PACKAGE_LIBWEBSOCKETS_OPENIPC is not set
# BR2_PACKAGE_LIBYAML is not set
# BR2_PACKAGE_MAJESTIC_FONTS is not set
BR2_PACKAGE_MBEDTLS_OPENIPC=y
# BR2_PACKAGE_MBEDTLS_OPENIPC_PROGRAMS is not set
# BR2_PACKAGE_MBEDTLS_OPENIPC_COMPRESSION is not set
# BR2_PACKAGE_MICROBE_WEB is not set
# BR2_PACKAGE_MINI_SNMPD is not set
# BR2_PACKAGE_OPUS_OPENIPC is not set
# BR2_PACKAGE_OPUS_OPENIPC_FIXED_POINT is not set
# BR2_PACKAGE_SSHPASS is not set
# BR2_PACKAGE_UACME_OPENIPC is not set
BR2_PACKAGE_VTUND_OPENIPC=y
# BR2_PACKAGE_YAML_CLI is not set
# BR2_PACKAGE_XMDP is not set
# WiFi
BR2_PACKAGE_WIRELESS_TOOLS=y
BR2_PACKAGE_WPA_SUPPLICANT=y
# BR2_PACKAGE_WPA_SUPPLICANT_CLI is not set
BR2_PACKAGE_WPA_SUPPLICANT_NL80211=y
BR2_PACKAGE_WPA_SUPPLICANT_PASSPHRASE=y
BR2_PACKAGE_LINUX_FIRMWARE_OPENIPC=y
# BR2_PACKAGE_LINUX_FIRMWARE_OPENIPC_MT7601U is not set
# BR2_PACKAGE_RTL8188EU is not set
BR2_PACKAGE_LINUX_FIRMWARE_OPENIPC_ATHEROS_9271=y
BR2_PACKAGE_RTL8812AU_OPENIPC=y
# FPV
BR2_PACKAGE_DATALINK=y
BR2_PACKAGE_WIFIBROADCAST=y
# BR2_PACKAGE_WFBOPENHD is not set
BR2_PACKAGE_MAVLINK_ROUTER=y
# BR2_PACKAGE_MAVFWD is not set
#FFMPEG
BR2_PACKAGE_FFMPEG_OPENIPC=y
# ZEROTIER
BR2_PACKAGE_ZEROTIER_ONE=y
# IPTABLES
# BR2_PACKAGE_IPTABLES is not set
# WIREGUARD
# BR2_PACKAGE_WIREGUARD_LINUX_COMPAT is not set
# BR2_PACKAGE_WIREGUARD_TOOLS is not set
# DEBUG
BR2_PACKAGE_HOST_GDB=y
BR2_PACKAGE_GDB=y
BR2_PACKAGE_ZLIB=y
# SDL2
# BR2_PACKAGE_SDL2 is not set
# BR2_PACKAGE_SDL2_IMAGE is not set
# BR2_PACKAGE_SDL2_TTF is not set

View File

@ -0,0 +1,35 @@
=== original ENV
hisilicon # printenv
bootcmd=sf probe 0;sf read 0x84000000 0xf60000 0x20000;logoload 0x84000000;decjpg;sf read 0x82000000 0x50000 0x500000;squashfsload 82000000;bootm 0x81000000
bootdelay=0
baudrate=115200
ethaddr=00:0b:3f:00:00:01
ipaddr=192.168.1.10
serverip=192.168.1.1
netmask=255.255.0.0
bootfile="uImage"
da=mw.b 0x82000000 ff 1000000;tftp 0x82000000 u-boot.bin.img;sf probe 0;flwrite
du=mw.b 0x82000000 ff 1000000;tftp 0x82000000 user-x.cramfs.img;sf probe 0;flwrite
dr=mw.b 0x82000000 ff 1000000;tftp 0x82000000 romfs-x.cramfs.img;sf probe 0;flwrite
dw=mw.b 0x82000000 ff 1000000;tftp 0x82000000 web-x.cramfs.img;sf probe 0;flwrite
dl=mw.b 0x82000000 ff 1000000;tftp 0x82000000 logo-x.cramfs.img;sf probe 0;flwrite
dc=mw.b 0x82000000 ff 1000000;tftp 0x82000000 custom-x.cramfs.img;sf probe 0;flwrite
up=mw.b 0x82000000 ff 1000000;tftp 0x82000000 update.img;sf probe 0;flwrite
tk=mw.b 0x82000000 ff 1000000;tftp 0x82000000 zImage.img; bootm 0x82000000
dd=mw.b 0x82000000 ff 1000000;tftp 0x82000000 mtd-x.jffs2.img;sf probe 0;flwrite
de=mw.b 0x82000000 ff 1000000;tftp 0x82000000 u-boot.env.bin.img;sf probe 0;flwrite
jpeg_addr=0x8dc00000
jpeg_size=0xb85f9
vobuf=0x8dd00000
loadlogo=sf probe 0;sf read 0x84000000 0xF60000 0x20000;logoload 0x84000000;decjpg
bootargs=mem=139M console=ttyAMA0,115200 root=/dev/mtdblock1 rootfstype=squashfs mtdparts=hi_sfc:320K(boot),3968K(romfs),7040K(usr),1600K(web),2816K(custom),128K(logo),512K(mtd) coherent_pool=2M
appVideoStandard=PAL
appSystemLanguage=English
appCloudExAbility=E7nsOhUNSfs=
stdin=serial
stdout=serial
stderr=serial
verify=n
ver=U-Boot 2010.06-svn1560 (May 06 2021 - 19:15:51)
Environment size: 1617/65532 bytes

View File

@ -0,0 +1,82 @@
##IR
##Y2 !17
##Y1 !6
##X2 !13
##Y3 !8
##X1 !7
##ALARM 10
##REC 11
function gpio_setup {
if [ ! -e /sys/class/gpio/gpio$1 ]; then
echo $1 > /sys/class/gpio/export
fi
echo $2 > /sys/class/gpio/gpio$1/direction
}
function set_gpio {
echo $2 > /sys/class/gpio/gpio$1/value
}
function get_gpio {
return `cat /sys/class/gpio/gpio${1}/value`
}
#buttons
for i in 6 7 8 13 17
do
gpio_setup $i in
done
#ALARM led
gpio_setup 10 out
while [ true ]
do
get_gpio 6
if [ "$?" -eq 0 ]; then
set_gpio 10 1
echo 6 >>/tmp/gpio.log
#ifdown usb0
#ifup usb0
/usr/bin/wifibroadcast restart
sleep .1
set_gpio 10 0
fi
get_gpio 7
if [ "$?" -eq 0 ]; then
set_gpio 10 1
echo 7 >>/tmp/gpio.log
ifconfig eth0:1 192.168.11.1
sleep .5
set_gpio 10 0
fi
get_gpio 8
if [ "$?" -eq 0 ]; then
set_gpio 10 1
echo 8 >>/tmp/gpio.log
sleep .5
set_gpio 10 0
fi
get_gpio 13
if [ "$?" -eq 0 ]; then
set_gpio 10 1
echo 13 >>/tmp/gpio.log
sleep .5
set_gpio 10 0
fi
get_gpio 17
if [ "$?" -eq 0 ]; then
set_gpio 10 1
echo 17 >>/tmp/gpio.log
sleep .5
set_gpio 10 0
fi
sleep .2
done

View File

@ -0,0 +1,12 @@
#!/bin/sh
ARG="`cat /etc/vdec.conf`"
value=${ARG#*mode=}
value2=${value%%p60*}
if [ $value2 == '720' ]; then
sed -i -e 's/mode=720p60/mode=1080p60/g' /etc/vdec.conf
elif [ $value2 == '1080' ]; then
sed -i -e 's/mode=1080p60/mode=720p60/g' /etc/vdec.conf
fi
reboot # Please probe this for re-read config: killall -1 vdec

Binary file not shown.

View File

@ -0,0 +1,89 @@
## Подключение камеры к планшету или ПК через LTE (4G) модем
Летать через 4G - крайне интересная тема для самолетов под стабилизацией или автоматическим маршрутом. Разобъем процесс настройки на задачи:
* настроить интернет через модем на камере
* настроить свой сервер zerotier (можно воспользоваться публичным)
* подключить камеру и ПК к одной сети zerotier и настроить стрим
Следуя [этим инструкциям](usb-modeswitch.md), настроим usb_modeswitch и сетевой интерфейс eth1 на камере под прошивкой OpenIPC LTE. Если у вас FPV или LITE прошивка, предварительно нужно ее сменить онлайн:
```
#тут меняем fpv на lte в файле /etc/os-release, можно это сделать вручную
sed -i 's/BUILD_OPTION=fpv/BUILD_OPTION=lte/' /etc/os-release
#а это если у вас lite версия
sed -i 's/BUILD_OPTION=lite/BUILD_OPTION=lte/' /etc/os-release
sysupgrade --force_ver -k -r -n
```
Мы получаем камеру с заводскими настройками и lte прошивкой, в которой в отличие от fpv удален wfb а взамен установлен zerotier-one клиент.
На самом деле, правильным решением будет не использовать usb_modeswitch а настроить вторичную композицию модема сразу на cdc_ethernet. Тогда модем перестанет быть универсальным и сразу будет отображаться как сетевая карта, но зато исчезнет вероятность возникновения ряда проблем.
#### zerotier
Это программное обеспечение для объединения нескольких устройств в одну локальную сеть. Существует публичный сервер для создания своей сети, но лучше поднять свой.
Для этого потребуется vps-сервер под ubuntu.
```
apt-get install -y apt-transport-https gnupg mc iftop #устанавливаем зависимости
curl -s https://install.zerotier.com | sudo bash #устанавливаем клиентскую часть
curl -O https://s3-us-west-1.amazonaws.com/key-networks/deb/ztncui/1/x86_64/ztncui_0.7.1_amd64.deb #устанавливаем панель управления
apt-get install ./ztncui_0.7.1_amd64.deb
echo 'HTTPS_PORT=6443' > /opt/key-networks/ztncui/.env #порт для вебморды управления
echo 'NODE_ENV=production' >> /opt/key-networks/ztncui/.env #режим работы
echo 'HTTPS_HOST=nn.mm.ff.dd' >> /opt/key-networks/ztncui/.env #внешний ip-адрес нашего сервера
systemctl restart ztncui
```
Входим по ссылке https://ip_addr:6443, логин admin, пароль password.
Далее создаем сеть и настраиваем параметры выдачи адресов, какие вам больше нравятся, остальные настройки по умолчанию.
В режиме private после подключения клиента требуется установить галочку Authorized чтобы разрешить ему подключение.
![ZTNCUI](https://github.com/OpenIPC/sandbox-fpv/raw/master/notes_files/ZTNCUI.png)
Существует альтернатива в виде [публичного сервера](https://my.zerotier.com/), но вопрос надежности и быстродействия остается подвешенным. Программы - клиенты для windows, android скачивать [тут](https://www.zerotier.com/download/).
Подключение к сети производится через указание Network ID, 16-значной символьной строки, которую берем из панели управления. Для камеры ее указываем в /etc/datalink.conf
```
use_zt=true
zt_netid=a8867b0bxxxxxxxxx
```
после чего перезагружаем камеру. При наличии интернет-подключения, хоть LTE хоть ethernet, камера должна подключиться к сети zerotier. Это можно проверить через веб-панель управления и на камере командой ifconfig.
```
ztuplek3wb Link encap:Ethernet HWaddr 92:31:B1:54:8B
inet addr:10.7.0.1 Bcast:10.7.0.255 Mask:255.255.255.0
inet6 addr: fe80::9031:b1ff:fe54/64 Scope:Link
UP BROADCAST RUNNING MULTICAST MTU:2800 Metric:1
RX packets:93 errors:0 dropped:0 overruns:0 frame:0
TX packets:1236835 errors:0 dropped:0 overruns:0 carrier:0
collisions:0 txqueuelen:1000
RX bytes:5677 (5.5 KiB) TX bytes:1493618333 (1.3 GiB)
```
Для ПК или андроид-устройства [устанавливаем](https://www.zerotier.com/download/) программу и аналогично добавляем сеть по ее id, авторизуем устройство в веб-панели. Пробуем перекрестный ping, он должен проходить. Если имеется файервол/брендмауер, как например под windows, нужно добавить в нем разрешающее правило с нашей подсетью.
#### Настройка стрима
Остается в /etc/majestic.yaml указать ip-адрес наземки из сети zerotier и видео можно принимать. Не забудьте согласовать кодеки.
```
outgoing:
- udp://ip_from_zerotier:5600
```
#### Телеметрия
Проверку телеметрии я еще не делал, но работать все должно как то так.
Используется mavlink-routerd с конфигом /etc/mavlink.conf. Нужно указать эндпоинты для локального serial и наземки по ip-адресу zerotier:
```
[General]
TcpServerPort = 0
[UartEndpoint drone]
Device = /dev/ttyAMA0
Baud = 115200
[UdpEndpoint qgroundcontrol]
Mode = Normal
Address = gs_ip_from_zerotier
Port = 14550
```
Так как соединение является двунаправленным, автоматически получаем телеметрию в обе стороны.

Binary file not shown.

View File

@ -0,0 +1,416 @@
#include <getopt.h>
#include <stdio.h>
#include <stdlib.h>
#include <fcntl.h>
#include <errno.h>
#include <string.h>
#include <unistd.h>
#include <signal.h>
#include <sys/socket.h>
#include <netinet/in.h>
#include <arpa/inet.h>
#include <stdbool.h>
#include <termios.h>
#include <assert.h>
#include <event2/event.h>
#include <event2/util.h>
#include <event2/buffer.h>
#include <event2/bufferevent.h>
#define MAX_MTU 9000
bool verbose = false;
const char *default_master = "/dev/ttyAMA0";
const int default_baudrate = 115200;
const char *defualt_out_addr = "127.0.0.1:14600";
const char *default_in_addr = "127.0.0.1:14601";
uint8_t ch_count = 0;
uint16_t ch[14];
struct bufferevent *serial_bev;
struct sockaddr_in sin_out = {
.sin_family = AF_INET,
};
int out_sock;
static void print_usage()
{
printf("Usage: mavfwd [OPTIONS]\n"
"Where:\n"
" --master Local MAVLink master port (%s by default)\n"
" --baudrate Serial port baudrate (%d by default)\n"
" --out Remote output port (%s by default)\n"
" --in Remote input port (%s by default)\n"
" --channels RC override channels to parse after first 4 and call /root/channels.sh $ch $val, default 0\n"
" --verbose display each packet, default not\n"
" --help Display this help\n",
default_master, default_baudrate, defualt_out_addr,
default_in_addr);
}
static speed_t speed_by_value(int baudrate)
{
switch (baudrate) {
case 9600:
return B9600;
case 19200:
return B19200;
case 38400:
return B38400;
case 57600:
return B57600;
case 115200:
return B115200;
case 230400:
return B230400;
case 460800:
return B460800;
case 500000:
return B500000;
case 921600:
return B921600;
case 1500000:
return B1500000;
default:
printf("Not implemented baudrate %d\n", baudrate);
exit(EXIT_FAILURE);
}
}
static bool parse_host_port(const char *s, struct in_addr *out_addr,
in_port_t *out_port)
{
char host_and_port[32] = { 0 };
strncpy(host_and_port, s, sizeof(host_and_port) - 1);
char *colon = strchr(host_and_port, ':');
if (NULL == colon) {
return -1;
}
*colon = '\0';
const char *host = host_and_port, *port_ptr = colon + 1;
const bool is_valid_addr = inet_aton(host, out_addr) != 0;
if (!is_valid_addr) {
printf("Cannot parse host `%s'.\n", host);
return false;
}
int port;
if (sscanf(port_ptr, "%d", &port) != 1) {
printf("Cannot parse port `%s'.\n", port_ptr);
return false;
}
*out_port = htons(port);
return true;
}
static void signal_cb(evutil_socket_t fd, short event, void *arg)
{
struct event_base *base = arg;
(void)event;
printf("%s signal received\n", strsignal(fd));
event_base_loopbreak(base);
}
static void dump_mavlink_packet(unsigned char *data, const char *direction)
{
uint8_t seq;
uint8_t sys_id;
uint8_t comp_id;
uint32_t msg_id;
if(data[0] == 0xFE) { //mavlink 1
seq = data[2];
sys_id = data[3];
comp_id = data[4];
msg_id = data[5];
} else { //mavlink 2
seq = data[4];
sys_id = data[5];
comp_id = data[6];
msg_id = data[7];
}
if (verbose) printf("%s %#02x sender %d/%d\t%d\t%d\n", direction, data[0], sys_id, comp_id, seq, msg_id);
uint16_t val;
//RC_CHANNELS ( #65 ) hook
if(msg_id == 65 && ch_count > 0) {
uint8_t offset = 18; //15 = 1ch;
for(uint8_t i=0; i < ch_count; i++) {
val = data[offset] | (data[offset+1] << 8);
if(ch[i] != val) {
ch[i] = val;
char buff[44];
sprintf(buff, "/root/channels.sh %d %d &", i+5, val);
system(buff);
if (verbose) printf("called /root/channels.sh %d %d\n", i+5, val);
}
offset = offset + 2;
} //for
} //msg_id
}
/* https://discuss.ardupilot.org/uploads/short-url/vS0JJd3BQfN9uF4DkY7bAeb6Svd.pdf
* 0. Message header, always 0xFE
* 1. Message length
* 2. Sequence number -- rolls around from 255 to 0 (0x4e, previous was 0x4d)
* 3. System ID - what system is sending this message
* 4. Component ID- what component of the system is sending the message
* 5. Message ID (e.g. 0 = heartbeat and many more! Dont be shy, you can add too..)
*/
static bool get_mavlink_packet(unsigned char *in_buffer, int buf_len,
int *packet_len)
{
if (buf_len < 6 /* header */) {
return false;
}
assert(in_buffer[0] == 0xFE || in_buffer[0] == 0xFD); //mavlink 1 or 2
uint8_t msg_len = in_buffer[1];
if (in_buffer[0] == 0xFE)
*packet_len = 6 /* header */ + msg_len + 2 /* crc */; //mavlink 1
else
*packet_len = 10 /* header */ + msg_len + 2 /* crc */; //mavlink 2
if (buf_len < *packet_len)
return false;
dump_mavlink_packet(in_buffer, ">>");
return true;
}
// Returns num bytes before first occurrence of 0xFE or full data length
static size_t until_first_fe(unsigned char *data, size_t len)
{
for (size_t i = 1; i < len; i++) {
if (data[i] == 0xFE || data[i] == 0xFD) {
return i;
}
}
return len;
}
static void serial_read_cb(struct bufferevent *bev, void *arg)
{
struct evbuffer *input = bufferevent_get_input(bev);
int packet_len, in_len;
struct event_base *base = arg;
while ((in_len = evbuffer_get_length(input))) {
unsigned char *data = evbuffer_pullup(input, in_len);
if (data == NULL) {
return;
}
// find first 0xFE and skip everything before it
if (*data != 0xFE && *data != 0xFD) {
int bad_len = until_first_fe(data, in_len);
if (verbose) printf(">> Skipping %d bytes of unknown data\n",
bad_len);
evbuffer_drain(input, bad_len);
continue;
}
if (!get_mavlink_packet(data, in_len, &packet_len))
return;
// TODO: check CRC correctness and skip bad packets
if (sendto(out_sock, data, packet_len, 0,
(struct sockaddr *)&sin_out,
sizeof(sin_out)) == -1) {
perror("sendto()");
event_base_loopbreak(base);
}
evbuffer_drain(input, packet_len);
}
}
static void serial_event_cb(struct bufferevent *bev, short events, void *arg)
{
(void)bev;
struct event_base *base = arg;
if (events & (BEV_EVENT_EOF | BEV_EVENT_ERROR | BEV_EVENT_TIMEOUT)) {
printf("Serial connection closed\n");
event_base_loopbreak(base);
}
}
static void in_read(evutil_socket_t sock, short event, void *arg)
{
(void)event;
unsigned char buf[MAX_MTU];
struct event_base *base = arg;
ssize_t nread;
nread = recvfrom(sock, &buf, sizeof(buf) - 1, 0, NULL, NULL);
if (nread == -1) {
perror("recvfrom()");
event_base_loopbreak(base);
}
assert(nread > 6);
dump_mavlink_packet(buf, "<<");
bufferevent_write(serial_bev, buf, nread);
}
static int handle_data(const char *port_name, int baudrate,
const char *out_addr, const char *in_addr)
{
struct event_base *base = NULL;
struct event *sig_int = NULL, *in_ev = NULL;
int ret = EXIT_SUCCESS;
int serial_fd = open(port_name, O_RDWR | O_NOCTTY);
if (serial_fd < 0) {
printf("Error while openning port %s: %s\n", port_name,
strerror(errno));
return EXIT_FAILURE;
};
evutil_make_socket_nonblocking(serial_fd);
struct termios options;
tcgetattr(serial_fd, &options);
cfsetspeed(&options, speed_by_value(baudrate));
options.c_cflag &= ~CSIZE; // Mask the character size bits
options.c_cflag |= CS8; // 8 bit data
options.c_cflag &= ~PARENB; // set parity to no
options.c_cflag &= ~PARODD; // set parity to no
options.c_cflag &= ~CSTOPB; // set one stop bit
options.c_cflag |= (CLOCAL | CREAD);
options.c_oflag &= ~OPOST;
options.c_lflag &= 0;
options.c_iflag &= 0; // disable software flow controll
options.c_oflag &= 0;
cfmakeraw(&options);
tcsetattr(serial_fd, TCSANOW, &options);
out_sock = socket(AF_INET, SOCK_DGRAM, 0);
int in_sock = socket(AF_INET, SOCK_DGRAM, 0);
struct sockaddr_in sin_in = {
.sin_family = AF_INET,
};
if (!parse_host_port(in_addr, (struct in_addr *)&sin_in.sin_addr.s_addr,
&sin_in.sin_port))
goto err;
if (!parse_host_port(out_addr,
(struct in_addr *)&sin_out.sin_addr.s_addr,
&sin_out.sin_port))
goto err;
if (bind(in_sock, (struct sockaddr *)&sin_in, sizeof(sin_in))) {
perror("bind()");
exit(EXIT_FAILURE);
}
printf("Listening on %s...\n", in_addr);
base = event_base_new();
sig_int = evsignal_new(base, SIGINT, signal_cb, base);
event_add(sig_int, NULL);
// it's recommended by libevent authors to ignore SIGPIPE
signal(SIGPIPE, SIG_IGN);
serial_bev = bufferevent_socket_new(base, serial_fd, 0);
bufferevent_setcb(serial_bev, serial_read_cb, NULL, serial_event_cb,
base);
bufferevent_enable(serial_bev, EV_READ);
in_ev = event_new(base, in_sock, EV_READ | EV_PERSIST, in_read, NULL);
event_add(in_ev, NULL);
event_base_dispatch(base);
err:
if (serial_fd >= 0)
close(serial_fd);
if (serial_bev)
bufferevent_free(serial_bev);
if (in_ev) {
event_del(in_ev);
event_free(in_ev);
}
if (sig_int)
event_free(sig_int);
if (base)
event_base_free(base);
libevent_global_shutdown();
return ret;
}
int main(int argc, char **argv)
{
const struct option long_options[] = {
{ "master", required_argument, NULL, 'm' },
{ "baudrate", required_argument, NULL, 'b' },
{ "out", required_argument, NULL, 'o' },
{ "in", required_argument, NULL, 'i' },
{ "channels", required_argument, NULL, 'c' },
{ "verbose", no_argument, NULL, 'v' },
{ "help", no_argument, NULL, 'h' },
{ NULL, 0, NULL, 0 }
};
const char *port_name = default_master;
int baudrate = default_baudrate;
const char *out_addr = defualt_out_addr;
const char *in_addr = default_in_addr;
int opt;
int long_index = 0;
while ((opt = getopt_long_only(argc, argv, "", long_options,
&long_index)) != -1) {
switch (opt) {
case 'm':
port_name = optarg;
break;
case 'b':
baudrate = atoi(optarg);
break;
case 'o':
out_addr = optarg;
break;
case 'i':
in_addr = optarg;
break;
case 'c':
ch_count = atoi(optarg);
if(ch_count == 0) printf("rc_channels_override monitoring disabled\n");
else printf("rc_channels_override monitoring %d channels after first 4\n", ch_count);
break;
case 'v':
verbose = true;
break;
case 'h':
default:
print_usage();
return EXIT_SUCCESS;
}
}
return handle_data(port_name, baudrate, out_addr, in_addr);
}

View File

@ -0,0 +1,13 @@
### Зачем нужен mavfwd
`mavfwd` в первую очередь необходим для связи телеметрийного потока wifibroadcast,
разделенного на входящий и исходящий на разных udp-портах, с uart камеры, который
подключен к uart полетного контроллера UAV, настроенного на обмен телеметрией.
Поддерживается mavlink 1 и 2 версий. Подробности о параметрах доступны по `mavfwd --help`.
Во вторую очередь, mavfwd способен мониторить передаваемые в mavlink-пакете [RC_CHANNELS #65](https://mavlink.io/en/messages/common.html#RC_CHANNELS)
значения каналов с 4-го и выше, указанное в параметре --channels числом. По изменению значений каналов вызывается bash-скрипт /root/channels.sh,
передавая ему параметрами номер канала и его значение. Это нужно, чтобы организовать какое-то управление хост-системой (камерой), например ее перезагрузку
или настройку каких-то параметров стримера. В приложенном примере производятся:
* переключение разрешений 1080p / 720p;
* включение и отключение ircut камеры;
* пороговое изменение яркости, три режима, для подбора нужного под текущие условия освещённости (яркий день, обычный день, ночь).

View File

@ -0,0 +1,13 @@
### Why you need mavfwd
`mavfwd` is primarily necessary for the connection of the telemetry stream wifibroadcast,
divided into incoming and outgoing on different udp ports, from a uart camera, which
connected to the uart flight controller UAV, configured to exchange telemetry.
maxlink 1 and 2 versions are supported. Details of the parameters are available for `mavfwd --help`.
In the second place, mavfwd is able to monitor transmitted in the mavlink-pack [RC_CHANNELS #65](htts://mavlink.io/en/messages/common.html#RC_CHANNELS)
the channel value with 4 and above, specified in the --channels number parameter. By changing the values of the channels, the bash-script /root/channels.sh is called,
passing the channel number and its value. This is necessary to organize some kind of control of the host system (camera), for example, its reboot
or setting up some streamer parameters. The attached example makes:
* 180p / 720p resolution switching;
* Turning on and off the ircut camera;
* threshold change of brightness, three modes, for selecting the necessary under current conditions of illumination (strong day, ordinary day, night).

View File

@ -0,0 +1,28 @@
## Подключение планшета к регистратору по wifi через AP планшета
Схема проста: в регистратор вставляется [TL-725n](https://www.tp-link.com/ru/home-networking/adapter/tl-wn725n/) или аналогичный адаптер на rtp8188eu, либо адаптер под
который есть драйвер в прошивке OpenIPC; планшет включает точку доступа; регистратор коннектится к этой точке доступа; при перезапуске сервис wfb обнаруживает указанный wlan и
настраивает трансляцию и телеметрию на планшет.
### Поднимем сеть
* Закачаем драйвер [8188eu](hi3536dv100/lib/modules/4.9.37/extra/8188eu.ko) в `/lib/modules/4.9.37/extra/`
* Настроим поднятие сети на адаптере в [`/etc/network/interfaces`](hi3536dv100/etc/network/interfaces), указывая свои ssid и password:
```
auto wlan1
iface wlan1 inet dhcp
pre-up if ! lsmod | grep 8188eu; then insmod /lib/modules/4.9.37/extra/8188eu.ko; fi
pre-up sleep 1
pre-up wpa_passphrase "ssid" "password" >/tmp/wpa_supplicant.conf
pre-up sed -i '2i \\tscan_ssid=1' /tmp/wpa_supplicant.conf
pre-up sleep 3
pre-up wpa_supplicant -B -D nl80211 -i wlan1 -c/tmp/wpa_supplicant.conf
post-down killall wpa_supplicant
```
### Поправим конфиги сервисы
* Закачаем обновленные [`/usr/bin/wifibroadcast`](hi3536dv100/usr/bin/wifibroadcast) и [`/usr/bin/telemetry`](hi3536dv100/usr/bin/telemetry) с детектированием подключения в /usr/bin.
* Добавим в [wfb.conf](hi3536dv100/etc/wfb.conf) новую строчку с параметром - наименованием интерфейса для ap
```
tab_wlan=wlan1
```
* Если мы не пользуемся отправкой потока на PC, можно закомментировать параметр `udp_addr`, это немного разгрузит регистратор.
* Включаем на планшете точку доступа и перезагружаем регистратор, либо нажимаем кнопку на [front panel](nvr_gpio.md).

View File

@ -0,0 +1,42 @@
## Несколько камер на одном линке
У камер есть сетевой интерфейс, который в случае двух камер можно использовать даже без свича, просто соединив четыре провода интерфейса друг с другом. Этот интерфейс и будем использовать для связи между камерами.
Если /etc/network/interfaces доработать примерно таким образом:
```
auto eth0
iface eth0 inet dhcp
hwaddress ether $(fw_printenv -n ethaddr || echo 00:24:B8:FF:FF:FF)
auto eth0:1
iface eth0:1 inet static
address $(fw_printenv -n ipaddr || echo 192.168.1.9)
netmask 255.255.255.0
```
то у камер появится саб-интерфейс с адресом, прописанным в переменной env `ipaddr` либо, если она пуста, указанным в address. Нам нужно, чтобы у камер были адреса из одной подсети, например пусть это будут 192.168.1.9 и 192.168.1.10 у "первой" и "второй" камер.
Первая - та, на которой расположен линк wfb и wifi-свисток. От второй нужен только поток на дополнительный порт, пусть 5601 на адрес первой камеры.
В случае, если на второй камере стоит openipc, нужно на ней отключить wfb через `daemon=0` в `datalink.conf` и настроить udp поток в majestic.yaml на 192.168.1.9:5601.
Теперь создадим на первой камере демонстрационный скрипт переключения камер `camswitch.sh`:
```
function wfb_restart {
kill -9 $(pidof wfb_tx)
. /etc/wfb.conf
wfb_tx -p ${stream} -u ${udp_port} -K /etc/drone.key -B ${bandwidth} -M ${mcs_index} -S ${stbc} -L ${ldpc} -G ${guard_interval} -k ${fec_k} -n ${fec_n} -T ${fec_timeout} -i ${link_id} ${wlan} &
}
function cam_1 {
# this is main cam, with wfb_tx
sed -i 's/udp_port=5601/udp_port=5600/' /etc/wfb.conf
wfb_restart
}
function cam_2 {
# set '- udp: cam1ip:5601' in /etc/majestic.yaml on cam2
sed -i 's/udp_port=5600/udp_port=5601/' /etc/wfb.conf
wfb_restart
}
cam_$1
```
Дадим ему права на выполнение через `chmod +x camswitch.sh` и теперь мы можем переключаться между камерами, вызывая `camswitch.sh 1` или `camswitch.sh 2`.
Скрипт останавливает wfb_tx, заменяет в его конфиге udp_port (основная камера шлет на 5600 а вторая на 5601) и запускает заново, таким образом переключаясь между потоками.
Можно подключить вызов скрипта например к [channels.sh](notes_cam_control.md) и управлять переключением с какого то канала RC.

View File

@ -0,0 +1,9 @@
## Отключение watchdog на регистраторе
Загрузчик на регистраторе запускает собаку, которая раз в полчаса перезагружает его. Для отключения копируем [`wdt.ko`](hi3536dv100/lib/wdt.ko) в `/lib` и добавляем в [`/etc/init.d/S95hisilicon`](hi3536dv100/etc/init.d/S95hisilicon) к загрузкам модулей, тут же выгружая:
```
insmod /lib/wdt.ko
rmmod /lib/wdt.ko
```
Перезагружаемся, watchdog больше не должен срабатывать.

View File

@ -0,0 +1,5 @@
## Заметка об отличной от 115200 скорости uart для телеметрии
TipoMan столкнулся с проблемой: камера зависала при подаче на uart телеметрии на скорости, отличной от 115200. Решение: установка нужной скорости в `/etc/inittab`.
![inittab](notes_files/baud38400.jpg)

View File

@ -0,0 +1,11 @@
### Управление камерой с земли
В качестве эксперимента [`mavfwd`](mavfwd) был дополнен парсером mavlink-пакета RC_CHANNELS (значения RC каналов, отправленные с любого RC-линка, например с наземной станции [(джойстика)](https://github.com/whoim2/arduremote) через [Mission Planner joystick](https://ardupilot.org/copter/docs/common-joystick.html)) или с [подключенного](rcjoystick.md) к регистратору джойстика.
Он мониторит изменения в указанном в аргументе `--channels X` или `-c X`каналах, считая после первых 4х, и при их наличии вызывает скрипт [`/root/channels.sh`](gk7205v200/root), передавая в него два параметра (номер канала и значение), и который производит необходимые операции. Например, `-c 1` будет мониторить только 5й канал, а `-c 4` будет мониторить 5,6,7,8 каналы. В текущем [примере](gk7205v200/root/channels.sh) это изменение режима работы камеры (1080p@30fsp / 720p@5-fps) на 5-м канале, смена luminance на 7м (трехпозиционный переключатель) и переключатель ircut (поляризационного фильтра). По умолчанию `-c 0`, т.е. отключен.
Для установки его на камеру замените в `/usr/sbin/` штатный mavfwd на [измененный](mavfwd/mavfwd), и добавьте параметр `-c` в [`/usr/bin/telemetry`](gk7205v200/usr/bin/telemetry#L39). Заодно получите возможность установить скорость телеметрии для связи с полетником выше чем 115200, конечно на свой страх и риск!
Приветствуются идеи и пожелания по этому поводу, которые можно высказать [здесь](https://t.me/+BMyMoolVOpkzNWUy).
upd 31.03.2023 Добавил распознавание mavlink 2 протокола.

Binary file not shown.

After

Width:  |  Height:  |  Size: 153 KiB

View File

@ -0,0 +1,27 @@
text,type,typeId,Description
,Rectangle,creately.basic.rectangle,
GROUND (NVR),Text,creately.basic.text,
WIFI,WiFi,creately.material-icons.wifi_twotone_2,
rtl8812au,Rectangle,creately.basic.rectangle,
wifi adapter driver in monitor mode,Rectangle,creately.basic.rectangle,
wfb-rx,Rectangle,creately.basic.rectangle,
LAN / WLAN or usb network,Ellipse,creately.basic.ellipse,
,Rectangle,creately.basic.rectangle,
PC or Pocket,Text,creately.basic.text,
GS telemetry program,Computer,creately.material-icons.computer_twotone_2,
udp:14551,Text,creately.basic.text,
udp:14550,Text,creately.basic.text,
,Rectangle,creately.basic.rectangle,
CAM,Text,creately.basic.text,
mavfwd,Rectangle,creately.basic.rectangle,
wfb-tx,Rectangle,creately.basic.rectangle,
wfb-rx,Rectangle,creately.basic.rectangle,
udp:14550,Text,creately.basic.text,
udp:14551,Text,creately.basic.text,
FC > cam uart,Rectangle,creately.basic.rectangle,
wifi adapter driver in monitor mode,Rectangle,creately.basic.rectangle,
rtl8812au,Rectangle,creately.basic.rectangle,
WIFI,WiFi,creately.material-icons.wifi_twotone_2,
wfb-rx,Rectangle,creately.basic.rectangle,
mavlink-routerd,Rectangle,creately.basic.rectangle,
udp:14550,Text,creately.basic.text,
1 text type typeId Description
2 Rectangle creately.basic.rectangle
3 GROUND (NVR) Text creately.basic.text
4 WIFI WiFi creately.material-icons.wifi_twotone_2
5 rtl8812au Rectangle creately.basic.rectangle
6 wifi adapter driver in monitor mode Rectangle creately.basic.rectangle
7 wfb-rx Rectangle creately.basic.rectangle
8 LAN / WLAN or usb network Ellipse creately.basic.ellipse
9 Rectangle creately.basic.rectangle
10 PC or Pocket Text creately.basic.text
11 GS telemetry program Computer creately.material-icons.computer_twotone_2
12 udp:14551 Text creately.basic.text
13 udp:14550 Text creately.basic.text
14 Rectangle creately.basic.rectangle
15 CAM Text creately.basic.text
16 mavfwd Rectangle creately.basic.rectangle
17 wfb-tx Rectangle creately.basic.rectangle
18 wfb-rx Rectangle creately.basic.rectangle
19 udp:14550 Text creately.basic.text
20 udp:14551 Text creately.basic.text
21 FC > cam uart Rectangle creately.basic.rectangle
22 wifi adapter driver in monitor mode Rectangle creately.basic.rectangle
23 rtl8812au Rectangle creately.basic.rectangle
24 WIFI WiFi creately.material-icons.wifi_twotone_2
25 wfb-rx Rectangle creately.basic.rectangle
26 mavlink-routerd Rectangle creately.basic.rectangle
27 udp:14550 Text creately.basic.text

View File

@ -0,0 +1,29 @@
text,type,typeId,Description
,Rectangle,creately.basic.rectangle,
sensor,Rectangle,creately.basic.rectangle,
CAM,Text,creately.basic.text,
majestic or vencoder,Rectangle,creately.basic.rectangle,
wfb-tx,Rectangle,creately.basic.rectangle,
wifi adapter driver in monitor mode,Rectangle,creately.basic.rectangle,
isp,Text,creately.basic.text,
rtp:5600,Text,creately.basic.text,
rtl8812au,Rectangle,creately.basic.rectangle,
WIFI,WiFi,creately.material-icons.wifi_twotone_2,
,Rectangle,creately.basic.rectangle,
GROUND (NVR),Text,creately.basic.text,
WIFI,WiFi,creately.material-icons.wifi_twotone_2,
rtl8812au,Rectangle,creately.basic.rectangle,
wifi adapter driver in monitor mode,Rectangle,creately.basic.rectangle,
wfb-rx,Rectangle,creately.basic.rectangle,
LAN / WLAN or usb network,Ellipse,creately.basic.ellipse,
,Rectangle,creately.basic.rectangle,
PC or Pocket,Text,creately.basic.text,
videoplayer or GS program,Computer,creately.material-icons.computer_twotone_2,
,To Right Arrow,creately.arrows.torightarrow,
,To Right Arrow,creately.arrows.torightarrow,
rtp:5600,Text,creately.basic.text,
rtp:5600,Text,creately.basic.text,
wfb-rx,Rectangle,creately.basic.rectangle,
vdecoder,Rectangle,creately.basic.rectangle,
HDMI,Rectangle,creately.basic.rectangle,
udp:5000,Text,creately.basic.text,
1 text type typeId Description
2 Rectangle creately.basic.rectangle
3 sensor Rectangle creately.basic.rectangle
4 CAM Text creately.basic.text
5 majestic or vencoder Rectangle creately.basic.rectangle
6 wfb-tx Rectangle creately.basic.rectangle
7 wifi adapter driver in monitor mode Rectangle creately.basic.rectangle
8 isp Text creately.basic.text
9 rtp:5600 Text creately.basic.text
10 rtl8812au Rectangle creately.basic.rectangle
11 WIFI WiFi creately.material-icons.wifi_twotone_2
12 Rectangle creately.basic.rectangle
13 GROUND (NVR) Text creately.basic.text
14 WIFI WiFi creately.material-icons.wifi_twotone_2
15 rtl8812au Rectangle creately.basic.rectangle
16 wifi adapter driver in monitor mode Rectangle creately.basic.rectangle
17 wfb-rx Rectangle creately.basic.rectangle
18 LAN / WLAN or usb network Ellipse creately.basic.ellipse
19 Rectangle creately.basic.rectangle
20 PC or Pocket Text creately.basic.text
21 videoplayer or GS program Computer creately.material-icons.computer_twotone_2
22 To Right Arrow creately.arrows.torightarrow
23 To Right Arrow creately.arrows.torightarrow
24 rtp:5600 Text creately.basic.text
25 rtp:5600 Text creately.basic.text
26 wfb-rx Rectangle creately.basic.rectangle
27 vdecoder Rectangle creately.basic.rectangle
28 HDMI Rectangle creately.basic.rectangle
29 udp:5000 Text creately.basic.text

Binary file not shown.

After

Width:  |  Height:  |  Size: 755 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 1.7 MiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 38 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 51 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 333 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 451 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 323 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 490 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 1.5 MiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 122 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 39 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 48 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 135 KiB

Binary file not shown.

After

Width:  |  Height:  |  Size: 47 KiB

View File

@ -0,0 +1,11 @@
## Заметки о использовании камеры gk7205v300 с сенсором imx335
В главном работа с камерой ничем не отличается от прочих камер gk. Точно так же прошивается lite или fpv, либо lite обновляется до fpv.
Наличие и расположение пинов для USB и UART нужно смотреть на странице продавца. Для примера, камера купленная по [ссылке ](https://aliexpress.ru/item/1005005492432144.html) имеет USB
на разъеме для шлейфа FPC и названы в описании WIFI_DP и WIFI_DN (USB DP/DN).
Нюансы касаются настройки разрешения. Режим 1080p (установка size: 1920x1080 в majestic.yaml) выдает 15 кадров / секунду, что конечно неприемлимо. Необходимо в файле `/etc/sensors/imx335_i2c_4M.ini`
закомментировать (через `;`) строчку `clock=27MHz` и установить `Isp_FrameRate=30`, после чего перезагрузить камеру. Исправленные файлы лежат в каталоге [imx335_gk7205v300](/imx335_gk7205v300).
Также работает режим `size: 2592x1520` и выдает 20fps, но угол обзора картинки не меняется, что наводит на мысли об интерполяции. Но неизвестно, из какого разрешения - в какое. По факту задержка в 1520p@20 ниже и составляет около 165мс, в 1080p@30 - 185мс.
Также необходим [gkrcparams](gkrcparams.md) для более плавной картинки.

View File

@ -0,0 +1,109 @@
### Заметки по постройке видеолинка с двухсторонней телеметрией mavlink
Воздушная часть линка представляет из себя камеру [gk7205v200](https://sl.aliexpress.ru/p?key=e1sTwWg) с подключенным по USB wifi-адаптером на чипе rtl8812au, например ASUS USB AC-56 или [недорогого более слабого адаптера с ali](https://sl.aliexpress.ru/p?key=8CsTwDB).
Наземная часть - это [видеорегистратор](https://sl.aliexpress.ru/p?key=L1sTwWG) на базе чипа hisilicon hi3536dv100 либо ev100, к которому точно так же подключен по USB адаптер rtl8812au или rtl8814au. Для РФ дешевле и быстрее заказать камеру и регистратор у [@ser177](https://t.me/ser177).
Данная статья описывает нюансы создания подобного линка, и является дополнением к [этой статье](https://github.com/OpenIPC/wiki/blob/master/ru/fpv.md).
![link_hw](https://github.com/OpenIPC/sandbox-fpv/raw/master/notes_files/link_hw.png)
### Возможности
Данный линк способен передавать видео
[(youtube)](https://youtu.be/ldfQ9CLE86I) с воздушной части форматом (разрешение@частота кадров) 1920x1080@30 или 1280x720@50 кодеками h264 либо h265 и телеметрию mavlink в обе стороны. Общая схема процессов для передачи видео выглядит так:
![video](https://github.com/OpenIPC/sandbox-fpv/raw/master/notes_files/video.png)
Передача видео на текущий момент возможна двумя способами. Классический - streamer `majestic` через udp порт 5600 засылает RTP/h264 или RTP/h265 поток в [wfb-ng](https://github.com/svpcom/wfb-ng) или [OpenHD-wfb](https://github.com/OpenHD/wifibroadcast) для передачи на землю, где принимается ответной частью wfb и отправляется для воспроизведения на PC или планшет / смартфон по LAN или USB ethernet (tethering). Формат RTP свободно воспроизводится программами для GS, такими как [QGroundControl](https://github.com/mavlink/qgroundcontrol), [Mission Planner](https://ardupilot.org/planner/), [QOpenHD](https://openhdfpv.org/download/) или [FPV-VR](https://github.com/Consti10/FPV_VR_OS). Но его пока невозможно вывести в порт HDMI регистратора, поскольку он построен на специализированном чипе со своим SDK и обычными способами, например через GStreamer как обычно выводят видео в случае Raspberry Pi, этого не сделать.
<sub>QGroundControl имеет баг при воспроизведении h265, проявляющийся в зависании картинки при входе в меню. Это лечится до перезапуска программы выбором потока видео h264 и назад h265.</sub>
Andrey Bezborodov из команды OpenIPC предоставил на тесты скомпилированные примеры *vencoder* и *vdecoder*, вытащенные из Hisilicon SDK и в оригинальном виде расположенные [тут](https://github.com/OpenIPC/silicon_research). `venc` запускается на камере и формирует поток h264 с фрагментацией HAL вместо `majestic`, `vdec` на регистраторе выводит этот поток в HDMI. Все работает, но естественно нет OSD и подобный нестандартный поток невозможно воспроизвести сторонними плеерами. Это очень перспективный путь, поскольку имеет возможности к снижению задержки передачи видео. На текущий момент она составляет от 110 до 130 мсек. На "классической схеме" задержки составляют обычно от 150 до 230 мсек, [вот пример 133 мсек](https://github.com/OpenIPC/sandbox-fpv/raw/master/notes_files/Screenshot_1.png), в зависимости от разрешения и наземных условий воспроизведения.
Этот вопрос можно решить, "научив" `vdec` распознавать RTP/h26[4-5] с помощью библиотеки *libavformat/avformat.h* и по прежнему "стримить" на камере через `majestic`. Для этого нужна помощь программиста C++, если вы желаете помочь проекту с этим - [обращайтесь](https://t.me/+BMyMoolVOpkzNWUy).
Пример настройки *GStreamer* на Mission Planner для воспроизведения h265: `udpsrc port=5600 buffer-size=32768 ! application/x-rtp ! rtph265depay ! avdec_h265 ! videoconvert ! video/x-raw,format=BGRA ! appsink name=outsink`
Поддерживаются частоты от 5,2ghz до 5,85ghz, на atheros 2.3 - 2.4ghz.
### Как все запускается?
При загрузке linux стартует в числе сервисов из `init.d` сервис `S98datalink`, который и является отправной точкой. Он запускает скрипт `/usr/bin/wifibroadcast`, который определяет через lsusb какой адаптер подключен, загружает его драйвер, переключает в режим монитора, стартует `wfb` на передачу или прием, для наземки определяя подключения по usb, второму адаптеру wifi или просто начиная передачу видео на `udp_addr`. Данные о настройках он берет из `/etc/wfb.conf`. Также, при включенной телеметрии, он запускает скрипт `/usr/bin/telemetry`, который занимается тем же но для телеметрийных целей, беря настройки из `/etc/telemetry.conf`.
### Нюансы на камере
Для данной камеры существует два драйвера сенсора - "медленный" 1080p@30fps и "быстрый" 720p@50fps. Их можно переключать на ходу скриптами из примеров в [root](https://github.com/OpenIPC/sandbox-fpv/tree/master/gk7205v200/root), если залить на камеру ["быстрый" драйвер](gk7205v200/lib/sensors/libsns_imx307_2l_720p.so) под отдельным именем и исправить к нему путь в его конфиге [`imx307_i2c_2l_720p_50fps.ini`](gk7205v200/etc/sensors/imx307_i2c_2l_720p_50fps.ini#L15). Все файлы по данной камере находятся в каталоге `gk7205v200`. Если запускать камеру с "быстрым" драйвером в настройках majestic, то передача видео идет рывками, поэтому при старте камеры через `S95goke` прописываются настройки "медленного" драйвера, после чего уже можно включить "быстрый". На текущий момент [ведется работа](notes_cam_control.md) по управлению подобными настройками камеры через RC каналы в mavlink.
### Нюансы на регистраторе
Так как регистратор относительно камеры имеет шикарные 16мб памяти spi flash, из которых мы можем использовать около 5мб, то нам доступен [драйвер адаптеров RTL](https://github.com/OpenIPC/sandbox-fpv/tree/master/hi3536dv100/88XXau-ko) который поддерживает rtl8814au в дополнение к популярному rtl8812au. Для этого нужно залить его поверх штатного в `lib/modules/4.9.37/extra`, не забыв переименовать.
Перекомпилирован [`mavlink-router`](https://github.com/OpenIPC/sandbox-fpv/tree/master/hi3536dv100/usr/bin), так как комплектный из прошивки собран на musl для воздушной части (где он не используется), а прошивка регистратора на glibc.
Также необходимо [отключить hisilicon watchdog](note_nvr_wdt.md).
### Нюансы телеметрии
Текущая схема работы телеметрии выглядит так:
![telemetry](https://github.com/OpenIPC/sandbox-fpv/raw/master/notes_files/telemetry.png)
~~С применением mavlink-routerd на текущий момент возможна только односторонняя телеметрия по udp, поскольку он не умеет использовать разные rx/tx udp порты в рамках одного endpoint, как того требует wfb, будучи запущенным разными процессами `telemetry_rx` и `telemetry_tx`.~~
Будучи запущенным разными процессами, `telemetry_rx` и `telemetry_tx` используют разные порты для приема и передачи данных (кстати, это просто символьные ссылки на wfb_rx и wfb_tx, создаваемые скриптом [запуска телеметрии](hi3536dv100/usr/bin/telemetry)), и mavlink-router требует в [конфигурации](hi3536dv100/etc/mavlink.conf) два UDP-endpoint, которые должны быть сгуппированны:
```
[UdpEndpoint telemetry_tx]
Group=wfb
Mode = Normal
Address = 127.0.0.1
Port = 14550
[UdpEndpoint telemetry_rx]
Group=wfb
Mode = Server
Address = 127.0.0.1
Port = 14551
```
Остальные endpoint нужны для связи с наземной станцией, например tcp:5760 для приема подключений от Mission Planner. Для [приложенного конфига](hi3536dv100/etc/mavlink.conf) в настройках UDP-линка нужно указать адрес регистратора:
![udp-qgc](notes_files/qgc-udp-settings.png)
Остается переключить в /usr/bin/telemetry на использование mavlink-routerd и подключать uart регистратора более не нужно.
```
/usr/bin/mavlink-routerd -c /etc/mavlink.conf &
#/usr/sbin/mavfwd --master ${serial} --baudrate ${baud} --out 127.0.0.1:${port_tx} --in 127.0.0.1:${port_rx} &
```
Если же вы хотите использовать uart, то можете настроить endpoint на /dev/ttyAMA0 или переключиться на mavfwd.
В таком случае необходимо отключить ssh консоль от uart в /etc/inittab, закомментировав строчку:
```
#console::respawn:/sbin/getty -L console 0 vt100 # GENERIC_SERIAL
```
Тогда телеметрия станет доступна на uart регистратора взамен или дополнительно к udp по сети, и ее можно будет использовать через usb-uart адаптер как serial port. На QGC для подключения к serial нужно отключить flow control в advanced, иначе загружает примерно половину параметров и выдает ошибку.
Я скомпилировал `mavfwd` для регистратора, поддерживающий скорости b230400, b500000, b921600 и b1500000, для поддержки более высокой скорости при работе с Mission Planner, проверил на b500000 при b115200 / b230400 на камере. Для регистратора его можно забрать [здесь](hi3536dv100/usr/sbin). Для камеры: [здесь](https://github.com/OpenIPC/sandbox-fpv/tree/master/gk7205v200/usr/sbin). [Исходник](https://github.com/OpenIPC/sandbox-fpv/tree/master/mavfwd). На камере удалось получить устойчивую связь с полетником на скорости 230400, выше stm32f4 не смог. Установка скорости полетника под ardupilot производится параметром `SERIALx_BAUD`, в моем случае: "230". Также не забывайте установить параметр `TELEM_DELAY` на 10 (секунд задержки перед началом выдачи телеметрии), иначе телеметрия может остановит загрузчик. К сожалению, если в полете камера перезапустится по какой то причине отдельно от полетника, то телеметрия ~~не даст ей загрузиться~~ может не дать ей загрузиться. ~~Необходимо доработать загрузчик u-boot, чтобы он не останавливал загрузку по любому символу.~~ ~~C [новым u-boot](gk7205v200_u-boot-7502v200-for-telemetry.md),~~ который прерывается только по Ctrl+C, и `bootdelay=0` этой проблемы по тестам нет. Этот U-boot уже включен во все FPV прошивки OpenIPC.
Также я [заложил в него](notes_cam_control.md) основы для наблюдения за выбранными каналами RC mavlink и передачи их значений при изменении в `/root/channels.sh` как параметров $1 (канал) и $2 (значение).
### Текущие проблемы
Если при загрузке камеры в majestic выбран "быстрый" драйвер 720p, то видео идёт рывками, поэтому в S95goke (автозапуск majestic) перед стартом идёт установка "обычного" драйвера 1080p. Если вы хотите использовать при загрузке камеры 720p@50 по умолчанию, вставьте после загрузки majestic вызов скрипта переключения в [`/etc/init.d/S95majestic`](gk7205v200/etc/init.d/S95majestic#L35) в функции `load_majestic`:
```
yaml-cli -s .isp.sensorConfig /etc/sensors/imx307_i2c_2l_1080p.ini
yaml-cli -s .video0.size 1920x1080
yaml-cli -s .video0.fps 30
start-stop-daemon -b -m -S -q -p "$PIDFILE" -x "/usr/bin/$DAEMON" \
-- $DAEMON_ARGS
status=$?
if [ "$status" -eq 0 ]; then
echo "OK"
else
echo "FAIL"
fi
sleep .5
/root/720.sh
return "$status"
```

View File

@ -0,0 +1,59 @@
### Заметки о прошивке NVR hi3536ev100 на OpenIPC для целей FPV
[EN](en_notes_start_hi3536ev100.md)
Данная статья неактуальна в части прошивки, используйте https://github.com/OpenIPC/wiki/blob/master/en/fpv-nvr.md, эта же статья может быть полезна отдельными моментами.
<details>
<summary>Как устроена память</summary>
Для начала, следует разобраться, как устроена память регистратора (да и камеры тоже) и что нужно прошивать. Данные хранятся на spi-flash 16mb в виде блоков mtd:
```
cat /proc/cmdline
mem=150M console=ttyAMA0,115200 panic=20 root=/dev/mtdblock3 rootfstype=squashfs init=/init mtdparts=hi_sfc:256k(boot),64k(env),2048k(kernel),8192k(rootfs),-(rootfs_data)
ls /dev/mtdb*
/dev/mtdblock0 /dev/mtdblock1 /dev/mtdblock2 /dev/mtdblock3 /dev/mtdblock4
```
Как следует из вывода, нулевой блок это загрузчик u-boot; далее идет блок для хранения переменных окружения (`printenv`, `setenv` команды пишут в ОЗУ, а `saveenv` сохраняет именно в этот блок); следом ядро uImage; потом rootfs.squashfs (неизменяемый образ файловой системы); и наконец rootfs_data или он же overlay - изменяемая часть, куда пишутся отличия от rootfs если вы изменяете какие-либо файлы. Таким образом, очистив overlay, мы "скинем" файловую систему до "дефолта":
```
sf probe 0 #выбираем устройство
sf erase 0xA50000 0x500000 #производим очистку
reset #перезагрузка
```
Еще проще сбросить до "заводских" прошивки командой `firstboot`.
Калькулятор адресов для команд доступен [здесь](https://openipc.org/tools/firmware-partitions-calculation). В нашем случае раздел rootfs: 8192kB, значит адрес начала overlay будет 0xA50000. Для камеры, у которой flash 8mB, размер rootfs 5120kB, адреса будут другие, включая переменные окружения!
</details>
Загрузчик у этого регистратора не имеет пароля, и в него можно попасть через uart/115200 бод, нажав при старте несколько раз Ctrl+C будучи подключенным к порту debug-uart регистратора через адаптер usb-uart 3v3 (ftdi, ch340). Debug uart расположен напротив разъема VGA на противоположном краю платы и подписан как gnd/tx/rx. Загрузчик нам прошивать не требуется, burn не нужен. ENV (переменные окружения) у нас отличаются от заводских, но их проще установить прямо из загрузчика построчно:
```
setenv ipaddr '192.168.0.222' #тут ip в вашей подсети из свободных
setenv serverip '192.168.0.107' #адрес ПК с tftp сервером
setenv netmask '255.255.255.0'
setenv bootcmd 'sf probe 0; sf read 0x82000000 0x50000 0x200000; bootm 0x82000000'
setenv uk 'mw.b 0x82000000 ff 1000000;tftp 0x82000000 uImage.${soc}; sf probe 0; sf erase 0x50000 0x200000; sf write 0x82000000 0x50000 ${filesize}'
setenv ur 'mw.b 0x82000000 ff 1000000;tftp 0x82000000 rootfs.squashfs.${soc}; sf probe 0; sf erase 0x250000 0x800000; sf write 0x82000000 0x250000 ${filesize}'
setenv bootargs 'mem=192M console=ttyAMA0,115200 panic=20 root=/dev/mtdblock3 rootfstype=squashfs init=/init mtdparts=hi_sfc:256k(boot),64k(env),2048k(kernel),8192k(rootfs),-(rootfs_data)'
setenv osmem '192M'
setenv totalmem '256M'
setenv soc 'hi3536dv100'
#тут очищаем ненужные далее переменные
setenv da; setenv du; setenv dr; setenv dw; setenv dl; setenv dc; setenv up; setenv tk; setenv dd; setenv de; setenv jpeg_addr; setenv jpeg_size; setenv vobuf; setenv loadlogo; setenv appVideoStandard; setenv appSystemLanguage; setenv appCloudExAbility
saveenv #сохраняем новое окружение переменных
printenv #смотрим, все ли в порядке
```
Оригинальные env и полный дамп микросхемы (бекап заводской прошивки 16mb на случай восстановления) доступны [здесь](https://github.com/OpenIPC/sandbox-fpv/tree/master/hi3536dv100/original_firmware).
Как вы могли заметить, в переменных uk и ur хранятся макросы для прошивки uImage и rootfs с загрузкой их с [tftp сервера](https://pjo2.github.io/tftpd64/), указанного в переменной serverip. Все адреса соответствуют переменной bootargs, содержимое которой и задает разметку файловой системы для ядра при загрузке. Разметка отличается от привычных для камер goke/hisilicone, ядро у нас как и у lite/fpv размером 2мб, однако файловая система размером 8мб, как у ultimate. Оставшиеся ~5мб используются оверлеем (вашими изменениями файлов относительно оригинальной rootfs). Для прошивки используйте официальные сборки со страницы релизов [openipc/firmware](https://github.com/OpenIPC/firmware/releases/download/latest/openipc.hi3536dv100-nor-fpv.tgz). Архив содержит ядро и файловую систему.
Итак, после установки переменных можно приступать к прошивке оставшейся части. Запустите tftpd сервер, положите в его корень uImage.hi3536dv100 и rootfs.squashfs.hi3536dv100, выберите соответствующий сетевой интерфейс и в загрузчике запустите макрос: `run uk`. Должен выполниться ряд команд, из вывода которых должно следовать, что файл uImage скачался и прошился во flash. Аналогично выполните `run ur` для прошивки rootfs. Если адреса установлены верно, но скачивание застревает на "Downloading", смените адрес регистратора на соседний свободный: `setenv ipaddr '192.168.0.223'`.
Если все прошло без ошибок, делайте `reset` и грузитесь в операционную систему, логин root, пароль 12345.
Конфиги из каталога hi3536dv100 неактуальны, однако могут представлять интерес касаемо подключения планшета по usb/wifi/ethernet hotspot, вы можете перенести их по аналогии в конфиги официальной прошивки или оформить отдельными bash-скриптами. Обычно суть этих изменений в определении адреса подключаемого планшета (который является для регистратора шлюзом в случаях, если планшет у нас dhcp-сервер) и указании этого адреса в дополнительном экземпляре wfb_rx для видеопотока и для телеметрийных потоков.
Обновление прошивки происходит через интернет командой `sysupgrade -r -k -n`.
<details>
<summary>Обновление без интернета из /tmp</summary>
В дальнейшем прошивку регистратора можно делать, залив в него через WinSCP ядро и rootfs в каталог `/tmp` и выполнив `sysupgrade --kernel=/tmp/uImage.hi3536dv100 --rootfs=/tmp/rootfs.squashfs.hi3536dv100 -z`. Параметр `-z` нужен если у вас нет подключения к интернету (не обновляет скрипт sysupgrade), `-n` очистит пользовательскую fs (overlay).
</details>

View File

@ -0,0 +1,117 @@
## Заметки по прошивке камеры IVG-G2S прошивкой OpenIPC.
ВНИМАНИЕ! Большая часть информации из этой статьи безнадежно устарела, все дополнительные помимо прошивки шаги уже неактуальны - они внесены в прошивку, и все работает из коробки, необходимо лишь произвести копирование ключа gs.key с камеры на наземную станцию и указать правильно каналы на обоих.
Цель этой заметки - помочь привлечь внимание к крайне перспективной теме запуска digital fpv на дешевых камерах без одноплатника на борту.
Разработчикам **ОЧЕНЬ** важны отзывы, при наличии популярности проект будет развиваться с их помощью значительно быстрее.
Переходите в специально созданный для этой темы [телеграмм-чат](https://t.me/+BMyMoolVOpkzNWUy), задавайте вопросы которые не описаны тут и по ссылкам ниже, публикуйте информацию о своих успехах и запрашивайте помощь в решении проблем.
Еще раз - фидбеки крайне важны, даже если у вас все получилось и работает - пожалуйста, не поленитесь описать свой сетап и опубликуйте в чате отзыв. Это позволит развиваться проекту с участием разработчиков.
* [Основная страница по OpenIPC + FPV теме, обязательна к прочтению](https://github.com/OpenIPC/wiki/blob/master/ru/fpv.md)
* [Основная wiki проекта](https://github.com/OpenIPC/wiki) (на текущий момент EN версия содержит больше информации)
* [Генератор инструкций на сайте](https://openipc.org/supported-hardware/featured)
### Термины
* Flash - в данном контексте SPI-flash, микросхема памяти.
* U-Boot - загрузчик. Есть "родной", есть от OpenIPC. Родной запаролен. Нам нужен скачанный из генератора инструкций.
* uImage - ядро Embedded Linux, в виде bin файла.
* Root-FS - файловая система выбранной версии (lite, ultimate, fpv), в виде squash-fs файла [https://ru.wikipedia.org/wiki/Squashfs]. uImage и rootfs нужно добывать через конструктор инструкций, раздельная прошивка u-boot и root-fs.
* Shell - командная строка linux камеры, доступна через uart и ssh (программа putty). Также есть shell загрузчика, только uart. Логин root, пароля нет.
* Majestic - утилита - стример потоков видео, из комплекта прошивки OpenIPC.
Платы оснащаются обычно spi-flash размером 8 или 16 мб. Версия ultimate требует 16, можно перепаять. Для fpv целей достаточно 8мб.
Если у вас нет кабеля ethernet для подключения камеры к вашему свичу/роутеру, его можно сделать из половинки обычного патч-корда и разъема jst xh1.25 8pin. Такие использовались в полетниках Omnibus F4 и много где еще.
Распиновки камеры и коннектора легко гуглятся, соединять необходимо 4 линии: rx+, rx-, tx+, tx- на кабеле и камере. На тот же разъем подается питание от 5 до 12в на пины 7(gnd) и 8(vcc).
Рекомендую сначала прошить lite, поскольку в ней разблокирован shell через uart (в файле /etc/inittab) и это позволит подключаться в нештатных ситуациях, например при отсутствии сети.
Существует три способа прошить камеру ivg-g2s на OpenIPC. В порядке усложнения: coupler, burn, программатор.
- Coupler [https://github.com/OpenIPC/coupler] - это загрузка ядра и rootfs одним файлом через родной веб-интерфейс камеры. Минусы - не меняется родной запароленный
загрузчик, можно выполнить только один раз, откат или смена прошивок только через прочие способы.
Алгоритм: выяснить в родном веб-интерфейсе версию, на ее основании скачать прошивку, загрузить как обновление в родном вебинтерфейсе. Для ivg-g2s/659A7 есть [прошивка с загрузчиком](gk7205v200/659A7_OpenIPC_FPV.bin).
- Burn [https://github.com/OpenIPC/burn] - загрузка незапароленного загрузчика u-boot от OpenIPC через uart камеры и uart-usb адаптер (например, ch340) и дальнейшая работа в загрузчике, согласно конструктору инструкций OpenIPC.
Минусов нет, меняется загрузчик которым в любой момент можно загрузить с tftpf сервера [https://pjo2.github.io/tftpd64/] нужный образ и прошить во flash.
Алгоритм описан видеоинструкциями на канале OpenIPC [https://www.youtube.com/@openipc/videos]. Далее, загрузив в RAM загрузчик (только [выбираем свой](gk7205v200_u-boot-7502v200-for-telemetry.md) ввиду нюансов), работаем через конструктор инструкций. uImage и root-fs распаковываем и кладем в каталог tftpd.
Я пробовал пробросить usb-uart в archlinux под virtualbox и ипользовать burn оттуда, но загрузка не проходила, связь с uart была в одну сторону, только на чтение. Из под windows 7 все прошло штатно.
Используйте короткие провода как от usb порта до адаптера, так и от адаптера до камеры. Распиновка uart на камере есть в первой статье из списка выше, соединять необходимо "накрест" - tx адаптера на rx камеры и rx адаптера на tx камеры.
Если все в порядке, но tftp не загружает файл - попробуйте сменить адрес камере на соседний свободный, `setenv ipaddr '192.168.0.223'`.
- Программатор - выпаивание флеш или одной ноги и подключение к программатору, прошивка всего через программатор.
Самый сложный способ, это единственный минус.
При первой загрузке необходимо выполнить команду firstboot.
Если камера циклично перезагружается - это срабатывает watchdog от majestic (стримера). Скорее всего нужно снять колпачок объектива и включить свет. Отключается в /etc/majestic.yaml, убить процесс быстро: `killall majestic`.
Управлять параметрами конфига с сохранением можно через утилиту cli шелла:
```
cli -s .image.contrast 50
cli -s .image.luminance 50
cli -s .video0.codec h264
cli -s .hls.enabled false
cli -s .isp.sensorConfig /etc/sensors/imx307_i2c_2l_1080p.ini
cli -s .video0.size 1920x1080
cli -s .video0.fps 30
```
Рекомендую выполнить эти команды, это настроит majestic для первоначальных попыток.
Перейти на версию FPV с обновлением. Внимание! В версии FPV отключен shell через uart (освобожден для работы телеметрии), после загрузки, остается только сетевой доступ. Сам загрузчик, конечно, работает через uart.
```
sed -i 's/BUILD_OPTION=lite/BUILD_OPTION=fpv/' /etc/os-release
sysupgrade --force_ver -k -r -n
```
Если вы не собираетесь использовать телеметрию сквозь этот видеолинк, можете включить его назад:
```
sed -i 's/#console::respawn:\/sbin\/getty/console::respawn:\/sbin\/getty/' /etc/inittab
reboot
```
Если flash заблокирована (вы как то прошили ядро предыдущих версий, которые не умеют разблокировать флеш), то эта и любые прочие команды выполнены не будут.
Пример вывода `dmesg | grep bsp-sfc` для определения блокировки флешки:
Разблокирована
```
bsp-sfc bsp_spi_nor.0: SR1:[02]->[00]
bsp-sfc bsp_spi_nor.0: SR2:[02]->[00]
bsp-sfc bsp_spi_nor.0: all blocks are unlocked.
bsp-sfc bsp_spi_nor.0: Winbond: SR1 [], SR2 [QE], SR3 [DRV0,DRV1]
```
Заблокирована
```
bsp-sfc bsp_spi_nor.0: SR1:[02]->[00]
bsp-sfc bsp_spi_nor.0: SR2:[02]->[00]
bsp-sfc bsp_spi_nor.0: all blocks are unlocked.
bsp-sfc bsp_spi_nor.0: Winbond: SR1 [TB], SR2 [QE], SR3 [WPS,DRV0,DRV1]
```
Попытка разблокировать флеш из shell (мне не помогла)
```
devmem 0x10010024 32 0x06;devmem 0x10010030 32 0;devmem 0x1001003C 32 0x81;devmem 0x14000000 16 0x0000;devmem 0x10010024 32 0x01;devmem 0x10010030 32 0;devmem 0x10010038 32 2;devmem 0x1001003C 32 0xA1
#
sysupgrade --force_ver -k -r -n
```
Путь к разблокировке flash лежит через загрузку свежего ядра, распакованного архиватором из tgz файла с ядром и rootfs, взятого из конструктора инструкций. Загрузившись, оно автоматически разблокирует flash. Делается из загрузчика, залитого в ram через burn.
```
# Устанавливаем адрес камеры и адрес сервера tftpd
setenv ipaddr 192.168.0.222; setenv serverip 192.168.0.107
# Устанавливаем аргументы окружения (env)
setenv bootargs 'mem=32M console=ttyAMA0,115200 panic=20 rootfstype=squashfs root=/dev/mtdblock3 init=/init mtdparts=sfc:256k(boot),64k(env),2048k(kernel),5120k(rootfs),-(rootfs_data)'
# Очищаем область оперативной памяти для скачивания ядра
mw.b 0x42000000 ff 1000000
# Загружаем ядро uImage.gk7205v200 с tftpd сервера
tftpboot 0x42000000 uImage.${soc}
# Запускаем ядро
bootm 0x42000000
```

View File

@ -0,0 +1,47 @@
## Настройка кнопок со своим функционалом на регистраторе
![front_panel](https://github.com/OpenIPC/sandbox-fpv/raw/master/notes_files/IMG_20230323_081622_212.jpg)
Регистратор имеет на борту разъем для подключения фронт-панели с кнопками, ir-ресивером:
![nvr-ports](notes_files/photo_2023-03-23_02-12-40.jpg)
Разъем cn5 подписан с обратной стороны. С назначением +3.3в и GND понятно, IR задействовать не удалось, остальные пины ведут на GPIO процессора:
```
Y2 ^17
Y1 ^6
X2 ^13
Y3 ^8
X1 ^7
ALARM 10
REC 11
```
Символ `^` означает подтяжку резистором к +3.3, значит кнопкой эти пины надо замыкать на GND и ловить значение 0. Это реализовано в файле [`root/gpio_monitor.sh`](hi3536dv100/root/gpio_monitor.sh).
По замыканию пина Y1 на землю он производит рестарт сервиса [wfb](hi3536dv100/etc/init.d/S98wfb), который следом рестартует [телеметрию](hi3536dv100/usr/bin/telemetry), для более удобного подключения смартфона или планшета [по USB](usb-tethering.md), или после смены wifi-адаптера. Скрипт мониторинга ведет лог нажатий, который можно наблюдать по `tail -f /tmp/gpio.log`.
Примеры использования GPIO на выход можно посмотреть в [`testgpio.sh`](hi3536dv100/root/testgpio.sh), и можно подключить пин ALARM или REC к малмощному светодиоду с резистором для индикации процессов, например перезапуска wfb-ng как сделано в `gpio_monitor.sh`.
Для запуска монитора как системного демона создадим файл [`/etc/init.d/S99gpio_monitor`](hi3536dv100/etc/init.d/S99gpio_monitor) откуда и будем запускать наш [`root/gpio_monitor.sh`](hi3536dv100/root/gpio_monitor.sh):
```
#!/bin/sh
#
# Start gpio monitor
#
case "$1" in
start)
echo "Starting gpio_monitor daemon..."
/root/gpio_monitor.sh &
;;
stop)
echo "Stopping gpio_monitor daemon..."
kill -9 $(pidof {exe} ash /root/gpio_monitor.sh)
;;
*)
echo "Usage: $0 {start|stop}"
exit 1
esac
```
Перезагружаемся без wifi адаптера и/или usb modem, активируем их уже после загрузки и убеждаемся, что по нажатию кнопки (хотя бы полсекунды подержите) сервисы запускаются.
Список запущенных процессов всегда можно посмотреть командой `ps axww`.

View File

@ -0,0 +1,46 @@
## Использование аппаратуры как джойстика для передачи каналов RC через mavlink
### Теория
Программы наземных станций, такие как Mission Planner или QGroundControl, способны распознавать подключенные джойстики либо аппаратуры в режиме usb-джойстика и
передавать на полетный контроллер значения осей в пакете RC_CHANNELS_OVERRIDE (#70). Однако, QGC передает только первые 4 канала (две оси), остальное можно назначить только на кнопки,
а MP может это делать только под Windows, что не всегда удобно. Я написал простейшее приложение для регистратора, которое распознает подключенный джойстик и отправляет пакеты [RC_CHANNELS_OVERRIDE](https://mavlink.io/en/messages/common.html#RC_CHANNELS_OVERRIDE) в версии протокола mavlink 2 для поддержки 18 каналов напрямую в порт telemetry_tx, который обычно опубликован на 127.0.0.1:14650 регистратора. Порт, адрес, время между отправками пакетов, число осей и устройство в системе можно переназначить, смотрите `rcjoystick -h`.
```
Usage:
[-v] verbose;
[-d device] default '/dev/input/js0';
[-a addr] ip address send to, default 127.0.0.1;
[-p port] udp port send to, default 14650;
[-t time] update RC_CHANNEL_OVERRIDE time in ms, default 50;
[-x axes_count] 2..9 axes, default 5, other channels mapping to js buttons from button 0;
[-r rssi_channel] store rx packets per second value to this channel, default 0 (disabled);
[-i interface] wlan interface for rx packets statistics, default wlan0;
```
Например, отправлять можно не в telemetry_tx, а в mavlink_routerd, если вам так нужно. Пакет для сборки в buildroot от OpenIPC [тут](rcjoystick).
### Запускаем
Нам необходимо ядро и rootfs с поддержкой usb-hid на регистраторе. Для этого [прошейте](notes_start_hi3536ev100) их из [`/hi3536dv100`](hi3536dv100) каталога.
~~Необходимо обеспечить запуск модуля `hid-generic.ko`, для этого добавьте `modprobe hid-generic.ko` в [`S95hisilicon`](hi3536dv100/etc/init.d/S95hisilicon).~~ В свежесобранном ядре модуль `hid-generic.ko` загружается автоматически.
Далее нужно скопировать бинарник [`rcjoystick`](hi3536dv100/usr/bin/rcjoystick) в /usr/bin регистратора, через WinSCP и назначить права на исполнение: `chmod +x /usr/bin/rcjoystick`.
Перезагружаемся, подключаем аппаратуру к регистратору по usb и пробуем в консоли запустить `rcjoystick -v`. Если все прошло хорошо, то на экране мы должны увидеть значения осей при изменении положения стиков и переключателей, а в программе телеметрии, например в QGC (analyse tools > Mavlink inspector > RC_CHANNELS_RAW) должны изменяться каналы. Для запуска на постоянную можно прописать его в отдельный сервис [`S99rcjoystick`](hi3536dv100/etc/init.d/S99rcjoystick), главное чтобы он запускался после wifibroadcast.
### RSSI
Также в rcjoystick была добавлена функция инжекции аналога rssi (числа полученных от воздушной части пакетов в секунду) для хоть какого то индикатора качества приема, так как отдельный сервис для этого заводить нет желания и смысла, учитывая невысокий уровень регистратора. В rcjoystick уже есть большая часть необходимого для инжекции.
Указываем `-r 16` и, если интерфейс wfb не wlan0, то и его `-i wlanX` и в указанный канал будет попадать число принятых наземкой пакетов в секунду. У меня оно в районе 800, вы можете увидеть свое применив ключ verbose (`-v`). Далее указываем на полетнике:
```
RSSI_TYPE 2
RSSI_CHANNEL 16
RSSI_CHAN_LOW 0
RSSI_CHAN_HIGH 800 //ваше обычное значение, примерно среднее, не максимальное и не минимальное.
```
Значение будет отправлено на полетник, где он его обработает и установит 0..99 в rssi.
Проект пока в стадии тестирования, поэтому [присылайте](https://t.me/+BMyMoolVOpkzNWUy) свои отзывы о попытках и пожелания.
### Текущие проблемы
Иногда наблюдаются кратковременные фризы, если активно долбить оба стика во всех направлениях. Дебаг говорит, что от драйвера не приходят в это время события о перемещении. Этот эффект не наблюдается, если использовать ["радиоудлинитель" джойстика](sbus-to-usb-joystick) в виде arduino pro micro, которая парсит SBUS от вашего приемника и переводит в usb-hid-joystick.

View File

@ -0,0 +1,6 @@
config BR2_PACKAGE_RCJOYSTICK
bool "rcjoystick"
help
joystick /dev/input/js0 to mavlink rc_channels_override udp 127.0.0.1:14550
https://github.com/whoim2/rcjoystick

View File

@ -0,0 +1,24 @@
################################################################################
#
# rcjoystick
#
################################################################################
RCJOYSTICK_LICENSE = GPL-2.0
define RCJOYSTICK_EXTRACT_CMDS
cp -avr ../general/package/rcjoystick/src/* $(@D)/
endef
RCJOYSTICK_MAKE_OPTS = \
CC="$(TARGET_CC)"
define RCJOYSTICK_BUILD_CMDS
$(MAKE) $(RCJOYSTICK_MAKE_OPTS) -C $(@D)
endef
define RCJOYSTICK_INSTALL_TARGET_CMDS
install -m 0755 -D $(@D)/rcjoystick $(TARGET_DIR)/usr/bin/rcjoystick
endef
$(eval $(generic-package))

View File

@ -0,0 +1,5 @@
CFLAGS=-O1 -g -fno-omit-frame-pointer -Wall -Wextra
LDFLAGS=-g
#LDLIBS=-levent_core
rcjoystick:

View File

@ -0,0 +1,95 @@
#pragma once
#if defined(MAVLINK_USE_CXX_NAMESPACE)
namespace mavlink {
#elif defined(__cplusplus)
extern "C" {
#endif
// Visual Studio versions before 2010 don't have stdint.h, so we just error out.
#if (defined _MSC_VER) && (_MSC_VER < 1600)
#error "The C-MAVLink implementation requires Visual Studio 2010 or greater"
#endif
#include <stdint.h>
/**
*
* CALCULATE THE CHECKSUM
*
*/
#define X25_INIT_CRC 0xffff
#define X25_VALIDATE_CRC 0xf0b8
#ifndef HAVE_CRC_ACCUMULATE
/**
* @brief Accumulate the 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).
*
* @param data new char to hash
* @param crcAccum the already accumulated checksum
**/
static inline void crc_accumulate(uint8_t data, uint16_t *crcAccum)
{
/*Accumulate one byte of data into the CRC*/
uint8_t tmp;
tmp = data ^ (uint8_t)(*crcAccum &0xff);
tmp ^= (tmp<<4);
*crcAccum = (*crcAccum>>8) ^ (tmp<<8) ^ (tmp <<3) ^ (tmp>>4);
}
#endif
/**
* @brief Initialize the buffer for the MCRF4XX CRC16
*
* @param crcAccum the 16 bit MCRF4XX CRC16
*/
static inline void crc_init(uint16_t* crcAccum)
{
*crcAccum = X25_INIT_CRC;
}
/**
* @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
* @return the checksum over the buffer bytes
**/
static inline uint16_t crc_calculate(const uint8_t* pBuffer, uint16_t length)
{
uint16_t crcTmp;
crc_init(&crcTmp);
while (length--) {
crc_accumulate(*pBuffer++, &crcTmp);
}
return crcTmp;
}
/**
* @brief Accumulate the 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).
*
* @param data new bytes to hash
* @param crcAccum the already accumulated checksum
**/
static inline void crc_accumulate_buffer(uint16_t *crcAccum, const char *pBuffer, uint16_t length)
{
const uint8_t *p = (const uint8_t *)pBuffer;
while (length--) {
crc_accumulate(*p++, crcAccum);
}
}
#if defined(MAVLINK_USE_CXX_NAMESPACE) || defined(__cplusplus)
}
#endif

File diff suppressed because one or more lines are too long

View File

@ -0,0 +1,34 @@
/** @file
* @brief MAVLink comm protocol built from common.xml
* @see http://mavlink.org
*/
#pragma once
#ifndef MAVLINK_H
#define MAVLINK_H
#define MAVLINK_PRIMARY_XML_HASH 7898611588819456034
#ifndef MAVLINK_STX
#define MAVLINK_STX 253
#endif
#ifndef MAVLINK_ENDIAN
#define MAVLINK_ENDIAN MAVLINK_LITTLE_ENDIAN
#endif
#ifndef MAVLINK_ALIGNED_FIELDS
#define MAVLINK_ALIGNED_FIELDS 1
#endif
#ifndef MAVLINK_CRC_EXTRA
#define MAVLINK_CRC_EXTRA 1
#endif
#ifndef MAVLINK_COMMAND_24BIT
#define MAVLINK_COMMAND_24BIT 1
#endif
#include "version.h"
#include "common.h"
#endif // MAVLINK_H

View File

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

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 variant 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,505 @@
#pragma once
// MESSAGE ADSB_VEHICLE PACKING
#define MAVLINK_MSG_ID_ADSB_VEHICLE 246
typedef struct __mavlink_adsb_vehicle_t {
uint32_t ICAO_address; /*< ICAO address*/
int32_t lat; /*< [degE7] Latitude*/
int32_t lon; /*< [degE7] Longitude*/
int32_t altitude; /*< [mm] Altitude(ASL)*/
uint16_t heading; /*< [cdeg] Course over ground*/
uint16_t hor_velocity; /*< [cm/s] The horizontal velocity*/
int16_t ver_velocity; /*< [cm/s] The vertical velocity. Positive is up*/
uint16_t flags; /*< Bitmap to indicate various statuses including valid data fields*/
uint16_t squawk; /*< Squawk code*/
uint8_t altitude_type; /*< ADSB altitude type.*/
char callsign[9]; /*< The callsign, 8+null*/
uint8_t emitter_type; /*< ADSB emitter type.*/
uint8_t tslc; /*< [s] Time since last communication in seconds*/
} mavlink_adsb_vehicle_t;
#define MAVLINK_MSG_ID_ADSB_VEHICLE_LEN 38
#define MAVLINK_MSG_ID_ADSB_VEHICLE_MIN_LEN 38
#define MAVLINK_MSG_ID_246_LEN 38
#define MAVLINK_MSG_ID_246_MIN_LEN 38
#define MAVLINK_MSG_ID_ADSB_VEHICLE_CRC 184
#define MAVLINK_MSG_ID_246_CRC 184
#define MAVLINK_MSG_ADSB_VEHICLE_FIELD_CALLSIGN_LEN 9
#if MAVLINK_COMMAND_24BIT
#define MAVLINK_MESSAGE_INFO_ADSB_VEHICLE { \
246, \
"ADSB_VEHICLE", \
13, \
{ { "ICAO_address", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_adsb_vehicle_t, ICAO_address) }, \
{ "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_adsb_vehicle_t, lat) }, \
{ "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_adsb_vehicle_t, lon) }, \
{ "altitude_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 26, offsetof(mavlink_adsb_vehicle_t, altitude_type) }, \
{ "altitude", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_adsb_vehicle_t, altitude) }, \
{ "heading", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_adsb_vehicle_t, heading) }, \
{ "hor_velocity", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_adsb_vehicle_t, hor_velocity) }, \
{ "ver_velocity", NULL, MAVLINK_TYPE_INT16_T, 0, 20, offsetof(mavlink_adsb_vehicle_t, ver_velocity) }, \
{ "callsign", NULL, MAVLINK_TYPE_CHAR, 9, 27, offsetof(mavlink_adsb_vehicle_t, callsign) }, \
{ "emitter_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 36, offsetof(mavlink_adsb_vehicle_t, emitter_type) }, \
{ "tslc", NULL, MAVLINK_TYPE_UINT8_T, 0, 37, offsetof(mavlink_adsb_vehicle_t, tslc) }, \
{ "flags", NULL, MAVLINK_TYPE_UINT16_T, 0, 22, offsetof(mavlink_adsb_vehicle_t, flags) }, \
{ "squawk", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_adsb_vehicle_t, squawk) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_ADSB_VEHICLE { \
"ADSB_VEHICLE", \
13, \
{ { "ICAO_address", NULL, MAVLINK_TYPE_UINT32_T, 0, 0, offsetof(mavlink_adsb_vehicle_t, ICAO_address) }, \
{ "lat", NULL, MAVLINK_TYPE_INT32_T, 0, 4, offsetof(mavlink_adsb_vehicle_t, lat) }, \
{ "lon", NULL, MAVLINK_TYPE_INT32_T, 0, 8, offsetof(mavlink_adsb_vehicle_t, lon) }, \
{ "altitude_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 26, offsetof(mavlink_adsb_vehicle_t, altitude_type) }, \
{ "altitude", NULL, MAVLINK_TYPE_INT32_T, 0, 12, offsetof(mavlink_adsb_vehicle_t, altitude) }, \
{ "heading", NULL, MAVLINK_TYPE_UINT16_T, 0, 16, offsetof(mavlink_adsb_vehicle_t, heading) }, \
{ "hor_velocity", NULL, MAVLINK_TYPE_UINT16_T, 0, 18, offsetof(mavlink_adsb_vehicle_t, hor_velocity) }, \
{ "ver_velocity", NULL, MAVLINK_TYPE_INT16_T, 0, 20, offsetof(mavlink_adsb_vehicle_t, ver_velocity) }, \
{ "callsign", NULL, MAVLINK_TYPE_CHAR, 9, 27, offsetof(mavlink_adsb_vehicle_t, callsign) }, \
{ "emitter_type", NULL, MAVLINK_TYPE_UINT8_T, 0, 36, offsetof(mavlink_adsb_vehicle_t, emitter_type) }, \
{ "tslc", NULL, MAVLINK_TYPE_UINT8_T, 0, 37, offsetof(mavlink_adsb_vehicle_t, tslc) }, \
{ "flags", NULL, MAVLINK_TYPE_UINT16_T, 0, 22, offsetof(mavlink_adsb_vehicle_t, flags) }, \
{ "squawk", NULL, MAVLINK_TYPE_UINT16_T, 0, 24, offsetof(mavlink_adsb_vehicle_t, squawk) }, \
} \
}
#endif
/**
* @brief Pack a adsb_vehicle message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param ICAO_address ICAO address
* @param lat [degE7] Latitude
* @param lon [degE7] Longitude
* @param altitude_type ADSB altitude type.
* @param altitude [mm] Altitude(ASL)
* @param heading [cdeg] Course over ground
* @param hor_velocity [cm/s] The horizontal velocity
* @param ver_velocity [cm/s] The vertical velocity. Positive is up
* @param callsign The callsign, 8+null
* @param emitter_type ADSB emitter type.
* @param tslc [s] Time since last communication in seconds
* @param flags Bitmap to indicate various statuses including valid data fields
* @param squawk Squawk code
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_adsb_vehicle_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint32_t ICAO_address, int32_t lat, int32_t lon, uint8_t altitude_type, int32_t altitude, uint16_t heading, uint16_t hor_velocity, int16_t ver_velocity, const char *callsign, uint8_t emitter_type, uint8_t tslc, uint16_t flags, uint16_t squawk)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_ADSB_VEHICLE_LEN];
_mav_put_uint32_t(buf, 0, ICAO_address);
_mav_put_int32_t(buf, 4, lat);
_mav_put_int32_t(buf, 8, lon);
_mav_put_int32_t(buf, 12, altitude);
_mav_put_uint16_t(buf, 16, heading);
_mav_put_uint16_t(buf, 18, hor_velocity);
_mav_put_int16_t(buf, 20, ver_velocity);
_mav_put_uint16_t(buf, 22, flags);
_mav_put_uint16_t(buf, 24, squawk);
_mav_put_uint8_t(buf, 26, altitude_type);
_mav_put_uint8_t(buf, 36, emitter_type);
_mav_put_uint8_t(buf, 37, tslc);
_mav_put_char_array(buf, 27, callsign, 9);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ADSB_VEHICLE_LEN);
#else
mavlink_adsb_vehicle_t packet;
packet.ICAO_address = ICAO_address;
packet.lat = lat;
packet.lon = lon;
packet.altitude = altitude;
packet.heading = heading;
packet.hor_velocity = hor_velocity;
packet.ver_velocity = ver_velocity;
packet.flags = flags;
packet.squawk = squawk;
packet.altitude_type = altitude_type;
packet.emitter_type = emitter_type;
packet.tslc = tslc;
mav_array_memcpy(packet.callsign, callsign, sizeof(char)*9);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ADSB_VEHICLE_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_ADSB_VEHICLE;
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ADSB_VEHICLE_MIN_LEN, MAVLINK_MSG_ID_ADSB_VEHICLE_LEN, MAVLINK_MSG_ID_ADSB_VEHICLE_CRC);
}
/**
* @brief Pack a adsb_vehicle message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param ICAO_address ICAO address
* @param lat [degE7] Latitude
* @param lon [degE7] Longitude
* @param altitude_type ADSB altitude type.
* @param altitude [mm] Altitude(ASL)
* @param heading [cdeg] Course over ground
* @param hor_velocity [cm/s] The horizontal velocity
* @param ver_velocity [cm/s] The vertical velocity. Positive is up
* @param callsign The callsign, 8+null
* @param emitter_type ADSB emitter type.
* @param tslc [s] Time since last communication in seconds
* @param flags Bitmap to indicate various statuses including valid data fields
* @param squawk Squawk code
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_adsb_vehicle_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint32_t ICAO_address,int32_t lat,int32_t lon,uint8_t altitude_type,int32_t altitude,uint16_t heading,uint16_t hor_velocity,int16_t ver_velocity,const char *callsign,uint8_t emitter_type,uint8_t tslc,uint16_t flags,uint16_t squawk)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_ADSB_VEHICLE_LEN];
_mav_put_uint32_t(buf, 0, ICAO_address);
_mav_put_int32_t(buf, 4, lat);
_mav_put_int32_t(buf, 8, lon);
_mav_put_int32_t(buf, 12, altitude);
_mav_put_uint16_t(buf, 16, heading);
_mav_put_uint16_t(buf, 18, hor_velocity);
_mav_put_int16_t(buf, 20, ver_velocity);
_mav_put_uint16_t(buf, 22, flags);
_mav_put_uint16_t(buf, 24, squawk);
_mav_put_uint8_t(buf, 26, altitude_type);
_mav_put_uint8_t(buf, 36, emitter_type);
_mav_put_uint8_t(buf, 37, tslc);
_mav_put_char_array(buf, 27, callsign, 9);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ADSB_VEHICLE_LEN);
#else
mavlink_adsb_vehicle_t packet;
packet.ICAO_address = ICAO_address;
packet.lat = lat;
packet.lon = lon;
packet.altitude = altitude;
packet.heading = heading;
packet.hor_velocity = hor_velocity;
packet.ver_velocity = ver_velocity;
packet.flags = flags;
packet.squawk = squawk;
packet.altitude_type = altitude_type;
packet.emitter_type = emitter_type;
packet.tslc = tslc;
mav_array_memcpy(packet.callsign, callsign, sizeof(char)*9);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ADSB_VEHICLE_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_ADSB_VEHICLE;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ADSB_VEHICLE_MIN_LEN, MAVLINK_MSG_ID_ADSB_VEHICLE_LEN, MAVLINK_MSG_ID_ADSB_VEHICLE_CRC);
}
/**
* @brief Encode a adsb_vehicle 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 adsb_vehicle C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_adsb_vehicle_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_adsb_vehicle_t* adsb_vehicle)
{
return mavlink_msg_adsb_vehicle_pack(system_id, component_id, msg, adsb_vehicle->ICAO_address, adsb_vehicle->lat, adsb_vehicle->lon, adsb_vehicle->altitude_type, adsb_vehicle->altitude, adsb_vehicle->heading, adsb_vehicle->hor_velocity, adsb_vehicle->ver_velocity, adsb_vehicle->callsign, adsb_vehicle->emitter_type, adsb_vehicle->tslc, adsb_vehicle->flags, adsb_vehicle->squawk);
}
/**
* @brief Encode a adsb_vehicle 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 adsb_vehicle C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_adsb_vehicle_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_adsb_vehicle_t* adsb_vehicle)
{
return mavlink_msg_adsb_vehicle_pack_chan(system_id, component_id, chan, msg, adsb_vehicle->ICAO_address, adsb_vehicle->lat, adsb_vehicle->lon, adsb_vehicle->altitude_type, adsb_vehicle->altitude, adsb_vehicle->heading, adsb_vehicle->hor_velocity, adsb_vehicle->ver_velocity, adsb_vehicle->callsign, adsb_vehicle->emitter_type, adsb_vehicle->tslc, adsb_vehicle->flags, adsb_vehicle->squawk);
}
/**
* @brief Send a adsb_vehicle message
* @param chan MAVLink channel to send the message
*
* @param ICAO_address ICAO address
* @param lat [degE7] Latitude
* @param lon [degE7] Longitude
* @param altitude_type ADSB altitude type.
* @param altitude [mm] Altitude(ASL)
* @param heading [cdeg] Course over ground
* @param hor_velocity [cm/s] The horizontal velocity
* @param ver_velocity [cm/s] The vertical velocity. Positive is up
* @param callsign The callsign, 8+null
* @param emitter_type ADSB emitter type.
* @param tslc [s] Time since last communication in seconds
* @param flags Bitmap to indicate various statuses including valid data fields
* @param squawk Squawk code
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_adsb_vehicle_send(mavlink_channel_t chan, uint32_t ICAO_address, int32_t lat, int32_t lon, uint8_t altitude_type, int32_t altitude, uint16_t heading, uint16_t hor_velocity, int16_t ver_velocity, const char *callsign, uint8_t emitter_type, uint8_t tslc, uint16_t flags, uint16_t squawk)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_ADSB_VEHICLE_LEN];
_mav_put_uint32_t(buf, 0, ICAO_address);
_mav_put_int32_t(buf, 4, lat);
_mav_put_int32_t(buf, 8, lon);
_mav_put_int32_t(buf, 12, altitude);
_mav_put_uint16_t(buf, 16, heading);
_mav_put_uint16_t(buf, 18, hor_velocity);
_mav_put_int16_t(buf, 20, ver_velocity);
_mav_put_uint16_t(buf, 22, flags);
_mav_put_uint16_t(buf, 24, squawk);
_mav_put_uint8_t(buf, 26, altitude_type);
_mav_put_uint8_t(buf, 36, emitter_type);
_mav_put_uint8_t(buf, 37, tslc);
_mav_put_char_array(buf, 27, callsign, 9);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ADSB_VEHICLE, buf, MAVLINK_MSG_ID_ADSB_VEHICLE_MIN_LEN, MAVLINK_MSG_ID_ADSB_VEHICLE_LEN, MAVLINK_MSG_ID_ADSB_VEHICLE_CRC);
#else
mavlink_adsb_vehicle_t packet;
packet.ICAO_address = ICAO_address;
packet.lat = lat;
packet.lon = lon;
packet.altitude = altitude;
packet.heading = heading;
packet.hor_velocity = hor_velocity;
packet.ver_velocity = ver_velocity;
packet.flags = flags;
packet.squawk = squawk;
packet.altitude_type = altitude_type;
packet.emitter_type = emitter_type;
packet.tslc = tslc;
mav_array_memcpy(packet.callsign, callsign, sizeof(char)*9);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ADSB_VEHICLE, (const char *)&packet, MAVLINK_MSG_ID_ADSB_VEHICLE_MIN_LEN, MAVLINK_MSG_ID_ADSB_VEHICLE_LEN, MAVLINK_MSG_ID_ADSB_VEHICLE_CRC);
#endif
}
/**
* @brief Send a adsb_vehicle message
* @param chan MAVLink channel to send the message
* @param struct The MAVLink struct to serialize
*/
static inline void mavlink_msg_adsb_vehicle_send_struct(mavlink_channel_t chan, const mavlink_adsb_vehicle_t* adsb_vehicle)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mavlink_msg_adsb_vehicle_send(chan, adsb_vehicle->ICAO_address, adsb_vehicle->lat, adsb_vehicle->lon, adsb_vehicle->altitude_type, adsb_vehicle->altitude, adsb_vehicle->heading, adsb_vehicle->hor_velocity, adsb_vehicle->ver_velocity, adsb_vehicle->callsign, adsb_vehicle->emitter_type, adsb_vehicle->tslc, adsb_vehicle->flags, adsb_vehicle->squawk);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ADSB_VEHICLE, (const char *)adsb_vehicle, MAVLINK_MSG_ID_ADSB_VEHICLE_MIN_LEN, MAVLINK_MSG_ID_ADSB_VEHICLE_LEN, MAVLINK_MSG_ID_ADSB_VEHICLE_CRC);
#endif
}
#if MAVLINK_MSG_ID_ADSB_VEHICLE_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This variant 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_adsb_vehicle_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint32_t ICAO_address, int32_t lat, int32_t lon, uint8_t altitude_type, int32_t altitude, uint16_t heading, uint16_t hor_velocity, int16_t ver_velocity, const char *callsign, uint8_t emitter_type, uint8_t tslc, uint16_t flags, uint16_t squawk)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
_mav_put_uint32_t(buf, 0, ICAO_address);
_mav_put_int32_t(buf, 4, lat);
_mav_put_int32_t(buf, 8, lon);
_mav_put_int32_t(buf, 12, altitude);
_mav_put_uint16_t(buf, 16, heading);
_mav_put_uint16_t(buf, 18, hor_velocity);
_mav_put_int16_t(buf, 20, ver_velocity);
_mav_put_uint16_t(buf, 22, flags);
_mav_put_uint16_t(buf, 24, squawk);
_mav_put_uint8_t(buf, 26, altitude_type);
_mav_put_uint8_t(buf, 36, emitter_type);
_mav_put_uint8_t(buf, 37, tslc);
_mav_put_char_array(buf, 27, callsign, 9);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ADSB_VEHICLE, buf, MAVLINK_MSG_ID_ADSB_VEHICLE_MIN_LEN, MAVLINK_MSG_ID_ADSB_VEHICLE_LEN, MAVLINK_MSG_ID_ADSB_VEHICLE_CRC);
#else
mavlink_adsb_vehicle_t *packet = (mavlink_adsb_vehicle_t *)msgbuf;
packet->ICAO_address = ICAO_address;
packet->lat = lat;
packet->lon = lon;
packet->altitude = altitude;
packet->heading = heading;
packet->hor_velocity = hor_velocity;
packet->ver_velocity = ver_velocity;
packet->flags = flags;
packet->squawk = squawk;
packet->altitude_type = altitude_type;
packet->emitter_type = emitter_type;
packet->tslc = tslc;
mav_array_memcpy(packet->callsign, callsign, sizeof(char)*9);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ADSB_VEHICLE, (const char *)packet, MAVLINK_MSG_ID_ADSB_VEHICLE_MIN_LEN, MAVLINK_MSG_ID_ADSB_VEHICLE_LEN, MAVLINK_MSG_ID_ADSB_VEHICLE_CRC);
#endif
}
#endif
#endif
// MESSAGE ADSB_VEHICLE UNPACKING
/**
* @brief Get field ICAO_address from adsb_vehicle message
*
* @return ICAO address
*/
static inline uint32_t mavlink_msg_adsb_vehicle_get_ICAO_address(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint32_t(msg, 0);
}
/**
* @brief Get field lat from adsb_vehicle message
*
* @return [degE7] Latitude
*/
static inline int32_t mavlink_msg_adsb_vehicle_get_lat(const mavlink_message_t* msg)
{
return _MAV_RETURN_int32_t(msg, 4);
}
/**
* @brief Get field lon from adsb_vehicle message
*
* @return [degE7] Longitude
*/
static inline int32_t mavlink_msg_adsb_vehicle_get_lon(const mavlink_message_t* msg)
{
return _MAV_RETURN_int32_t(msg, 8);
}
/**
* @brief Get field altitude_type from adsb_vehicle message
*
* @return ADSB altitude type.
*/
static inline uint8_t mavlink_msg_adsb_vehicle_get_altitude_type(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 26);
}
/**
* @brief Get field altitude from adsb_vehicle message
*
* @return [mm] Altitude(ASL)
*/
static inline int32_t mavlink_msg_adsb_vehicle_get_altitude(const mavlink_message_t* msg)
{
return _MAV_RETURN_int32_t(msg, 12);
}
/**
* @brief Get field heading from adsb_vehicle message
*
* @return [cdeg] Course over ground
*/
static inline uint16_t mavlink_msg_adsb_vehicle_get_heading(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 16);
}
/**
* @brief Get field hor_velocity from adsb_vehicle message
*
* @return [cm/s] The horizontal velocity
*/
static inline uint16_t mavlink_msg_adsb_vehicle_get_hor_velocity(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 18);
}
/**
* @brief Get field ver_velocity from adsb_vehicle message
*
* @return [cm/s] The vertical velocity. Positive is up
*/
static inline int16_t mavlink_msg_adsb_vehicle_get_ver_velocity(const mavlink_message_t* msg)
{
return _MAV_RETURN_int16_t(msg, 20);
}
/**
* @brief Get field callsign from adsb_vehicle message
*
* @return The callsign, 8+null
*/
static inline uint16_t mavlink_msg_adsb_vehicle_get_callsign(const mavlink_message_t* msg, char *callsign)
{
return _MAV_RETURN_char_array(msg, callsign, 9, 27);
}
/**
* @brief Get field emitter_type from adsb_vehicle message
*
* @return ADSB emitter type.
*/
static inline uint8_t mavlink_msg_adsb_vehicle_get_emitter_type(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 36);
}
/**
* @brief Get field tslc from adsb_vehicle message
*
* @return [s] Time since last communication in seconds
*/
static inline uint8_t mavlink_msg_adsb_vehicle_get_tslc(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint8_t(msg, 37);
}
/**
* @brief Get field flags from adsb_vehicle message
*
* @return Bitmap to indicate various statuses including valid data fields
*/
static inline uint16_t mavlink_msg_adsb_vehicle_get_flags(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 22);
}
/**
* @brief Get field squawk from adsb_vehicle message
*
* @return Squawk code
*/
static inline uint16_t mavlink_msg_adsb_vehicle_get_squawk(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint16_t(msg, 24);
}
/**
* @brief Decode a adsb_vehicle message into a struct
*
* @param msg The message to decode
* @param adsb_vehicle C-struct to decode the message contents into
*/
static inline void mavlink_msg_adsb_vehicle_decode(const mavlink_message_t* msg, mavlink_adsb_vehicle_t* adsb_vehicle)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
adsb_vehicle->ICAO_address = mavlink_msg_adsb_vehicle_get_ICAO_address(msg);
adsb_vehicle->lat = mavlink_msg_adsb_vehicle_get_lat(msg);
adsb_vehicle->lon = mavlink_msg_adsb_vehicle_get_lon(msg);
adsb_vehicle->altitude = mavlink_msg_adsb_vehicle_get_altitude(msg);
adsb_vehicle->heading = mavlink_msg_adsb_vehicle_get_heading(msg);
adsb_vehicle->hor_velocity = mavlink_msg_adsb_vehicle_get_hor_velocity(msg);
adsb_vehicle->ver_velocity = mavlink_msg_adsb_vehicle_get_ver_velocity(msg);
adsb_vehicle->flags = mavlink_msg_adsb_vehicle_get_flags(msg);
adsb_vehicle->squawk = mavlink_msg_adsb_vehicle_get_squawk(msg);
adsb_vehicle->altitude_type = mavlink_msg_adsb_vehicle_get_altitude_type(msg);
mavlink_msg_adsb_vehicle_get_callsign(msg, adsb_vehicle->callsign);
adsb_vehicle->emitter_type = mavlink_msg_adsb_vehicle_get_emitter_type(msg);
adsb_vehicle->tslc = mavlink_msg_adsb_vehicle_get_tslc(msg);
#else
uint8_t len = msg->len < MAVLINK_MSG_ID_ADSB_VEHICLE_LEN? msg->len : MAVLINK_MSG_ID_ADSB_VEHICLE_LEN;
memset(adsb_vehicle, 0, MAVLINK_MSG_ID_ADSB_VEHICLE_LEN);
memcpy(adsb_vehicle, _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 variant 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

@ -0,0 +1,363 @@
#pragma once
// MESSAGE ALTITUDE PACKING
#define MAVLINK_MSG_ID_ALTITUDE 141
typedef struct __mavlink_altitude_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 altitude_monotonic; /*< [m] This altitude measure is initialized on system boot and monotonic (it is never reset, but represents the local altitude change). The only guarantee on this field is that it will never be reset and is consistent within a flight. The recommended value for this field is the uncorrected barometric altitude at boot time. This altitude will also drift and vary between flights.*/
float altitude_amsl; /*< [m] This altitude measure is strictly above mean sea level and might be non-monotonic (it might reset on events like GPS lock or when a new QNH value is set). It should be the altitude to which global altitude waypoints are compared to. Note that it is *not* the GPS altitude, however, most GPS modules already output MSL by default and not the WGS84 altitude.*/
float altitude_local; /*< [m] This is the local altitude in the local coordinate frame. It is not the altitude above home, but in reference to the coordinate origin (0, 0, 0). It is up-positive.*/
float altitude_relative; /*< [m] This is the altitude above the home position. It resets on each change of the current home position.*/
float altitude_terrain; /*< [m] This is the altitude above terrain. It might be fed by a terrain database or an altimeter. Values smaller than -1000 should be interpreted as unknown.*/
float bottom_clearance; /*< [m] This is not the altitude, but the clear space below the system according to the fused clearance estimate. It generally should max out at the maximum range of e.g. the laser altimeter. It is generally a moving target. A negative value indicates no measurement available.*/
} mavlink_altitude_t;
#define MAVLINK_MSG_ID_ALTITUDE_LEN 32
#define MAVLINK_MSG_ID_ALTITUDE_MIN_LEN 32
#define MAVLINK_MSG_ID_141_LEN 32
#define MAVLINK_MSG_ID_141_MIN_LEN 32
#define MAVLINK_MSG_ID_ALTITUDE_CRC 47
#define MAVLINK_MSG_ID_141_CRC 47
#if MAVLINK_COMMAND_24BIT
#define MAVLINK_MESSAGE_INFO_ALTITUDE { \
141, \
"ALTITUDE", \
7, \
{ { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_altitude_t, time_usec) }, \
{ "altitude_monotonic", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_altitude_t, altitude_monotonic) }, \
{ "altitude_amsl", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_altitude_t, altitude_amsl) }, \
{ "altitude_local", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_altitude_t, altitude_local) }, \
{ "altitude_relative", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_altitude_t, altitude_relative) }, \
{ "altitude_terrain", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_altitude_t, altitude_terrain) }, \
{ "bottom_clearance", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_altitude_t, bottom_clearance) }, \
} \
}
#else
#define MAVLINK_MESSAGE_INFO_ALTITUDE { \
"ALTITUDE", \
7, \
{ { "time_usec", NULL, MAVLINK_TYPE_UINT64_T, 0, 0, offsetof(mavlink_altitude_t, time_usec) }, \
{ "altitude_monotonic", NULL, MAVLINK_TYPE_FLOAT, 0, 8, offsetof(mavlink_altitude_t, altitude_monotonic) }, \
{ "altitude_amsl", NULL, MAVLINK_TYPE_FLOAT, 0, 12, offsetof(mavlink_altitude_t, altitude_amsl) }, \
{ "altitude_local", NULL, MAVLINK_TYPE_FLOAT, 0, 16, offsetof(mavlink_altitude_t, altitude_local) }, \
{ "altitude_relative", NULL, MAVLINK_TYPE_FLOAT, 0, 20, offsetof(mavlink_altitude_t, altitude_relative) }, \
{ "altitude_terrain", NULL, MAVLINK_TYPE_FLOAT, 0, 24, offsetof(mavlink_altitude_t, altitude_terrain) }, \
{ "bottom_clearance", NULL, MAVLINK_TYPE_FLOAT, 0, 28, offsetof(mavlink_altitude_t, bottom_clearance) }, \
} \
}
#endif
/**
* @brief Pack a altitude message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param 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 altitude_monotonic [m] This altitude measure is initialized on system boot and monotonic (it is never reset, but represents the local altitude change). The only guarantee on this field is that it will never be reset and is consistent within a flight. The recommended value for this field is the uncorrected barometric altitude at boot time. This altitude will also drift and vary between flights.
* @param altitude_amsl [m] This altitude measure is strictly above mean sea level and might be non-monotonic (it might reset on events like GPS lock or when a new QNH value is set). It should be the altitude to which global altitude waypoints are compared to. Note that it is *not* the GPS altitude, however, most GPS modules already output MSL by default and not the WGS84 altitude.
* @param altitude_local [m] This is the local altitude in the local coordinate frame. It is not the altitude above home, but in reference to the coordinate origin (0, 0, 0). It is up-positive.
* @param altitude_relative [m] This is the altitude above the home position. It resets on each change of the current home position.
* @param altitude_terrain [m] This is the altitude above terrain. It might be fed by a terrain database or an altimeter. Values smaller than -1000 should be interpreted as unknown.
* @param bottom_clearance [m] This is not the altitude, but the clear space below the system according to the fused clearance estimate. It generally should max out at the maximum range of e.g. the laser altimeter. It is generally a moving target. A negative value indicates no measurement available.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_altitude_pack(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg,
uint64_t time_usec, float altitude_monotonic, float altitude_amsl, float altitude_local, float altitude_relative, float altitude_terrain, float bottom_clearance)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_ALTITUDE_LEN];
_mav_put_uint64_t(buf, 0, time_usec);
_mav_put_float(buf, 8, altitude_monotonic);
_mav_put_float(buf, 12, altitude_amsl);
_mav_put_float(buf, 16, altitude_local);
_mav_put_float(buf, 20, altitude_relative);
_mav_put_float(buf, 24, altitude_terrain);
_mav_put_float(buf, 28, bottom_clearance);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ALTITUDE_LEN);
#else
mavlink_altitude_t packet;
packet.time_usec = time_usec;
packet.altitude_monotonic = altitude_monotonic;
packet.altitude_amsl = altitude_amsl;
packet.altitude_local = altitude_local;
packet.altitude_relative = altitude_relative;
packet.altitude_terrain = altitude_terrain;
packet.bottom_clearance = bottom_clearance;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ALTITUDE_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_ALTITUDE;
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ALTITUDE_MIN_LEN, MAVLINK_MSG_ID_ALTITUDE_LEN, MAVLINK_MSG_ID_ALTITUDE_CRC);
}
/**
* @brief Pack a altitude message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message 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 altitude_monotonic [m] This altitude measure is initialized on system boot and monotonic (it is never reset, but represents the local altitude change). The only guarantee on this field is that it will never be reset and is consistent within a flight. The recommended value for this field is the uncorrected barometric altitude at boot time. This altitude will also drift and vary between flights.
* @param altitude_amsl [m] This altitude measure is strictly above mean sea level and might be non-monotonic (it might reset on events like GPS lock or when a new QNH value is set). It should be the altitude to which global altitude waypoints are compared to. Note that it is *not* the GPS altitude, however, most GPS modules already output MSL by default and not the WGS84 altitude.
* @param altitude_local [m] This is the local altitude in the local coordinate frame. It is not the altitude above home, but in reference to the coordinate origin (0, 0, 0). It is up-positive.
* @param altitude_relative [m] This is the altitude above the home position. It resets on each change of the current home position.
* @param altitude_terrain [m] This is the altitude above terrain. It might be fed by a terrain database or an altimeter. Values smaller than -1000 should be interpreted as unknown.
* @param bottom_clearance [m] This is not the altitude, but the clear space below the system according to the fused clearance estimate. It generally should max out at the maximum range of e.g. the laser altimeter. It is generally a moving target. A negative value indicates no measurement available.
* @return length of the message in bytes (excluding serial stream start sign)
*/
static inline uint16_t mavlink_msg_altitude_pack_chan(uint8_t system_id, uint8_t component_id, uint8_t chan,
mavlink_message_t* msg,
uint64_t time_usec,float altitude_monotonic,float altitude_amsl,float altitude_local,float altitude_relative,float altitude_terrain,float bottom_clearance)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_ALTITUDE_LEN];
_mav_put_uint64_t(buf, 0, time_usec);
_mav_put_float(buf, 8, altitude_monotonic);
_mav_put_float(buf, 12, altitude_amsl);
_mav_put_float(buf, 16, altitude_local);
_mav_put_float(buf, 20, altitude_relative);
_mav_put_float(buf, 24, altitude_terrain);
_mav_put_float(buf, 28, bottom_clearance);
memcpy(_MAV_PAYLOAD_NON_CONST(msg), buf, MAVLINK_MSG_ID_ALTITUDE_LEN);
#else
mavlink_altitude_t packet;
packet.time_usec = time_usec;
packet.altitude_monotonic = altitude_monotonic;
packet.altitude_amsl = altitude_amsl;
packet.altitude_local = altitude_local;
packet.altitude_relative = altitude_relative;
packet.altitude_terrain = altitude_terrain;
packet.bottom_clearance = bottom_clearance;
memcpy(_MAV_PAYLOAD_NON_CONST(msg), &packet, MAVLINK_MSG_ID_ALTITUDE_LEN);
#endif
msg->msgid = MAVLINK_MSG_ID_ALTITUDE;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ALTITUDE_MIN_LEN, MAVLINK_MSG_ID_ALTITUDE_LEN, MAVLINK_MSG_ID_ALTITUDE_CRC);
}
/**
* @brief Encode a altitude 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 altitude C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_altitude_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_altitude_t* altitude)
{
return mavlink_msg_altitude_pack(system_id, component_id, msg, altitude->time_usec, altitude->altitude_monotonic, altitude->altitude_amsl, altitude->altitude_local, altitude->altitude_relative, altitude->altitude_terrain, altitude->bottom_clearance);
}
/**
* @brief Encode a altitude 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 altitude C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_altitude_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_altitude_t* altitude)
{
return mavlink_msg_altitude_pack_chan(system_id, component_id, chan, msg, altitude->time_usec, altitude->altitude_monotonic, altitude->altitude_amsl, altitude->altitude_local, altitude->altitude_relative, altitude->altitude_terrain, altitude->bottom_clearance);
}
/**
* @brief Send a altitude 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 altitude_monotonic [m] This altitude measure is initialized on system boot and monotonic (it is never reset, but represents the local altitude change). The only guarantee on this field is that it will never be reset and is consistent within a flight. The recommended value for this field is the uncorrected barometric altitude at boot time. This altitude will also drift and vary between flights.
* @param altitude_amsl [m] This altitude measure is strictly above mean sea level and might be non-monotonic (it might reset on events like GPS lock or when a new QNH value is set). It should be the altitude to which global altitude waypoints are compared to. Note that it is *not* the GPS altitude, however, most GPS modules already output MSL by default and not the WGS84 altitude.
* @param altitude_local [m] This is the local altitude in the local coordinate frame. It is not the altitude above home, but in reference to the coordinate origin (0, 0, 0). It is up-positive.
* @param altitude_relative [m] This is the altitude above the home position. It resets on each change of the current home position.
* @param altitude_terrain [m] This is the altitude above terrain. It might be fed by a terrain database or an altimeter. Values smaller than -1000 should be interpreted as unknown.
* @param bottom_clearance [m] This is not the altitude, but the clear space below the system according to the fused clearance estimate. It generally should max out at the maximum range of e.g. the laser altimeter. It is generally a moving target. A negative value indicates no measurement available.
*/
#ifdef MAVLINK_USE_CONVENIENCE_FUNCTIONS
static inline void mavlink_msg_altitude_send(mavlink_channel_t chan, uint64_t time_usec, float altitude_monotonic, float altitude_amsl, float altitude_local, float altitude_relative, float altitude_terrain, float bottom_clearance)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_ALTITUDE_LEN];
_mav_put_uint64_t(buf, 0, time_usec);
_mav_put_float(buf, 8, altitude_monotonic);
_mav_put_float(buf, 12, altitude_amsl);
_mav_put_float(buf, 16, altitude_local);
_mav_put_float(buf, 20, altitude_relative);
_mav_put_float(buf, 24, altitude_terrain);
_mav_put_float(buf, 28, bottom_clearance);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ALTITUDE, buf, MAVLINK_MSG_ID_ALTITUDE_MIN_LEN, MAVLINK_MSG_ID_ALTITUDE_LEN, MAVLINK_MSG_ID_ALTITUDE_CRC);
#else
mavlink_altitude_t packet;
packet.time_usec = time_usec;
packet.altitude_monotonic = altitude_monotonic;
packet.altitude_amsl = altitude_amsl;
packet.altitude_local = altitude_local;
packet.altitude_relative = altitude_relative;
packet.altitude_terrain = altitude_terrain;
packet.bottom_clearance = bottom_clearance;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ALTITUDE, (const char *)&packet, MAVLINK_MSG_ID_ALTITUDE_MIN_LEN, MAVLINK_MSG_ID_ALTITUDE_LEN, MAVLINK_MSG_ID_ALTITUDE_CRC);
#endif
}
/**
* @brief Send a altitude message
* @param chan MAVLink channel to send the message
* @param struct The MAVLink struct to serialize
*/
static inline void mavlink_msg_altitude_send_struct(mavlink_channel_t chan, const mavlink_altitude_t* altitude)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
mavlink_msg_altitude_send(chan, altitude->time_usec, altitude->altitude_monotonic, altitude->altitude_amsl, altitude->altitude_local, altitude->altitude_relative, altitude->altitude_terrain, altitude->bottom_clearance);
#else
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ALTITUDE, (const char *)altitude, MAVLINK_MSG_ID_ALTITUDE_MIN_LEN, MAVLINK_MSG_ID_ALTITUDE_LEN, MAVLINK_MSG_ID_ALTITUDE_CRC);
#endif
}
#if MAVLINK_MSG_ID_ALTITUDE_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This variant 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_altitude_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, float altitude_monotonic, float altitude_amsl, float altitude_local, float altitude_relative, float altitude_terrain, float bottom_clearance)
{
#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, altitude_monotonic);
_mav_put_float(buf, 12, altitude_amsl);
_mav_put_float(buf, 16, altitude_local);
_mav_put_float(buf, 20, altitude_relative);
_mav_put_float(buf, 24, altitude_terrain);
_mav_put_float(buf, 28, bottom_clearance);
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ALTITUDE, buf, MAVLINK_MSG_ID_ALTITUDE_MIN_LEN, MAVLINK_MSG_ID_ALTITUDE_LEN, MAVLINK_MSG_ID_ALTITUDE_CRC);
#else
mavlink_altitude_t *packet = (mavlink_altitude_t *)msgbuf;
packet->time_usec = time_usec;
packet->altitude_monotonic = altitude_monotonic;
packet->altitude_amsl = altitude_amsl;
packet->altitude_local = altitude_local;
packet->altitude_relative = altitude_relative;
packet->altitude_terrain = altitude_terrain;
packet->bottom_clearance = bottom_clearance;
_mav_finalize_message_chan_send(chan, MAVLINK_MSG_ID_ALTITUDE, (const char *)packet, MAVLINK_MSG_ID_ALTITUDE_MIN_LEN, MAVLINK_MSG_ID_ALTITUDE_LEN, MAVLINK_MSG_ID_ALTITUDE_CRC);
#endif
}
#endif
#endif
// MESSAGE ALTITUDE UNPACKING
/**
* @brief Get field time_usec from altitude 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_altitude_get_time_usec(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint64_t(msg, 0);
}
/**
* @brief Get field altitude_monotonic from altitude message
*
* @return [m] This altitude measure is initialized on system boot and monotonic (it is never reset, but represents the local altitude change). The only guarantee on this field is that it will never be reset and is consistent within a flight. The recommended value for this field is the uncorrected barometric altitude at boot time. This altitude will also drift and vary between flights.
*/
static inline float mavlink_msg_altitude_get_altitude_monotonic(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 8);
}
/**
* @brief Get field altitude_amsl from altitude message
*
* @return [m] This altitude measure is strictly above mean sea level and might be non-monotonic (it might reset on events like GPS lock or when a new QNH value is set). It should be the altitude to which global altitude waypoints are compared to. Note that it is *not* the GPS altitude, however, most GPS modules already output MSL by default and not the WGS84 altitude.
*/
static inline float mavlink_msg_altitude_get_altitude_amsl(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 12);
}
/**
* @brief Get field altitude_local from altitude message
*
* @return [m] This is the local altitude in the local coordinate frame. It is not the altitude above home, but in reference to the coordinate origin (0, 0, 0). It is up-positive.
*/
static inline float mavlink_msg_altitude_get_altitude_local(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 16);
}
/**
* @brief Get field altitude_relative from altitude message
*
* @return [m] This is the altitude above the home position. It resets on each change of the current home position.
*/
static inline float mavlink_msg_altitude_get_altitude_relative(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 20);
}
/**
* @brief Get field altitude_terrain from altitude message
*
* @return [m] This is the altitude above terrain. It might be fed by a terrain database or an altimeter. Values smaller than -1000 should be interpreted as unknown.
*/
static inline float mavlink_msg_altitude_get_altitude_terrain(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 24);
}
/**
* @brief Get field bottom_clearance from altitude message
*
* @return [m] This is not the altitude, but the clear space below the system according to the fused clearance estimate. It generally should max out at the maximum range of e.g. the laser altimeter. It is generally a moving target. A negative value indicates no measurement available.
*/
static inline float mavlink_msg_altitude_get_bottom_clearance(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 28);
}
/**
* @brief Decode a altitude message into a struct
*
* @param msg The message to decode
* @param altitude C-struct to decode the message contents into
*/
static inline void mavlink_msg_altitude_decode(const mavlink_message_t* msg, mavlink_altitude_t* altitude)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
altitude->time_usec = mavlink_msg_altitude_get_time_usec(msg);
altitude->altitude_monotonic = mavlink_msg_altitude_get_altitude_monotonic(msg);
altitude->altitude_amsl = mavlink_msg_altitude_get_altitude_amsl(msg);
altitude->altitude_local = mavlink_msg_altitude_get_altitude_local(msg);
altitude->altitude_relative = mavlink_msg_altitude_get_altitude_relative(msg);
altitude->altitude_terrain = mavlink_msg_altitude_get_altitude_terrain(msg);
altitude->bottom_clearance = mavlink_msg_altitude_get_bottom_clearance(msg);
#else
uint8_t len = msg->len < MAVLINK_MSG_ID_ALTITUDE_LEN? msg->len : MAVLINK_MSG_ID_ALTITUDE_LEN;
memset(altitude, 0, MAVLINK_MSG_ID_ALTITUDE_LEN);
memcpy(altitude, _MAV_PAYLOAD(msg), len);
#endif
}

View File

@ -0,0 +1,331 @@
#pragma once
// MESSAGE ATT_POS_MOCAP PACKING
#define MAVLINK_MSG_ID_ATT_POS_MOCAP 138
typedef struct __mavlink_att_pos_mocap_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 q[4]; /*< Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0)*/
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 120
#define MAVLINK_MSG_ID_ATT_POS_MOCAP_MIN_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", \
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", \
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
/**
* @brief Pack a att_pos_mocap message
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
*
* @param time_usec [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 q Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0)
* @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, const float *covariance)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN];
_mav_put_uint64_t(buf, 0, time_usec);
_mav_put_float(buf, 24, x);
_mav_put_float(buf, 28, y);
_mav_put_float(buf, 32, z);
_mav_put_float_array(buf, 8, q, 4);
_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;
packet.time_usec = time_usec;
packet.x = x;
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
msg->msgid = MAVLINK_MSG_ID_ATT_POS_MOCAP;
return mavlink_finalize_message(msg, system_id, component_id, MAVLINK_MSG_ID_ATT_POS_MOCAP_MIN_LEN, MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN, MAVLINK_MSG_ID_ATT_POS_MOCAP_CRC);
}
/**
* @brief Pack a att_pos_mocap message on a channel
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param time_usec [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 q Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0)
* @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,const float *covariance)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN];
_mav_put_uint64_t(buf, 0, time_usec);
_mav_put_float(buf, 24, x);
_mav_put_float(buf, 28, y);
_mav_put_float(buf, 32, z);
_mav_put_float_array(buf, 8, q, 4);
_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;
packet.time_usec = time_usec;
packet.x = x;
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
msg->msgid = MAVLINK_MSG_ID_ATT_POS_MOCAP;
return mavlink_finalize_message_chan(msg, system_id, component_id, chan, MAVLINK_MSG_ID_ATT_POS_MOCAP_MIN_LEN, MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN, MAVLINK_MSG_ID_ATT_POS_MOCAP_CRC);
}
/**
* @brief Encode a att_pos_mocap struct
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param msg The MAVLink message to compress the data into
* @param att_pos_mocap C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_att_pos_mocap_encode(uint8_t system_id, uint8_t component_id, mavlink_message_t* msg, const mavlink_att_pos_mocap_t* att_pos_mocap)
{
return mavlink_msg_att_pos_mocap_pack(system_id, component_id, msg, att_pos_mocap->time_usec, att_pos_mocap->q, att_pos_mocap->x, att_pos_mocap->y, att_pos_mocap->z, att_pos_mocap->covariance);
}
/**
* @brief Encode a att_pos_mocap struct on a channel
*
* @param system_id ID of this system
* @param component_id ID of this component (e.g. 200 for IMU)
* @param chan The MAVLink channel this message will be sent over
* @param msg The MAVLink message to compress the data into
* @param att_pos_mocap C-struct to read the message contents from
*/
static inline uint16_t mavlink_msg_att_pos_mocap_encode_chan(uint8_t system_id, uint8_t component_id, uint8_t chan, mavlink_message_t* msg, const mavlink_att_pos_mocap_t* att_pos_mocap)
{
return mavlink_msg_att_pos_mocap_pack_chan(system_id, component_id, chan, msg, att_pos_mocap->time_usec, att_pos_mocap->q, att_pos_mocap->x, att_pos_mocap->y, att_pos_mocap->z, att_pos_mocap->covariance);
}
/**
* @brief Send a att_pos_mocap 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 q Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0)
* @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, const float *covariance)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char buf[MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN];
_mav_put_uint64_t(buf, 0, time_usec);
_mav_put_float(buf, 24, x);
_mav_put_float(buf, 28, y);
_mav_put_float(buf, 32, z);
_mav_put_float_array(buf, 8, q, 4);
_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;
packet.time_usec = time_usec;
packet.x = x;
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
}
/**
* @brief Send a att_pos_mocap message
* @param chan MAVLink channel to send the message
* @param struct The MAVLink struct to serialize
*/
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, 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
}
#if MAVLINK_MSG_ID_ATT_POS_MOCAP_LEN <= MAVLINK_MAX_PAYLOAD_LEN
/*
This variant of _send() can be used to save stack space by re-using
memory from the receive buffer. The caller provides a
mavlink_message_t which is the size of a full mavlink message. This
is usually the receive buffer for the channel, and allows a reply to an
incoming message with minimum stack space usage.
*/
static inline void mavlink_msg_att_pos_mocap_send_buf(mavlink_message_t *msgbuf, mavlink_channel_t chan, uint64_t time_usec, const float *q, float x, float y, float z, const float *covariance)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
char *buf = (char *)msgbuf;
_mav_put_uint64_t(buf, 0, time_usec);
_mav_put_float(buf, 24, x);
_mav_put_float(buf, 28, y);
_mav_put_float(buf, 32, z);
_mav_put_float_array(buf, 8, q, 4);
_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;
packet->time_usec = time_usec;
packet->x = x;
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
}
#endif
#endif
// MESSAGE ATT_POS_MOCAP UNPACKING
/**
* @brief Get field time_usec from att_pos_mocap 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_att_pos_mocap_get_time_usec(const mavlink_message_t* msg)
{
return _MAV_RETURN_uint64_t(msg, 0);
}
/**
* @brief Get field q from att_pos_mocap message
*
* @return Attitude quaternion (w, x, y, z order, zero-rotation is 1, 0, 0, 0)
*/
static inline uint16_t mavlink_msg_att_pos_mocap_get_q(const mavlink_message_t* msg, float *q)
{
return _MAV_RETURN_float_array(msg, q, 4, 8);
}
/**
* @brief Get field x from att_pos_mocap message
*
* @return [m] X position (NED)
*/
static inline float mavlink_msg_att_pos_mocap_get_x(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 24);
}
/**
* @brief Get field y from att_pos_mocap message
*
* @return [m] Y position (NED)
*/
static inline float mavlink_msg_att_pos_mocap_get_y(const mavlink_message_t* msg)
{
return _MAV_RETURN_float(msg, 28);
}
/**
* @brief Get field z from att_pos_mocap message
*
* @return [m] Z position (NED)
*/
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
*
* @param msg The message to decode
* @param att_pos_mocap C-struct to decode the message contents into
*/
static inline void mavlink_msg_att_pos_mocap_decode(const mavlink_message_t* msg, mavlink_att_pos_mocap_t* att_pos_mocap)
{
#if MAVLINK_NEED_BYTE_SWAP || !MAVLINK_ALIGNED_FIELDS
att_pos_mocap->time_usec = mavlink_msg_att_pos_mocap_get_time_usec(msg);
mavlink_msg_att_pos_mocap_get_q(msg, att_pos_mocap->q);
att_pos_mocap->x = mavlink_msg_att_pos_mocap_get_x(msg);
att_pos_mocap->y = mavlink_msg_att_pos_mocap_get_y(msg);
att_pos_mocap->z = mavlink_msg_att_pos_mocap_get_z(msg);
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);
memcpy(att_pos_mocap, _MAV_PAYLOAD(msg), len);
#endif
}

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