mirror of https://github.com/OpenIPC/firmware.git
Add msposd tunnel support
parent
fb525438e1
commit
bada6ae2ab
|
@ -24,9 +24,7 @@ start_drone_telemetry() {
|
||||||
-M "$mcs_index" -S "$stbc" -L "$ldpc" -G "$guard_interval" -k "$fec_k" -n "$fec_n" \
|
-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 &
|
-T "$pool_timeout" -i "$link_id" -f "$frame_type" "$wlan" > /dev/null &
|
||||||
elif [ "$router" -eq 3 ]; then
|
elif [ "$router" -eq 3 ]; then
|
||||||
# Increment $port_tx by 1 if $router is equal to 3 for ground station OSD
|
telemetry_tx -p "$stream_tx" -u "$tel_port" -K "$keydir/$unit.key" -B "$bandwidth" \
|
||||||
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" \
|
-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 &
|
-T "$pool_timeout" -i "$link_id" -f "$frame_type" "$wlan" > /dev/null &
|
||||||
fi
|
fi
|
||||||
|
@ -49,10 +47,13 @@ case "$1" in
|
||||||
else
|
else
|
||||||
if [ "$router" -eq 2 ]; then
|
if [ "$router" -eq 2 ]; then
|
||||||
msposd --channels "$channels" --master "$serial" --baudrate "$baud" \
|
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
|
elif [ "$router" -eq 3 ]; then
|
||||||
msposd --channels "$channels" --master "$serial" --baudrate "$baud" \
|
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
|
else
|
||||||
mavfwd --channels "$channels" --master "$serial" --baudrate "$baud" -p 100 -t -a "$aggregate" \
|
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 &
|
--out 127.0.0.1:$port_tx --in 127.0.0.1:$port_rx > /dev/null &
|
||||||
|
|
|
@ -4,7 +4,12 @@ unit=drone
|
||||||
serial=/dev/ttyAMA0
|
serial=/dev/ttyAMA0
|
||||||
baud=115200
|
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
|
router=0
|
||||||
|
|
||||||
wlan=wlan0
|
wlan=wlan0
|
||||||
|
@ -31,3 +36,6 @@ channels=8
|
||||||
### for msposd: OSD over video
|
### for msposd: OSD over video
|
||||||
fps=20
|
fps=20
|
||||||
ahi=0
|
ahi=0
|
||||||
|
tel_port=14551
|
||||||
|
tun_ip=10.5.0.1
|
||||||
|
tun_port=5000
|
||||||
|
|
Loading…
Reference in New Issue