From 2b7c61e9a1a14228488d24e09f56aec5560966d8 Mon Sep 17 00:00:00 2001 From: gomavlib-bot Date: Wed, 4 Sep 2024 05:18:49 +0000 Subject: [PATCH] (automatic) update dialects to rev https://github.com/mavlink/mavlink/tree/ad6fab510fe35f0f5673faaeb6c594800f33853d --- pkg/dialects/common/message_camera_capture_status.go | 2 ++ pkg/dialects/common/message_camera_fov_status.go | 2 ++ pkg/dialects/common/message_camera_information.go | 2 +- pkg/dialects/common/message_camera_settings.go | 2 ++ pkg/dialects/common/message_camera_tracking_geo_status.go | 2 ++ pkg/dialects/common/message_camera_tracking_image_status.go | 2 ++ pkg/dialects/common/message_video_stream_information.go | 2 ++ pkg/dialects/common/message_video_stream_status.go | 2 ++ 8 files changed, 15 insertions(+), 1 deletion(-) diff --git a/pkg/dialects/common/message_camera_capture_status.go b/pkg/dialects/common/message_camera_capture_status.go index 2f3201a98..79874eaf0 100644 --- a/pkg/dialects/common/message_camera_capture_status.go +++ b/pkg/dialects/common/message_camera_capture_status.go @@ -18,6 +18,8 @@ type MessageCameraCaptureStatus struct { AvailableCapacity float32 // Total number of images captured ('forever', or until reset using MAV_CMD_STORAGE_FORMAT). ImageCount int32 `mavext:"true"` + // Camera id of a non-MAVLink camera attached to an autopilot (1-6). 0 if the component is a MAVLink camera (with its own component id). + CameraDeviceId uint8 `mavext:"true"` } // GetID implements the message.Message interface. diff --git a/pkg/dialects/common/message_camera_fov_status.go b/pkg/dialects/common/message_camera_fov_status.go index e2137158a..32ecd6282 100644 --- a/pkg/dialects/common/message_camera_fov_status.go +++ b/pkg/dialects/common/message_camera_fov_status.go @@ -24,6 +24,8 @@ type MessageCameraFovStatus struct { Hfov float32 // Vertical field of view (NaN if unknown). Vfov float32 + // Camera id of a non-MAVLink camera attached to an autopilot (1-6). 0 if the component is a MAVLink camera (with its own component id). + CameraDeviceId uint8 `mavext:"true"` } // GetID implements the message.Message interface. diff --git a/pkg/dialects/common/message_camera_information.go b/pkg/dialects/common/message_camera_information.go index 20083f817..ca6488fad 100644 --- a/pkg/dialects/common/message_camera_information.go +++ b/pkg/dialects/common/message_camera_information.go @@ -32,7 +32,7 @@ type MessageCameraInformation struct { CamDefinitionUri string `mavlen:"140"` // Gimbal id of a gimbal associated with this camera. This is the component id of the gimbal device, or 1-6 for non mavlink gimbals. Use 0 if no gimbal is associated with the camera. GimbalDeviceId uint8 `mavext:"true"` - // Camera id of a camera associated with this component. This is the component id of a proxied MAVLink camera, or 1-6 for a non-MAVLink camera attached to the component. Use 0 if the component is a camera (not something else providing access to a camera). + // Camera id of a non-MAVLink camera attached to an autopilot (1-6). 0 if the component is a MAVLink camera (with its own component id). CameraDeviceId uint8 `mavext:"true"` } diff --git a/pkg/dialects/common/message_camera_settings.go b/pkg/dialects/common/message_camera_settings.go index af734b601..bd3efbf11 100644 --- a/pkg/dialects/common/message_camera_settings.go +++ b/pkg/dialects/common/message_camera_settings.go @@ -12,6 +12,8 @@ type MessageCameraSettings struct { Zoomlevel float32 `mavext:"true" mavname:"zoomLevel"` // Current focus level as a percentage of the full range (0.0 to 100.0, NaN if not known) Focuslevel float32 `mavext:"true" mavname:"focusLevel"` + // Camera id of a non-MAVLink camera attached to an autopilot (1-6). 0 if the component is a MAVLink camera (with its own component id). + CameraDeviceId uint8 `mavext:"true"` } // GetID implements the message.Message interface. diff --git a/pkg/dialects/common/message_camera_tracking_geo_status.go b/pkg/dialects/common/message_camera_tracking_geo_status.go index 52a5d7c2b..0b1a6f40d 100644 --- a/pkg/dialects/common/message_camera_tracking_geo_status.go +++ b/pkg/dialects/common/message_camera_tracking_geo_status.go @@ -30,6 +30,8 @@ type MessageCameraTrackingGeoStatus struct { Hdg float32 // Accuracy of heading, in NED. NAN if unknown HdgAcc float32 + // Camera id of a non-MAVLink camera attached to an autopilot (1-6). 0 if the component is a MAVLink camera (with its own component id). + CameraDeviceId uint8 `mavext:"true"` } // GetID implements the message.Message interface. diff --git a/pkg/dialects/common/message_camera_tracking_image_status.go b/pkg/dialects/common/message_camera_tracking_image_status.go index d7b9c7110..9db8a0a7e 100644 --- a/pkg/dialects/common/message_camera_tracking_image_status.go +++ b/pkg/dialects/common/message_camera_tracking_image_status.go @@ -24,6 +24,8 @@ type MessageCameraTrackingImageStatus struct { RecBottomX float32 // Current tracked rectangle bottom y value if CAMERA_TRACKING_MODE_RECTANGLE (normalized 0..1, 0 is top, 1 is bottom), NAN if unknown RecBottomY float32 + // Camera id of a non-MAVLink camera attached to an autopilot (1-6). 0 if the component is a MAVLink camera (with its own component id). + CameraDeviceId uint8 `mavext:"true"` } // GetID implements the message.Message interface. diff --git a/pkg/dialects/common/message_video_stream_information.go b/pkg/dialects/common/message_video_stream_information.go index 5de6990bc..141a854a7 100644 --- a/pkg/dialects/common/message_video_stream_information.go +++ b/pkg/dialects/common/message_video_stream_information.go @@ -30,6 +30,8 @@ type MessageVideoStreamInformation struct { Uri string `mavlen:"160"` // Encoding of stream. Encoding VIDEO_STREAM_ENCODING `mavenum:"uint8" mavext:"true"` + // Camera id of a non-MAVLink camera attached to an autopilot (1-6). 0 if the component is a MAVLink camera (with its own component id). + CameraDeviceId uint8 `mavext:"true"` } // GetID implements the message.Message interface. diff --git a/pkg/dialects/common/message_video_stream_status.go b/pkg/dialects/common/message_video_stream_status.go index d3a14d71d..c0de3cb45 100644 --- a/pkg/dialects/common/message_video_stream_status.go +++ b/pkg/dialects/common/message_video_stream_status.go @@ -20,6 +20,8 @@ type MessageVideoStreamStatus struct { Rotation uint16 // Horizontal Field of view Hfov uint16 + // Camera id of a non-MAVLink camera attached to an autopilot (1-6). 0 if the component is a MAVLink camera (with its own component id). + CameraDeviceId uint8 `mavext:"true"` } // GetID implements the message.Message interface.