From 78e072686a414035cc3a46dcc17b1b12ddcc2de0 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Mon, 24 Apr 2023 13:59:55 +0900 Subject: [PATCH] GCS_MAVLink: support requests for gimbal-manager-information --- libraries/GCS_MAVLink/GCS.h | 1 + libraries/GCS_MAVLink/GCS_Common.cpp | 19 ++++++++++++++++++- libraries/GCS_MAVLink/ap_message.h | 1 + 3 files changed, 20 insertions(+), 1 deletion(-) diff --git a/libraries/GCS_MAVLink/GCS.h b/libraries/GCS_MAVLink/GCS.h index 23363283a75b1..4bbbcf9b6449b 100644 --- a/libraries/GCS_MAVLink/GCS.h +++ b/libraries/GCS_MAVLink/GCS.h @@ -371,6 +371,7 @@ class GCS_MAVLINK void send_vfr_hud(); void send_vibration() const; void send_gimbal_device_attitude_status() const; + void send_gimbal_manager_information() const; void send_named_float(const char *name, float value) const; void send_home_position() const; void send_gps_global_origin() const; diff --git a/libraries/GCS_MAVLink/GCS_Common.cpp b/libraries/GCS_MAVLink/GCS_Common.cpp index 5409998fc5a27..7e9b8f2c5c3fe 100644 --- a/libraries/GCS_MAVLink/GCS_Common.cpp +++ b/libraries/GCS_MAVLink/GCS_Common.cpp @@ -989,6 +989,7 @@ ap_message GCS_MAVLINK::mavlink_id_to_ap_message_id(const uint32_t mavlink_id) c #if HAL_MOUNT_ENABLED { MAVLINK_MSG_ID_GIMBAL_DEVICE_ATTITUDE_STATUS, MSG_GIMBAL_DEVICE_ATTITUDE_STATUS}, { MAVLINK_MSG_ID_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE, MSG_AUTOPILOT_STATE_FOR_GIMBAL_DEVICE}, + { MAVLINK_MSG_ID_GIMBAL_MANAGER_INFORMATION, MSG_GIMBAL_MANAGER_INFORMATION}, #endif #if AP_OPTICALFLOW_ENABLED { MAVLINK_MSG_ID_OPTICAL_FLOW, MSG_OPTICAL_FLOW}, @@ -5324,6 +5325,17 @@ void GCS_MAVLINK::send_gimbal_device_attitude_status() const } #endif +#if HAL_MOUNT_ENABLED +void GCS_MAVLINK::send_gimbal_manager_information() const +{ + AP_Mount *mount = AP::mount(); + if (mount == nullptr) { + return; + } + mount->send_gimbal_manager_information(chan); +} +#endif + void GCS_MAVLINK::send_set_position_target_global_int(uint8_t target_system, uint8_t target_component, const Location& loc) { @@ -5648,7 +5660,12 @@ bool GCS_MAVLINK::try_send_message(const enum ap_message id) send_autopilot_state_for_gimbal_device(); #endif break; - + case MSG_GIMBAL_MANAGER_INFORMATION: +#if HAL_MOUNT_ENABLED + CHECK_PAYLOAD_SIZE(GIMBAL_MANAGER_INFORMATION); + send_gimbal_manager_information(); +#endif + break; case MSG_OPTICAL_FLOW: #if AP_OPTICALFLOW_ENABLED CHECK_PAYLOAD_SIZE(OPTICAL_FLOW); diff --git a/libraries/GCS_MAVLink/ap_message.h b/libraries/GCS_MAVLink/ap_message.h index 532c476273a8a..9179c4b90b072 100644 --- a/libraries/GCS_MAVLink/ap_message.h +++ b/libraries/GCS_MAVLink/ap_message.h @@ -50,6 +50,7 @@ enum ap_message : uint8_t { MSG_BATTERY2, MSG_CAMERA_FEEDBACK, MSG_GIMBAL_DEVICE_ATTITUDE_STATUS, + MSG_GIMBAL_MANAGER_INFORMATION, MSG_OPTICAL_FLOW, MSG_MAG_CAL_PROGRESS, MSG_MAG_CAL_REPORT,