AP_Beacon.h 5.0 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149
  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 <AP_Param/AP_Param.h>
  17. #include <AP_Math/AP_Math.h>
  18. #include <AP_SerialManager/AP_SerialManager.h>
  19. #include <AP_Common/Location.h>
  20. class AP_Beacon_Backend;
  21. #define AP_BEACON_MAX_BEACONS 4
  22. #define AP_BEACON_TIMEOUT_MS 300
  23. #define AP_BEACON_MINIMUM_FENCE_BEACONS 3
  24. class AP_Beacon
  25. {
  26. public:
  27. friend class AP_Beacon_Backend;
  28. AP_Beacon(AP_SerialManager &_serial_manager);
  29. // get singleton instance
  30. static AP_Beacon *get_singleton() { return _singleton; }
  31. // external position backend types (used by _TYPE parameter)
  32. enum AP_BeaconType {
  33. AP_BeaconType_None = 0,
  34. AP_BeaconType_Pozyx = 1,
  35. AP_BeaconType_Marvelmind = 2,
  36. AP_BeaconType_SITL = 10
  37. };
  38. // The AP_BeaconState structure is filled in by the backend driver
  39. struct BeaconState {
  40. uint16_t id; // unique id of beacon
  41. bool healthy; // true if beacon is healthy
  42. float distance; // distance from vehicle to beacon (in meters)
  43. uint32_t distance_update_ms; // system time of last update from this beacon
  44. Vector3f position; // location of beacon as an offset from origin in NED in meters
  45. };
  46. // initialise any available position estimators
  47. void init(void);
  48. // return true if beacon feature is enabled
  49. bool enabled(void);
  50. // return true if sensor is basically healthy (we are receiving data)
  51. bool healthy(void);
  52. // update state of all beacons
  53. void update(void);
  54. // return origin of position estimate system in lat/lon
  55. bool get_origin(Location &origin_loc) const;
  56. // return vehicle position in NED from position estimate system's origin in meters
  57. bool get_vehicle_position_ned(Vector3f& pos, float& accuracy_estimate) const;
  58. // return the number of beacons
  59. uint8_t count() const;
  60. // methods to return beacon specific information
  61. // return all beacon data
  62. bool get_beacon_data(uint8_t beacon_instance, struct BeaconState& state) const;
  63. // return individual beacon's id
  64. uint8_t beacon_id(uint8_t beacon_instance) const;
  65. // return beacon health
  66. bool beacon_healthy(uint8_t beacon_instance) const;
  67. // return distance to beacon in meters
  68. float beacon_distance(uint8_t beacon_instance) const;
  69. // return NED position of beacon in meters relative to the beacon systems origin
  70. Vector3f beacon_position(uint8_t beacon_instance) const;
  71. // return last update time from beacon in milliseconds
  72. uint32_t beacon_last_update_ms(uint8_t beacon_instance) const;
  73. // update fence boundary array
  74. void update_boundary_points();
  75. // return fence boundary array
  76. const Vector2f* get_boundary_points(uint16_t& num_points) const;
  77. static const struct AP_Param::GroupInfo var_info[];
  78. private:
  79. static AP_Beacon *_singleton;
  80. // check if device is ready
  81. bool device_ready(void) const;
  82. // find next boundary point from an array of boundary points given the current index into that array
  83. // returns true if a next point can be found
  84. // current_index should be an index into the boundary_pts array
  85. // start_angle is an angle (in radians), the search will sweep clockwise from this angle
  86. // the index of the next point is returned in the next_index argument
  87. // the angle to the next point is returned in the next_angle argument
  88. static bool get_next_boundary_point(const Vector2f* boundary, uint8_t num_points, uint8_t current_index, float start_angle, uint8_t& next_index, float& next_angle);
  89. // parameters
  90. AP_Int8 _type;
  91. AP_Float origin_lat;
  92. AP_Float origin_lon;
  93. AP_Float origin_alt;
  94. AP_Int16 orient_yaw;
  95. // external references
  96. AP_Beacon_Backend *_driver;
  97. AP_SerialManager &serial_manager;
  98. // last known position
  99. Vector3f veh_pos_ned;
  100. float veh_pos_accuracy;
  101. uint32_t veh_pos_update_ms;
  102. // individual beacon data
  103. uint8_t num_beacons = 0;
  104. BeaconState beacon_state[AP_BEACON_MAX_BEACONS];
  105. // fence boundary
  106. Vector2f boundary[AP_BEACON_MAX_BEACONS+1]; // array of boundary points (used for fence)
  107. uint8_t boundary_num_points; // number of points in boundary
  108. uint8_t boundary_num_beacons; // total number of beacon points consumed while building boundary
  109. };
  110. namespace AP {
  111. AP_Beacon *beacon();
  112. };