From 148fa03d6b38e66a1c9b04e6cf7355bbafaad8e1 Mon Sep 17 00:00:00 2001 From: Ricardo de Almeida Gonzaga Date: Tue, 19 Apr 2016 18:32:17 -0300 Subject: [PATCH] AP_RangeFinder: support MaxBotix Serial rangefinders MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit This has been tested with LV-MaxSonar®-EZ1 MB1010 --- .../AP_RangeFinder_MaxsonarSerialLV.cpp | 111 ++++++++++++++++++ .../AP_RangeFinder_MaxsonarSerialLV.h | 29 +++++ libraries/AP_RangeFinder/RangeFinder.cpp | 16 ++- libraries/AP_RangeFinder/RangeFinder.h | 3 +- 4 files changed, 154 insertions(+), 5 deletions(-) create mode 100644 libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarSerialLV.cpp create mode 100644 libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarSerialLV.h diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarSerialLV.cpp b/libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarSerialLV.cpp new file mode 100644 index 0000000000..330daffede --- /dev/null +++ b/libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarSerialLV.cpp @@ -0,0 +1,111 @@ +// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- +/* + * Copyright (C) 2016 Intel Corporation. All rights reserved. + * + * This file 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 file 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_MaxsonarSerialLV.h" +#include +#include + +#define MAXSONAR_SERIAL_LV_BAUD_RATE 9600 + +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_MaxsonarSerialLV::AP_RangeFinder_MaxsonarSerialLV(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_Lidar, 0); + if (uart != nullptr) { + uart->begin(serial_manager.find_baudrate(AP_SerialManager::SerialProtocol_Lidar, 0)); + } +} + +/* + detect if a MaxSonar 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_MaxsonarSerialLV::detect(RangeFinder &_ranger, uint8_t instance, AP_SerialManager &serial_manager) +{ + return serial_manager.find_serial(AP_SerialManager::SerialProtocol_Lidar, 0) != nullptr; +} + +// read - return last value measured by sensor +bool AP_RangeFinder_MaxsonarSerialLV::get_reading(uint16_t &reading_cm) +{ + if (uart == nullptr) { + return false; + } + + int32_t sum = 0; + int16_t nbytes = uart->available(); + uint16_t count = 0; + + /* MaxSonarSeriaLV might need a manual reconection */ + if (nbytes == 0) { + uart->end(); + uart->begin(MAXSONAR_SERIAL_LV_BAUD_RATE); + nbytes = uart->available(); + } + + while (nbytes-- > 0) { + char c = uart->read(); + if (c == '\r') { + linebuf[linebuf_len] = 0; + sum += (int)atoi(linebuf); + count++; + linebuf_len = 0; + } else if (isdigit(c)) { + linebuf[linebuf_len++] = c; + if (linebuf_len == sizeof(linebuf)) { + // too long, discard the line + linebuf_len = 0; + } + } + } + + + if (count == 0) { + return false; + } + + // This sonar gives the metrics in inches, so we have to transform this to centimeters + reading_cm = 2.54 * sum / count; + + return true; +} + +/* + update the state of the sensor +*/ +void AP_RangeFinder_MaxsonarSerialLV::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 > 500) { + set_status(RangeFinder::RangeFinder_NoData); + } +} diff --git a/libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarSerialLV.h b/libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarSerialLV.h new file mode 100644 index 0000000000..76c9cf9df9 --- /dev/null +++ b/libraries/AP_RangeFinder/AP_RangeFinder_MaxsonarSerialLV.h @@ -0,0 +1,29 @@ +// -*- 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_MaxsonarSerialLV : public AP_RangeFinder_Backend +{ + +public: + // constructor + AP_RangeFinder_MaxsonarSerialLV(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; + char linebuf[10]; + uint8_t linebuf_len = 0; +}; diff --git a/libraries/AP_RangeFinder/RangeFinder.cpp b/libraries/AP_RangeFinder/RangeFinder.cpp index 9d5362d531..0f4435975a 100644 --- a/libraries/AP_RangeFinder/RangeFinder.cpp +++ b/libraries/AP_RangeFinder/RangeFinder.cpp @@ -17,6 +17,7 @@ #include "AP_RangeFinder_analog.h" #include "AP_RangeFinder_PulsedLightLRF.h" #include "AP_RangeFinder_MaxsonarI2CXL.h" +#include "AP_RangeFinder_MaxsonarSerialLV.h" #include "AP_RangeFinder_PX4.h" #include "AP_RangeFinder_PX4_PWM.h" #include "AP_RangeFinder_BBB_PRU.h" @@ -35,7 +36,7 @@ const AP_Param::GroupInfo RangeFinder::var_info[] = { // @Param: _TYPE // @DisplayName: Rangefinder type // @Description: What type of rangefinder device that is connected - // @Values: 0:None,1:Analog,2:MaxbotixI2C,3:PulsedLightI2C,4:PX4-I2C,5:PX4-PWM,6:BBB-PRU,7:LightWareI2C,8:LightWareSerial,9:Bebop,10:MAVLink,12:LeddarOne + // @Values: 0:None,1:Analog,2:MaxbotixI2C,3:PulsedLightI2C,4:PX4-I2C,5:PX4-PWM,6:BBB-PRU,7:LightWareI2C,8:LightWareSerial,9:Bebop,10:MAVLink,12:LeddarOne,13:MaxbotixSerial // @User: Standard AP_GROUPINFO("_TYPE", 0, RangeFinder, _type[0], 0), @@ -155,7 +156,7 @@ const AP_Param::GroupInfo RangeFinder::var_info[] = { // @Param: 2_TYPE // @DisplayName: Second Rangefinder type // @Description: What type of rangefinder device that is connected - // @Values: 0:None,1:Analog,2:MaxbotixI2C,3:PulsedLightI2C,4:PX4-I2C,5:PX4-PWM,6:BBB-PRU,7:LightWareI2C,8:LightWareSerial,9:Bebop,10:MAVLink,12:LeddarOne + // @Values: 0:None,1:Analog,2:MaxbotixI2C,3:PulsedLightI2C,4:PX4-I2C,5:PX4-PWM,6:BBB-PRU,7:LightWareI2C,8:LightWareSerial,9:Bebop,10:MAVLink,12:LeddarOne,13:MaxbotixSerial // @User: Advanced AP_GROUPINFO("2_TYPE", 12, RangeFinder, _type[1], 0), @@ -270,7 +271,7 @@ const AP_Param::GroupInfo RangeFinder::var_info[] = { // @Param: 3_TYPE // @DisplayName: Third Rangefinder type // @Description: What type of rangefinder device that is connected - // @Values: 0:None,1:Analog,2:APM2-MaxbotixI2C,3:APM2-PulsedLightI2C,4:PX4-I2C,5:PX4-PWM,6:BBB-PRU,7:LightWareI2C,8:LightWareSerial,9:Bebop,10:MAVLink,12:LeddarOne + // @Values: 0:None,1:Analog,2:APM2-MaxbotixI2C,3:APM2-PulsedLightI2C,4:PX4-I2C,5:PX4-PWM,6:BBB-PRU,7:LightWareI2C,8:LightWareSerial,9:Bebop,10:MAVLink,12:LeddarOne,13:MaxbotixSerial // @User: Advanced AP_GROUPINFO("3_TYPE", 25, RangeFinder, _type[2], 0), @@ -385,7 +386,7 @@ const AP_Param::GroupInfo RangeFinder::var_info[] = { // @Param: 4_TYPE // @DisplayName: Fourth Rangefinder type // @Description: What type of rangefinder device that is connected - // @Values: 0:None,1:Analog,2:APM2-MaxbotixI2C,3:APM2-PulsedLightI2C,4:PX4-I2C,5:PX4-PWM,6:BBB-PRU,7:LightWareI2C,8:LightWareSerial,9:Bebop,10:MAVLink,12:LeddarOne + // @Values: 0:None,1:Analog,2:APM2-MaxbotixI2C,3:APM2-PulsedLightI2C,4:PX4-I2C,5:PX4-PWM,6:BBB-PRU,7:LightWareI2C,8:LightWareSerial,9:Bebop,10:MAVLink,12:LeddarOne,13:MaxbotixSerial // @User: Advanced AP_GROUPINFO("4_TYPE", 37, RangeFinder, _type[3], 0), @@ -662,6 +663,13 @@ void RangeFinder::detect_instance(uint8_t instance) return; } } + if (type == RangeFinder_TYPE_MBSER) { + if (AP_RangeFinder_MaxsonarSerialLV::detect(*this, instance, serial_manager)) { + state[instance].instance = instance; + drivers[instance] = new AP_RangeFinder_MaxsonarSerialLV(*this, instance, state[instance], serial_manager); + return; + } + } if (type == RangeFinder_TYPE_ANALOG) { // note that analog must be the last to be checked, as it will // always come back as present if the pin is valid diff --git a/libraries/AP_RangeFinder/RangeFinder.h b/libraries/AP_RangeFinder/RangeFinder.h index e00fcb57d8..f13eb1bbd3 100644 --- a/libraries/AP_RangeFinder/RangeFinder.h +++ b/libraries/AP_RangeFinder/RangeFinder.h @@ -49,7 +49,8 @@ public: RangeFinder_TYPE_BEBOP = 9, RangeFinder_TYPE_MAVLink = 10, RangeFinder_TYPE_ULANDING= 11, - RangeFinder_TYPE_LEDDARONE = 12 + RangeFinder_TYPE_LEDDARONE = 12, + RangeFinder_TYPE_MBSER = 13 }; enum RangeFinder_Function {