mirror of https://github.com/ArduPilot/ardupilot
AP_Scripting: Add binding for AP_Camera::set_camera_information()
This commit is contained in:
parent
55de48b60a
commit
e6ac9c3108
|
@ -1419,6 +1419,136 @@ function camera:get_state(instance) end
|
|||
---@return boolean
|
||||
function camera:change_setting(instance, setting, value) end
|
||||
|
||||
-- The MAVLink CAMERA_INFORMATION message struct
|
||||
---@class (exact) mavlink_camera_information_t_ud
|
||||
local mavlink_camera_information_t_ud = {}
|
||||
|
||||
---@return mavlink_camera_information_t_ud
|
||||
function mavlink_camera_information_t() end
|
||||
|
||||
-- get field
|
||||
---@return uint32_t_ud
|
||||
function mavlink_camera_information_t_ud:time_boot_ms() end
|
||||
|
||||
-- set field
|
||||
---@param value uint32_t_ud|integer|number
|
||||
function mavlink_camera_information_t_ud:time_boot_ms(value) end
|
||||
|
||||
-- get field
|
||||
---@return uint32_t_ud
|
||||
function mavlink_camera_information_t_ud:firmware_version() end
|
||||
|
||||
-- set field
|
||||
---@param value uint32_t_ud|integer|number
|
||||
function mavlink_camera_information_t_ud:firmware_version(value) end
|
||||
|
||||
-- get field
|
||||
---@return number
|
||||
function mavlink_camera_information_t_ud:focal_length() end
|
||||
|
||||
-- set field
|
||||
---@param value number
|
||||
function mavlink_camera_information_t_ud:focal_length(value) end
|
||||
|
||||
-- get field
|
||||
---@return number
|
||||
function mavlink_camera_information_t_ud:sensor_size_h() end
|
||||
|
||||
-- set field
|
||||
---@param value number
|
||||
function mavlink_camera_information_t_ud:sensor_size_h(value) end
|
||||
|
||||
-- get field
|
||||
---@return number
|
||||
function mavlink_camera_information_t_ud:sensor_size_v() end
|
||||
|
||||
-- set field
|
||||
---@param value number
|
||||
function mavlink_camera_information_t_ud:sensor_size_v(value) end
|
||||
|
||||
-- get field
|
||||
---@return uint32_t_ud
|
||||
function mavlink_camera_information_t_ud:flags() end
|
||||
|
||||
-- set field
|
||||
---@param value uint32_t_ud|integer|number
|
||||
function mavlink_camera_information_t_ud:flags(value) end
|
||||
|
||||
-- get field
|
||||
---@return integer
|
||||
function mavlink_camera_information_t_ud:resolution_h() end
|
||||
|
||||
-- set field
|
||||
---@param value integer
|
||||
function mavlink_camera_information_t_ud:resolution_h(value) end
|
||||
|
||||
-- get field
|
||||
---@return integer
|
||||
function mavlink_camera_information_t_ud:resolution_v() end
|
||||
|
||||
-- set field
|
||||
---@param value integer
|
||||
function mavlink_camera_information_t_ud:resolution_v(value) end
|
||||
|
||||
-- get field
|
||||
---@return integer
|
||||
function mavlink_camera_information_t_ud:cam_definition_version() end
|
||||
|
||||
-- set field
|
||||
---@param value integer
|
||||
function mavlink_camera_information_t_ud:cam_definition_version(value) end
|
||||
|
||||
-- get array field
|
||||
---@param index integer
|
||||
---@return integer
|
||||
function mavlink_camera_information_t_ud:vendor_name(index) end
|
||||
|
||||
-- set array field
|
||||
---@param index integer
|
||||
---@param value integer
|
||||
function mavlink_camera_information_t_ud:vendor_name(index, value) end
|
||||
|
||||
-- get array field
|
||||
---@param index integer
|
||||
---@return integer
|
||||
function mavlink_camera_information_t_ud:model_name(index) end
|
||||
|
||||
-- set array field
|
||||
---@param index integer
|
||||
---@param value integer
|
||||
function mavlink_camera_information_t_ud:model_name(index, value) end
|
||||
|
||||
-- get field
|
||||
---@return integer
|
||||
function mavlink_camera_information_t_ud:lens_id() end
|
||||
|
||||
-- set field
|
||||
---@param value integer
|
||||
function mavlink_camera_information_t_ud:lens_id(value) end
|
||||
|
||||
-- get array field
|
||||
---@param index integer
|
||||
---@return integer
|
||||
function mavlink_camera_information_t_ud:cam_definition_uri(index) end
|
||||
|
||||
-- set array field
|
||||
---@param index integer
|
||||
---@param value integer
|
||||
function mavlink_camera_information_t_ud:cam_definition_uri(index, value) end
|
||||
|
||||
-- get field
|
||||
---@return integer
|
||||
function mavlink_camera_information_t_ud:gimbal_device_id() end
|
||||
|
||||
-- set field
|
||||
---@param value integer
|
||||
function mavlink_camera_information_t_ud:gimbal_device_id(value) end
|
||||
|
||||
-- Populate the fields of the CAMERA_INFORMATION message
|
||||
---@param instance integer
|
||||
---@param cam_info mavlink_camera_information_t_ud
|
||||
function camera:set_camera_information(instance, cam_info) end
|
||||
|
||||
-- desc
|
||||
mount = {}
|
||||
|
||||
|
|
|
@ -0,0 +1,38 @@
|
|||
--[[
|
||||
Populate the fields of the CAMERA_INFORMATION message sent by the selected camera instance.
|
||||
--]]
|
||||
function set_camera_information()
|
||||
-- set the Camera Information data
|
||||
local cam_info = mavlink_camera_information_t()
|
||||
|
||||
local INSTANCE = 0
|
||||
local vendor_name = 'Unknown'
|
||||
local model_name = 'Camera'
|
||||
local uri = ''
|
||||
|
||||
-- "time_boot_ms" is populated automatically by the camera backend
|
||||
for i = 0, #vendor_name do
|
||||
cam_info:vendor_name(i, vendor_name:byte(i+1))
|
||||
end
|
||||
for i = 0, #model_name do
|
||||
cam_info:model_name(i, model_name:byte(i+1))
|
||||
end
|
||||
cam_info:firmware_version(0)
|
||||
cam_info:focal_length(1.6)
|
||||
cam_info:sensor_size_h(3840)
|
||||
cam_info:sensor_size_v(2160)
|
||||
cam_info:resolution_h(1920)
|
||||
cam_info:resolution_v(1080)
|
||||
-- "lens_id" is populated automatically by the camera backend
|
||||
cam_info:flags(256) -- CAMERA_CAP_FLAGS_HAS_VIDEO_STREAM
|
||||
cam_info:cam_definition_version(0)
|
||||
for i = 0, #uri do
|
||||
cam_info:cam_definition_uri(i, uri:byte(i+1))
|
||||
end
|
||||
-- "gimbal_device_id" is populated automatically by the camera backend
|
||||
|
||||
camera:set_camera_information(INSTANCE, cam_info)
|
||||
|
||||
end
|
||||
|
||||
return set_camera_information()
|
|
@ -778,6 +778,22 @@ singleton AP_Mount method get_angle_target boolean uint8_t'skip_check float'Null
|
|||
singleton AP_Mount method get_location_target boolean uint8_t'skip_check Location'Null
|
||||
singleton AP_Mount method set_attitude_euler void uint8_t'skip_check float'skip_check float'skip_check float'skip_check
|
||||
|
||||
userdata mavlink_camera_information_t depends AP_CAMERA_INFO_FROM_SCRIPT_ENABLED
|
||||
userdata mavlink_camera_information_t field time_boot_ms uint32_t'skip_check read write
|
||||
userdata mavlink_camera_information_t field firmware_version uint32_t'skip_check read write
|
||||
userdata mavlink_camera_information_t field focal_length float'skip_check read write
|
||||
userdata mavlink_camera_information_t field sensor_size_h float'skip_check read write
|
||||
userdata mavlink_camera_information_t field sensor_size_v float'skip_check read write
|
||||
userdata mavlink_camera_information_t field flags uint32_t'skip_check read write
|
||||
userdata mavlink_camera_information_t field resolution_h uint16_t'skip_check read write
|
||||
userdata mavlink_camera_information_t field resolution_v uint16_t'skip_check read write
|
||||
userdata mavlink_camera_information_t field cam_definition_version uint16_t'skip_check read write
|
||||
userdata mavlink_camera_information_t field vendor_name'array 32 uint8_t'skip_check read write
|
||||
userdata mavlink_camera_information_t field model_name'array 32 uint8_t'skip_check read write
|
||||
userdata mavlink_camera_information_t field lens_id uint8_t'skip_check read write
|
||||
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
|
||||
|
||||
include AP_Camera/AP_Camera.h
|
||||
singleton AP_Camera depends AP_CAMERA_ENABLED && (AP_CAMERA_SCRIPTING_ENABLED == 1)
|
||||
singleton AP_Camera rename camera
|
||||
|
@ -797,6 +813,8 @@ userdata AP_Camera::camera_state_t field tracking_p1 Vector2f read
|
|||
userdata AP_Camera::camera_state_t field tracking_p2 Vector2f read
|
||||
singleton AP_Camera method get_state boolean uint8_t'skip_check AP_Camera::camera_state_t'Null
|
||||
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
|
||||
|
||||
include AP_Winch/AP_Winch.h
|
||||
singleton AP_Winch depends AP_WINCH_ENABLED && APM_BUILD_COPTER_OR_HELI
|
||||
|
|
Loading…
Reference in New Issue