AP_RangeFinder: make NMEA backend use new intermediate class

This commit is contained in:
Peter Barker 2019-11-01 17:19:39 +11:00 committed by Peter Barker
parent 82268ab12c
commit 15d3a59d67
2 changed files with 7 additions and 37 deletions

View File

@ -13,36 +13,13 @@
along with this program. If not, see <http://www.gnu.org/licenses/>.
*/
#include <AP_HAL/AP_HAL.h>
#include "AP_RangeFinder_LightWareSerial.h"
#include <AP_SerialManager/AP_SerialManager.h>
#include <ctype.h>
#include "AP_RangeFinder_NMEA.h"
#include <AP_HAL/AP_HAL.h>
#include <ctype.h>
extern const AP_HAL::HAL& hal;
// constructor initialises the rangefinder
// Note this is called after detect() returns true, so we
// already know that we should setup the rangefinder
AP_RangeFinder_NMEA::AP_RangeFinder_NMEA(RangeFinder::RangeFinder_State &_state,
AP_RangeFinder_Params &_params,
uint8_t serial_instance) :
AP_RangeFinder_Backend(_state, _params),
_distance_m(-1.0f)
{
const AP_SerialManager &serial_manager = AP::serialmanager();
uart = serial_manager.find_serial(AP_SerialManager::SerialProtocol_Rangefinder, serial_instance);
if (uart != nullptr) {
uart->begin(serial_manager.find_baudrate(AP_SerialManager::SerialProtocol_Rangefinder, serial_instance));
}
}
// detect if a NMEA rangefinder by looking to see if the user has configured it
bool AP_RangeFinder_NMEA::detect(uint8_t serial_instance)
{
return AP::serialmanager().find_serial(AP_SerialManager::SerialProtocol_Rangefinder, serial_instance) != nullptr;
}
// update the state of the sensor
void AP_RangeFinder_NMEA::update(void)
{

View File

@ -16,19 +16,14 @@
#pragma once
#include "RangeFinder.h"
#include "RangeFinder_Backend.h"
#include "RangeFinder_Backend_Serial.h"
class AP_RangeFinder_NMEA : public AP_RangeFinder_Backend
class AP_RangeFinder_NMEA : public AP_RangeFinder_Backend_Serial
{
public:
// constructor
AP_RangeFinder_NMEA(RangeFinder::RangeFinder_State &_state,
AP_RangeFinder_Params &_params,
uint8_t serial_instance);
// static detection function
static bool detect(uint8_t serial_instance);
using AP_RangeFinder_Backend_Serial::AP_RangeFinder_Backend_Serial;
// update state
void update(void) override;
@ -60,13 +55,11 @@ private:
// returns true if new sentence has just passed checksum test and is validated
bool decode_latest_term();
AP_HAL::UARTDriver *uart = nullptr; // pointer to serial uart
// message decoding related members
char _term[15]; // buffer for the current term within the current sentence
uint8_t _term_offset; // offset within the _term buffer where the next character should be placed
uint8_t _term_number; // term index within the current sentence
float _distance_m; // distance in meters parsed from a term, -1 if no distance
float _distance_m = -1.0f; // distance in meters parsed from a term, -1 if no distance
uint8_t _checksum; // checksum accumulator
bool _term_is_checksum; // current term is the checksum
sentence_types _sentence_type; // the sentence type currently being processed