mirror of https://github.com/OpenIPC/firmware.git
[no ci] Package: add rtl8733bu to wifibroadcast
parent
d70825d942
commit
c722a3d042
|
@ -7,7 +7,6 @@
|
||||||
. /etc/telemetry.conf
|
. /etc/telemetry.conf
|
||||||
|
|
||||||
keydir="/etc"
|
keydir="/etc"
|
||||||
|
|
||||||
fw=$(grep "BUILD_OPTION" "/etc/os-release" | cut -d= -f2)
|
fw=$(grep "BUILD_OPTION" "/etc/os-release" | cut -d= -f2)
|
||||||
|
|
||||||
if [ ! -f /usr/bin/telemetry_rx -a ! -f /usr/bin/telemetry_tx ]; then
|
if [ ! -f /usr/bin/telemetry_rx -a ! -f /usr/bin/telemetry_tx ]; then
|
||||||
|
@ -19,12 +18,16 @@ start_drone_telemetry() {
|
||||||
if [ ${one_way} = "false" ]; then
|
if [ ${one_way} = "false" ]; then
|
||||||
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 &
|
||||||
fi
|
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() {
|
start_gs_telemetry() {
|
||||||
if [ ${one_way} = "false" ]; then
|
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 &
|
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
|
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 &
|
||||||
}
|
}
|
||||||
|
@ -32,25 +35,28 @@ start_gs_telemetry() {
|
||||||
case "$1" in
|
case "$1" in
|
||||||
start)
|
start)
|
||||||
echo "Loading MAVLink telemetry service..."
|
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 &
|
mavlink-routerd -c /etc/mavlink.conf > /dev/null 2>&1 &
|
||||||
else
|
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
|
fi
|
||||||
if [ ${fw} = "fpv" ] || [ ${fw} = "venc" ]; then
|
if [ ${fw} = "fpv" ] || [ ${fw} = "venc" ]; then
|
||||||
start_${unit}_telemetry
|
start_${unit}_telemetry
|
||||||
fi
|
fi
|
||||||
echo "Done."
|
echo "Done."
|
||||||
;;
|
;;
|
||||||
|
|
||||||
stop)
|
stop)
|
||||||
echo "Stopping telemetry services..."
|
echo "Stopping telemetry services..."
|
||||||
kill -9 $(pidof telemetry_rx)
|
killall -q telemetry_rx
|
||||||
kill -9 $(pidof telemetry_tx)
|
killall -q telemetry_tx
|
||||||
kill -9 $(pidof mavlink-routerd)
|
killall -q mavlink-routerd
|
||||||
kill -9 $(pidof mavfwd)
|
killall -q mavfwd
|
||||||
;;
|
;;
|
||||||
|
|
||||||
*)
|
*)
|
||||||
echo "Usage: $0 {start|stop}"
|
echo "Usage: $0 {start|stop}"
|
||||||
exit 1
|
exit 1
|
||||||
|
;;
|
||||||
esac
|
esac
|
||||||
|
|
|
@ -9,7 +9,6 @@
|
||||||
keydir="/etc"
|
keydir="/etc"
|
||||||
chip=$(ipcinfo -c)
|
chip=$(ipcinfo -c)
|
||||||
vendor=$(ipcinfo -v)
|
vendor=$(ipcinfo -v)
|
||||||
|
|
||||||
driver=""
|
driver=""
|
||||||
|
|
||||||
set_mcs() {
|
set_mcs() {
|
||||||
|
@ -18,9 +17,11 @@ set_mcs() {
|
||||||
else
|
else
|
||||||
mcs=$(ls -l /lib/firmware/ath9k_htc | grep "htc_9271-1.4.0.fw" | cut -d "." -f6)
|
mcs=$(ls -l /lib/firmware/ath9k_htc | grep "htc_9271-1.4.0.fw" | cut -d "." -f6)
|
||||||
fi
|
fi
|
||||||
|
|
||||||
if [ -z "${mcs}" ]; then
|
if [ -z "${mcs}" ]; then
|
||||||
setmcs ${mcs_index}
|
setmcs ${mcs_index}
|
||||||
fi
|
fi
|
||||||
|
|
||||||
if [ ${mcs_index} -eq 1 ] || [ ${mcs_index} -eq 3 ]; then
|
if [ ${mcs_index} -eq 1 ] || [ ${mcs_index} -eq 3 ]; then
|
||||||
if [ ! ${mcs_index} -eq ${mcs} ]; then
|
if [ ! ${mcs_index} -eq ${mcs} ]; then
|
||||||
setmcs ${mcs_index}
|
setmcs ${mcs_index}
|
||||||
|
@ -35,13 +36,18 @@ set_mcs() {
|
||||||
detect_wifi_card() {
|
detect_wifi_card() {
|
||||||
echo "Detecting wifi card vendor..."
|
echo "Detecting wifi card vendor..."
|
||||||
devices=$(lsusb | cut -d ' ' -f6 | sort | uniq)
|
devices=$(lsusb | cut -d ' ' -f6 | sort | uniq)
|
||||||
for card in ${devices}
|
for card in ${devices}; do
|
||||||
do
|
|
||||||
case "${card}" in
|
case "${card}" in
|
||||||
"0bda:8812" | "0bda:881a" | "0b05:17d2" | "2357:0101" | "2604:0012")
|
"0bda:8812" | "0bda:881a" | "0b05:17d2" | "2357:0101" | "2604:0012")
|
||||||
driver="realtek"
|
driver="realtek"
|
||||||
modprobe 88XXau rtw_tx_pwr_idx_override=${driver_txpower_override}
|
modprobe 88XXau rtw_tx_pwr_idx_override=${driver_txpower_override}
|
||||||
;;
|
;;
|
||||||
|
|
||||||
|
"0bda:f72b")
|
||||||
|
driver="realtek"
|
||||||
|
modprobe 8733bu
|
||||||
|
;;
|
||||||
|
|
||||||
"0cf3:9271" | "040d:3801")
|
"0cf3:9271" | "040d:3801")
|
||||||
driver="atheros"
|
driver="atheros"
|
||||||
if ! [ ${unit} = "gs" ]; then
|
if ! [ ${unit} = "gs" ]; then
|
||||||
|
@ -64,8 +70,7 @@ detect_wifi_card() {
|
||||||
echo "Awaiting interface ${wlan} in system..."
|
echo "Awaiting interface ${wlan} in system..."
|
||||||
|
|
||||||
local n=0
|
local n=0
|
||||||
while ! $(ifconfig -a | grep -q ${wlan})
|
while ! $(ifconfig -a | grep -q ${wlan}); do
|
||||||
do
|
|
||||||
if [ ${n} -ge 5 ]; then
|
if [ ${n} -ge 5 ]; then
|
||||||
echo "No interface ${wlan}. Check wifi stick connection, usb power or possible bad soldering."
|
echo "No interface ${wlan}. Check wifi stick connection, usb power or possible bad soldering."
|
||||||
exit
|
exit
|
||||||
|
@ -96,12 +101,15 @@ load_interface() {
|
||||||
else
|
else
|
||||||
iwconfig ${wlan} channel ${channel}
|
iwconfig ${wlan} channel ${channel}
|
||||||
fi
|
fi
|
||||||
|
|
||||||
# dirty fix crash if txpower set. setting txpower disabled because patched driver always set txpower level 58
|
# dirty fix crash if txpower set. setting txpower disabled because patched driver always set txpower level 58
|
||||||
# iw dev ${wlan} set txpower fixed $((${txpower} * 100))
|
# iw dev ${wlan} set txpower fixed $((${txpower} * 100))
|
||||||
}
|
}
|
||||||
|
|
||||||
start_drone_wfb() {
|
start_drone_wfb() {
|
||||||
wfb_tx -p ${stream} -u ${udp_port} -R ${rcv_buf} -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 &
|
wfb_tx -p ${stream} -u ${udp_port} -R ${rcv_buf} -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_wfb() {
|
start_gs_wfb() {
|
||||||
|
@ -111,13 +119,10 @@ start_gs_wfb() {
|
||||||
case "$1" in
|
case "$1" in
|
||||||
start)
|
start)
|
||||||
if [ ${daemon} -eq 1 ]; then
|
if [ ${daemon} -eq 1 ]; then
|
||||||
|
|
||||||
echo "Loading modules and wifi card driver..."
|
echo "Loading modules and wifi card driver..."
|
||||||
|
|
||||||
load_modules
|
load_modules
|
||||||
|
|
||||||
echo "Preparing interface wlan..."
|
echo "Preparing interface wlan..."
|
||||||
|
|
||||||
load_interface
|
load_interface
|
||||||
|
|
||||||
if ! cat ${keydir}/${unit}.key > /dev/null 2>&1; then
|
if ! cat ${keydir}/${unit}.key > /dev/null 2>&1; then
|
||||||
|
@ -128,9 +133,7 @@ case "$1" in
|
||||||
fi
|
fi
|
||||||
|
|
||||||
echo "Starting Wifibroadcast service..."
|
echo "Starting Wifibroadcast service..."
|
||||||
|
|
||||||
start_${unit}_wfb
|
start_${unit}_wfb
|
||||||
|
|
||||||
echo "Done."
|
echo "Done."
|
||||||
|
|
||||||
if [ ${telemetry} = "true" ]; then
|
if [ ${telemetry} = "true" ]; then
|
||||||
|
@ -140,21 +143,23 @@ case "$1" in
|
||||||
fi
|
fi
|
||||||
telemetry start
|
telemetry start
|
||||||
fi
|
fi
|
||||||
|
|
||||||
else
|
else
|
||||||
echo "Wifibroadcast service disabled in wfb.conf..."
|
echo "Wifibroadcast service disabled in wfb.conf..."
|
||||||
fi
|
fi
|
||||||
;;
|
;;
|
||||||
|
|
||||||
stop)
|
stop)
|
||||||
echo "Stopping all services..."
|
echo "Stopping all services..."
|
||||||
kill -9 $(pidof wfb_tx)
|
killall -q wfb_tx
|
||||||
kill -9 $(pidof wfb_rx)
|
killall -q wfb_rx
|
||||||
kill -9 $(pidof telemetry_rx)
|
killall -q telemetry_rx
|
||||||
kill -9 $(pidof telemetry_tx)
|
killall -q telemetry_tx
|
||||||
kill -9 $(pidof mavlink-routerd)
|
killall -q mavlink-routerd
|
||||||
kill -9 $(pidof mavfwd)
|
killall -q mavfwd
|
||||||
;;
|
;;
|
||||||
|
|
||||||
*)
|
*)
|
||||||
echo "Usage: $0 {start|stop}"
|
echo "Usage: $0 {start|stop}"
|
||||||
exit 1
|
exit 1
|
||||||
|
;;
|
||||||
esac
|
esac
|
||||||
|
|
Loading…
Reference in New Issue