AP_Scripting: Add binding for AP_Camera::set_stream_information()

This commit is contained in:
Nick Exton 2024-08-08 17:02:37 +10:00 committed by Randy Mackay
parent cb620126b3
commit 2989d623bd
3 changed files with 161 additions and 0 deletions

View File

@ -1549,6 +1549,118 @@ function mavlink_camera_information_t_ud:gimbal_device_id(value) end
---@param cam_info mavlink_camera_information_t_ud
function camera:set_camera_information(instance, cam_info) end
-- The MAVLink VIDEO_STREAM_INFORMATION message struct
---@class (exact) mavlink_video_stream_information_t_ud
local mavlink_video_stream_information_t_ud = {}
---@return mavlink_video_stream_information_t_ud
function mavlink_video_stream_information_t() end
-- get field
---@return number
function mavlink_video_stream_information_t_ud:framerate() end
-- set field
---@param value number
function mavlink_video_stream_information_t_ud:framerate(value) end
-- get field
---@return uint32_t_ud
function mavlink_video_stream_information_t_ud:bitrate() end
-- set field
---@param value uint32_t_ud|integer|number
function mavlink_video_stream_information_t_ud:bitrate(value) end
-- get field
---@return integer
function mavlink_video_stream_information_t_ud:flags() end
-- set field
---@param value integer
function mavlink_video_stream_information_t_ud:flags(value) end
-- get field
---@return integer
function mavlink_video_stream_information_t_ud:resolution_h() end
-- set field
---@param value integer
function mavlink_video_stream_information_t_ud:resolution_h(value) end
-- get field
---@return integer
function mavlink_video_stream_information_t_ud:resolution_v() end
-- set field
---@param value integer
function mavlink_video_stream_information_t_ud:resolution_v(value) end
-- get field
---@return integer
function mavlink_video_stream_information_t_ud:rotation() end
-- set field
---@param value integer
function mavlink_video_stream_information_t_ud:rotation(value) end
-- get field
---@return integer
function mavlink_video_stream_information_t_ud:hfov() end
-- set field
---@param value integer
function mavlink_video_stream_information_t_ud:hfov(value) end
-- get field
---@return integer
function mavlink_video_stream_information_t_ud:stream_id() end
-- set field
---@param value integer
function mavlink_video_stream_information_t_ud:stream_id(value) end
-- get field
---@return integer
function mavlink_video_stream_information_t_ud:count() end
-- set field
---@param value integer
function mavlink_video_stream_information_t_ud:count(value) end
-- get field
---@return integer
function mavlink_video_stream_information_t_ud:type() end
-- set field
---@param value integer
function mavlink_video_stream_information_t_ud:type(value) end
-- get array field
---@param index integer
---@return integer
function mavlink_video_stream_information_t_ud:name(index) end
-- set array field
---@param index integer
---@param value integer
function mavlink_video_stream_information_t_ud:name(index, value) end
-- get array field
---@param index integer
---@return integer
function mavlink_video_stream_information_t_ud:uri(index) end
-- set array field
---@param index integer
---@param value integer
function mavlink_video_stream_information_t_ud:uri(index, value) end
-- Populate the fields of the VIDEO_STREAM_INFORMATION message
---@param instance integer
---@param stream_info mavlink_video_stream_information_t_ud
function camera:set_stream_information(instance, stream_info) end
-- desc
mount = {}

View File

@ -0,0 +1,33 @@
--[[
Populate the fields of the VIDEO_STREAM_INFORMATION message sent by the selected camera instance.
--]]
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
for i = 0, #name do
stream_info:name(i, name:byte(i+1))
end
for i = 0, #uri do
stream_info:uri(i, uri:byte(i+1))
end
camera:set_stream_information(INSTANCE, stream_info)
end
return set_video_stream_information()

View File

@ -794,6 +794,20 @@ userdata mavlink_camera_information_t field lens_id uint8_t'skip_check read writ
userdata mavlink_camera_information_t field cam_definition_uri'array 140 uint8_t'skip_check read write
userdata mavlink_camera_information_t field gimbal_device_id uint8_t'skip_check read write
userdata mavlink_video_stream_information_t depends AP_CAMERA_INFO_FROM_SCRIPT_ENABLED
userdata mavlink_video_stream_information_t field framerate float'skip_check read write
userdata mavlink_video_stream_information_t field bitrate uint32_t'skip_check read write
userdata mavlink_video_stream_information_t field flags uint16_t'skip_check read write
userdata mavlink_video_stream_information_t field resolution_h uint16_t'skip_check read write
userdata mavlink_video_stream_information_t field resolution_v uint16_t'skip_check read write
userdata mavlink_video_stream_information_t field rotation uint16_t'skip_check read write
userdata mavlink_video_stream_information_t field hfov uint16_t'skip_check read write
userdata mavlink_video_stream_information_t field stream_id uint8_t'skip_check read write
userdata mavlink_video_stream_information_t field count uint8_t'skip_check read write
userdata mavlink_video_stream_information_t field type uint8_t'skip_check read write
userdata mavlink_video_stream_information_t field name'array 32 uint8_t'skip_check read write
userdata mavlink_video_stream_information_t field uri'array 160 uint8_t'skip_check read write
include AP_Camera/AP_Camera.h
singleton AP_Camera depends AP_CAMERA_ENABLED && (AP_CAMERA_SCRIPTING_ENABLED == 1)
singleton AP_Camera rename camera
@ -815,6 +829,8 @@ singleton AP_Camera method get_state boolean uint8_t'skip_check AP_Camera::camer
singleton AP_Camera method change_setting boolean uint8_t'skip_check CameraSetting'enum CameraSetting::THERMAL_PALETTE CameraSetting::THERMAL_RAW_DATA float'skip_check
singleton AP_Camera method set_camera_information void uint8_t'skip_check mavlink_camera_information_t
singleton AP_Camera method set_camera_information depends AP_CAMERA_INFO_FROM_SCRIPT_ENABLED
singleton AP_Camera method set_stream_information void uint8_t'skip_check mavlink_video_stream_information_t
singleton AP_Camera method set_stream_information depends AP_CAMERA_INFO_FROM_SCRIPT_ENABLED
include AP_Winch/AP_Winch.h
singleton AP_Winch depends AP_WINCH_ENABLED && APM_BUILD_COPTER_OR_HELI