AP_Beacon.cpp 13 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399
  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_Beacon.h"
  14. #include "AP_Beacon_Backend.h"
  15. #include "AP_Beacon_Pozyx.h"
  16. #include "AP_Beacon_Marvelmind.h"
  17. #include "AP_Beacon_SITL.h"
  18. #include <AP_Common/Location.h>
  19. extern const AP_HAL::HAL &hal;
  20. // table of user settable parameters
  21. const AP_Param::GroupInfo AP_Beacon::var_info[] = {
  22. // @Param: _TYPE
  23. // @DisplayName: Beacon based position estimation device type
  24. // @Description: What type of beacon based position estimation device is connected
  25. // @Values: 0:None,1:Pozyx,2:Marvelmind,10:SITL
  26. // @User: Advanced
  27. AP_GROUPINFO("_TYPE", 0, AP_Beacon, _type, 0),
  28. // @Param: _LATITUDE
  29. // @DisplayName: Beacon origin's latitude
  30. // @Description: Beacon origin's latitude
  31. // @Units: deg
  32. // @Increment: 0.000001
  33. // @Range: -90 90
  34. // @User: Advanced
  35. AP_GROUPINFO("_LATITUDE", 1, AP_Beacon, origin_lat, 0),
  36. // @Param: _LONGITUDE
  37. // @DisplayName: Beacon origin's longitude
  38. // @Description: Beacon origin's longitude
  39. // @Units: deg
  40. // @Increment: 0.000001
  41. // @Range: -180 180
  42. // @User: Advanced
  43. AP_GROUPINFO("_LONGITUDE", 2, AP_Beacon, origin_lon, 0),
  44. // @Param: _ALT
  45. // @DisplayName: Beacon origin's altitude above sealevel in meters
  46. // @Description: Beacon origin's altitude above sealevel in meters
  47. // @Units: m
  48. // @Increment: 1
  49. // @Range: 0 10000
  50. // @User: Advanced
  51. AP_GROUPINFO("_ALT", 3, AP_Beacon, origin_alt, 0),
  52. // @Param: _ORIENT_YAW
  53. // @DisplayName: Beacon systems rotation from north in degrees
  54. // @Description: Beacon systems rotation from north in degrees
  55. // @Units: deg
  56. // @Increment: 1
  57. // @Range: -180 +180
  58. // @User: Advanced
  59. AP_GROUPINFO("_ORIENT_YAW", 4, AP_Beacon, orient_yaw, 0),
  60. AP_GROUPEND
  61. };
  62. AP_Beacon::AP_Beacon(AP_SerialManager &_serial_manager) :
  63. serial_manager(_serial_manager)
  64. {
  65. #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
  66. if (_singleton != nullptr) {
  67. AP_HAL::panic("Fence must be singleton");
  68. }
  69. #endif
  70. _singleton = this;
  71. AP_Param::setup_object_defaults(this, var_info);
  72. }
  73. // initialise the AP_Beacon class
  74. void AP_Beacon::init(void)
  75. {
  76. if (_driver != nullptr) {
  77. // init called a 2nd time?
  78. return;
  79. }
  80. // create backend
  81. if (_type == AP_BeaconType_Pozyx) {
  82. _driver = new AP_Beacon_Pozyx(*this, serial_manager);
  83. } else if (_type == AP_BeaconType_Marvelmind) {
  84. _driver = new AP_Beacon_Marvelmind(*this, serial_manager);
  85. }
  86. #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
  87. if (_type == AP_BeaconType_SITL) {
  88. _driver = new AP_Beacon_SITL(*this);
  89. }
  90. #endif
  91. }
  92. // return true if beacon feature is enabled
  93. bool AP_Beacon::enabled(void)
  94. {
  95. return (_type != AP_BeaconType_None);
  96. }
  97. // return true if sensor is basically healthy (we are receiving data)
  98. bool AP_Beacon::healthy(void)
  99. {
  100. if (!device_ready()) {
  101. return false;
  102. }
  103. return _driver->healthy();
  104. }
  105. // update state. This should be called often from the main loop
  106. void AP_Beacon::update(void)
  107. {
  108. if (!device_ready()) {
  109. return;
  110. }
  111. _driver->update();
  112. // update boundary for fence
  113. update_boundary_points();
  114. }
  115. // return origin of position estimate system
  116. bool AP_Beacon::get_origin(Location &origin_loc) const
  117. {
  118. if (!device_ready()) {
  119. return false;
  120. }
  121. // check for un-initialised origin
  122. if (is_zero(origin_lat) && is_zero(origin_lon) && is_zero(origin_alt)) {
  123. return false;
  124. }
  125. // return origin
  126. origin_loc = {};
  127. origin_loc.lat = origin_lat * 1.0e7f;
  128. origin_loc.lng = origin_lon * 1.0e7f;
  129. origin_loc.alt = origin_alt * 100;
  130. return true;
  131. }
  132. // return position in NED from position estimate system's origin in meters
  133. bool AP_Beacon::get_vehicle_position_ned(Vector3f &position, float& accuracy_estimate) const
  134. {
  135. if (!device_ready()) {
  136. return false;
  137. }
  138. // check for timeout
  139. if (AP_HAL::millis() - veh_pos_update_ms > AP_BEACON_TIMEOUT_MS) {
  140. return false;
  141. }
  142. // return position
  143. position = veh_pos_ned;
  144. accuracy_estimate = veh_pos_accuracy;
  145. return true;
  146. }
  147. // return the number of beacons
  148. uint8_t AP_Beacon::count() const
  149. {
  150. if (!device_ready()) {
  151. return 0;
  152. }
  153. return num_beacons;
  154. }
  155. // return all beacon data
  156. bool AP_Beacon::get_beacon_data(uint8_t beacon_instance, struct BeaconState& state) const
  157. {
  158. if (!device_ready() || beacon_instance >= num_beacons) {
  159. return false;
  160. }
  161. state = beacon_state[beacon_instance];
  162. return true;
  163. }
  164. // return individual beacon's id
  165. uint8_t AP_Beacon::beacon_id(uint8_t beacon_instance) const
  166. {
  167. if (beacon_instance >= num_beacons) {
  168. return 0;
  169. }
  170. return beacon_state[beacon_instance].id;
  171. }
  172. // return beacon health
  173. bool AP_Beacon::beacon_healthy(uint8_t beacon_instance) const
  174. {
  175. if (beacon_instance >= num_beacons) {
  176. return false;
  177. }
  178. return beacon_state[beacon_instance].healthy;
  179. }
  180. // return distance to beacon in meters
  181. float AP_Beacon::beacon_distance(uint8_t beacon_instance) const
  182. {
  183. if (!beacon_state[beacon_instance].healthy || beacon_instance >= num_beacons) {
  184. return 0.0f;
  185. }
  186. return beacon_state[beacon_instance].distance;
  187. }
  188. // return beacon position in meters
  189. Vector3f AP_Beacon::beacon_position(uint8_t beacon_instance) const
  190. {
  191. if (!device_ready() || beacon_instance >= num_beacons) {
  192. Vector3f temp = {};
  193. return temp;
  194. }
  195. return beacon_state[beacon_instance].position;
  196. }
  197. // return last update time from beacon in milliseconds
  198. uint32_t AP_Beacon::beacon_last_update_ms(uint8_t beacon_instance) const
  199. {
  200. if (_type == AP_BeaconType_None || beacon_instance >= num_beacons) {
  201. return 0;
  202. }
  203. return beacon_state[beacon_instance].distance_update_ms;
  204. }
  205. // create fence boundary points
  206. void AP_Beacon::update_boundary_points()
  207. {
  208. // we need three beacons at least to create boundary fence.
  209. // update boundary fence if number of beacons changes
  210. if (!device_ready() || num_beacons < AP_BEACON_MINIMUM_FENCE_BEACONS || boundary_num_beacons == num_beacons) {
  211. return;
  212. }
  213. // record number of beacons so we do not repeat calculations
  214. boundary_num_beacons = num_beacons;
  215. // accumulate beacon points
  216. Vector2f beacon_points[AP_BEACON_MAX_BEACONS];
  217. for (uint8_t index = 0; index < num_beacons; index++) {
  218. const Vector3f& point_3d = beacon_position(index);
  219. beacon_points[index].x = point_3d.x;
  220. beacon_points[index].y = point_3d.y;
  221. }
  222. // create polygon around boundary points using the following algorithm
  223. // set the "current point" as the first boundary point
  224. // loop through all the boundary points looking for the point which creates a vector (from the current point to this new point) with the lowest angle
  225. // check if point is already in boundary
  226. // - no: add to boundary, move current point to this new point and repeat the above
  227. // - yes: we've completed the bounding box, delete any boundary points found earlier than the duplicate
  228. Vector2f boundary_points[AP_BEACON_MAX_BEACONS+1]; // array of boundary points
  229. uint8_t curr_boundary_idx = 0; // index into boundary_sorted index. always points to the highest filled in element of the array
  230. uint8_t curr_beacon_idx = 0; // index into beacon_point array. point indexed is same point as curr_boundary_idx's
  231. // initialise first point of boundary_sorted with first beacon's position (this point may be removed later if it is found to not be on the outer boundary)
  232. boundary_points[curr_boundary_idx] = beacon_points[curr_beacon_idx];
  233. bool boundary_success = false; // true once the boundary has been successfully found
  234. bool boundary_failure = false; // true if we fail to build the boundary
  235. float start_angle = 0.0f; // starting angle used when searching for next boundary point, on each iteration this climbs but never climbs past PI * 2
  236. while (!boundary_success && !boundary_failure) {
  237. // look for next outer point
  238. uint8_t next_idx;
  239. float next_angle;
  240. if (get_next_boundary_point(beacon_points, num_beacons, curr_beacon_idx, start_angle, next_idx, next_angle)) {
  241. // add boundary point to boundary_sorted array
  242. curr_boundary_idx++;
  243. boundary_points[curr_boundary_idx] = beacon_points[next_idx];
  244. curr_beacon_idx = next_idx;
  245. start_angle = next_angle;
  246. // check if we have a complete boundary by looking for duplicate points within the boundary_sorted
  247. uint8_t dup_idx = 0;
  248. bool dup_found = false;
  249. while (dup_idx < curr_boundary_idx && !dup_found) {
  250. dup_found = (boundary_points[dup_idx] == boundary_points[curr_boundary_idx]);
  251. if (!dup_found) {
  252. dup_idx++;
  253. }
  254. }
  255. // if duplicate is found, remove all boundary points before the duplicate because they are inner points
  256. if (dup_found) {
  257. // note that the closing/duplicate point is not
  258. // included in the boundary points.
  259. const uint8_t num_pts = curr_boundary_idx - dup_idx;
  260. if (num_pts >= AP_BEACON_MINIMUM_FENCE_BEACONS) { // we consider three points to be a polygon
  261. // success, copy boundary points to boundary array and convert meters to cm
  262. for (uint8_t j = 0; j < num_pts; j++) {
  263. boundary[j] = boundary_points[j+dup_idx] * 100.0f;
  264. }
  265. boundary_num_points = num_pts;
  266. boundary_success = true;
  267. } else {
  268. // boundary has too few points
  269. boundary_failure = true;
  270. }
  271. }
  272. } else {
  273. // failed to create boundary - give up!
  274. boundary_failure = true;
  275. }
  276. }
  277. // clear boundary on failure
  278. if (boundary_failure) {
  279. boundary_num_points = 0;
  280. }
  281. }
  282. // find next boundary point from an array of boundary points given the current index into that array
  283. // returns true if a next point can be found
  284. // current_index should be an index into the boundary_pts array
  285. // start_angle is an angle (in radians), the search will sweep clockwise from this angle
  286. // the index of the next point is returned in the next_index argument
  287. // the angle to the next point is returned in the next_angle argument
  288. bool AP_Beacon::get_next_boundary_point(const Vector2f* boundary_pts, uint8_t num_points, uint8_t current_index, float start_angle, uint8_t& next_index, float& next_angle)
  289. {
  290. // sanity check
  291. if (boundary_pts == nullptr || current_index >= num_points) {
  292. return false;
  293. }
  294. // get current point
  295. Vector2f curr_point = boundary_pts[current_index];
  296. // search through all points for next boundary point in a clockwise direction
  297. float lowest_angle = M_PI_2;
  298. float lowest_angle_relative = M_PI_2;
  299. bool lowest_found = false;
  300. uint8_t lowest_index = 0;
  301. for (uint8_t i=0; i < num_points; i++) {
  302. if (i != current_index) {
  303. Vector2f vec = boundary_pts[i] - curr_point;
  304. if (!vec.is_zero()) {
  305. float angle = wrap_2PI(atan2f(vec.y, vec.x));
  306. float angle_relative = wrap_2PI(angle - start_angle);
  307. if ((angle_relative < lowest_angle_relative) || !lowest_found) {
  308. lowest_angle = angle;
  309. lowest_angle_relative = angle_relative;
  310. lowest_index = i;
  311. lowest_found = true;
  312. }
  313. }
  314. }
  315. }
  316. // return results
  317. if (lowest_found) {
  318. next_index = lowest_index;
  319. next_angle = lowest_angle;
  320. }
  321. return lowest_found;
  322. }
  323. // return fence boundary array
  324. const Vector2f* AP_Beacon::get_boundary_points(uint16_t& num_points) const
  325. {
  326. if (!device_ready()) {
  327. num_points = 0;
  328. return nullptr;
  329. }
  330. num_points = boundary_num_points;
  331. return boundary;
  332. }
  333. // check if the device is ready
  334. bool AP_Beacon::device_ready(void) const
  335. {
  336. return ((_driver != nullptr) && (_type != AP_BeaconType_None));
  337. }
  338. // singleton instance
  339. AP_Beacon *AP_Beacon::_singleton;
  340. namespace AP {
  341. AP_Beacon *beacon()
  342. {
  343. return AP_Beacon::get_singleton();
  344. }
  345. }