/* 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_LightWareSerial.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_LightWareSerial::AP_RangeFinder_LightWareSerial(RangeFinder::RangeFinder_State &_state, AP_SerialManager &serial_manager, uint8_t serial_instance) : AP_RangeFinder_Backend(_state) { 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 Lightware 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_LightWareSerial::detect(AP_SerialManager &serial_manager, uint8_t serial_instance) { return serial_manager.find_serial(AP_SerialManager::SerialProtocol_Rangefinder, serial_instance) != nullptr; } // read - return last value measured by sensor bool AP_RangeFinder_LightWareSerial::get_reading(uint16_t &reading_cm) { if (uart == nullptr) { return false; } // read any available lines from the lidar float sum = 0; uint16_t count = 0; int16_t nbytes = uart->available(); while (nbytes-- > 0) { char c = uart->read(); if (c == '\r') { linebuf[linebuf_len] = 0; sum += (float)atof(linebuf); count++; linebuf_len = 0; } else if (isdigit(c) || c == '.') { linebuf[linebuf_len++] = c; if (linebuf_len == sizeof(linebuf)) { // too long, discard the line linebuf_len = 0; } } } uint32_t now = AP_HAL::millis(); if (last_init_ms == 0 || (now - last_init_ms > 1000 && now - last_reading_ms > 1000)) { // send enough serial transitions to trigger LW20 into serial // mode. It starts in dual I2C/serial mode, and wants to see // enough transitions to switch into serial mode. uart->write("www\r\n"); last_init_ms = now; } else { uart->write('d'); } if (count == 0) { return false; } reading_cm = 100 * sum / count; return true; } /* update the state of the sensor */ void AP_RangeFinder_LightWareSerial::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); } }