mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-01 13:38:38 -04:00
GCS_MAVLink: add SEND_FOV_STATUS support
This commit is contained in:
parent
2235a8e063
commit
8a791d6082
@ -998,6 +998,7 @@ ap_message GCS_MAVLINK::mavlink_id_to_ap_message_id(const uint32_t mavlink_id) c
|
||||
{ MAVLINK_MSG_ID_CAMERA_FEEDBACK, MSG_CAMERA_FEEDBACK},
|
||||
{ MAVLINK_MSG_ID_CAMERA_INFORMATION, MSG_CAMERA_INFORMATION},
|
||||
{ MAVLINK_MSG_ID_CAMERA_SETTINGS, MSG_CAMERA_SETTINGS},
|
||||
{ MAVLINK_MSG_ID_CAMERA_FOV_STATUS, MSG_CAMERA_FOV_STATUS},
|
||||
#endif
|
||||
#if HAL_MOUNT_ENABLED
|
||||
{ MAVLINK_MSG_ID_GIMBAL_DEVICE_ATTITUDE_STATUS, MSG_GIMBAL_DEVICE_ATTITUDE_STATUS},
|
||||
@ -5775,6 +5776,18 @@ bool GCS_MAVLINK::try_send_message(const enum ap_message id)
|
||||
camera->send_camera_settings(chan);
|
||||
}
|
||||
break;
|
||||
#if AP_CAMERA_SEND_FOV_STATUS_ENABLED
|
||||
case MSG_CAMERA_FOV_STATUS:
|
||||
{
|
||||
AP_Camera *camera = AP::camera();
|
||||
if (camera == nullptr) {
|
||||
break;
|
||||
}
|
||||
CHECK_PAYLOAD_SIZE(CAMERA_FOV_STATUS);
|
||||
camera->send_camera_fov_status(chan);
|
||||
}
|
||||
break;
|
||||
#endif
|
||||
#endif
|
||||
|
||||
case MSG_SYSTEM_TIME:
|
||||
|
@ -51,6 +51,7 @@ enum ap_message : uint8_t {
|
||||
MSG_CAMERA_FEEDBACK,
|
||||
MSG_CAMERA_INFORMATION,
|
||||
MSG_CAMERA_SETTINGS,
|
||||
MSG_CAMERA_FOV_STATUS,
|
||||
MSG_GIMBAL_DEVICE_ATTITUDE_STATUS,
|
||||
MSG_GIMBAL_MANAGER_INFORMATION,
|
||||
MSG_GIMBAL_MANAGER_STATUS,
|
||||
|
Loading…
Reference in New Issue
Block a user