AP_Proximity_RangeFinder.cpp 3.5 KB

12345678910111213141516171819202122232425262728293031323334353637383940414243444546474849505152535455565758596061626364656667686970717273747576777879808182838485868788899091929394
  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. This program is distributed in the hope that it will be useful,
  7. but WITHOUT ANY WARRANTY; without even the implied warranty of
  8. MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
  9. GNU General Public License for more details.
  10. You should have received a copy of the GNU General Public License
  11. along with this program. If not, see <http://www.gnu.org/licenses/>.
  12. */
  13. #include <AP_HAL/AP_HAL.h>
  14. #include "AP_Proximity_RangeFinder.h"
  15. #include <AP_SerialManager/AP_SerialManager.h>
  16. #include <ctype.h>
  17. #include <stdio.h>
  18. #include <AP_RangeFinder/RangeFinder_Backend.h>
  19. extern const AP_HAL::HAL& hal;
  20. AP_Proximity_RangeFinder::AP_Proximity_RangeFinder(AP_Proximity &_frontend,
  21. AP_Proximity::Proximity_State &_state) :
  22. AP_Proximity_Backend(_frontend, _state),
  23. _distance_upward(-1)
  24. {
  25. }
  26. // update the state of the sensor
  27. void AP_Proximity_RangeFinder::update(void)
  28. {
  29. // exit immediately if no rangefinder object
  30. const RangeFinder *rngfnd = frontend.get_rangefinder();
  31. if (rngfnd == nullptr) {
  32. set_status(AP_Proximity::Proximity_NoData);
  33. return;
  34. }
  35. uint32_t now = AP_HAL::millis();
  36. // look through all rangefinders
  37. for (uint8_t i=0; i < rngfnd->num_sensors(); i++) {
  38. AP_RangeFinder_Backend *sensor = rngfnd->get_backend(i);
  39. if (sensor == nullptr) {
  40. continue;
  41. }
  42. if (sensor->has_data()) {
  43. // check for horizontal range finders
  44. if (sensor->orientation() <= ROTATION_YAW_315) {
  45. uint8_t sector = (uint8_t)sensor->orientation();
  46. _angle[sector] = sector * 45;
  47. _distance[sector] = sensor->distance_cm() * 0.01f;
  48. _distance_min = sensor->min_distance_cm() * 0.01f;
  49. _distance_max = sensor->max_distance_cm() * 0.01f;
  50. _distance_valid[sector] = (_distance[sector] >= _distance_min) && (_distance[sector] <= _distance_max);
  51. _last_update_ms = now;
  52. update_boundary_for_sector(sector, true);
  53. }
  54. // check upward facing range finder
  55. if (sensor->orientation() == ROTATION_PITCH_90) {
  56. int16_t distance_upward = sensor->distance_cm();
  57. int16_t up_distance_min = sensor->min_distance_cm();
  58. int16_t up_distance_max = sensor->max_distance_cm();
  59. if ((distance_upward >= up_distance_min) && (distance_upward <= up_distance_max)) {
  60. _distance_upward = distance_upward * 0.01f;
  61. } else {
  62. _distance_upward = -1.0; // mark an valid reading
  63. }
  64. _last_upward_update_ms = now;
  65. }
  66. }
  67. }
  68. // check for timeout and set health status
  69. if ((_last_update_ms == 0) || (now - _last_update_ms > PROXIMITY_RANGEFIDER_TIMEOUT_MS)) {
  70. set_status(AP_Proximity::Proximity_NoData);
  71. } else {
  72. set_status(AP_Proximity::Proximity_Good);
  73. }
  74. }
  75. // get distance upwards in meters. returns true on success
  76. bool AP_Proximity_RangeFinder::get_upward_distance(float &distance) const
  77. {
  78. if ((AP_HAL::millis() - _last_upward_update_ms <= PROXIMITY_RANGEFIDER_TIMEOUT_MS) &&
  79. is_positive(_distance_upward)) {
  80. distance = _distance_upward;
  81. return true;
  82. }
  83. return false;
  84. }