diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_uLanding.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_uLanding.cpp
new file mode 100644
index 0000000000..db1681439c
--- /dev/null
+++ b/libraries/AP_RangeFinder/AP_RangeFinder_uLanding.cpp
@@ -0,0 +1,104 @@
+// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
+/*
+ This program is free software: you can redistribute it and/or modify
+ it under the terms of the GNU General Public License as published by
+ the Free Software Foundation, either version 3 of the License, or
+ (at your option) any later version.
+
+ This program is distributed in the hope that it will be useful,
+ but WITHOUT ANY WARRANTY; without even the implied warranty of
+ MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ GNU General Public License for more details.
+
+ You should have received a copy of the GNU General Public License
+ along with this program. If not, see .
+ */
+
+#include
+#include "AP_RangeFinder_uLanding.h"
+#include
+#include
+
+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 &_ranger, uint8_t instance,
+ RangeFinder::RangeFinder_State &_state,
+ AP_SerialManager &serial_manager) :
+ AP_RangeFinder_Backend(_ranger, instance, _state)
+{
+ uart = serial_manager.find_serial(AP_SerialManager::SerialProtocol_Aerotenna_uLanding, 0);
+ if (uart != nullptr) {
+ uart->begin(serial_manager.find_baudrate(AP_SerialManager::SerialProtocol_Aerotenna_uLanding, 0));
+ }
+}
+
+/*
+ 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(RangeFinder &_ranger, uint8_t instance, AP_SerialManager &serial_manager)
+{
+ return serial_manager.find_serial(AP_SerialManager::SerialProtocol_Aerotenna_uLanding, 0) != nullptr;
+}
+
+// read - return last value measured by sensor
+bool AP_RangeFinder_uLanding::get_reading(uint16_t &reading_cm)
+{
+ if (uart == nullptr) {
+ return false;
+ }
+
+ // read any available lines from the uLanding
+ float sum = 0;
+ uint16_t count = 0;
+ uint8_t index = 0;
+
+ int16_t nbytes = uart->available();
+ while (nbytes-- > 0) {
+ uint8_t c = uart->read();
+ // ok, we have located start byte
+ if ( c == 72 && index ==0 ) {
+ linebuf_len = 0;
+ index = 1;
+ }
+ // now it is ready to decode index information
+ if ( index == 1 ){
+ linebuf[linebuf_len] = c;
+ linebuf_len ++;
+ if ( linebuf_len == 3 ){
+ index = 0;
+ sum += ( linebuf[2]&0x7F ) *128 + ( linebuf[1]&0x7F );
+ linebuf_len = 0;
+ count ++;
+ }
+ }
+
+ }
+
+ if (count == 0) {
+ return false;
+ }
+ //reading_cm = 4.5 * sum / count;
+ reading_cm = 2.5 * sum / count;
+ return true;
+}
+
+/*
+ update the state of the sensor
+*/
+void AP_RangeFinder_uLanding::update(void)
+{
+ if (get_reading(state.distance_cm)) {
+ // update range_valid state based on distance measured
+ last_reading_ms = AP_HAL::millis();
+ update_status();
+ } else if (AP_HAL::millis() - last_reading_ms > 200) {
+ set_status(RangeFinder::RangeFinder_NoData);
+ }
+}
diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_uLanding.h b/libraries/AP_RangeFinder/AP_RangeFinder_uLanding.h
new file mode 100644
index 0000000000..a97604c9ae
--- /dev/null
+++ b/libraries/AP_RangeFinder/AP_RangeFinder_uLanding.h
@@ -0,0 +1,31 @@
+// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
+#pragma once
+
+#include "RangeFinder.h"
+#include "RangeFinder_Backend.h"
+
+class AP_RangeFinder_uLanding : public AP_RangeFinder_Backend
+{
+
+public:
+ // constructor
+ AP_RangeFinder_uLanding(RangeFinder &ranger, uint8_t instance, RangeFinder::RangeFinder_State &_state,
+ AP_SerialManager &serial_manager);
+
+ // static detection function
+ static bool detect(RangeFinder &ranger, uint8_t instance, AP_SerialManager &serial_manager);
+
+ // update state
+ void update(void);
+
+private:
+ // get a reading
+ bool get_reading(uint16_t &reading_cm);
+
+ AP_HAL::UARTDriver *uart = nullptr;
+ uint32_t last_reading_ms = 0;
+ uint8_t linebuf[10];
+ uint8_t linebuf_len = 0;
+};
+
+
diff --git a/libraries/AP_RangeFinder/RangeFinder.cpp b/libraries/AP_RangeFinder/RangeFinder.cpp
index f7fff08be1..9d5362d531 100644
--- a/libraries/AP_RangeFinder/RangeFinder.cpp
+++ b/libraries/AP_RangeFinder/RangeFinder.cpp
@@ -25,6 +25,7 @@
#include "AP_RangeFinder_Bebop.h"
#include "AP_RangeFinder_MAVLink.h"
#include "AP_RangeFinder_LeddarOne.h"
+#include "AP_RangeFinder_uLanding.h"
#include
extern const AP_HAL::HAL &hal;
@@ -637,6 +638,13 @@ void RangeFinder::detect_instance(uint8_t instance)
return;
}
}
+ if (type == RangeFinder_TYPE_ULANDING) {
+ if (AP_RangeFinder_uLanding::detect(*this, instance, serial_manager)) {
+ state[instance].instance = instance;
+ drivers[instance] = new AP_RangeFinder_uLanding(*this, instance, state[instance], serial_manager);
+ return;
+ }
+ }
#if (CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BEBOP || \
CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_DISCO) && defined(HAVE_LIBIIO)
if (type == RangeFinder_TYPE_BEBOP) {
diff --git a/libraries/AP_RangeFinder/RangeFinder.h b/libraries/AP_RangeFinder/RangeFinder.h
index a5e9257a8f..e00fcb57d8 100644
--- a/libraries/AP_RangeFinder/RangeFinder.h
+++ b/libraries/AP_RangeFinder/RangeFinder.h
@@ -48,6 +48,7 @@ public:
RangeFinder_TYPE_LWSER = 8,
RangeFinder_TYPE_BEBOP = 9,
RangeFinder_TYPE_MAVLink = 10,
+ RangeFinder_TYPE_ULANDING= 11,
RangeFinder_TYPE_LEDDARONE = 12
};