diff --git a/libraries/GCS_MAVLink/GCS.h b/libraries/GCS_MAVLink/GCS.h index 94e5c67444..a16015a481 100644 --- a/libraries/GCS_MAVLink/GCS.h +++ b/libraries/GCS_MAVLink/GCS.h @@ -298,7 +298,6 @@ public: void send_vibration() const; void send_mount_status() const; void send_named_float(const char *name, float value) const; - void send_gimbal_report() const; void send_home_position() const; void send_gps_global_origin() const; virtual void send_attitude_target() {}; diff --git a/libraries/GCS_MAVLink/GCS_Common.cpp b/libraries/GCS_MAVLink/GCS_Common.cpp index a3082eff8b..75b6a7c647 100644 --- a/libraries/GCS_MAVLink/GCS_Common.cpp +++ b/libraries/GCS_MAVLink/GCS_Common.cpp @@ -892,7 +892,6 @@ 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_MOUNT_STATUS, MSG_MOUNT_STATUS}, { MAVLINK_MSG_ID_OPTICAL_FLOW, MSG_OPTICAL_FLOW}, - { MAVLINK_MSG_ID_GIMBAL_REPORT, MSG_GIMBAL_REPORT}, { MAVLINK_MSG_ID_MAG_CAL_PROGRESS, MSG_MAG_CAL_PROGRESS}, { MAVLINK_MSG_ID_MAG_CAL_REPORT, MSG_MAG_CAL_REPORT}, { MAVLINK_MSG_ID_EKF_STATUS_REPORT, MSG_EKF_STATUS_REPORT}, @@ -5040,17 +5039,6 @@ void GCS_MAVLINK::send_global_position_int() ahrs.yaw_sensor); // compass heading in 1/100 degree } -void GCS_MAVLINK::send_gimbal_report() const -{ -#if HAL_MOUNT_ENABLED - AP_Mount *mount = AP::mount(); - if (mount == nullptr) { - return; - } - mount->send_gimbal_report(chan); -#endif -} - void GCS_MAVLINK::send_mount_status() const { #if HAL_MOUNT_ENABLED @@ -5201,11 +5189,6 @@ bool GCS_MAVLINK::try_send_message(const enum ap_message id) queued_param_send(); break; - case MSG_GIMBAL_REPORT: - CHECK_PAYLOAD_SIZE(GIMBAL_REPORT); - send_gimbal_report(); - break; - case MSG_HEARTBEAT: CHECK_PAYLOAD_SIZE(HEARTBEAT); last_heartbeat_time = AP_HAL::millis(); diff --git a/libraries/GCS_MAVLink/ap_message.h b/libraries/GCS_MAVLink/ap_message.h index 7e314fe69e..ea6a6474f3 100644 --- a/libraries/GCS_MAVLink/ap_message.h +++ b/libraries/GCS_MAVLink/ap_message.h @@ -51,7 +51,6 @@ enum ap_message : uint8_t { MSG_CAMERA_FEEDBACK, MSG_MOUNT_STATUS, MSG_OPTICAL_FLOW, - MSG_GIMBAL_REPORT, MSG_MAG_CAL_PROGRESS, MSG_MAG_CAL_REPORT, MSG_EKF_STATUS_REPORT,