123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103 |
- /*
- * 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 <http://www.gnu.org/licenses/>.
- */
- #include <AP_HAL/AP_HAL.h>
- #include <AP_SerialManager/AP_SerialManager.h>
- #include <ctype.h>
- #include "AP_RangeFinder_MaxsonarSerialLV.h"
- #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::RangeFinder_State &_state,
- AP_RangeFinder_Params &_params,
- uint8_t serial_instance) :
- AP_RangeFinder_Backend(_state, _params)
- {
- 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 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(uint8_t serial_instance)
- {
- return AP::serialmanager().find_serial(AP_SerialManager::SerialProtocol_Rangefinder, serial_instance) != 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;
- 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.54f * 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
- state.last_reading_ms = AP_HAL::millis();
- update_status();
- } else if (AP_HAL::millis() - state.last_reading_ms > 500) {
- set_status(RangeFinder::RangeFinder_NoData);
- }
- }
|