mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-11 17:13:56 -03:00
AP_Mount: Viewpro inherits from serial backend
This commit is contained in:
parent
790b5e8565
commit
7fc00efe7e
@ -7,7 +7,6 @@
|
|||||||
#include <AP_RTC/AP_RTC.h>
|
#include <AP_RTC/AP_RTC.h>
|
||||||
#include <GCS_MAVLink/GCS.h>
|
#include <GCS_MAVLink/GCS.h>
|
||||||
#include <GCS_MAVLink/include/mavlink/v2.0/checksum.h>
|
#include <GCS_MAVLink/include/mavlink/v2.0/checksum.h>
|
||||||
#include <AP_SerialManager/AP_SerialManager.h>
|
|
||||||
|
|
||||||
extern const AP_HAL::HAL& hal;
|
extern const AP_HAL::HAL& hal;
|
||||||
|
|
||||||
@ -28,20 +27,6 @@ extern const AP_HAL::HAL& hal;
|
|||||||
|
|
||||||
const char* AP_Mount_Viewpro::send_text_prefix = "Viewpro:";
|
const char* AP_Mount_Viewpro::send_text_prefix = "Viewpro:";
|
||||||
|
|
||||||
// init - performs any required initialisation for this instance
|
|
||||||
void AP_Mount_Viewpro::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
|
// update mount position - should be called periodically
|
||||||
void AP_Mount_Viewpro::update()
|
void AP_Mount_Viewpro::update()
|
||||||
{
|
{
|
||||||
|
@ -16,7 +16,7 @@
|
|||||||
|
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
#include "AP_Mount_Backend.h"
|
#include "AP_Mount_Backend_Serial.h"
|
||||||
|
|
||||||
#if HAL_MOUNT_VIEWPRO_ENABLED
|
#if HAL_MOUNT_VIEWPRO_ENABLED
|
||||||
|
|
||||||
@ -27,19 +27,16 @@
|
|||||||
|
|
||||||
#define AP_MOUNT_VIEWPRO_PACKETLEN_MAX 63 // maximum number of bytes in a packet sent to or received from the gimbal
|
#define AP_MOUNT_VIEWPRO_PACKETLEN_MAX 63 // maximum number of bytes in a packet sent to or received from the gimbal
|
||||||
|
|
||||||
class AP_Mount_Viewpro : public AP_Mount_Backend
|
class AP_Mount_Viewpro : public AP_Mount_Backend_Serial
|
||||||
{
|
{
|
||||||
|
|
||||||
public:
|
public:
|
||||||
// Constructor
|
// Constructor
|
||||||
using AP_Mount_Backend::AP_Mount_Backend;
|
using AP_Mount_Backend_Serial::AP_Mount_Backend_Serial;
|
||||||
|
|
||||||
/* Do not allow copies */
|
/* Do not allow copies */
|
||||||
CLASS_NO_COPY(AP_Mount_Viewpro);
|
CLASS_NO_COPY(AP_Mount_Viewpro);
|
||||||
|
|
||||||
// init - performs any required initialisation for this instance
|
|
||||||
void init() override;
|
|
||||||
|
|
||||||
// update mount position - should be called periodically
|
// update mount position - should be called periodically
|
||||||
void update() override;
|
void update() override;
|
||||||
|
|
||||||
@ -378,8 +375,6 @@ private:
|
|||||||
bool send_m_ahrs();
|
bool send_m_ahrs();
|
||||||
|
|
||||||
// internal variables
|
// internal variables
|
||||||
AP_HAL::UARTDriver *_uart; // uart connected to gimbal
|
|
||||||
bool _initialised; // true once the driver has been initialised
|
|
||||||
uint8_t _msg_buff[AP_MOUNT_VIEWPRO_PACKETLEN_MAX]; // buffer holding latest bytes from gimbal
|
uint8_t _msg_buff[AP_MOUNT_VIEWPRO_PACKETLEN_MAX]; // buffer holding latest bytes from gimbal
|
||||||
uint8_t _msg_buff_len; // number of bytes held in msg buff
|
uint8_t _msg_buff_len; // number of bytes held in msg buff
|
||||||
const uint8_t _msg_buff_data_start = 2; // data starts at this byte of _msg_buff
|
const uint8_t _msg_buff_data_start = 2; // data starts at this byte of _msg_buff
|
||||||
|
Loading…
Reference in New Issue
Block a user