Skip to content

Commit 4ea1cf7

Browse files
committed
AP_Scripting: promote video-stream-information to applet
1 parent 21307c3 commit 4ea1cf7

File tree

3 files changed

+309
-33
lines changed

3 files changed

+309
-33
lines changed
Lines changed: 277 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,277 @@
1+
--[[
2+
Populate the VIDEO_STREAM_INFORMATION message based on user parameters
3+
--]]
4+
5+
local PARAM_TABLE_KEY = 87
6+
local PARAM_TABLE_PREFIX = "VID1_"
7+
8+
local MAV_SEVERITY = {EMERGENCY=0, ALERT=1, CRITICAL=2, ERROR=3, WARNING=4, NOTICE=5, INFO=6, DEBUG=7}
9+
local VID_TYPE_ENUM = {RTSP=0, RTPUDP=1, TCP_MPEG=2, MPEG_TS=3}
10+
local CAMMODEL_ENUM = {UNKNOWN=0, SIYI_A8=1, SIYI_ZR10=2, SIYI_ZR30=3, SIYI_ZT30_ZOOM=4, SIYI_ZT30_WIDE=5, SIYI_ZT30_IR=6, SIYI_ZT6_RGB=7, SIYI_ZT6_IR=8}
11+
local TEXT_PREFIX_STR = "video-stream-information:"
12+
local SIYI_IP_DEFAULT = '192.168.144.25:8554'
13+
14+
-- add a parameter and bind it to a variable
15+
function bind_add_param(name, idx, default_value)
16+
assert(param:add_param(PARAM_TABLE_KEY, idx, name, default_value), string.format('could not add param %s', name))
17+
return Parameter(PARAM_TABLE_PREFIX .. name)
18+
end
19+
20+
-- setup script specific parameters
21+
assert(param:add_table(PARAM_TABLE_KEY, PARAM_TABLE_PREFIX, 15), 'could not add param table')
22+
23+
--[[
24+
// @Param: VID1_CAMMODEL
25+
// @DisplayName: Camera1 Video Stream Camera Model
26+
// @Description: Video stream camera model
27+
// @Values: 0:Unknown, 1:Siyi A8, 2:Siyi ZR10, 3:Siyi ZR30, 4:Siyi ZT30 Zoom, 5:Siyi ZT30 Wide, 6:Siyi ZT30 IR, 7:Siyi ZT6 RGB, 8:Siyi ZT6 IR
28+
// @User: Standard
29+
--]]
30+
-- values should match CAMMODEL_ENUM
31+
local VID1_CAMMODEL = bind_add_param('CAMMODEL', 1, 0)
32+
33+
--[[
34+
// @Param: VID1_ID
35+
// @DisplayName: Camera1 Video Stream Id
36+
// @Description: Video stream id
37+
// @Range: 0 50
38+
// @User: Standard
39+
--]]
40+
local VID1_ID = bind_add_param('ID', 2, 1)
41+
42+
--[[
43+
// @Param: VID1_TYPE
44+
// @DisplayName: Camera1 Video Stream Type
45+
// @Description: Video stream type
46+
// @Values: 0:RTSP, 1:RTPUDP, 2:TCP_MPEG, 3:MPEG_TS
47+
// @User: Standard
48+
--]]
49+
-- values should match VID_TYPE_ENUM
50+
local VID1_TYPE = bind_add_param('TYPE', 3, 0)
51+
52+
--[[
53+
// @Param: VID1_FLAG
54+
// @DisplayName: Camera1 Video Stream Flags
55+
// @Description: Video stream flags
56+
// @Bitmask: 0:Running,1:Thermal,2:Thermal Range Enabled
57+
// @User: Standard
58+
--]]
59+
local VID1_FLAG = bind_add_param('FLAG', 4, 1)
60+
61+
--[[
62+
// @Param: VID1_FRAME_RATE
63+
// @DisplayName: Camera1 Video Stream Frame Rate
64+
// @Description: Video stream frame rate
65+
// @Range: 0 50
66+
// @User: Standard
67+
--]]
68+
local VID1_FR = bind_add_param('FRAME_RATE', 5, 30)
69+
70+
--[[
71+
// @Param: VID1_HRES
72+
// @DisplayName: Camera1 Video Stream Horizontal Resolution
73+
// @Description: Video stream horizontal resolution
74+
// @Range: 0 4096
75+
// @User: Standard
76+
--]]
77+
local VID1_HRES = bind_add_param('HRES', 6, 1920)
78+
79+
--[[
80+
// @Param: VID1_VRES
81+
// @DisplayName: Camera1 Video Stream Vertical Resolution
82+
// @Description: Video stream vertical resolution
83+
// @Range: 0 4096
84+
// @User: Standard
85+
--]]
86+
local VID1_VRES = bind_add_param('VRES', 7, 1080)
87+
88+
--[[
89+
// @Param: VID1_BITRATE
90+
// @DisplayName: Camera1 Video Stream Bitrate
91+
// @Description: Video stream bitrate
92+
// @Range: 0 10000
93+
// @User: Standard
94+
--]]
95+
local VID1_BITR = bind_add_param('BITRATE', 8, 1500)
96+
97+
--[[
98+
// @Param: VID1_HFOV
99+
// @DisplayName: Camera1 Video Stream Horizontal FOV
100+
// @Description: Video stream horizontal FOV
101+
// @Range: 0 360
102+
// @User: Standard
103+
--]]
104+
local VID1_HFOV = bind_add_param('HFOV', 9, 0)
105+
106+
--[[
107+
// @Param: VID1_ENCODING
108+
// @DisplayName: Camera1 Video Stream Encoding
109+
// @Description: Video stream encoding
110+
// @Values: 0:Unknown, 1:H264, 2:H265
111+
// @User: Standard
112+
--]]
113+
local VID1_ENC = bind_add_param('ENCODING', 10, 1)
114+
115+
--[[
116+
// @Param: VID1_IPADDR0
117+
// @DisplayName: Camera1 Video Stream IP Address 0
118+
// @Description: Video stream IP Address first octet
119+
// @Range: 0 255
120+
// @User: Standard
121+
--]]
122+
local VID1_IPADDR0 = bind_add_param('IPADDR0', 11, -1)
123+
124+
--[[
125+
// @Param: VID1_IPADDR1
126+
// @DisplayName: Camera1 Video Stream IP Address 1
127+
// @Description: Video stream IP Address second octet
128+
// @Range: 0 255
129+
// @User: Standard
130+
--]]
131+
local VID1_IPADDR1 = bind_add_param('IPADDR1', 12, -1)
132+
133+
--[[
134+
// @Param: VID1_IPADDR2
135+
// @DisplayName: Camera1 Video Stream IP Address 2
136+
// @Description: Video stream IP Address third octet
137+
// @Range: 0 255
138+
// @User: Standard
139+
--]]
140+
local VID1_IPADDR2 = bind_add_param('IPADDR2', 13, -1)
141+
142+
--[[
143+
// @Param: VID1_IPADDR3
144+
// @DisplayName: Camera1 Video Stream IP Address 3
145+
// @Description: Video stream IP Address fourth octet
146+
// @Range: 0 255
147+
// @User: Standard
148+
--]]
149+
local VID1_IPADDR3 = bind_add_param('IPADDR3', 14, -1)
150+
151+
--[[
152+
// @Param: VID1_IPPORT
153+
// @DisplayName: Camera1 Video Stream IP Address Port
154+
// @Description: Video stream IP Address Port
155+
// @Range: 0 65535
156+
// @User: Standard
157+
--]]
158+
local VID1_IPPORT = bind_add_param('IPPORT', 15, 5600)
159+
160+
function set_video_stream_information()
161+
local INSTANCE = 0
162+
local name = 'Video'
163+
164+
-- set defaults by camera model
165+
local uri_ip = ''
166+
local uri_suffix = ''
167+
local hfov = 50
168+
if VID1_CAMMODEL:get() == CAMMODEL_ENUM.SIYI_A8 then
169+
uri_ip = SIYI_IP_DEFAULT
170+
uri_suffix = '/main.264'
171+
hfov = 81
172+
end
173+
if VID1_CAMMODEL:get() == CAMMODEL_ENUM.SIYI_ZR10 then
174+
uri_ip = SIYI_IP_DEFAULT
175+
uri_suffix = '/main.264'
176+
hfov = 62
177+
end
178+
if VID1_CAMMODEL:get() == CAMMODEL_ENUM.SIYI_ZR30 then
179+
uri_ip = SIYI_IP_DEFAULT
180+
uri_suffix = '/main.264'
181+
hfov = 58
182+
end
183+
if VID1_CAMMODEL:get() == CAMMODEL_ENUM.SIYI_ZT30_ZOOM then
184+
uri_ip = SIYI_IP_DEFAULT
185+
uri_suffix = '/video2'
186+
hfov = 58
187+
end
188+
if VID1_CAMMODEL:get() == CAMMODEL_ENUM.SIYI_ZT30_WIDE then
189+
uri_ip = SIYI_IP_DEFAULT
190+
uri_suffix = '/video2'
191+
hfov = 85
192+
end
193+
if VID1_CAMMODEL:get() == CAMMODEL_ENUM.SIYI_ZT30_IR then
194+
uri_ip = SIYI_IP_DEFAULT
195+
uri_suffix = '/video1'
196+
hfov = 24
197+
end
198+
if VID1_CAMMODEL:get() == CAMMODEL_ENUM.SIYI_ZT6_RGB then
199+
uri_ip = SIYI_IP_DEFAULT
200+
uri_suffix = '/video2'
201+
hfov = 85
202+
end
203+
if VID1_CAMMODEL:get() == CAMMODEL_ENUM.SIYI_ZT6_IR then
204+
uri_ip = SIYI_IP_DEFAULT
205+
uri_suffix = '/video1'
206+
hfov = 32
207+
end
208+
209+
-- calculate hfov
210+
if VID1_HFOV:get() ~= 0 then
211+
hfov = VID1_HFOV:get()
212+
end
213+
214+
-- construct uri
215+
if VID1_IPADDR0:get() > 0 or VID1_IPADDR1:get() > 0 or
216+
VID1_IPADDR2:get() > 0 or VID1_IPADDR3:get() > 0 or
217+
VID1_IPPORT:get() > 0 then
218+
uri_ip = math.floor(VID1_IPADDR0:get()) .. '.' ..
219+
math.floor(VID1_IPADDR1:get()) .. '.' ..
220+
math.floor(VID1_IPADDR2:get()) .. '.' ..
221+
math.floor(VID1_IPADDR3:get()) .. ':' ..
222+
math.floor(VID1_IPPORT:get())
223+
end
224+
local uri
225+
if VID1_TYPE:get() == VID_TYPE_ENUM.RTPUDP or VID1_TYPE:get() == VID_TYPE_ENUM.MPEG_TS then
226+
-- sanity check port number
227+
if VID1_IPPORT:get() < 0 then
228+
gcs:send_text(MAV_SEVERITY.ERROR, TEXT_PREFIX_STR .. "check VID1_IPPORT")
229+
do return end
230+
end
231+
uri = tostring(math.floor(VID1_IPPORT:get()))
232+
elseif VID1_TYPE:get() == VID_TYPE_ENUM.RTSP then
233+
-- sanity check IP address
234+
if uri_ip == '' then
235+
gcs:send_text(MAV_SEVERITY.ERROR, TEXT_PREFIX_STR .. "check VID1_IPADDR params")
236+
do return end
237+
end
238+
uri = 'rtsp://' .. uri_ip .. uri_suffix
239+
else
240+
uri = uri_ip .. uri_suffix
241+
end
242+
243+
-- create Video Stream Information message
244+
local stream_info = mavlink_video_stream_information_t()
245+
stream_info:stream_id(VID1_ID:get())
246+
stream_info:count(1) -- hard coded to just a single stream
247+
stream_info:type(VID1_TYPE:get())
248+
stream_info:flags(VID1_FLAG:get())
249+
stream_info:framerate(VID1_FR:get())
250+
stream_info:resolution_h(VID1_HRES:get())
251+
stream_info:resolution_v(VID1_VRES:get())
252+
stream_info:bitrate(VID1_BITR:get())
253+
stream_info:rotation(0) -- video image rotation clockwise, hardcoded to zero
254+
stream_info:hfov(hfov)
255+
stream_info:encoding(VID1_ENC:get())
256+
257+
for i = 0, #name do
258+
stream_info:name(i, name:byte(i+1))
259+
end
260+
for i = 0, #uri do
261+
stream_info:uri(i, uri:byte(i+1))
262+
end
263+
264+
-- update camera library with the latest stream information
265+
camera:set_stream_information(INSTANCE, stream_info)
266+
end
267+
268+
-- print welcome message
269+
gcs:send_text(MAV_SEVERITY.INFO, "video-stream-information script loaded")
270+
271+
-- update function runs every 5 secs
272+
function update()
273+
set_video_stream_information()
274+
return update, 5000
275+
end
276+
277+
return update()
Lines changed: 32 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,32 @@
1+
# Video Stream Information
2+
3+
This script updates the ArduPilot Camera library with the values required to populate the VIDEO_STREAM_INFORMATION
4+
mavlink message allow the GCS to find and display live video to the user
5+
6+
# Parameters
7+
8+
-- VID1_CAMMODEL: Video stream camera model (1:Siyi A8, 2:Siyi ZR10, 3:Siyi ZR30, 4:Siyi ZT30 Zoom, 5:Siyi ZT30 Wide, 6:Siyi ZT30 IR, 7:Siyi ZT6 RGB, 8:Siyi ZT6 IR)
9+
-- VID1_ID: Video stream id
10+
-- VID1_TYPE: Video stream type (0:RTSP, 1:RTPUDP, 2:TCP_MPEG, 3:MPEG_TS)
11+
-- VID1_FLAG: Video stream flags (Bitmask: 0:Running,1:Thermal,2:Thermal Range Enabled)
12+
-- VID1_FRAME_RATE: Video stream frame rate
13+
-- VID1_HRES: Video stream horizontal resolution
14+
-- VID1_VRES: Video stream vertical resolution
15+
-- VID1_BITR: Video stream bitrate
16+
-- VID1_HFOV: Video stream horizontal FOV in degrees
17+
-- VID1_ENCODING: Video stream encoding (0:Unknown, 1:H264, 2:H265)
18+
-- VID1_IPADDR0: Video stream IP Address first octet
19+
-- VID1_IPADDR1: Video stream IP Address second octet
20+
-- VID1_IPADDR2: Video stream IP Address third octet
21+
-- VID1_IPADDR3: Video stream IP Address fourth octet
22+
-- VID1_IPPORT: Video Stream IP Address Port
23+
24+
# How To Use
25+
26+
1. Setup the camera gimbal as described on the ArduPilot wiki including ethernet setup
27+
2. Check the IP address of the camera gimbal
28+
3. Setup scripting per https://ardupilot.org/plane/docs/common-lua-scripts.html and reboot the autopilot
29+
4. Copy this script to the vehicle autopilot's "scripts" directory
30+
5. Set the VID1_CAMMODEL parameter to the camera gimbal model and adjust the new VID1 params as required
31+
6. If necessary using the GCS's mavlink inspector to confirm the VIDEO_STREAM_INFORMATION URI field is correct
32+
7. Confirm the ground station can display the live video

libraries/AP_Scripting/examples/set_VIDEO_STREAM_INFORMATION.lua

Lines changed: 0 additions & 33 deletions
This file was deleted.

0 commit comments

Comments
 (0)