AP_Avoidance.cpp 24 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663664665666667
  1. #include "AP_Avoidance.h"
  2. extern const AP_HAL::HAL& hal;
  3. #include <limits>
  4. #include <AP_AHRS/AP_AHRS.h>
  5. #include <GCS_MAVLink/GCS.h>
  6. #define AVOIDANCE_DEBUGGING 0
  7. #if APM_BUILD_TYPE(APM_BUILD_ArduPlane)
  8. #define AP_AVOIDANCE_WARN_TIME_DEFAULT 30
  9. #define AP_AVOIDANCE_FAIL_TIME_DEFAULT 30
  10. #define AP_AVOIDANCE_WARN_DISTANCE_XY_DEFAULT 1000
  11. #define AP_AVOIDANCE_WARN_DISTANCE_Z_DEFAULT 300
  12. #define AP_AVOIDANCE_FAIL_DISTANCE_XY_DEFAULT 300
  13. #define AP_AVOIDANCE_FAIL_DISTANCE_Z_DEFAULT 100
  14. #define AP_AVOIDANCE_RECOVERY_DEFAULT AP_AVOIDANCE_RECOVERY_RESUME_IF_AUTO_ELSE_LOITER
  15. #define AP_AVOIDANCE_FAIL_ACTION_DEFAULT MAV_COLLISION_ACTION_REPORT
  16. #else // APM_BUILD_TYPE(APM_BUILD_ArduCopter), Rover, Boat
  17. #define AP_AVOIDANCE_WARN_TIME_DEFAULT 30
  18. #define AP_AVOIDANCE_FAIL_TIME_DEFAULT 30
  19. #define AP_AVOIDANCE_WARN_DISTANCE_XY_DEFAULT 300
  20. #define AP_AVOIDANCE_WARN_DISTANCE_Z_DEFAULT 300
  21. #define AP_AVOIDANCE_FAIL_DISTANCE_XY_DEFAULT 100
  22. #define AP_AVOIDANCE_FAIL_DISTANCE_Z_DEFAULT 100
  23. #define AP_AVOIDANCE_RECOVERY_DEFAULT AP_AVOIDANCE_RECOVERY_RTL
  24. #define AP_AVOIDANCE_FAIL_ACTION_DEFAULT MAV_COLLISION_ACTION_REPORT
  25. #endif
  26. #if AVOIDANCE_DEBUGGING
  27. #include <stdio.h>
  28. #define debug(fmt, args ...) do {::fprintf(stderr,"%s:%d: " fmt "\n", __FUNCTION__, __LINE__, ## args); } while(0)
  29. #else
  30. #define debug(fmt, args ...)
  31. #endif
  32. // table of user settable parameters
  33. const AP_Param::GroupInfo AP_Avoidance::var_info[] = {
  34. // @Param: ENABLE
  35. // @DisplayName: Enable Avoidance using ADSB
  36. // @Description: Enable Avoidance using ADSB
  37. // @Values: 0:Disabled,1:Enabled
  38. // @User: Advanced
  39. AP_GROUPINFO_FLAGS("ENABLE", 1, AP_Avoidance, _enabled, 0, AP_PARAM_FLAG_ENABLE),
  40. // @Param: F_ACTION
  41. // @DisplayName: Collision Avoidance Behavior
  42. // @Description: Specifies aircraft behaviour when a collision is imminent
  43. // The following values should come from the mavlink COLLISION_ACTION enum
  44. // @Values: 0:None,1:Report,2:Climb Or Descend,3:Move Horizontally,4:Move Perpendicularly in 3D,5:RTL,6:Hover
  45. // @User: Advanced
  46. AP_GROUPINFO("F_ACTION", 2, AP_Avoidance, _fail_action, AP_AVOIDANCE_FAIL_ACTION_DEFAULT),
  47. // @Param: W_ACTION
  48. // @DisplayName: Collision Avoidance Behavior - Warn
  49. // @Description: Specifies aircraft behaviour when a collision may occur
  50. // The following values should come from the mavlink COLLISION_ACTION enum
  51. // @Values: 0:None,1:Report
  52. // @User: Advanced
  53. AP_GROUPINFO("W_ACTION", 3, AP_Avoidance, _warn_action, MAV_COLLISION_ACTION_REPORT),
  54. // @Param: F_RCVRY
  55. // @DisplayName: Recovery behaviour after a fail event
  56. // @Description: Determines what the aircraft will do after a fail event is resolved
  57. // @Values: 0:Remain in AVOID_ADSB,1:Resume previous flight mode,2:RTL,3:Resume if AUTO else Loiter
  58. // @User: Advanced
  59. AP_GROUPINFO("F_RCVRY", 4, AP_Avoidance, _fail_recovery, AP_AVOIDANCE_RECOVERY_DEFAULT),
  60. // @Param: OBS_MAX
  61. // @DisplayName: Maximum number of obstacles to track
  62. // @Description: Maximum number of obstacles to track
  63. // @User: Advanced
  64. AP_GROUPINFO("OBS_MAX", 5, AP_Avoidance, _obstacles_max, 20),
  65. // @Param: W_TIME
  66. // @DisplayName: Time Horizon Warn
  67. // @Description: Aircraft velocity vectors are multiplied by this time to determine closest approach. If this results in an approach closer than W_DIST_XY or W_DIST_Z then W_ACTION is undertaken (assuming F_ACTION is not undertaken)
  68. // @Units: s
  69. // @User: Advanced
  70. AP_GROUPINFO("W_TIME", 6, AP_Avoidance, _warn_time_horizon, AP_AVOIDANCE_WARN_TIME_DEFAULT),
  71. // @Param: F_TIME
  72. // @DisplayName: Time Horizon Fail
  73. // @Description: Aircraft velocity vectors are multiplied by this time to determine closest approach. If this results in an approach closer than F_DIST_XY or F_DIST_Z then F_ACTION is undertaken
  74. // @Units: s
  75. // @User: Advanced
  76. AP_GROUPINFO("F_TIME", 7, AP_Avoidance, _fail_time_horizon, AP_AVOIDANCE_FAIL_TIME_DEFAULT),
  77. // @Param: W_DIST_XY
  78. // @DisplayName: Distance Warn XY
  79. // @Description: Closest allowed projected distance before W_ACTION is undertaken
  80. // @Units: m
  81. // @User: Advanced
  82. AP_GROUPINFO("W_DIST_XY", 8, AP_Avoidance, _warn_distance_xy, AP_AVOIDANCE_WARN_DISTANCE_XY_DEFAULT),
  83. // @Param: F_DIST_XY
  84. // @DisplayName: Distance Fail XY
  85. // @Description: Closest allowed projected distance before F_ACTION is undertaken
  86. // @Units: m
  87. // @User: Advanced
  88. AP_GROUPINFO("F_DIST_XY", 9, AP_Avoidance, _fail_distance_xy, AP_AVOIDANCE_FAIL_DISTANCE_XY_DEFAULT),
  89. // @Param: W_DIST_Z
  90. // @DisplayName: Distance Warn Z
  91. // @Description: Closest allowed projected distance before BEHAVIOUR_W is undertaken
  92. // @Units: m
  93. // @User: Advanced
  94. AP_GROUPINFO("W_DIST_Z", 10, AP_Avoidance, _warn_distance_z, AP_AVOIDANCE_WARN_DISTANCE_Z_DEFAULT),
  95. // @Param: F_DIST_Z
  96. // @DisplayName: Distance Fail Z
  97. // @Description: Closest allowed projected distance before BEHAVIOUR_F is undertaken
  98. // @Units: m
  99. // @User: Advanced
  100. AP_GROUPINFO("F_DIST_Z", 11, AP_Avoidance, _fail_distance_z, AP_AVOIDANCE_FAIL_DISTANCE_Z_DEFAULT),
  101. // @Param: F_ALT_MIN
  102. // @DisplayName: ADS-B avoidance minimum altitude
  103. // @Description: Minimum altitude for ADS-B avoidance. If the vehicle is below this altitude, no avoidance action will take place. Useful to prevent ADS-B avoidance from activating while below the tree line or around structures. Default of 0 is no minimum.
  104. // @Units: m
  105. // @User: Advanced
  106. AP_GROUPINFO("F_ALT_MIN", 12, AP_Avoidance, _fail_altitude_minimum, 0),
  107. AP_GROUPEND
  108. };
  109. AP_Avoidance::AP_Avoidance(AP_ADSB &adsb) :
  110. _adsb(adsb)
  111. {
  112. AP_Param::setup_object_defaults(this, var_info);
  113. }
  114. /*
  115. * Initialize variables and allocate memory for array
  116. */
  117. void AP_Avoidance::init(void)
  118. {
  119. debug("ADSB initialisation: %d obstacles", _obstacles_max.get());
  120. if (_obstacles == nullptr) {
  121. _obstacles = new AP_Avoidance::Obstacle[_obstacles_max];
  122. if (_obstacles == nullptr) {
  123. // dynamic RAM allocation of _obstacles[] failed, disable gracefully
  124. hal.console->printf("Unable to initialize Avoidance obstacle list\n");
  125. // disable ourselves to avoid repeated allocation attempts
  126. _enabled.set(0);
  127. return;
  128. }
  129. _obstacles_allocated = _obstacles_max;
  130. }
  131. _obstacle_count = 0;
  132. _last_state_change_ms = 0;
  133. _threat_level = MAV_COLLISION_THREAT_LEVEL_NONE;
  134. _gcs_cleared_messages_first_sent = std::numeric_limits<uint32_t>::max();
  135. _current_most_serious_threat = -1;
  136. }
  137. /*
  138. * de-initialize and free up some memory
  139. */
  140. void AP_Avoidance::deinit(void)
  141. {
  142. if (_obstacles != nullptr) {
  143. delete [] _obstacles;
  144. _obstacles = nullptr;
  145. _obstacles_allocated = 0;
  146. handle_recovery(AP_AVOIDANCE_RECOVERY_RTL);
  147. }
  148. _obstacle_count = 0;
  149. }
  150. bool AP_Avoidance::check_startup()
  151. {
  152. if (!_enabled) {
  153. if (_obstacles != nullptr) {
  154. deinit();
  155. }
  156. // nothing to do
  157. return false;
  158. }
  159. if (_obstacles == nullptr) {
  160. init();
  161. }
  162. return _obstacles != nullptr;
  163. }
  164. // vel is north/east/down!
  165. void AP_Avoidance::add_obstacle(const uint32_t obstacle_timestamp_ms,
  166. const MAV_COLLISION_SRC src,
  167. const uint32_t src_id,
  168. const Location &loc,
  169. const Vector3f &vel_ned)
  170. {
  171. if (! check_startup()) {
  172. return;
  173. }
  174. uint32_t oldest_timestamp = std::numeric_limits<uint32_t>::max();
  175. uint8_t oldest_index = 255; // avoid compiler warning with initialisation
  176. int16_t index = -1;
  177. uint8_t i;
  178. for (i=0; i<_obstacle_count; i++) {
  179. if (_obstacles[i].src_id == src_id &&
  180. _obstacles[i].src == src) {
  181. // pre-existing obstacle found; we will update its information
  182. index = i;
  183. break;
  184. }
  185. if (_obstacles[i].timestamp_ms < oldest_timestamp) {
  186. oldest_timestamp = _obstacles[i].timestamp_ms;
  187. oldest_index = i;
  188. }
  189. }
  190. WITH_SEMAPHORE(_rsem);
  191. if (index == -1) {
  192. // existing obstacle not found. See if we can store it anyway:
  193. if (i <_obstacles_allocated) {
  194. // have room to store more vehicles...
  195. index = _obstacle_count++;
  196. } else if (oldest_timestamp < obstacle_timestamp_ms) {
  197. // replace this very old entry with this new data
  198. index = oldest_index;
  199. } else {
  200. // no room for this (old?!) data
  201. return;
  202. }
  203. _obstacles[index].src = src;
  204. _obstacles[index].src_id = src_id;
  205. }
  206. _obstacles[index]._location = loc;
  207. _obstacles[index]._velocity = vel_ned;
  208. _obstacles[index].timestamp_ms = obstacle_timestamp_ms;
  209. }
  210. void AP_Avoidance::add_obstacle(const uint32_t obstacle_timestamp_ms,
  211. const MAV_COLLISION_SRC src,
  212. const uint32_t src_id,
  213. const Location &loc,
  214. const float cog,
  215. const float hspeed,
  216. const float vspeed)
  217. {
  218. Vector3f vel;
  219. vel[0] = hspeed * cosf(radians(cog));
  220. vel[1] = hspeed * sinf(radians(cog));
  221. vel[2] = vspeed;
  222. // debug("cog=%f hspeed=%f veln=%f vele=%f", cog, hspeed, vel[0], vel[1]);
  223. return add_obstacle(obstacle_timestamp_ms, src, src_id, loc, vel);
  224. }
  225. uint32_t AP_Avoidance::src_id_for_adsb_vehicle(const AP_ADSB::adsb_vehicle_t &vehicle) const
  226. {
  227. // TODO: need to include squawk code and callsign
  228. return vehicle.info.ICAO_address;
  229. }
  230. void AP_Avoidance::get_adsb_samples()
  231. {
  232. AP_ADSB::adsb_vehicle_t vehicle;
  233. while (_adsb.next_sample(vehicle)) {
  234. uint32_t src_id = src_id_for_adsb_vehicle(vehicle);
  235. Location loc = _adsb.get_location(vehicle);
  236. add_obstacle(vehicle.last_update_ms,
  237. MAV_COLLISION_SRC_ADSB,
  238. src_id,
  239. loc,
  240. vehicle.info.heading/100.0f,
  241. vehicle.info.hor_velocity/100.0f,
  242. -vehicle.info.ver_velocity/1000.0f); // convert mm-up to m-down
  243. }
  244. }
  245. float closest_approach_xy(const Location &my_loc,
  246. const Vector3f &my_vel,
  247. const Location &obstacle_loc,
  248. const Vector3f &obstacle_vel,
  249. const uint8_t time_horizon)
  250. {
  251. Vector2f delta_vel_ne = Vector2f(obstacle_vel[0] - my_vel[0], obstacle_vel[1] - my_vel[1]);
  252. const Vector2f delta_pos_ne = obstacle_loc.get_distance_NE(my_loc);
  253. Vector2f line_segment_ne = delta_vel_ne * time_horizon;
  254. float ret = Vector2<float>::closest_distance_between_radial_and_point
  255. (line_segment_ne,
  256. delta_pos_ne);
  257. debug(" time_horizon: (%d)", time_horizon);
  258. debug(" delta pos: (y=%f,x=%f)", delta_pos_ne[0], delta_pos_ne[1]);
  259. debug(" delta vel: (y=%f,x=%f)", delta_vel_ne[0], delta_vel_ne[1]);
  260. debug(" line segment: (y=%f,x=%f)", line_segment_ne[0], line_segment_ne[1]);
  261. debug(" closest: (%f)", ret);
  262. return ret;
  263. }
  264. // returns the closest these objects will get in the body z axis (in metres)
  265. float closest_approach_z(const Location &my_loc,
  266. const Vector3f &my_vel,
  267. const Location &obstacle_loc,
  268. const Vector3f &obstacle_vel,
  269. const uint8_t time_horizon)
  270. {
  271. float delta_vel_d = obstacle_vel[2] - my_vel[2];
  272. float delta_pos_d = obstacle_loc.alt - my_loc.alt;
  273. float ret;
  274. if (delta_pos_d >= 0 && delta_vel_d >= 0) {
  275. ret = delta_pos_d;
  276. } else if (delta_pos_d <= 0 && delta_vel_d <= 0) {
  277. ret = fabsf(delta_pos_d);
  278. } else {
  279. ret = fabsf(delta_pos_d - delta_vel_d * time_horizon);
  280. }
  281. debug(" time_horizon: (%d)", time_horizon);
  282. debug(" delta pos: (%f) metres", delta_pos_d/100.0f);
  283. debug(" delta vel: (%f) m/s", delta_vel_d);
  284. debug(" closest: (%f) metres", ret/100.0f);
  285. return ret/100.0f;
  286. }
  287. void AP_Avoidance::update_threat_level(const Location &my_loc,
  288. const Vector3f &my_vel,
  289. AP_Avoidance::Obstacle &obstacle)
  290. {
  291. Location &obstacle_loc = obstacle._location;
  292. Vector3f &obstacle_vel = obstacle._velocity;
  293. obstacle.threat_level = MAV_COLLISION_THREAT_LEVEL_NONE;
  294. const uint32_t obstacle_age = AP_HAL::millis() - obstacle.timestamp_ms;
  295. float closest_xy = closest_approach_xy(my_loc, my_vel, obstacle_loc, obstacle_vel, _fail_time_horizon + obstacle_age/1000);
  296. if (closest_xy < _fail_distance_xy) {
  297. obstacle.threat_level = MAV_COLLISION_THREAT_LEVEL_HIGH;
  298. } else {
  299. closest_xy = closest_approach_xy(my_loc, my_vel, obstacle_loc, obstacle_vel, _warn_time_horizon + obstacle_age/1000);
  300. if (closest_xy < _warn_distance_xy) {
  301. obstacle.threat_level = MAV_COLLISION_THREAT_LEVEL_LOW;
  302. }
  303. }
  304. // check for vertical separation; our threat level is the minimum
  305. // of vertical and horizontal threat levels
  306. float closest_z = closest_approach_z(my_loc, my_vel, obstacle_loc, obstacle_vel, _warn_time_horizon + obstacle_age/1000);
  307. if (obstacle.threat_level != MAV_COLLISION_THREAT_LEVEL_NONE) {
  308. if (closest_z > _warn_distance_z) {
  309. obstacle.threat_level = MAV_COLLISION_THREAT_LEVEL_NONE;
  310. } else {
  311. closest_z = closest_approach_z(my_loc, my_vel, obstacle_loc, obstacle_vel, _fail_time_horizon + obstacle_age/1000);
  312. if (closest_z > _fail_distance_z) {
  313. obstacle.threat_level = MAV_COLLISION_THREAT_LEVEL_LOW;
  314. }
  315. }
  316. }
  317. // If we haven't heard from a vehicle then assume it is no threat
  318. if (obstacle_age > MAX_OBSTACLE_AGE_MS) {
  319. obstacle.threat_level = MAV_COLLISION_THREAT_LEVEL_NONE;
  320. }
  321. // could optimise this to not calculate a lot of this if threat
  322. // level is none - but only *once the GCS has been informed*!
  323. obstacle.closest_approach_xy = closest_xy;
  324. obstacle.closest_approach_z = closest_z;
  325. float current_distance = my_loc.get_distance(obstacle_loc);
  326. obstacle.distance_to_closest_approach = current_distance - closest_xy;
  327. Vector2f net_velocity_ne = Vector2f(my_vel[0] - obstacle_vel[0], my_vel[1] - obstacle_vel[1]);
  328. obstacle.time_to_closest_approach = 0.0f;
  329. if (!is_zero(obstacle.distance_to_closest_approach) &&
  330. ! is_zero(net_velocity_ne.length())) {
  331. obstacle.time_to_closest_approach = obstacle.distance_to_closest_approach / net_velocity_ne.length();
  332. }
  333. }
  334. MAV_COLLISION_THREAT_LEVEL AP_Avoidance::current_threat_level() const {
  335. if (_obstacles == nullptr) {
  336. return MAV_COLLISION_THREAT_LEVEL_NONE;
  337. }
  338. if (_current_most_serious_threat == -1) {
  339. return MAV_COLLISION_THREAT_LEVEL_NONE;
  340. }
  341. return _obstacles[_current_most_serious_threat].threat_level;
  342. }
  343. void AP_Avoidance::send_collision_all(const AP_Avoidance::Obstacle &threat, MAV_COLLISION_ACTION behaviour) const
  344. {
  345. const mavlink_collision_t packet{
  346. id: threat.src_id,
  347. time_to_minimum_delta: threat.time_to_closest_approach,
  348. altitude_minimum_delta: threat.closest_approach_z,
  349. horizontal_minimum_delta: threat.closest_approach_xy,
  350. src: MAV_COLLISION_SRC_ADSB,
  351. action: (uint8_t)behaviour,
  352. threat_level: (uint8_t)threat.threat_level,
  353. };
  354. gcs().send_to_active_channels(MAVLINK_MSG_ID_COLLISION, (const char *)&packet);
  355. }
  356. void AP_Avoidance::handle_threat_gcs_notify(AP_Avoidance::Obstacle *threat)
  357. {
  358. if (threat == nullptr) {
  359. return;
  360. }
  361. uint32_t now = AP_HAL::millis();
  362. if (threat->threat_level == MAV_COLLISION_THREAT_LEVEL_NONE) {
  363. // only send cleared messages for a few seconds:
  364. if (_gcs_cleared_messages_first_sent == 0) {
  365. _gcs_cleared_messages_first_sent = now;
  366. }
  367. if (now - _gcs_cleared_messages_first_sent > _gcs_cleared_messages_duration * 1000) {
  368. return;
  369. }
  370. } else {
  371. _gcs_cleared_messages_first_sent = 0;
  372. }
  373. if (now - threat->last_gcs_report_time > _gcs_notify_interval * 1000) {
  374. send_collision_all(*threat, mav_avoidance_action());
  375. threat->last_gcs_report_time = now;
  376. }
  377. }
  378. bool AP_Avoidance::obstacle_is_more_serious_threat(const AP_Avoidance::Obstacle &obstacle) const
  379. {
  380. if (_current_most_serious_threat == -1) {
  381. // any threat is more of a threat than no threat
  382. return true;
  383. }
  384. const AP_Avoidance::Obstacle &current = _obstacles[_current_most_serious_threat];
  385. if (obstacle.threat_level > current.threat_level) {
  386. // threat_level is updated by update_threat_level
  387. return true;
  388. }
  389. if (obstacle.threat_level == current.threat_level &&
  390. obstacle.time_to_closest_approach < current.time_to_closest_approach) {
  391. return true;
  392. }
  393. return false;
  394. }
  395. void AP_Avoidance::check_for_threats()
  396. {
  397. const AP_AHRS &_ahrs = AP::ahrs();
  398. Location my_loc;
  399. if (!_ahrs.get_position(my_loc)) {
  400. // if we don't know our own location we can't determine any threat level
  401. return;
  402. }
  403. Vector3f my_vel;
  404. if (!_ahrs.get_velocity_NED(my_vel)) {
  405. // assuming our own velocity to be zero here may cause us to
  406. // fly into something. Better not to attempt to avoid in this
  407. // case.
  408. return;
  409. }
  410. // we always check all obstacles to see if they are threats since it
  411. // is most likely our own position and/or velocity have changed
  412. // determine the current most-serious-threat
  413. _current_most_serious_threat = -1;
  414. for (uint8_t i=0; i<_obstacle_count; i++) {
  415. AP_Avoidance::Obstacle &obstacle = _obstacles[i];
  416. const uint32_t obstacle_age = AP_HAL::millis() - obstacle.timestamp_ms;
  417. debug("i=%d src_id=%d timestamp=%u age=%d", i, obstacle.src_id, obstacle.timestamp_ms, obstacle_age);
  418. update_threat_level(my_loc, my_vel, obstacle);
  419. debug(" threat-level=%d", obstacle.threat_level);
  420. // ignore any really old data:
  421. if (obstacle_age > MAX_OBSTACLE_AGE_MS) {
  422. // shrink list if this is the last entry:
  423. if (i == _obstacle_count-1) {
  424. _obstacle_count -= 1;
  425. }
  426. continue;
  427. }
  428. if (obstacle_is_more_serious_threat(obstacle)) {
  429. _current_most_serious_threat = i;
  430. }
  431. }
  432. if (_current_most_serious_threat != -1) {
  433. debug("Current most serious threat: %d level=%d", _current_most_serious_threat, _obstacles[_current_most_serious_threat].threat_level);
  434. }
  435. }
  436. AP_Avoidance::Obstacle *AP_Avoidance::most_serious_threat()
  437. {
  438. if (_current_most_serious_threat < 0) {
  439. // we *really_ should not have been called!
  440. return nullptr;
  441. }
  442. return &_obstacles[_current_most_serious_threat];
  443. }
  444. void AP_Avoidance::update()
  445. {
  446. if (!check_startup()) {
  447. return;
  448. }
  449. if (_adsb.enabled()) {
  450. get_adsb_samples();
  451. }
  452. check_for_threats();
  453. // notify GCS of most serious thread
  454. handle_threat_gcs_notify(most_serious_threat());
  455. // avoid object (if necessary)
  456. handle_avoidance_local(most_serious_threat());
  457. }
  458. void AP_Avoidance::handle_avoidance_local(AP_Avoidance::Obstacle *threat)
  459. {
  460. MAV_COLLISION_THREAT_LEVEL new_threat_level = MAV_COLLISION_THREAT_LEVEL_NONE;
  461. MAV_COLLISION_ACTION action = MAV_COLLISION_ACTION_NONE;
  462. if (threat != nullptr) {
  463. new_threat_level = threat->threat_level;
  464. if (new_threat_level == MAV_COLLISION_THREAT_LEVEL_HIGH) {
  465. action = (MAV_COLLISION_ACTION)_fail_action.get();
  466. Location my_loc;
  467. if (action != MAV_COLLISION_ACTION_NONE && _fail_altitude_minimum > 0 &&
  468. AP::ahrs().get_position(my_loc) && ((my_loc.alt*0.01f) < _fail_altitude_minimum)) {
  469. // disable avoidance when close to ground, report only
  470. action = MAV_COLLISION_ACTION_REPORT;
  471. }
  472. }
  473. }
  474. uint32_t now = AP_HAL::millis();
  475. if (new_threat_level != _threat_level) {
  476. // transition to higher states immediately, recovery to lower states more slowly
  477. if (((now - _last_state_change_ms) > AP_AVOIDANCE_STATE_RECOVERY_TIME_MS) || (new_threat_level > _threat_level)) {
  478. // handle recovery from high threat level
  479. if (_threat_level == MAV_COLLISION_THREAT_LEVEL_HIGH) {
  480. handle_recovery(_fail_recovery);
  481. _latest_action = MAV_COLLISION_ACTION_NONE;
  482. }
  483. // update state
  484. _last_state_change_ms = now;
  485. _threat_level = new_threat_level;
  486. }
  487. }
  488. // handle ongoing threat by calling vehicle specific handler
  489. if ((threat != nullptr) && (_threat_level == MAV_COLLISION_THREAT_LEVEL_HIGH) && (action > MAV_COLLISION_ACTION_REPORT)) {
  490. _latest_action = handle_avoidance(threat, action);
  491. }
  492. }
  493. void AP_Avoidance::handle_msg(const mavlink_message_t &msg)
  494. {
  495. if (!check_startup()) {
  496. // avoidance is not active / allocated
  497. return;
  498. }
  499. if (msg.msgid != MAVLINK_MSG_ID_GLOBAL_POSITION_INT) {
  500. // we only take position from GLOBAL_POSITION_INT
  501. return;
  502. }
  503. if (msg.sysid == mavlink_system.sysid) {
  504. // we do not obstruct ourselves....
  505. return;
  506. }
  507. // inform AP_Avoidance we have a new player
  508. mavlink_global_position_int_t packet;
  509. mavlink_msg_global_position_int_decode(&msg, &packet);
  510. Location loc;
  511. loc.lat = packet.lat;
  512. loc.lng = packet.lon;
  513. loc.alt = packet.alt / 10; // mm -> cm
  514. loc.relative_alt = false;
  515. Vector3f vel = Vector3f(packet.vx/100.0f, // cm to m
  516. packet.vy/100.0f,
  517. packet.vz/100.0f);
  518. add_obstacle(AP_HAL::millis(),
  519. MAV_COLLISION_SRC_MAVLINK_GPS_GLOBAL_INT,
  520. msg.sysid,
  521. loc,
  522. vel);
  523. }
  524. // get unit vector away from the nearest obstacle
  525. bool AP_Avoidance::get_vector_perpendicular(const AP_Avoidance::Obstacle *obstacle, Vector3f &vec_neu)
  526. {
  527. if (obstacle == nullptr) {
  528. // why where we called?!
  529. return false;
  530. }
  531. Location my_abs_pos;
  532. if (!AP::ahrs().get_position(my_abs_pos)) {
  533. // we should not get to here! If we don't know our position
  534. // we can't know if there are any threats, for starters!
  535. return false;
  536. }
  537. // if their velocity is moving around close to zero then flying
  538. // perpendicular to that velocity may mean we do weird things.
  539. // Instead, we will fly directly away from them
  540. if (obstacle->_velocity.length() < _low_velocity_threshold) {
  541. const Vector2f delta_pos_xy = obstacle->_location.get_distance_NE(my_abs_pos);
  542. const float delta_pos_z = my_abs_pos.alt - obstacle->_location.alt;
  543. Vector3f delta_pos_xyz = Vector3f(delta_pos_xy.x, delta_pos_xy.y, delta_pos_z);
  544. // avoid div by zero
  545. if (delta_pos_xyz.is_zero()) {
  546. return false;
  547. }
  548. delta_pos_xyz.normalize();
  549. vec_neu = delta_pos_xyz;
  550. return true;
  551. } else {
  552. vec_neu = perpendicular_xyz(obstacle->_location, obstacle->_velocity, my_abs_pos);
  553. // avoid div by zero
  554. if (vec_neu.is_zero()) {
  555. return false;
  556. }
  557. vec_neu.normalize();
  558. return true;
  559. }
  560. }
  561. // helper functions to calculate 3D destination to get us away from obstacle
  562. // v1 is NED
  563. Vector3f AP_Avoidance::perpendicular_xyz(const Location &p1, const Vector3f &v1, const Location &p2)
  564. {
  565. const Vector2f delta_p_2d = p1.get_distance_NE(p2);
  566. Vector3f delta_p_xyz = Vector3f(delta_p_2d[0],delta_p_2d[1],(p2.alt-p1.alt)/100.0f); //check this line
  567. Vector3f v1_xyz = Vector3f(v1[0], v1[1], -v1[2]);
  568. Vector3f ret = Vector3f::perpendicular(delta_p_xyz, v1_xyz);
  569. return ret;
  570. }
  571. // helper functions to calculate horizontal destination to get us away from obstacle
  572. // v1 is NED
  573. Vector2f AP_Avoidance::perpendicular_xy(const Location &p1, const Vector3f &v1, const Location &p2)
  574. {
  575. const Vector2f delta_p = p1.get_distance_NE(p2);
  576. Vector2f delta_p_n = Vector2f(delta_p[0],delta_p[1]);
  577. Vector2f v1n(v1[0],v1[1]);
  578. Vector2f ret_xy = Vector2f::perpendicular(delta_p_n, v1n);
  579. return ret_xy;
  580. }