From 7618ec0a1a99475f39d8830d369453e50f2d6cb6 Mon Sep 17 00:00:00 2001 From: Daniel Li Date: Wed, 19 Feb 2025 12:27:50 +0800 Subject: [PATCH 1/4] Add msposd ground station OSD support --- general/package/legacy/datalink/files/telemetry | 9 +++++++++ 1 file changed, 9 insertions(+) diff --git a/general/package/legacy/datalink/files/telemetry b/general/package/legacy/datalink/files/telemetry index 7479eeee5..7cf1a5970 100755 --- a/general/package/legacy/datalink/files/telemetry +++ b/general/package/legacy/datalink/files/telemetry @@ -23,6 +23,12 @@ start_drone_telemetry() { 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 & + elif [ "$router" -eq 3 ]; then + # Increment $port_tx by 1 if $router is equal to 3 for ground station OSD + port_tx=$((port_tx + 1)) + 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 } @@ -44,6 +50,9 @@ case "$1" in 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 & + elif [ "$router" -eq 3 ]; then + msposd --channels "$channels" --master "$serial" --baudrate "$baud" \ + --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 & From fb525438e18cda27891095f4e74c7d59b2ee6fba Mon Sep 17 00:00:00 2001 From: Daniel Li Date: Wed, 19 Feb 2025 18:31:19 +0800 Subject: [PATCH 2/4] Fix tab/space alignement format --- general/package/legacy/datalink/files/telemetry | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/general/package/legacy/datalink/files/telemetry b/general/package/legacy/datalink/files/telemetry index 7cf1a5970..6553b90ee 100755 --- a/general/package/legacy/datalink/files/telemetry +++ b/general/package/legacy/datalink/files/telemetry @@ -23,12 +23,12 @@ start_drone_telemetry() { 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 & - elif [ "$router" -eq 3 ]; then - # Increment $port_tx by 1 if $router is equal to 3 for ground station OSD - port_tx=$((port_tx + 1)) - 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 & + elif [ "$router" -eq 3 ]; then + # Increment $port_tx by 1 if $router is equal to 3 for ground station OSD + port_tx=$((port_tx + 1)) + 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 } From bada6ae2abc6a845307faf4d9a0f52a18c845d8e Mon Sep 17 00:00:00 2001 From: Daniel Li Date: Wed, 26 Feb 2025 09:34:05 +0800 Subject: [PATCH 3/4] Add msposd tunnel support --- general/package/legacy/datalink/files/telemetry | 11 ++++++----- .../legacy/datalink/files/telemetry_drone.conf | 10 +++++++++- 2 files changed, 15 insertions(+), 6 deletions(-) diff --git a/general/package/legacy/datalink/files/telemetry b/general/package/legacy/datalink/files/telemetry index 6553b90ee..bfe2f1cdb 100755 --- a/general/package/legacy/datalink/files/telemetry +++ b/general/package/legacy/datalink/files/telemetry @@ -24,9 +24,7 @@ start_drone_telemetry() { -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 & elif [ "$router" -eq 3 ]; then - # Increment $port_tx by 1 if $router is equal to 3 for ground station OSD - port_tx=$((port_tx + 1)) - telemetry_tx -p "$stream_tx" -u "$port_tx" -K "$keydir/$unit.key" -B "$bandwidth" \ + telemetry_tx -p "$stream_tx" -u "$tel_port" -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 @@ -49,10 +47,13 @@ case "$1" in 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:$tel_port -osd -r "$fps" --ahi "$ahi" > /dev/null & elif [ "$router" -eq 3 ]; then msposd --channels "$channels" --master "$serial" --baudrate "$baud" \ - --out 127.0.0.1:$(($port_tx + 1)) -r "$fps" --ahi "$ahi" > /dev/null & + --out 127.0.0.1:$tel_port -r "$fps" --ahi "$ahi" > /dev/null & + elif [ "$router" -eq 4 ]; then + msposd --channels "$channels" --master "$serial" --baudrate "$baud" \ + --out $tun_ip:$tun_port -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 & diff --git a/general/package/legacy/datalink/files/telemetry_drone.conf b/general/package/legacy/datalink/files/telemetry_drone.conf index 14d2f7e45..4f0cb6b77 100644 --- a/general/package/legacy/datalink/files/telemetry_drone.conf +++ b/general/package/legacy/datalink/files/telemetry_drone.conf @@ -4,7 +4,12 @@ unit=drone serial=/dev/ttyAMA0 baud=115200 -### router: use simple mavfwd (0), classic mavlink-routerd (1) or msposd instead of mavfwd (2) +### router: +# 0: simple mavfwd (default) +# 1: classic mavlink-routerd +# 2: msposd airunit embedded osd +# 3: msposd ground osd using telemetry +# 4: msposd ground osd using tunnel router=0 wlan=wlan0 @@ -31,3 +36,6 @@ channels=8 ### for msposd: OSD over video fps=20 ahi=0 +tel_port=14551 +tun_ip=10.5.0.1 +tun_port=5000 From 736b827722b776161e34785bc27a2c30680abd1a Mon Sep 17 00:00:00 2001 From: Daniel Li Date: Thu, 27 Feb 2025 06:59:16 +0800 Subject: [PATCH 4/4] Change msposd tunnel port from 5000 to 14551 --- general/package/legacy/datalink/files/telemetry_drone.conf | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/general/package/legacy/datalink/files/telemetry_drone.conf b/general/package/legacy/datalink/files/telemetry_drone.conf index 4f0cb6b77..e0408271b 100644 --- a/general/package/legacy/datalink/files/telemetry_drone.conf +++ b/general/package/legacy/datalink/files/telemetry_drone.conf @@ -38,4 +38,4 @@ fps=20 ahi=0 tel_port=14551 tun_ip=10.5.0.1 -tun_port=5000 +tun_port=14551