[no ci] add venc.conf, fix local build script (#1115)

pull/1117/head
cronyx 2023-11-06 23:39:48 +03:00 committed by GitHub
parent b14ca83c58
commit 456fe583e8
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
11 changed files with 106 additions and 12 deletions

View File

@ -159,7 +159,7 @@ should_fit() {
}
rename() {
if grep -q ultimate_defconfig ./output/.config || grep -q sdcard_defconfig ./output/.config; then
if grep -q 'BR2_OPENIPC_FLASH_SIZE="16"' ./output/.config; then
should_fit uImage $MAX_KERNEL_SIZE_ULTIMATE
should_fit rootfs.squashfs $MAX_ROOTFS_SIZE_ULTIMATE
else

View File

@ -33,11 +33,11 @@ case "$1" in
fi
fi
if [ ${telemetry} = "true" ]; then
/usr/bin/telemetry start
telemetry start
fi
else
echo "Starting wifibroadcast service..."
/usr/bin/wifibroadcast start
wifibroadcast start
fi
;;
stop)

View File

@ -19,12 +19,12 @@ 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 &
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 ${fec_timeout} -i ${link_id} ${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 ${fec_timeout} -i ${link_id} ${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
telemetry_rx -p ${stream_rx} -u ${port_rx} -K ${keydir}/${unit}.key -i ${link_id} ${wlan} > /dev/null &
}

View File

@ -15,11 +15,12 @@ mcs_index=1
stream_rx=144
stream_tx=16
link_id=7669206
frame_type=data
port_rx=14551
port_tx=14550
fec_k=1
fec_n=2
fec_timeout=0
pool_timeout=0
guard_interval=long
one_way=false

View File

@ -15,11 +15,12 @@ mcs_index=1
stream_rx=16
stream_tx=144
link_id=7669206
frame_type=data
port_rx=14651
port_tx=14650
fec_k=1
fec_n=2
fec_timeout=0
pool_timeout=0
guard_interval=long
one_way=false

View File

@ -23,7 +23,7 @@ mode=720p60
mavlink_port=14750
### Osd: none, simple or custom for use own lvgl based osd (custom osd binary need to be upload to /usr/bin) (default: simple)
### Osd: none, simple or custom for use own lvgl based osd (custom osd binary need to be upload to /usr/bin directory) (default: simple)
osd=simple

View File

@ -6,7 +6,7 @@
case "$1" in
start)
echo "Starting venc encoder service..."
venc -p 5600 -f 30 -r 7168 -n 1400 -c 264cbr -d frame -v 200_imx307F -s 720p &
venc -h ${host} -p ${port} -v ${version} -s ${size} -f ${fps} -c ${codec} -g ${gop} -m ${mode} -d ${data_format} -r ${rate} -n ${payload_size} ${extra} > /dev/null 2>&1 &
;;
stop)
echo "Stopping venc encoder service..."

View File

@ -0,0 +1,87 @@
# GK7205v200 / IMX307
# 200_imx307B - v200, IMX307, 2-lane MIPI | 720p | any fps
# 200_imx307F - v200, IMX307, 2-lane MIPI | 1080p | 30 fps only
#
# GK7205v300 / IMX307
# 300_imx307B - v300, IMX307, 4-lane MIPI | 720p | any fps
# 300_imx307F - v300, IMX307, 4-lane MIPI | 1080p | 30 fps only
#
# GK7205v300 / IMX335
# 300_imx335F - v300, IMX335, 4-lane MIPI | 4MP | 30 fps only
version=200_imx307B
# Sink IP address (Default: 127.0.0.1)
host=127.0.0.1
# Sink port (Default: 5000)
port=5600
# Max video rate in Kbit/sec (Default: 8192)
rate=4096
# Max payload frame size in bytes (Default: 1400)
payload_size=1400
# Streaming mode: compact or rtp (Default: compact)
mode=compact
# Encoded image size (Default: version specific)
# Standard resolutions:
# D1 - 720 x 480
# 960h - 960 x 576
# 720p - 1280 x 720
# 1.3MP - 1280 x 1024
# 1080p - 1920 x 1080
# 4MP - 2592 x 1520
# Custom resolution format:
# WxH - Custom resolution W x H pixels
size=720p
# Encoder FPS (25,30,50,60) (Default: 60)
fps=60
# GOP denominator (Default: 10)
gop=10
# Encoder mode (Default: 264avbr)
# --- H264 ---
# 264avbr - h264 AVBR
# 264qvbr - h264 QVBR
# 264vbr - h264 VBR
# 264cbr - h264 CBR
# --- H265 ---
# 265avbr - h265 AVBR
# 265qvbr - h265 QVBR
# 265vbr - h265 VBR
# 265cbr - h265 CBR
codec=264cbr
# Data format (Default: stream)
# stream - Produce NALUs in stream mode
# frame - Produce NALUs in packet mode
data_format=frame
# Extra param (must be splitted by space)
# --no-slices - Disable slices
# --slice-size [size] - Slices size in lines (Default: 4)
#
# --low-delay - Enable low delay mode
# --mirror - Mirror image
# --flip - Flip image
# --exp - Limit exposure
#
# --roi - Enable ROI
# --roi-qp [QP] - ROI quality points (Default: 20)
extra="--low-delay"

View File

@ -24,6 +24,9 @@ define VENC_OPENIPC_INSTALL_TARGET_CMDS
$(INSTALL) -m 755 -d $(TARGET_DIR)/etc/init.d
$(INSTALL) -m 755 -t $(TARGET_DIR)/etc/init.d $(VENC_OPENIPC_PKGDIR)/files/S98venc
$(INSTALL) -m 755 -d $(TARGET_DIR)/etc
$(INSTALL) -m 644 -t $(TARGET_DIR)/etc $(VENC_OPENIPC_PKGDIR)/files/venc.conf
$(INSTALL) -m 755 -d $(TARGET_DIR)/usr/bin
$(INSTALL) -m 755 -t $(TARGET_DIR)/usr/bin $(@D)/venc/venc
endef

View File

@ -15,7 +15,9 @@ mcs_index=1
stream=0
link_id=7669206
udp_port=5600
rcv_buf=456000
frame_type=data
fec_k=8
fec_n=12
fec_timeout=0
pool_timeout=0
guard_interval=long

View File

@ -100,7 +100,7 @@ load_interface() {
}
start_drone_wfb() {
wfb_tx -p ${stream} -u ${udp_port} -K ${keydir}/${unit}.key -B ${bandwidth} -M ${mcs_index} -S ${stbc} -L ${ldpc} -G ${guard_interval} -k ${fec_k} -n ${fec_n} -T ${fec_timeout} -i ${link_id} ${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() {
@ -137,7 +137,7 @@ case "$1" in
# UART2_RX mux
devmem 0x120c0010 32 0x1e04
fi
/usr/bin/telemetry start
telemetry start
fi
else