mirror of https://github.com/ArduPilot/ardupilot
AP_RangeFinder: move uLanding to using common serial backend
This commit is contained in:
parent
9829a1d08b
commit
b18f1a8e22
|
@ -15,44 +15,13 @@
|
|||
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#include "AP_RangeFinder_uLanding.h"
|
||||
#include <AP_SerialManager/AP_SerialManager.h>
|
||||
#include <ctype.h>
|
||||
|
||||
#define ULANDING_HDR 254 // Header Byte from uLanding (0xFE)
|
||||
#define ULANDING_HDR_V0 72 // Header Byte for beta V0 of uLanding (0x48)
|
||||
|
||||
#define ULANDING_BAUD 115200
|
||||
#define ULANDING_BUFSIZE_RX 128
|
||||
#define ULANDING_BUFSIZE_TX 128
|
||||
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
||||
/*
|
||||
The constructor also initialises the rangefinder. Note that this
|
||||
constructor is not called until detect() returns true, so we
|
||||
already know that we should setup the rangefinder
|
||||
*/
|
||||
AP_RangeFinder_uLanding::AP_RangeFinder_uLanding(RangeFinder::RangeFinder_State &_state,
|
||||
AP_RangeFinder_Params &_params,
|
||||
uint8_t serial_instance) :
|
||||
AP_RangeFinder_Backend(_state, _params)
|
||||
{
|
||||
uart = AP::serialmanager().find_serial(AP_SerialManager::SerialProtocol_Rangefinder, serial_instance);
|
||||
if (uart != nullptr) {
|
||||
uart->begin(ULANDING_BAUD, ULANDING_BUFSIZE_RX, ULANDING_BUFSIZE_TX);
|
||||
}
|
||||
}
|
||||
|
||||
/*
|
||||
detect if a uLanding rangefinder is connected. We'll detect by
|
||||
trying to take a reading on Serial. If we get a result the sensor is
|
||||
there.
|
||||
*/
|
||||
bool AP_RangeFinder_uLanding::detect(uint8_t serial_instance)
|
||||
{
|
||||
return AP::serialmanager().find_serial(AP_SerialManager::SerialProtocol_Rangefinder, serial_instance) != nullptr;
|
||||
}
|
||||
|
||||
/*
|
||||
detect uLanding Firmware Version
|
||||
*/
|
||||
|
|
|
@ -1,19 +1,14 @@
|
|||
#pragma once
|
||||
|
||||
#include "RangeFinder.h"
|
||||
#include "RangeFinder_Backend.h"
|
||||
#include "RangeFinder_Backend_Serial.h"
|
||||
|
||||
class AP_RangeFinder_uLanding : public AP_RangeFinder_Backend
|
||||
class AP_RangeFinder_uLanding : public AP_RangeFinder_Backend_Serial
|
||||
{
|
||||
|
||||
public:
|
||||
// constructor
|
||||
AP_RangeFinder_uLanding(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;
|
||||
|
@ -24,6 +19,14 @@ protected:
|
|||
return MAV_DISTANCE_SENSOR_RADAR;
|
||||
}
|
||||
|
||||
// baudrate used during object construction:
|
||||
uint32_t initial_baudrate(uint8_t serial_instance) const override {
|
||||
return 115200;
|
||||
}
|
||||
|
||||
uint16_t rx_bufsize() const override { return 128; }
|
||||
uint16_t tx_bufsize() const override { return 128; }
|
||||
|
||||
private:
|
||||
// detect uLanding Firmware Version
|
||||
bool detect_version(void);
|
||||
|
@ -31,7 +34,6 @@ private:
|
|||
// get a reading
|
||||
bool get_reading(uint16_t &reading_cm);
|
||||
|
||||
AP_HAL::UARTDriver *uart;
|
||||
uint8_t _linebuf[6];
|
||||
uint8_t _linebuf_len;
|
||||
bool _version_known;
|
||||
|
|
|
@ -34,7 +34,7 @@ AP_RangeFinder_Backend_Serial::AP_RangeFinder_Backend_Serial(
|
|||
{
|
||||
uart = AP::serialmanager().find_serial(AP_SerialManager::SerialProtocol_Rangefinder, serial_instance);
|
||||
if (uart != nullptr) {
|
||||
uart->begin(initial_baudrate(serial_instance));
|
||||
uart->begin(initial_baudrate(serial_instance), rx_bufsize(), tx_bufsize());
|
||||
}
|
||||
}
|
||||
|
||||
|
|
|
@ -18,5 +18,9 @@ protected:
|
|||
// baudrate used during object construction:
|
||||
virtual uint32_t initial_baudrate(uint8_t serial_instance) const;
|
||||
|
||||
// the value 0 is special to the UARTDriver - it's "use default"
|
||||
virtual uint16_t rx_bufsize() const { return 0; }
|
||||
virtual uint16_t tx_bufsize() const { return 0; }
|
||||
|
||||
AP_HAL::UARTDriver *uart = nullptr;
|
||||
};
|
||||
|
|
Loading…
Reference in New Issue