Merge pull request #11198 from SteveCEvans/sce_rc2
[betaflight.git] / src / main / sensors / rangefinder.c
blobdde36b3d1f714ee7fe2718c7466c5c383a837319
1 /*
2 * This file is part of Cleanflight and Betaflight.
4 * Cleanflight and Betaflight are free software. You can redistribute
5 * this software and/or modify this software under the terms of the
6 * GNU General Public License as published by the Free Software
7 * Foundation, either version 3 of the License, or (at your option)
8 * any later version.
10 * Cleanflight and Betaflight are distributed in the hope that they
11 * will be useful, but WITHOUT ANY WARRANTY; without even the implied
12 * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
13 * See the GNU General Public License for more details.
15 * You should have received a copy of the GNU General Public License
16 * along with this software.
18 * If not, see <http://www.gnu.org/licenses/>.
21 #include <stdbool.h>
22 #include <stdint.h>
23 #include <string.h>
24 #include <math.h>
26 #include "platform.h"
28 #ifdef USE_RANGEFINDER
30 #include "build/build_config.h"
31 #include "build/debug.h"
33 #include "common/maths.h"
34 #include "common/time.h"
35 #include "common/utils.h"
37 #include "config/config.h"
38 #include "config/feature.h"
40 #include "drivers/io.h"
41 #include "drivers/rangefinder/rangefinder.h"
42 #include "drivers/rangefinder/rangefinder_hcsr04.h"
43 #include "drivers/rangefinder/rangefinder_lidartf.h"
44 #include "drivers/time.h"
46 #include "fc/runtime_config.h"
48 #include "pg/pg.h"
49 #include "pg/pg_ids.h"
51 #include "scheduler/scheduler.h"
53 #include "sensors/sensors.h"
54 #include "sensors/rangefinder.h"
55 #include "sensors/battery.h"
57 //#include "uav_interconnect/uav_interconnect.h"
59 // XXX Interface to CF/BF legacy(?) altitude estimation code.
60 // XXX Will be gone once iNav's estimator is ported.
61 int16_t rangefinderMaxRangeCm;
62 int16_t rangefinderMaxAltWithTiltCm;
63 int16_t rangefinderCfAltCm; // Complimentary Filter altitude
65 rangefinder_t rangefinder;
67 #define RANGEFINDER_HARDWARE_TIMEOUT_MS 500 // Accept 500ms of non-responsive sensor, report HW failure otherwise
69 #define RANGEFINDER_DYNAMIC_THRESHOLD 600 //Used to determine max. usable rangefinder disatance
70 #define RANGEFINDER_DYNAMIC_FACTOR 75
72 PG_REGISTER_WITH_RESET_TEMPLATE(rangefinderConfig_t, rangefinderConfig, PG_RANGEFINDER_CONFIG, 0);
74 PG_RESET_TEMPLATE(rangefinderConfig_t, rangefinderConfig,
75 .rangefinder_hardware = RANGEFINDER_NONE,
78 #ifdef USE_RANGEFINDER_HCSR04
79 PG_REGISTER_WITH_RESET_TEMPLATE(sonarConfig_t, sonarConfig, PG_SONAR_CONFIG, 1);
81 PG_RESET_TEMPLATE(sonarConfig_t, sonarConfig,
82 .triggerTag = IO_TAG(RANGEFINDER_HCSR04_TRIGGER_PIN),
83 .echoTag = IO_TAG(RANGEFINDER_HCSR04_ECHO_PIN),
85 #endif
88 * Detect which rangefinder is present
90 static bool rangefinderDetect(rangefinderDev_t * dev, uint8_t rangefinderHardwareToUse)
92 rangefinderType_e rangefinderHardware = RANGEFINDER_NONE;
93 requestedSensors[SENSOR_INDEX_RANGEFINDER] = rangefinderHardwareToUse;
95 switch (rangefinderHardwareToUse) {
96 case RANGEFINDER_HCSR04:
97 #ifdef USE_RANGEFINDER_HCSR04
99 if (hcsr04Detect(dev, sonarConfig())) { // FIXME: Do actual detection if HC-SR04 is plugged in
100 rangefinderHardware = RANGEFINDER_HCSR04;
101 rescheduleTask(TASK_RANGEFINDER, TASK_PERIOD_MS(RANGEFINDER_HCSR04_TASK_PERIOD_MS));
104 #endif
105 break;
107 case RANGEFINDER_TFMINI:
108 #if defined(USE_RANGEFINDER_TF)
109 if (lidarTFminiDetect(dev)) {
110 rangefinderHardware = RANGEFINDER_TFMINI;
111 rescheduleTask(TASK_RANGEFINDER, TASK_PERIOD_MS(RANGEFINDER_TF_TASK_PERIOD_MS));
113 #endif
114 break;
116 case RANGEFINDER_TF02:
117 #if defined(USE_RANGEFINDER_TF)
118 if (lidarTF02Detect(dev)) {
119 rangefinderHardware = RANGEFINDER_TF02;
120 rescheduleTask(TASK_RANGEFINDER, TASK_PERIOD_MS(RANGEFINDER_TF_TASK_PERIOD_MS));
122 #endif
123 break;
125 case RANGEFINDER_NONE:
126 rangefinderHardware = RANGEFINDER_NONE;
127 break;
130 if (rangefinderHardware == RANGEFINDER_NONE) {
131 sensorsClear(SENSOR_RANGEFINDER);
132 return false;
135 detectedSensors[SENSOR_INDEX_RANGEFINDER] = rangefinderHardware;
136 sensorsSet(SENSOR_RANGEFINDER);
137 return true;
140 void rangefinderResetDynamicThreshold(void)
142 rangefinder.snrThresholdReached = false;
143 rangefinder.dynamicDistanceThreshold = 0;
146 bool rangefinderInit(void)
148 if (!rangefinderDetect(&rangefinder.dev, rangefinderConfig()->rangefinder_hardware)) {
149 return false;
152 rangefinder.dev.init(&rangefinder.dev);
153 rangefinder.rawAltitude = RANGEFINDER_OUT_OF_RANGE;
154 rangefinder.calculatedAltitude = RANGEFINDER_OUT_OF_RANGE;
155 rangefinder.maxTiltCos = cos_approx(DECIDEGREES_TO_RADIANS(rangefinder.dev.detectionConeExtendedDeciDegrees / 2.0f));
156 rangefinder.lastValidResponseTimeMs = millis();
157 rangefinder.snr = 0;
159 rangefinderResetDynamicThreshold();
161 // XXX Interface to CF/BF legacy(?) altitude estimation code.
162 // XXX Will be gone once iNav's estimator is ported.
163 rangefinderMaxRangeCm = rangefinder.dev.maxRangeCm;
164 rangefinderMaxAltWithTiltCm = rangefinderMaxRangeCm * rangefinder.maxTiltCos;
165 rangefinderCfAltCm = rangefinder.dev.maxRangeCm / 2 ; // Complimentary Filter altitude
167 return true;
170 static int32_t applyMedianFilter(int32_t newReading)
172 #define DISTANCE_SAMPLES_MEDIAN 5
173 static int32_t filterSamples[DISTANCE_SAMPLES_MEDIAN];
174 static int filterSampleIndex = 0;
175 static bool medianFilterReady = false;
177 if (newReading > RANGEFINDER_OUT_OF_RANGE) {// only accept samples that are in range
178 filterSamples[filterSampleIndex] = newReading;
179 ++filterSampleIndex;
180 if (filterSampleIndex == DISTANCE_SAMPLES_MEDIAN) {
181 filterSampleIndex = 0;
182 medianFilterReady = true;
185 return medianFilterReady ? quickMedianFilter5(filterSamples) : newReading;
188 static int16_t computePseudoSnr(int32_t newReading) {
189 #define SNR_SAMPLES 5
190 static int16_t snrSamples[SNR_SAMPLES];
191 static uint8_t snrSampleIndex = 0;
192 static int32_t previousReading = RANGEFINDER_OUT_OF_RANGE;
193 static bool snrReady = false;
194 int16_t pseudoSnr = 0;
196 const int delta = newReading - previousReading;
197 snrSamples[snrSampleIndex] = constrain(delta * delta / 10, 0, 6400);
198 ++snrSampleIndex;
199 if (snrSampleIndex == SNR_SAMPLES) {
200 snrSampleIndex = 0;
201 snrReady = true;
204 previousReading = newReading;
206 if (snrReady) {
208 for (uint8_t i = 0; i < SNR_SAMPLES; i++) {
209 pseudoSnr += snrSamples[i];
212 return constrain(pseudoSnr, 0, 32000);
213 } else {
214 return RANGEFINDER_OUT_OF_RANGE;
219 * This is called periodically by the scheduler
221 void rangefinderUpdate(void)
223 if (rangefinder.dev.update) {
224 rangefinder.dev.update(&rangefinder.dev);
228 bool isSurfaceAltitudeValid() {
231 * Preconditions: raw and calculated altidude > 0
232 * SNR lower than threshold
234 if (
235 rangefinder.calculatedAltitude > 0 &&
236 rangefinder.rawAltitude > 0 &&
237 rangefinder.snr < RANGEFINDER_DYNAMIC_THRESHOLD
241 * When critical altitude was determined, distance reported by rangefinder
242 * has to be lower than it to assume healthy readout
244 if (rangefinder.snrThresholdReached) {
245 return (rangefinder.rawAltitude < rangefinder.dynamicDistanceThreshold);
246 } else {
247 return true;
250 } else {
251 return false;
257 * Get the last distance measured by the sonar in centimeters. When the ground is too far away, RANGEFINDER_OUT_OF_RANGE is returned.
259 bool rangefinderProcess(float cosTiltAngle)
261 if (rangefinder.dev.read) {
262 const int32_t distance = rangefinder.dev.read(&rangefinder.dev);
264 // If driver reported no new measurement - don't do anything
265 if (distance == RANGEFINDER_NO_NEW_DATA) {
266 return false;
269 if (distance >= 0) {
270 rangefinder.lastValidResponseTimeMs = millis();
271 rangefinder.rawAltitude = applyMedianFilter(distance);
272 } else if (distance == RANGEFINDER_OUT_OF_RANGE) {
273 rangefinder.lastValidResponseTimeMs = millis();
274 rangefinder.rawAltitude = RANGEFINDER_OUT_OF_RANGE;
276 else {
277 // Invalid response / hardware failure
278 rangefinder.rawAltitude = RANGEFINDER_HARDWARE_FAILURE;
281 rangefinder.snr = computePseudoSnr(distance);
283 if (rangefinder.snrThresholdReached == false && rangefinder.rawAltitude > 0) {
285 if (rangefinder.snr < RANGEFINDER_DYNAMIC_THRESHOLD && rangefinder.dynamicDistanceThreshold < rangefinder.rawAltitude) {
286 rangefinder.dynamicDistanceThreshold = rangefinder.rawAltitude * RANGEFINDER_DYNAMIC_FACTOR / 100;
289 if (rangefinder.snr >= RANGEFINDER_DYNAMIC_THRESHOLD) {
290 rangefinder.snrThresholdReached = true;
295 DEBUG_SET(DEBUG_RANGEFINDER, 3, rangefinder.snr);
297 DEBUG_SET(DEBUG_RANGEFINDER_QUALITY, 0, rangefinder.rawAltitude);
298 DEBUG_SET(DEBUG_RANGEFINDER_QUALITY, 1, rangefinder.snrThresholdReached);
299 DEBUG_SET(DEBUG_RANGEFINDER_QUALITY, 2, rangefinder.dynamicDistanceThreshold);
300 DEBUG_SET(DEBUG_RANGEFINDER_QUALITY, 3, isSurfaceAltitudeValid());
303 else {
304 // Bad configuration
305 rangefinder.rawAltitude = RANGEFINDER_OUT_OF_RANGE;
309 * Apply tilt correction to the given raw sonar reading in order to compensate for the tilt of the craft when estimating
310 * the altitude. Returns the computed altitude in centimeters.
312 * When the ground is too far away or the tilt is too large, RANGEFINDER_OUT_OF_RANGE is returned.
314 if (cosTiltAngle < rangefinder.maxTiltCos || rangefinder.rawAltitude < 0) {
315 rangefinder.calculatedAltitude = RANGEFINDER_OUT_OF_RANGE;
316 } else {
317 rangefinder.calculatedAltitude = rangefinder.rawAltitude * cosTiltAngle;
320 DEBUG_SET(DEBUG_RANGEFINDER, 1, rangefinder.rawAltitude);
321 DEBUG_SET(DEBUG_RANGEFINDER, 2, rangefinder.calculatedAltitude);
323 return true;
327 * Get the latest altitude that was computed, or RANGEFINDER_OUT_OF_RANGE if sonarCalculateAltitude
328 * has never been called.
330 int32_t rangefinderGetLatestAltitude(void)
332 return rangefinder.calculatedAltitude;
335 int32_t rangefinderGetLatestRawAltitude(void) {
336 return rangefinder.rawAltitude;
339 bool rangefinderIsHealthy(void)
341 return (millis() - rangefinder.lastValidResponseTimeMs) < RANGEFINDER_HARDWARE_TIMEOUT_MS;
343 #endif