mirror of https://github.com/OpenIPC/firmware.git
Add msposd ground station OSD support (#1715)
parent
c80e5b8648
commit
9f42c00153
|
@ -23,6 +23,10 @@ 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
|
||||
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
|
||||
}
|
||||
|
||||
|
@ -43,7 +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:$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 &
|
||||
|
|
|
@ -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=14551
|
||||
|
|
Loading…
Reference in New Issue