RangeFinder_Backend.h 2.9 KB

1234567891011121314151617181920212223242526272829303132333435363738394041424344454647484950515253545556575859606162636465666768697071727374757677
  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. #pragma once
  14. #include <AP_Common/AP_Common.h>
  15. #include <AP_HAL/AP_HAL.h>
  16. #include "RangeFinder.h"
  17. class AP_RangeFinder_Backend
  18. {
  19. public:
  20. // constructor. This incorporates initialisation as well.
  21. AP_RangeFinder_Backend(RangeFinder::RangeFinder_State &_state, AP_RangeFinder_Params &_params);
  22. // we declare a virtual destructor so that RangeFinder drivers can
  23. // override with a custom destructor if need be
  24. virtual ~AP_RangeFinder_Backend(void) {}
  25. // update the state structure
  26. virtual void update() = 0;
  27. virtual void handle_msg(const mavlink_message_t &msg) { return; }
  28. enum Rotation orientation() const { return (Rotation)params.orientation.get(); }
  29. uint16_t distance_cm() const { return state.distance_cm; }
  30. uint16_t voltage_mv() const { return state.voltage_mv; }
  31. int16_t max_distance_cm() const { return params.max_distance_cm; }
  32. int16_t min_distance_cm() const { return params.min_distance_cm; }
  33. int16_t ground_clearance_cm() const { return params.ground_clearance_cm; }
  34. MAV_DISTANCE_SENSOR get_mav_distance_sensor_type() const;
  35. RangeFinder::RangeFinder_Status status() const;
  36. RangeFinder::RangeFinder_Type type() const { return (RangeFinder::RangeFinder_Type)params.type.get(); }
  37. // true if sensor is returning data
  38. bool has_data() const;
  39. // returns count of consecutive good readings
  40. uint8_t range_valid_count() const { return state.range_valid_count; }
  41. // return a 3D vector defining the position offset of the sensor
  42. // in metres relative to the body frame origin
  43. const Vector3f &get_pos_offset() const { return params.pos_offset; }
  44. // return system time of last successful read from the sensor
  45. uint32_t last_reading_ms() const { return state.last_reading_ms; }
  46. protected:
  47. // update status based on distance measurement
  48. void update_status();
  49. // set status and update valid_count
  50. void set_status(RangeFinder::RangeFinder_Status status);
  51. RangeFinder::RangeFinder_State &state;
  52. AP_RangeFinder_Params &params;
  53. // semaphore for access to shared frontend data
  54. HAL_Semaphore _sem;
  55. //Type Backend initialised with
  56. RangeFinder::RangeFinder_Type _backend_type;
  57. virtual MAV_DISTANCE_SENSOR _get_mav_distance_sensor_type() const = 0;
  58. };