APM:Libraries
AP_RangeFinder_MaxsonarSerialLV.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2016 Intel Corporation. All rights reserved.
3  *
4  * This file is free software: you can redistribute it and/or modify it
5  * under the terms of the GNU General Public License as published by the
6  * Free Software Foundation, either version 3 of the License, or
7  * (at your option) any later version.
8  *
9  * This file is distributed in the hope that it will be useful, but
10  * WITHOUT ANY WARRANTY; without even the implied warranty of
11  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
12  * See the GNU General Public License for more details.
13  *
14  * You should have received a copy of the GNU General Public License along
15  * with this program. If not, see <http://www.gnu.org/licenses/>.
16  */
17 
18 #include <AP_HAL/AP_HAL.h>
20 #include <ctype.h>
22 
23 #define MAXSONAR_SERIAL_LV_BAUD_RATE 9600
24 
25 extern const AP_HAL::HAL& hal;
26 
27 /*
28  The constructor also initialises the rangefinder. Note that this
29  constructor is not called until detect() returns true, so we
30  already know that we should setup the rangefinder
31 */
34  uint8_t serial_instance) :
36 {
37  uart = serial_manager.find_serial(AP_SerialManager::SerialProtocol_Rangefinder, serial_instance);
38  if (uart != nullptr) {
39  uart->begin(serial_manager.find_baudrate(AP_SerialManager::SerialProtocol_Rangefinder, serial_instance));
40  }
41 }
42 
43 /*
44  detect if a MaxSonar rangefinder is connected. We'll detect by
45  trying to take a reading on Serial. If we get a result the sensor is
46  there.
47 */
49 {
50  return serial_manager.find_serial(AP_SerialManager::SerialProtocol_Rangefinder, serial_instance) != nullptr;
51 }
52 
53 // read - return last value measured by sensor
55 {
56  if (uart == nullptr) {
57  return false;
58  }
59 
60  int32_t sum = 0;
61  int16_t nbytes = uart->available();
62  uint16_t count = 0;
63 
64  while (nbytes-- > 0) {
65  char c = uart->read();
66  if (c == '\r') {
67  linebuf[linebuf_len] = 0;
68  sum += (int)atoi(linebuf);
69  count++;
70  linebuf_len = 0;
71  } else if (isdigit(c)) {
72  linebuf[linebuf_len++] = c;
73  if (linebuf_len == sizeof(linebuf)) {
74  // too long, discard the line
75  linebuf_len = 0;
76  }
77  }
78  }
79 
80  if (count == 0) {
81  return false;
82  }
83 
84  // This sonar gives the metrics in inches, so we have to transform this to centimeters
85  reading_cm = 2.54f * sum / count;
86 
87  return true;
88 }
89 
90 /*
91  update the state of the sensor
92 */
94 {
96  // update range_valid state based on distance measured
98  update_status();
99  } else if (AP_HAL::millis() - last_reading_ms > 500) {
101  }
102 }
static AP_SerialManager serial_manager
Definition: AHRS_Test.cpp:24
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: AC_PID_test.cpp:14
static bool detect(AP_SerialManager &serial_manager, uint8_t serial_instance)
virtual void begin(uint32_t baud)=0
uint32_t find_baudrate(enum SerialProtocol protocol, uint8_t instance) const
AP_RangeFinder_MaxsonarSerialLV(RangeFinder::RangeFinder_State &_state, AP_SerialManager &serial_manager, uint8_t serial_instance)
uint32_t millis()
Definition: system.cpp:157
virtual int16_t read()=0
virtual uint32_t available()=0
void set_status(RangeFinder::RangeFinder_Status status)
RangeFinder::RangeFinder_State & state
AP_HAL::UARTDriver * find_serial(enum SerialProtocol protocol, uint8_t instance) const