RangeFinder_Backend.cpp 2.6 KB

12345678910111213141516171819202122232425262728293031323334353637383940414243444546474849505152535455565758596061626364656667686970717273747576777879808182
  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_Common/AP_Common.h>
  14. #include <AP_HAL/AP_HAL.h>
  15. #include "RangeFinder.h"
  16. #include "RangeFinder_Backend.h"
  17. extern const AP_HAL::HAL& hal;
  18. /*
  19. base class constructor.
  20. This incorporates initialisation as well.
  21. */
  22. AP_RangeFinder_Backend::AP_RangeFinder_Backend(RangeFinder::RangeFinder_State &_state, AP_RangeFinder_Params &_params) :
  23. state(_state),
  24. params(_params)
  25. {
  26. _backend_type = (RangeFinder::RangeFinder_Type)params.type.get();
  27. }
  28. MAV_DISTANCE_SENSOR AP_RangeFinder_Backend::get_mav_distance_sensor_type() const {
  29. if (params.type == RangeFinder::RangeFinder_TYPE_NONE) {
  30. return MAV_DISTANCE_SENSOR_UNKNOWN;
  31. }
  32. return _get_mav_distance_sensor_type();
  33. }
  34. RangeFinder::RangeFinder_Status AP_RangeFinder_Backend::status() const {
  35. if (params.type == RangeFinder::RangeFinder_TYPE_NONE) {
  36. // turned off at runtime?
  37. return RangeFinder::RangeFinder_NotConnected;
  38. }
  39. return state.status;
  40. }
  41. // true if sensor is returning data
  42. bool AP_RangeFinder_Backend::has_data() const {
  43. return ((state.status != RangeFinder::RangeFinder_NotConnected) &&
  44. (state.status != RangeFinder::RangeFinder_NoData));
  45. }
  46. // update status based on distance measurement
  47. void AP_RangeFinder_Backend::update_status()
  48. {
  49. // check distance
  50. if ((int16_t)state.distance_cm > params.max_distance_cm) {
  51. set_status(RangeFinder::RangeFinder_OutOfRangeHigh);
  52. } else if ((int16_t)state.distance_cm < params.min_distance_cm) {
  53. set_status(RangeFinder::RangeFinder_OutOfRangeLow);
  54. } else {
  55. set_status(RangeFinder::RangeFinder_Good);
  56. }
  57. }
  58. // set status and update valid count
  59. void AP_RangeFinder_Backend::set_status(RangeFinder::RangeFinder_Status _status)
  60. {
  61. state.status = _status;
  62. // update valid count
  63. if (_status == RangeFinder::RangeFinder_Good) {
  64. if (state.range_valid_count < 10) {
  65. state.range_valid_count++;
  66. }
  67. } else {
  68. state.range_valid_count = 0;
  69. }
  70. }