From 790b5e85659851c227e4252a8879661087b5ebac Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Wed, 22 May 2024 10:13:27 +0900 Subject: [PATCH] AP_Mount: Siyi inherits from serial backend --- libraries/AP_Mount/AP_Mount_Siyi.cpp | 15 --------------- libraries/AP_Mount/AP_Mount_Siyi.h | 11 +++-------- 2 files changed, 3 insertions(+), 23 deletions(-) diff --git a/libraries/AP_Mount/AP_Mount_Siyi.cpp b/libraries/AP_Mount/AP_Mount_Siyi.cpp index 3f00d1caa0..77704637dc 100644 --- a/libraries/AP_Mount/AP_Mount_Siyi.cpp +++ b/libraries/AP_Mount/AP_Mount_Siyi.cpp @@ -5,7 +5,6 @@ #include #include #include -#include #include extern const AP_HAL::HAL& hal; @@ -32,20 +31,6 @@ const AP_Mount_Siyi::HWInfo AP_Mount_Siyi::hardware_lookup_table[] { {{'7','A'}, "ZT30"}, }; -// init - performs any required initialisation for this instance -void AP_Mount_Siyi::init() -{ - const AP_SerialManager& serial_manager = AP::serialmanager(); - - _uart = serial_manager.find_serial(AP_SerialManager::SerialProtocol_Gimbal, 0); - if (_uart == nullptr) { - return; - } - - _initialised = true; - AP_Mount_Backend::init(); -} - // update mount position - should be called periodically void AP_Mount_Siyi::update() { diff --git a/libraries/AP_Mount/AP_Mount_Siyi.h b/libraries/AP_Mount/AP_Mount_Siyi.h index 75a03efda3..c6366e6b29 100644 --- a/libraries/AP_Mount/AP_Mount_Siyi.h +++ b/libraries/AP_Mount/AP_Mount_Siyi.h @@ -19,7 +19,7 @@ #pragma once -#include "AP_Mount_Backend.h" +#include "AP_Mount_Backend_Serial.h" #if HAL_MOUNT_SIYI_ENABLED @@ -29,19 +29,16 @@ #define AP_MOUNT_SIYI_PACKETLEN_MAX 38 // maximum number of bytes in a packet sent to or received from the gimbal -class AP_Mount_Siyi : public AP_Mount_Backend +class AP_Mount_Siyi : public AP_Mount_Backend_Serial { public: // Constructor - using AP_Mount_Backend::AP_Mount_Backend; + using AP_Mount_Backend_Serial::AP_Mount_Backend_Serial; /* Do not allow copies */ CLASS_NO_COPY(AP_Mount_Siyi); - // init - performs any required initialisation for this instance - void init() override; - // update mount position - should be called periodically void update() override; @@ -293,8 +290,6 @@ private: void check_firmware_version() const; // internal variables - AP_HAL::UARTDriver *_uart; // uart connected to gimbal - bool _initialised; // true once the driver has been initialised bool _got_hardware_id; // true once hardware id ha been received FirmwareVersion _fw_version; // firmware version (for reporting for GCS)