From d59ff8501cfe2e96fe487984ee40a47838ba4bd4 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Mon, 28 Aug 2023 20:27:06 +0900 Subject: [PATCH] AP_Mount: Siyi loses unused definitions --- libraries/AP_Mount/AP_Mount_Siyi.cpp | 2 -- 1 file changed, 2 deletions(-) diff --git a/libraries/AP_Mount/AP_Mount_Siyi.cpp b/libraries/AP_Mount/AP_Mount_Siyi.cpp index d91ca6558b..299169d160 100644 --- a/libraries/AP_Mount/AP_Mount_Siyi.cpp +++ b/libraries/AP_Mount/AP_Mount_Siyi.cpp @@ -13,8 +13,6 @@ extern const AP_HAL::HAL& hal; #define AP_MOUNT_SIYI_HEADER2 0x66 // second header byte #define AP_MOUNT_SIYI_PACKETLEN_MIN 10 // minimum number of bytes in a packet. this is a packet with no data bytes #define AP_MOUNT_SIYI_DATALEN_MAX (AP_MOUNT_SIYI_PACKETLEN_MAX-AP_MOUNT_SIYI_PACKETLEN_MIN) // max bytes for data portion of packet -#define AP_MOUNT_SIYI_SERIAL_RESEND_MS 1000 // resend angle targets to gimbal once per second -#define AP_MOUNT_SIYI_MSG_BUF_DATA_START 8 // data starts at this byte in _msg_buf #define AP_MOUNT_SIYI_RATE_MAX_RADS radians(90) // maximum physical rotation rate of gimbal in radans/sec #define AP_MOUNT_SIYI_PITCH_P 1.50 // pitch controller P gain (converts pitch angle error to target rate) #define AP_MOUNT_SIYI_YAW_P 1.50 // yaw controller P gain (converts yaw angle error to target rate)