Skip to content

Commit 1924237

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

File tree

3 files changed

+298
-33
lines changed

3 files changed

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