From 6a46ccf01906bd60f3cacbd1199b904c653c393a Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Mon, 25 Oct 2021 08:14:40 +1100 Subject: [PATCH] AP_Beacon: have nooploop use base-class uart instance --- libraries/AP_Beacon/AP_Beacon_Nooploop.cpp | 16 ++++++++-------- libraries/AP_Beacon/AP_Beacon_Nooploop.h | 1 - 2 files changed, 8 insertions(+), 9 deletions(-) diff --git a/libraries/AP_Beacon/AP_Beacon_Nooploop.cpp b/libraries/AP_Beacon/AP_Beacon_Nooploop.cpp index 8a6c67dee9..2bd1d819b9 100644 --- a/libraries/AP_Beacon/AP_Beacon_Nooploop.cpp +++ b/libraries/AP_Beacon/AP_Beacon_Nooploop.cpp @@ -53,14 +53,14 @@ bool AP_Beacon_Nooploop::healthy() void AP_Beacon_Nooploop::update(void) { // return immediately if not serial port - if (_uart == nullptr) { + if (uart == nullptr) { return; } // check uart for any incoming messages - uint32_t nbytes = MIN(_uart->available(), 1024U); + uint32_t nbytes = MIN(uart->available(), 1024U); while (nbytes-- > 0) { - int16_t b = _uart->read(); + int16_t b = uart->read(); if (b >= 0 ) { MsgType type = parse_byte((uint8_t)b); if (type == MsgType::NODE_FRAME2) { @@ -80,13 +80,13 @@ void AP_Beacon_Nooploop::update(void) void AP_Beacon_Nooploop::request_setting() { //send setting_frame0 to tag, tag will fill anchor position and ack - _uart->write((uint8_t)0x54); - _uart->write((uint8_t)0); - _uart->write((uint8_t)1); + uart->write((uint8_t)0x54); + uart->write((uint8_t)0); + uart->write((uint8_t)1); for (uint8_t i = 0; i < 124; i++) { - _uart->write((uint8_t)0); //manual states filled with any char, but in fact only 0 works + uart->write((uint8_t)0); //manual states filled with any char, but in fact only 0 works } - _uart->write((uint8_t)0x55); + uart->write((uint8_t)0x55); } // process one byte received on serial port diff --git a/libraries/AP_Beacon/AP_Beacon_Nooploop.h b/libraries/AP_Beacon/AP_Beacon_Nooploop.h index 9952529f71..ab42713e0c 100644 --- a/libraries/AP_Beacon/AP_Beacon_Nooploop.h +++ b/libraries/AP_Beacon/AP_Beacon_Nooploop.h @@ -48,7 +48,6 @@ private: } _state = ParseState::HEADER; // members - AP_HAL::UARTDriver *_uart; // pointer to uart configured for use with nooploop uint8_t _msgbuf[NOOPLOOP_MSG_BUF_MAX]; // buffer to hold most recent message from tag uint16_t _msg_len; // number of bytes received from the current message (may be larger than size of _msgbuf) uint16_t _frame_len; // message supplied frame length