mirror of https://github.com/OpenIPC/firmware.git
[no ci] Datalink: adjust telemetry script (#1400)
parent
dcad60a46e
commit
2e6f6f304c
|
@ -8,16 +8,6 @@ fi
|
|||
|
||||
case "$1" in
|
||||
start)
|
||||
if [ "$(fw_printenv -n fpv)" = "false" ]; then
|
||||
if grep -q "#console" /etc/inittab; then
|
||||
sed -i "s/#console/console/g" /etc/inittab
|
||||
rm -f /etc/system.ok
|
||||
echo "Restart system to restore console..."
|
||||
reboot
|
||||
fi
|
||||
exit 0
|
||||
fi
|
||||
|
||||
if [ ! -f /etc/system.ok ]; then
|
||||
tweaksys "$chip"
|
||||
fi
|
||||
|
|
|
@ -1,47 +1,50 @@
|
|||
#!/bin/sh
|
||||
#
|
||||
# Start telemetry
|
||||
#
|
||||
|
||||
. /etc/datalink.conf
|
||||
. /etc/telemetry.conf
|
||||
|
||||
keydir="/etc"
|
||||
fw=$(grep "BUILD_OPTION" "/etc/os-release" | cut -d= -f2)
|
||||
keydir=/etc
|
||||
|
||||
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
|
||||
if [ -e /etc/datalink.conf ]; then
|
||||
. /etc/datalink.conf
|
||||
fi
|
||||
|
||||
if [ -e /etc/telemetry.conf ]; then
|
||||
. /etc/telemetry.conf
|
||||
fi
|
||||
|
||||
if [ ! -f /usr/bin/telemetry_rx ] && [ ! -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
|
||||
fi
|
||||
|
||||
start_drone_telemetry() {
|
||||
if [ ${one_way} = "false" ]; then
|
||||
telemetry_rx -p ${stream_rx} -u ${port_rx} -K ${keydir}/${unit}.key -i ${link_id} ${wlan} > /dev/null &
|
||||
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 &
|
||||
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 &
|
||||
}
|
||||
|
||||
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 &
|
||||
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 &
|
||||
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
|
||||
if [ "$router" -eq 1 ] || [ "$fw" = "lte" ]; then
|
||||
mavlink-routerd -c /etc/mavlink.conf > /dev/null 2>&1 &
|
||||
else
|
||||
mavfwd --channels ${channels} --master ${serial} --baudrate ${baud} \
|
||||
--out 127.0.0.1:${port_tx} --in 127.0.0.1:${port_rx} > /dev/null &
|
||||
mavfwd --channels "$channels" --master "$serial" --baudrate "$baud" \
|
||||
--out 127.0.0.1:$port_tx --in 127.0.0.1:$port_rx > /dev/null &
|
||||
fi
|
||||
if [ ${fw} = "fpv" ] || [ ${fw} = "venc" ]; then
|
||||
if [ "$fw" = "fpv" ] || [ "$fw" = "venc" ]; then
|
||||
start_${unit}_telemetry
|
||||
fi
|
||||
echo "Done."
|
||||
|
|
|
@ -43,8 +43,8 @@ hisi_goke() {
|
|||
}
|
||||
|
||||
sigmastar() {
|
||||
sed -i "s!serial=/dev/ttyAMA0!serial=/dev/ttyS0!g" /etc/telemetry.conf
|
||||
sed -i "s!Device = /dev/ttyAMA0!Device = /dev/ttyS0!g" /etc/mavlink.conf
|
||||
sed -i "s!serial=/dev/ttyAMA0!serial=/dev/ttyS2!g" /etc/telemetry.conf
|
||||
sed -i "s!Device = /dev/ttyAMA0!Device = /dev/ttyS2!g" /etc/mavlink.conf
|
||||
}
|
||||
|
||||
majestic_generic() {
|
||||
|
|
|
@ -135,6 +135,9 @@ case "$1" in
|
|||
if [ "$chip" = "gk7205v200" ]; then
|
||||
# UART2_RX mux
|
||||
devmem 0x120c0010 32 0x1e04
|
||||
elif [ "$chip" = "ssc33x" ]; then
|
||||
# UART2
|
||||
devmem 0x1F207890 16 0x8
|
||||
fi
|
||||
telemetry start
|
||||
fi
|
||||
|
|
Loading…
Reference in New Issue