APM:Libraries
AP_RangeFinder_analog.cpp
Go to the documentation of this file.
1 /*
2  This program is free software: you can redistribute it and/or modify
3  it under the terms of the GNU General Public License as published by
4  the Free Software Foundation, either version 3 of the License, or
5  (at your option) any later version.
6 
7  This program is distributed in the hope that it will be useful,
8  but WITHOUT ANY WARRANTY; without even the implied warranty of
9  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
10  GNU General Public License for more details.
11 
12  You should have received a copy of the GNU General Public License
13  along with this program. If not, see <http://www.gnu.org/licenses/>.
14  */
15 
16 /*
17  * AP_RangeFinder_analog.cpp - rangefinder for analog source
18  *
19  */
20 
21 #include <AP_HAL/AP_HAL.h>
22 #include <AP_Common/AP_Common.h>
23 #include <AP_Math/AP_Math.h>
24 #include "RangeFinder.h"
25 #include "AP_RangeFinder_analog.h"
26 
27 extern const AP_HAL::HAL& hal;
28 
29 /*
30  The constructor also initialises the rangefinder. Note that this
31  constructor is not called until detect() returns true, so we
32  already know that we should setup the rangefinder
33 */
36 {
37  source = hal.analogin->channel(_state.pin);
38  if (source == nullptr) {
39  // failed to allocate a ADC channel? This shouldn't happen
41  return;
42  }
43  source->set_stop_pin((uint8_t)_state.stop_pin);
44  source->set_settle_time((uint16_t)_state.settle_time_ms);
46 }
47 
48 /*
49  detect if an analog rangefinder is connected. The only thing we
50  can do is check if the pin number is valid. If it is, then assume
51  that the device is connected
52 */
54 {
55  if (_state.pin != -1) {
56  return true;
57  }
58  return false;
59 }
60 
61 
62 /*
63  update raw voltage state
64  */
66 {
67  if (source == nullptr) {
68  state.voltage_mv = 0;
69  return;
70  }
71  // cope with changed settings
73  source->set_stop_pin((uint8_t)state.stop_pin);
75  if (state.ratiometric) {
77  } else {
79  }
80 }
81 
82 /*
83  update distance_cm
84  */
86 {
88  float v = state.voltage_mv * 0.001f;
89  float dist_m = 0;
90  float scaling = state.scaling;
91  float offset = state.offset;
93  int16_t _max_distance_cm = state.max_distance_cm;
94 
95  switch (function) {
97  dist_m = (v - offset) * scaling;
98  break;
99 
101  dist_m = (offset - v) * scaling;
102  break;
103 
105  if (v <= offset) {
106  dist_m = 0;
107  } else {
108  dist_m = scaling / (v - offset);
109  }
110  if (isinf(dist_m) || dist_m > _max_distance_cm * 0.01f) {
111  dist_m = _max_distance_cm * 0.01f;
112  }
113  break;
114  }
115  if (dist_m < 0) {
116  dist_m = 0;
117  }
118  state.distance_cm = dist_m * 100.0f;
119 
120  // update range_valid state based on distance measured
121  update_status();
122 }
123 
float scaling
Definition: AnalogIn.cpp:40
virtual float voltage_average()=0
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: AC_PID_test.cpp:14
virtual void set_settle_time(uint16_t settle_time_ms)=0
virtual void set_stop_pin(uint8_t p)=0
static bool detect(RangeFinder::RangeFinder_State &_state)
float v
Definition: Printf.cpp:15
Common definitions and utility routines for the ArduPilot libraries.
AP_RangeFinder_analog(RangeFinder::RangeFinder_State &_state)
void set_status(RangeFinder::RangeFinder_Status status)
RangeFinder::RangeFinder_State & state
virtual void set_pin(uint8_t p)=0
virtual float voltage_average_ratiometric()=0
AP_HAL::AnalogSource * source
AP_HAL::AnalogIn * analogin
Definition: HAL.h:108
virtual AP_HAL::AnalogSource * channel(int16_t n)=0