APM:Libraries
AP_Proximity_RangeFinder.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 #include <AP_HAL/AP_HAL.h>
19 #include <ctype.h>
20 #include <stdio.h>
22 
23 extern const AP_HAL::HAL& hal;
24 
27  AP_Proximity_Backend(_frontend, _state),
28  _distance_upward(-1)
29 {
30 }
31 
32 // update the state of the sensor
34 {
35  // exit immediately if no rangefinder object
36  const RangeFinder *rngfnd = frontend.get_rangefinder();
37  if (rngfnd == nullptr) {
39  return;
40  }
41 
42  uint32_t now = AP_HAL::millis();
43 
44  // look through all rangefinders
45  for (uint8_t i=0; i < rngfnd->num_sensors(); i++) {
46  AP_RangeFinder_Backend *sensor = rngfnd->get_backend(i);
47  if (sensor == nullptr) {
48  continue;
49  }
50  if (sensor->has_data()) {
51  // check for horizontal range finders
52  if (sensor->orientation() <= ROTATION_YAW_315) {
53  uint8_t sector = (uint8_t)sensor->orientation();
54  _angle[sector] = sector * 45;
55  _distance[sector] = sensor->distance_cm() / 100.0f;
56  _distance_min = sensor->min_distance_cm() / 100.0f;
57  _distance_max = sensor->max_distance_cm() / 100.0f;
58  _distance_valid[sector] = (_distance[sector] >= _distance_min) && (_distance[sector] <= _distance_max);
59  _last_update_ms = now;
61  }
62  // check upward facing range finder
63  if (sensor->orientation() == ROTATION_PITCH_90) {
64  int16_t distance_upward = sensor->distance_cm();
65  int16_t up_distance_min = sensor->min_distance_cm();
66  int16_t up_distance_max = sensor->max_distance_cm();
67  if ((distance_upward >= up_distance_min) && (distance_upward <= up_distance_max)) {
68  _distance_upward = distance_upward * 1e2;
69  } else {
70  _distance_upward = -1.0; // mark an valid reading
71  }
73  }
74  }
75  }
76 
77  // check for timeout and set health status
80  } else {
82  }
83 }
84 
85 // get distance upwards in meters. returns true on success
87 {
90  distance = _distance_upward;
91  return true;
92  }
93  return false;
94 }
#define PROXIMITY_RANGEFIDER_TIMEOUT_MS
AP_RangeFinder_Backend * get_backend(uint8_t id) const
AP_Proximity_RangeFinder(AP_Proximity &_frontend, AP_Proximity::Proximity_State &_state)
bool _distance_valid[PROXIMITY_SECTORS_MAX]
float _angle[PROXIMITY_SECTORS_MAX]
enum Rotation orientation() const
uint16_t distance_cm() const
bool is_positive(const T fVal1)
Definition: AP_Math.h:50
void set_status(AP_Proximity::Proximity_Status status)
uint8_t num_sensors(void) const
Definition: RangeFinder.h:117
float distance
Definition: location.cpp:94
bool get_upward_distance(float &distance) const
float _distance[PROXIMITY_SECTORS_MAX]
uint32_t millis()
Definition: system.cpp:157
const RangeFinder * get_rangefinder() const
Definition: AP_Proximity.h:73
void update_boundary_for_sector(uint8_t sector)
int16_t min_distance_cm() const
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: AC_PID_test.cpp:14
int16_t max_distance_cm() const