Skip to content

Commit

Permalink
AP_Scripting: set-video-stream-information gets params
Browse files Browse the repository at this point in the history
  • Loading branch information
rmackay9 committed Nov 13, 2024
1 parent da708b7 commit f8cf45b
Showing 1 changed file with 112 additions and 12 deletions.
124 changes: 112 additions & 12 deletions libraries/AP_Scripting/examples/set_VIDEO_STREAM_INFORMATION.lua
Original file line number Diff line number Diff line change
@@ -1,24 +1,122 @@
--[[
Populate the fields of the VIDEO_STREAM_INFORMATION message sent by the selected camera instance.
--]]
function set_video_stream_information()

local PARAM_TABLE_KEY = 87
local PARAM_TABLE_PREFIX = "CAM1_"

local MAV_SEVERITY = {EMERGENCY=0, ALERT=1, CRITICAL=2, ERROR=3, WARNING=4, NOTICE=5, INFO=6, DEBUG=7}

-- add a parameter and bind it to a variable
function bind_add_param(name, idx, default_value)
assert(param:add_param(PARAM_TABLE_KEY, idx, name, default_value), string.format('could not add param %s', name))
return Parameter(PARAM_TABLE_PREFIX .. name)
end

-- setup script specific parameters
assert(param:add_table(PARAM_TABLE_KEY, PARAM_TABLE_PREFIX, 9), 'could not add param table')

--[[
// @Param: CAM1_STREAM_ID
// @DisplayName: Camera1 Video Stream Id
// @Description: Video stream id
// @Range: 0 50
// @User: Standard
--]]
local CAM1_STREAM_ID = bind_add_param('STREAM_ID', 1, 1)

--[[
// @Param: CAM1_STREAM_TYPE
// @DisplayName: Camera1 Video Stream Type
// @Description: Video stream type
// @Values: 0:RTSP, 1:RTPUDP, 2:TCP_MPEG, 3:MPEG_TS
// @User: Standard
--]]
local CAM1_STREAM_TYPE = bind_add_param('STREAM_TYPE', 2, 0)

--[[
// @Param: CAM1_STREAM_FLAG
// @DisplayName: Camera1 Video Stream Flags
// @Description: Video stream flags
// @Bitmask: 0:Running,1:Thermal,2:Thermal Range Enabled
// @User: Standard
--]]
local CAM1_STREAM_FLAG = bind_add_param('STREAM_FLAG', 3, 1)

--[[
// @Param: CAM1_FRAME_RATE
// @DisplayName: Camera1 Video Stream Frame Rate
// @Description: Video stream frame rate
// @Range: 0 50
// @User: Standard
--]]
local CAM1_FRAME_RATE = bind_add_param('FRAME_RATE', 4, 30)

--[[
// @Param: CAM1_RES_H
// @DisplayName: Camera1 Video Stream Horizontal Resolution
// @Description: Video stream horizontal resolution
// @Range: 0 4096
// @User: Standard
--]]
local CAM1_RES_H = bind_add_param('RES_H', 5, 1920)

--[[
// @Param: CAM1_RES_V
// @DisplayName: Camera1 Video Stream Vertical Resolution
// @Description: Video stream vertical resolution
// @Range: 0 4096
// @User: Standard
--]]
local CAM1_RES_V = bind_add_param('RES_V', 6, 1080)

--[[
// @Param: CAM1_BITRATE
// @DisplayName: Camera1 Video Stream Bitrate
// @Description: Video stream bitrate
// @Range: 0 10000
// @User: Standard
--]]
local CAM1_BITRATE = bind_add_param('BITRATE', 7, 1500)

--[[
// @Param: CAM1_HFOV
// @DisplayName: Camera1 Video Stream Horizontal FOV
// @Description: Video stream horizontal FOV
// @Range: 0 360
// @User: Standard
--]]
local CAM1_HFOV = bind_add_param('HFOV', 8, 50)

--[[
// @Param: CAM1_STREAM_ENC
// @DisplayName: Camera1 Video Stream Encoding
// @Description: Video stream encoding
// @Values: 0:Unknown, 1:H264, 2:H265
// @User: Standard
--]]
local CAM1_STREAM_ENC = bind_add_param('STREAM_ENC', 9, 0)

function set_video_stream_information()
-- set the Video Stream Information data
local stream_info = mavlink_video_stream_information_t()

local INSTANCE = 0
local name = 'Video'
local uri = '127.0.0.1:5600'

stream_info:framerate(30)
stream_info:bitrate(1500)
stream_info:flags(1) -- VIDEO_STREAM_STATUS_FLAGS_RUNNING
stream_info:resolution_h(1920)
stream_info:resolution_v(1080)
stream_info:rotation(0)
stream_info:hfov(50)
stream_info:stream_id(1)
stream_info:count(1)
stream_info:type(1) -- VIDEO_STREAM_TYPE_RTPUDP
stream_info:stream_id(CAM1_STREAM_ID:get())
stream_info:count(1) -- hard coded to just a single stream
stream_info:type(CAM1_STREAM_TYPE:get())
stream_info:flags(CAM1_STREAM_FLAG:get())
stream_info:framerate(CAM1_FRAME_RATE:get())
stream_info:resolution_h(CAM1_RES_H:get())
stream_info:resolution_v(CAM1_RES_V:get())
stream_info:bitrate(CAM1_BITRATE:get())
stream_info:rotation(0) -- video image rotation clockwise, hardcoded to zero
stream_info:hfov(CAM1_HFOV:get())
stream_info:encoding(CAM1_STREAM_ENC:get())

for i = 0, #name do
stream_info:name(i, name:byte(i+1))
end
Expand All @@ -27,7 +125,9 @@
end

camera:set_stream_information(INSTANCE, stream_info)

end

-- print welcome message
gcs:send_text(MAV_SEVERITY.INFO, "Loaded set_VIDEO_STREAM_INFOMRATION.lua")

return set_video_stream_information()

0 comments on commit f8cf45b

Please sign in to comment.