AP_Proximity_Backend.cpp 13 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374
  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_Common/Location.h>
  15. #include <AP_AHRS/AP_AHRS.h>
  16. #include <AC_Avoidance/AP_OADatabase.h>
  17. #include <AP_HAL/AP_HAL.h>
  18. #include "AP_Proximity.h"
  19. #include "AP_Proximity_Backend.h"
  20. /*
  21. base class constructor.
  22. This incorporates initialisation as well.
  23. */
  24. AP_Proximity_Backend::AP_Proximity_Backend(AP_Proximity &_frontend, AP_Proximity::Proximity_State &_state) :
  25. frontend(_frontend),
  26. state(_state)
  27. {
  28. // initialise sector edge vector used for building the boundary fence
  29. init_boundary();
  30. }
  31. // get distance in meters in a particular direction in degrees (0 is forward, angles increase in the clockwise direction)
  32. bool AP_Proximity_Backend::get_horizontal_distance(float angle_deg, float &distance) const
  33. {
  34. uint8_t sector;
  35. if (convert_angle_to_sector(angle_deg, sector)) {
  36. if (_distance_valid[sector]) {
  37. distance = _distance[sector];
  38. return true;
  39. }
  40. }
  41. return false;
  42. }
  43. // get distance and angle to closest object (used for pre-arm check)
  44. // returns true on success, false if no valid readings
  45. bool AP_Proximity_Backend::get_closest_object(float& angle_deg, float &distance) const
  46. {
  47. bool sector_found = false;
  48. uint8_t sector = 0;
  49. // check all sectors for shorter distance
  50. for (uint8_t i=0; i<_num_sectors; i++) {
  51. if (_distance_valid[i]) {
  52. if (!sector_found || (_distance[i] < _distance[sector])) {
  53. sector = i;
  54. sector_found = true;
  55. }
  56. }
  57. }
  58. if (sector_found) {
  59. angle_deg = _angle[sector];
  60. distance = _distance[sector];
  61. }
  62. return sector_found;
  63. }
  64. // get number of objects, used for non-GPS avoidance
  65. uint8_t AP_Proximity_Backend::get_object_count() const
  66. {
  67. return _num_sectors;
  68. }
  69. // get an object's angle and distance, used for non-GPS avoidance
  70. // returns false if no angle or distance could be returned for some reason
  71. bool AP_Proximity_Backend::get_object_angle_and_distance(uint8_t object_number, float& angle_deg, float &distance) const
  72. {
  73. if (object_number < _num_sectors && _distance_valid[object_number]) {
  74. angle_deg = _angle[object_number];
  75. distance = _distance[object_number];
  76. return true;
  77. }
  78. return false;
  79. }
  80. // get distances in PROXIMITY_MAX_DIRECTION directions. used for sending distances to ground station
  81. bool AP_Proximity_Backend::get_horizontal_distances(AP_Proximity::Proximity_Distance_Array &prx_dist_array) const
  82. {
  83. // exit immediately if we have no good ranges
  84. bool valid_distances = false;
  85. for (uint8_t i=0; i<_num_sectors; i++) {
  86. if (_distance_valid[i]) {
  87. valid_distances = true;
  88. break;
  89. }
  90. }
  91. if (!valid_distances) {
  92. return false;
  93. }
  94. // initialise orientations and directions
  95. // see MAV_SENSOR_ORIENTATION for orientations (0 = forward, 1 = 45 degree clockwise from north, etc)
  96. // distances initialised to maximum distances
  97. bool dist_set[PROXIMITY_MAX_DIRECTION]{};
  98. for (uint8_t i=0; i<PROXIMITY_MAX_DIRECTION; i++) {
  99. prx_dist_array.orientation[i] = i;
  100. prx_dist_array.distance[i] = distance_max();
  101. }
  102. // cycle through all sectors filling in distances
  103. for (uint8_t i=0; i<_num_sectors; i++) {
  104. if (_distance_valid[i]) {
  105. // convert angle to orientation
  106. int16_t orientation = static_cast<int16_t>(_angle[i] * (PROXIMITY_MAX_DIRECTION / 360.0f));
  107. if ((orientation >= 0) && (orientation < PROXIMITY_MAX_DIRECTION) && (_distance[i] < prx_dist_array.distance[orientation])) {
  108. prx_dist_array.distance[orientation] = _distance[i];
  109. dist_set[orientation] = true;
  110. }
  111. }
  112. }
  113. // fill in missing orientations with average of adjacent orientations if necessary and possible
  114. for (uint8_t i=0; i<PROXIMITY_MAX_DIRECTION; i++) {
  115. if (!dist_set[i]) {
  116. uint8_t orient_before = (i==0) ? (PROXIMITY_MAX_DIRECTION - 1) : (i-1);
  117. uint8_t orient_after = (i==(PROXIMITY_MAX_DIRECTION - 1)) ? 0 : (i+1);
  118. if (dist_set[orient_before] && dist_set[orient_after]) {
  119. prx_dist_array.distance[i] = (prx_dist_array.distance[orient_before] + prx_dist_array.distance[orient_after]) / 2.0f;
  120. }
  121. }
  122. }
  123. return true;
  124. }
  125. // get boundary points around vehicle for use by avoidance
  126. // returns nullptr and sets num_points to zero if no boundary can be returned
  127. const Vector2f* AP_Proximity_Backend::get_boundary_points(uint16_t& num_points) const
  128. {
  129. // high-level status check
  130. if (state.status != AP_Proximity::Proximity_Good) {
  131. num_points = 0;
  132. return nullptr;
  133. }
  134. // check at least one sector has valid data, if not, exit
  135. bool some_valid = false;
  136. for (uint8_t i=0; i<_num_sectors; i++) {
  137. if (_distance_valid[i]) {
  138. some_valid = true;
  139. break;
  140. }
  141. }
  142. if (!some_valid) {
  143. num_points = 0;
  144. return nullptr;
  145. }
  146. // return boundary points
  147. num_points = _num_sectors;
  148. return _boundary_point;
  149. }
  150. // initialise the boundary and sector_edge_vector array used for object avoidance
  151. // should be called if the sector_middle_deg or _setor_width_deg arrays are changed
  152. void AP_Proximity_Backend::init_boundary()
  153. {
  154. for (uint8_t sector=0; sector < _num_sectors; sector++) {
  155. float angle_rad = radians((float)_sector_middle_deg[sector]+(float)_sector_width_deg[sector]/2.0f);
  156. _sector_edge_vector[sector].x = cosf(angle_rad) * 100.0f;
  157. _sector_edge_vector[sector].y = sinf(angle_rad) * 100.0f;
  158. _boundary_point[sector] = _sector_edge_vector[sector] * PROXIMITY_BOUNDARY_DIST_DEFAULT;
  159. }
  160. }
  161. // update boundary points used for object avoidance based on a single sector's distance changing
  162. // the boundary points lie on the line between sectors meaning two boundary points may be updated based on a single sector's distance changing
  163. // the boundary point is set to the shortest distance found in the two adjacent sectors, this is a conservative boundary around the vehicle
  164. void AP_Proximity_Backend::update_boundary_for_sector(const uint8_t sector, const bool push_to_OA_DB)
  165. {
  166. // sanity check
  167. if (sector >= _num_sectors) {
  168. return;
  169. }
  170. if (push_to_OA_DB) {
  171. database_push(_angle[sector], _distance[sector]);
  172. }
  173. // find adjacent sector (clockwise)
  174. uint8_t next_sector = sector + 1;
  175. if (next_sector >= _num_sectors) {
  176. next_sector = 0;
  177. }
  178. // boundary point lies on the line between the two sectors at the shorter distance found in the two sectors
  179. float shortest_distance = PROXIMITY_BOUNDARY_DIST_DEFAULT;
  180. if (_distance_valid[sector] && _distance_valid[next_sector]) {
  181. shortest_distance = MIN(_distance[sector], _distance[next_sector]);
  182. } else if (_distance_valid[sector]) {
  183. shortest_distance = _distance[sector];
  184. } else if (_distance_valid[next_sector]) {
  185. shortest_distance = _distance[next_sector];
  186. }
  187. if (shortest_distance < PROXIMITY_BOUNDARY_DIST_MIN) {
  188. shortest_distance = PROXIMITY_BOUNDARY_DIST_MIN;
  189. }
  190. _boundary_point[sector] = _sector_edge_vector[sector] * shortest_distance;
  191. // if the next sector (clockwise) has an invalid distance, set boundary to create a cup like boundary
  192. if (!_distance_valid[next_sector]) {
  193. _boundary_point[next_sector] = _sector_edge_vector[next_sector] * shortest_distance;
  194. }
  195. // repeat for edge between sector and previous sector
  196. uint8_t prev_sector = (sector == 0) ? _num_sectors-1 : sector-1;
  197. shortest_distance = PROXIMITY_BOUNDARY_DIST_DEFAULT;
  198. if (_distance_valid[prev_sector] && _distance_valid[sector]) {
  199. shortest_distance = MIN(_distance[prev_sector], _distance[sector]);
  200. } else if (_distance_valid[prev_sector]) {
  201. shortest_distance = _distance[prev_sector];
  202. } else if (_distance_valid[sector]) {
  203. shortest_distance = _distance[sector];
  204. }
  205. _boundary_point[prev_sector] = _sector_edge_vector[prev_sector] * shortest_distance;
  206. // if the sector counter-clockwise from the previous sector has an invalid distance, set boundary to create a cup like boundary
  207. uint8_t prev_sector_ccw = (prev_sector == 0) ? _num_sectors-1 : prev_sector-1;
  208. if (!_distance_valid[prev_sector_ccw]) {
  209. _boundary_point[prev_sector_ccw] = _sector_edge_vector[prev_sector_ccw] * shortest_distance;
  210. }
  211. }
  212. // set status and update valid count
  213. void AP_Proximity_Backend::set_status(AP_Proximity::Proximity_Status status)
  214. {
  215. state.status = status;
  216. }
  217. bool AP_Proximity_Backend::convert_angle_to_sector(float angle_degrees, uint8_t &sector) const
  218. {
  219. // sanity check angle
  220. if (angle_degrees > 360.0f || angle_degrees < -180.0f) {
  221. return false;
  222. }
  223. // convert to 0 ~ 360
  224. if (angle_degrees < 0.0f) {
  225. angle_degrees += 360.0f;
  226. }
  227. bool closest_found = false;
  228. uint8_t closest_sector;
  229. float closest_angle;
  230. // search for which sector angle_degrees falls into
  231. for (uint8_t i = 0; i < _num_sectors; i++) {
  232. float angle_diff = fabsf(wrap_180(_sector_middle_deg[i] - angle_degrees));
  233. // record if closest
  234. if (!closest_found || angle_diff < closest_angle) {
  235. closest_found = true;
  236. closest_sector = i;
  237. closest_angle = angle_diff;
  238. }
  239. if (fabsf(angle_diff) <= _sector_width_deg[i] / 2.0f) {
  240. sector = i;
  241. return true;
  242. }
  243. }
  244. // angle_degrees might have been within a gap between sectors
  245. if (closest_found) {
  246. sector = closest_sector;
  247. return true;
  248. }
  249. return false;
  250. }
  251. // get ignore area info
  252. uint8_t AP_Proximity_Backend::get_ignore_area_count() const
  253. {
  254. // count number of ignore sectors
  255. uint8_t count = 0;
  256. for (uint8_t i=0; i < PROXIMITY_MAX_IGNORE; i++) {
  257. if (frontend._ignore_width_deg[i] != 0) {
  258. count++;
  259. }
  260. }
  261. return count;
  262. }
  263. // get next ignore angle
  264. bool AP_Proximity_Backend::get_ignore_area(uint8_t index, uint16_t &angle_deg, uint8_t &width_deg) const
  265. {
  266. if (index >= PROXIMITY_MAX_IGNORE) {
  267. return false;
  268. }
  269. angle_deg = frontend._ignore_angle_deg[index];
  270. width_deg = frontend._ignore_width_deg[index];
  271. return true;
  272. }
  273. // retrieve start or end angle of next ignore area (i.e. closest ignore area higher than the start_angle)
  274. // start_or_end = 0 to get start, 1 to retrieve end
  275. bool AP_Proximity_Backend::get_next_ignore_start_or_end(uint8_t start_or_end, int16_t start_angle, int16_t &ignore_start) const
  276. {
  277. bool found = false;
  278. int16_t smallest_angle_diff = 0;
  279. int16_t smallest_angle_start = 0;
  280. for (uint8_t i=0; i < PROXIMITY_MAX_IGNORE; i++) {
  281. if (frontend._ignore_width_deg[i] != 0) {
  282. int16_t offset = start_or_end == 0 ? -frontend._ignore_width_deg[i] : +frontend._ignore_width_deg[i];
  283. int16_t ignore_start_angle = wrap_360(frontend._ignore_angle_deg[i] + offset/2.0f);
  284. int16_t ang_diff = wrap_360(ignore_start_angle - start_angle);
  285. if (!found || ang_diff < smallest_angle_diff) {
  286. smallest_angle_diff = ang_diff;
  287. smallest_angle_start = ignore_start_angle;
  288. found = true;
  289. }
  290. }
  291. }
  292. if (found) {
  293. ignore_start = smallest_angle_start;
  294. }
  295. return found;
  296. }
  297. // returns true if database is ready to be pushed to and all cached data is ready
  298. bool AP_Proximity_Backend::database_prepare_for_push(Location &current_loc, float &current_vehicle_bearing)
  299. {
  300. AP_OADatabase *oaDb = AP::oadatabase();
  301. if (oaDb == nullptr || !oaDb->healthy()) {
  302. return false;
  303. }
  304. if (!AP::ahrs().get_position(current_loc)) {
  305. return false;
  306. }
  307. current_vehicle_bearing = AP::ahrs().yaw_sensor * 0.01f;
  308. return true;
  309. }
  310. // update Object Avoidance database with Earth-frame point
  311. void AP_Proximity_Backend::database_push(const float angle, const float distance)
  312. {
  313. Location current_loc;
  314. float current_vehicle_bearing;
  315. if (database_prepare_for_push(current_loc, current_vehicle_bearing) == true) {
  316. database_push(angle, distance, AP_HAL::millis(), current_loc, current_vehicle_bearing);
  317. }
  318. }
  319. // update Object Avoidance database with Earth-frame point
  320. void AP_Proximity_Backend::database_push(const float angle, const float distance, const uint32_t timestamp_ms, const Location &current_loc, const float current_vehicle_bearing)
  321. {
  322. AP_OADatabase *oaDb = AP::oadatabase();
  323. if (oaDb == nullptr || !oaDb->healthy()) {
  324. return;
  325. }
  326. Location temp_loc = current_loc;
  327. temp_loc.offset_bearing(wrap_180(current_vehicle_bearing + angle), distance);
  328. oaDb->queue_push(temp_loc, timestamp_ms, distance, angle);
  329. }