1. 源由
现在OpenIPC的msposd
做了部分更新:
- 【支持】betaflight/inav/ardupilot图标库(支持仅支持其中一个)
- 【支持】地面站OSD/嵌入式OSD功能(前期停留在研发测试阶段)
- 【问题】目前启动脚本/端口规划方面尚未定型
本地之前的一套树莓派 Bookworm Rover需要更新下配置脚本。
2. 状态
【1】wfb-ng 开源代码之树莓派3B+ Bookworm无线配置
【2】msposd 开源代码之树莓派3B+ Bookworm部署
【3】libcamera_mon 开源代码之树莓派3B+ Bookworm部署
3. 更新
虽然从脚本上看,目前OpenIPC并未支持Ground Station OSD功能。
但是相信会很快支持,为此 jetson-fpv 先行切换到MAVLink端口14551作为地面站OSD的UDP接收端口。
$ diff -uN fpv-drone.sh /usr/local/bin/fpvdrone/fpv-drone.sh
--- fpv-drone.sh 2025-01-19 17:42:24.987273259 +0800
+++ /usr/local/bin/fpvdrone/fpv-drone.sh 2025-01-19 17:26:43.352025597 +0800
@@ -6,8 +6,8 @@
# Start the wfb_tx process
/usr/bin/wfb_tx \
- -p 17 \
- -u 14560 \
+ -p 16 \
+ -u 14551 \
-K /etc/drone.key \
-B 20 \
-M 1 \
@@ -30,6 +30,7 @@
/usr/local/bin/fpvdrone/libcamera_mon &
+sleep 5
# Start libcamera-vid and pipe its output to GStreamer while logging to /tmp/libcamera/logs
/usr/bin/libcamera-vid \
--verbose \
@@ -50,7 +51,7 @@
/usr/local/bin/fpvdrone/msposd \
--master /dev/ttyUSB0 \
--baudrate 115200 \
- --out 127.0.0.1:14560 \
+ --out 127.0.0.1:14551 \
--matrix 11 \
--ahi 1 \
-r 30 \
- 1
- 2
- 3
- 4
- 5
- 6
- 7
- 8
- 9
- 10
- 11
- 12
- 13
- 14
- 15
- 16
- 17
- 18
- 19
- 20
- 21
- 22
- 23
- 24
- 25
- 26
- 27
- 28
- 29
- 30
- 31
4. OpenIPC修改
- 增加UDP 14551端口报文发送
- 调整地面站OSD配置的
msposd
命令
4.1 原始telemetry
脚本
root@openipc-ssc338q:~# cat telemetry.bak
#!/bin/sh
fw=$(grep "BUILD_OPTION" "/etc/os-release" | cut -d= -f2)
keydir=/etc
if [ -e /etc/datalink.conf ]; then
. /etc/datalink.conf
fi
if [ -e /etc/telemetry.conf ]; then
. /etc/telemetry.conf
fi
if [ ! -e /usr/bin/telemetry_rx ] || [ ! -e /usr/bin/telemetry_tx ]; then
ln -fs /usr/bin/wfb_rx /usr/bin/telemetry_rx
ln -fs /usr/bin/wfb_tx /usr/bin/telemetry_tx
fi
start_drone_telemetry() {
if [ "$router" -lt 2 ]; then
if [ "$one_way" = "false" ]; then
telemetry_rx -p "$stream_rx" -u "$port_rx" -K "$keydir/$unit.key" -i "$link_id" "$wlan" > /dev/null &
fi
telemetry_tx -p "$stream_tx" -u "$port_tx" -K "$keydir/$unit.key" -B "$bandwidth" \
-M "$mcs_index" -S "$stbc" -L "$ldpc" -G "$guard_interval" -k "$fec_k" -n "$fec_n" \
-T "$pool_timeout" -i "$link_id" -f "$frame_type" "$wlan" > /dev/null &
fi
}
start_gs_telemetry() {
if [ "$one_way" = "false" ]; then
telemetry_tx -p "$stream_tx" -u "$port_tx" -K "$keydir/$unit.key" -B "$bandwidth" \
-M "$mcs_index" -S "$stbc" -L "$ldpc" -G "$guard_interval" -k "$fec_k" -n "$fec_n" \
-T "$pool_timeout" -i "$link_id" -f "$frame_type" "$wlan" > /dev/null &
fi
telemetry_rx -p "$stream_rx" -u "$port_rx" -K "$keydir/$unit.key" -i "$link_id" "$wlan" > /dev/null &
}
case "$1" in
start)
echo "Loading MAVLink telemetry service..."
if [ "$router" -eq 1 ] || [ "$fw" = "lte" ]; then
mavlink-routerd -c /etc/mavlink.conf > /dev/null 2>&1 &
else
if [ "$router" -eq 2 ]; then
msposd --channels "$channels" --master "$serial" --baudrate "$baud" \
--out 127.0.0.1:$(($port_tx + 1)) -osd -r "$fps" --ahi "$ahi" > /dev/null &
else
mavfwd --channels "$channels" --master "$serial" --baudrate "$baud" -p 100 -t -a "$aggregate" \
--out 127.0.0.1:$port_tx --in 127.0.0.1:$port_rx > /dev/null &
fi
fi
if [ "$fw" = "fpv" ] || [ "$fw" = "venc" ]; then
start_${unit}_telemetry
fi
;;
stop)
echo "Stopping telemetry services..."
killall -q telemetry_rx
killall -q telemetry_tx
killall -q mavlink-routerd
killall -q mavfwd
killall -q msposd
;;
*)
echo "Usage: $0 {start|stop}"
exit 1
;;
esac
- 1
- 2
- 3
- 4
- 5
- 6
- 7
- 8
- 9
- 10
- 11
- 12
- 13
- 14
- 15
- 16
- 17
- 18
- 19
- 20
- 21
- 22
- 23
- 24
- 25
- 26
- 27
- 28
- 29
- 30
- 31
- 32
- 33
- 34
- 35
- 36
- 37
- 38
- 39
- 40
- 41
- 42
- 43
- 44
- 45
- 46
- 47
- 48
- 49
- 50
- 51
- 52
- 53
- 54
- 55
- 56
- 57
- 58
- 59
- 60
- 61
- 62
- 63
- 64
- 65
- 66
- 67
- 68
- 69
- 70
- 71
- 72
4.2 脚本telemetry
差异
root@openipc-ssc338q:~# diff -uN telemetry.bak /usr/bin/telemetry
--- telemetry.bak
+++ /usr/bin/telemetry
@@ -23,6 +23,10 @@
telemetry_tx -p "$stream_tx" -u "$port_tx" -K "$keydir/$unit.key" -B "$bandwidth" \
-M "$mcs_index" -S "$stbc" -L "$ldpc" -G "$guard_interval" -k "$fec_k" -n "$fec_n" \
-T "$pool_timeout" -i "$link_id" -f "$frame_type" "$wlan" > /dev/null &
+ else
+ telemetry_tx -p "$stream_tx" -u "$(($port_tx + 1))" -K "$keydir/$unit.key" -B "$bandwidth" \
+ -M "$mcs_index" -S "$stbc" -L "$ldpc" -G "$guard_interval" -k "$fec_k" -n "$fec_n" \
+ -T "$pool_timeout" -i "$link_id" -f "$frame_type" "$wlan" > /dev/null &
fi
}
@@ -43,7 +47,7 @@
else
if [ "$router" -eq 2 ]; then
msposd --channels "$channels" --master "$serial" --baudrate "$baud" \
- --out 127.0.0.1:$(($port_tx + 1)) -osd -r "$fps" --ahi "$ahi" > /dev/null &
+ --out 127.0.0.1:$(($port_tx + 1)) -r "$fps" --ahi "$ahi" > /dev/null &
else
mavfwd --channels "$channels" --master "$serial" --baudrate "$baud" -p 100 -t -a "$aggregate" \
--out 127.0.0.1:$port_tx --in 127.0.0.1:$port_rx > /dev/null &
- 1
- 2
- 3
- 4
- 5
- 6
- 7
- 8
- 9
- 10
- 11
- 12
- 13
- 14
- 15
- 16
- 17
- 18
- 19
- 20
- 21
- 22
- 23
- 24
评论记录:
回复评论: