mirror of https://github.com/ArduPilot/ardupilot
AP_Mount: Siyi inherits from serial backend
This commit is contained in:
parent
1e777390b2
commit
790b5e8565
|
@ -5,7 +5,6 @@
|
|||
#include <AP_AHRS/AP_AHRS.h>
|
||||
#include <GCS_MAVLink/GCS.h>
|
||||
#include <GCS_MAVLink/include/mavlink/v2.0/checksum.h>
|
||||
#include <AP_SerialManager/AP_SerialManager.h>
|
||||
#include <AP_RTC/AP_RTC.h>
|
||||
|
||||
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()
|
||||
{
|
||||
|
|
|
@ -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)
|
||||
|
|
Loading…
Reference in New Issue