Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Path: blob/master/libraries/AP_Avoidance/AP_Avoidance.cpp
Views: 1798
#include "AP_Avoidance.h"12#if HAL_ADSB_ENABLED34extern const AP_HAL::HAL& hal;56#include <limits>7#include <AP_AHRS/AP_AHRS.h>8#include <GCS_MAVLink/GCS.h>9#include <AP_Vehicle/AP_Vehicle_Type.h>1011#define AVOIDANCE_DEBUGGING 01213#if APM_BUILD_TYPE(APM_BUILD_ArduPlane)14#define AP_AVOIDANCE_WARN_TIME_DEFAULT 3015#define AP_AVOIDANCE_FAIL_TIME_DEFAULT 3016#define AP_AVOIDANCE_WARN_DISTANCE_XY_DEFAULT 100017#define AP_AVOIDANCE_WARN_DISTANCE_Z_DEFAULT 30018#define AP_AVOIDANCE_FAIL_DISTANCE_XY_DEFAULT 30019#define AP_AVOIDANCE_FAIL_DISTANCE_Z_DEFAULT 10020#define AP_AVOIDANCE_RECOVERY_DEFAULT RecoveryAction::RESUME_IF_AUTO_ELSE_LOITER21#define AP_AVOIDANCE_FAIL_ACTION_DEFAULT MAV_COLLISION_ACTION_REPORT22#else // APM_BUILD_TYPE(APM_BUILD_ArduCopter),Heli, Rover, Boat23#define AP_AVOIDANCE_WARN_TIME_DEFAULT 3024#define AP_AVOIDANCE_FAIL_TIME_DEFAULT 3025#define AP_AVOIDANCE_WARN_DISTANCE_XY_DEFAULT 30026#define AP_AVOIDANCE_WARN_DISTANCE_Z_DEFAULT 30027#define AP_AVOIDANCE_FAIL_DISTANCE_XY_DEFAULT 10028#define AP_AVOIDANCE_FAIL_DISTANCE_Z_DEFAULT 10029#define AP_AVOIDANCE_RECOVERY_DEFAULT RecoveryAction::RTL30#define AP_AVOIDANCE_FAIL_ACTION_DEFAULT MAV_COLLISION_ACTION_REPORT31#endif3233#if AVOIDANCE_DEBUGGING34#include <stdio.h>35#define debug(fmt, args ...) do {::fprintf(stderr,"%s:%d: " fmt "\n", __FUNCTION__, __LINE__, ## args); } while(0)36#else37#define debug(fmt, args ...)38#endif3940// table of user settable parameters41const AP_Param::GroupInfo AP_Avoidance::var_info[] = {4243// @Param: ENABLE44// @DisplayName: Enable Avoidance using ADSB45// @Description: Enable Avoidance using ADSB46// @Values: 0:Disabled,1:Enabled47// @User: Advanced48AP_GROUPINFO_FLAGS("ENABLE", 1, AP_Avoidance, _enabled, 0, AP_PARAM_FLAG_ENABLE),4950// @Param: F_ACTION51// @DisplayName: Collision Avoidance Behavior52// @Description: Specifies aircraft behaviour when a collision is imminent53// @Values: 0:None,1:Report,2:Climb Or Descend,3:Move Horizontally,4:Move Perpendicularly in 3D,5:RTL,6:Hover54// @User: Advanced55AP_GROUPINFO("F_ACTION", 2, AP_Avoidance, _fail_action, AP_AVOIDANCE_FAIL_ACTION_DEFAULT),5657// @Param: W_ACTION58// @DisplayName: Collision Avoidance Behavior - Warn59// @Description: Specifies aircraft behaviour when a collision may occur60// @Values: 0:None,1:Report61// @User: Advanced62AP_GROUPINFO("W_ACTION", 3, AP_Avoidance, _warn_action, MAV_COLLISION_ACTION_REPORT),6364// @Param: F_RCVRY65// @DisplayName: Recovery behaviour after a fail event66// @Description: Determines what the aircraft will do after a fail event is resolved67// @Values: 0:Remain in AVOID_ADSB,1:Resume previous flight mode,2:RTL,3:Resume if AUTO else Loiter68// @User: Advanced69AP_GROUPINFO("F_RCVRY", 4, AP_Avoidance, _fail_recovery, uint8_t(AP_AVOIDANCE_RECOVERY_DEFAULT)),7071// @Param: OBS_MAX72// @DisplayName: Maximum number of obstacles to track73// @Description: Maximum number of obstacles to track74// @User: Advanced75AP_GROUPINFO("OBS_MAX", 5, AP_Avoidance, _obstacles_max, 20),7677// @Param: W_TIME78// @DisplayName: Time Horizon Warn79// @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)80// @Units: s81// @User: Advanced82AP_GROUPINFO("W_TIME", 6, AP_Avoidance, _warn_time_horizon, AP_AVOIDANCE_WARN_TIME_DEFAULT),8384// @Param: F_TIME85// @DisplayName: Time Horizon Fail86// @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 undertaken87// @Units: s88// @User: Advanced89AP_GROUPINFO("F_TIME", 7, AP_Avoidance, _fail_time_horizon, AP_AVOIDANCE_FAIL_TIME_DEFAULT),9091// @Param: W_DIST_XY92// @DisplayName: Distance Warn XY93// @Description: Closest allowed projected distance before W_ACTION is undertaken94// @Units: m95// @User: Advanced96AP_GROUPINFO("W_DIST_XY", 8, AP_Avoidance, _warn_distance_xy, AP_AVOIDANCE_WARN_DISTANCE_XY_DEFAULT),9798// @Param: F_DIST_XY99// @DisplayName: Distance Fail XY100// @Description: Closest allowed projected distance before F_ACTION is undertaken101// @Units: m102// @User: Advanced103AP_GROUPINFO("F_DIST_XY", 9, AP_Avoidance, _fail_distance_xy, AP_AVOIDANCE_FAIL_DISTANCE_XY_DEFAULT),104105// @Param: W_DIST_Z106// @DisplayName: Distance Warn Z107// @Description: Closest allowed projected distance before BEHAVIOUR_W is undertaken108// @Units: m109// @User: Advanced110AP_GROUPINFO("W_DIST_Z", 10, AP_Avoidance, _warn_distance_z, AP_AVOIDANCE_WARN_DISTANCE_Z_DEFAULT),111112// @Param: F_DIST_Z113// @DisplayName: Distance Fail Z114// @Description: Closest allowed projected distance before BEHAVIOUR_F is undertaken115// @Units: m116// @User: Advanced117AP_GROUPINFO("F_DIST_Z", 11, AP_Avoidance, _fail_distance_z, AP_AVOIDANCE_FAIL_DISTANCE_Z_DEFAULT),118119// @Param: F_ALT_MIN120// @DisplayName: ADS-B avoidance minimum altitude121// @Description: Minimum AMSL (above mean sea level) 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.122// @Units: m123// @User: Advanced124AP_GROUPINFO("F_ALT_MIN", 12, AP_Avoidance, _fail_altitude_minimum, 0),125126AP_GROUPEND127};128129AP_Avoidance::AP_Avoidance(AP_ADSB &adsb) :130_adsb(adsb)131{132AP_Param::setup_object_defaults(this, var_info);133if (_singleton != nullptr) {134AP_HAL::panic("AP_Avoidance must be singleton");135}136_singleton = this;137}138139/*140* Initialize variables and allocate memory for array141*/142void AP_Avoidance::init(void)143{144debug("ADSB initialisation: %d obstacles", _obstacles_max.get());145if (_obstacles == nullptr) {146_obstacles = NEW_NOTHROW AP_Avoidance::Obstacle[_obstacles_max];147148if (_obstacles == nullptr) {149// dynamic RAM allocation of _obstacles[] failed, disable gracefully150DEV_PRINTF("Unable to initialize Avoidance obstacle list\n");151// disable ourselves to avoid repeated allocation attempts152_enabled.set(0);153return;154}155_obstacles_allocated = _obstacles_max;156}157_obstacle_count = 0;158_last_state_change_ms = 0;159_threat_level = MAV_COLLISION_THREAT_LEVEL_NONE;160_gcs_cleared_messages_first_sent = std::numeric_limits<uint32_t>::max();161_current_most_serious_threat = -1;162}163164/*165* de-initialize and free up some memory166*/167void AP_Avoidance::deinit(void)168{169if (_obstacles != nullptr) {170delete [] _obstacles;171_obstacles = nullptr;172_obstacles_allocated = 0;173handle_recovery(RecoveryAction::RTL);174}175_obstacle_count = 0;176}177178bool AP_Avoidance::check_startup()179{180if (!_enabled) {181if (_obstacles != nullptr) {182deinit();183}184// nothing to do185return false;186}187if (_obstacles == nullptr) {188init();189}190return _obstacles != nullptr;191}192193// vel is north/east/down!194void AP_Avoidance::add_obstacle(const uint32_t obstacle_timestamp_ms,195const MAV_COLLISION_SRC src,196const uint32_t src_id,197const Location &loc,198const Vector3f &vel_ned)199{200if (! check_startup()) {201return;202}203uint32_t oldest_timestamp = std::numeric_limits<uint32_t>::max();204uint8_t oldest_index = 255; // avoid compiler warning with initialisation205int16_t index = -1;206uint8_t i;207for (i=0; i<_obstacle_count; i++) {208if (_obstacles[i].src_id == src_id &&209_obstacles[i].src == src) {210// pre-existing obstacle found; we will update its information211index = i;212break;213}214if (_obstacles[i].timestamp_ms < oldest_timestamp) {215oldest_timestamp = _obstacles[i].timestamp_ms;216oldest_index = i;217}218}219WITH_SEMAPHORE(_rsem);220221if (index == -1) {222// existing obstacle not found. See if we can store it anyway:223if (i <_obstacles_allocated) {224// have room to store more vehicles...225index = _obstacle_count++;226} else if (oldest_timestamp < obstacle_timestamp_ms) {227// replace this very old entry with this new data228index = oldest_index;229} else {230// no room for this (old?!) data231return;232}233234_obstacles[index].src = src;235_obstacles[index].src_id = src_id;236}237238_obstacles[index]._location = loc;239_obstacles[index]._velocity = vel_ned;240_obstacles[index].timestamp_ms = obstacle_timestamp_ms;241}242243void AP_Avoidance::add_obstacle(const uint32_t obstacle_timestamp_ms,244const MAV_COLLISION_SRC src,245const uint32_t src_id,246const Location &loc,247const float cog,248const float hspeed,249const float vspeed)250{251Vector3f vel;252vel[0] = hspeed * cosf(radians(cog));253vel[1] = hspeed * sinf(radians(cog));254vel[2] = vspeed;255// debug("cog=%f hspeed=%f veln=%f vele=%f", cog, hspeed, vel[0], vel[1]);256return add_obstacle(obstacle_timestamp_ms, src, src_id, loc, vel);257}258259uint32_t AP_Avoidance::src_id_for_adsb_vehicle(const AP_ADSB::adsb_vehicle_t &vehicle) const260{261// TODO: need to include squawk code and callsign262return vehicle.info.ICAO_address;263}264265void AP_Avoidance::get_adsb_samples()266{267AP_ADSB::adsb_vehicle_t vehicle;268while (_adsb.next_sample(vehicle)) {269uint32_t src_id = src_id_for_adsb_vehicle(vehicle);270Location loc = _adsb.get_location(vehicle);271add_obstacle(vehicle.last_update_ms,272MAV_COLLISION_SRC_ADSB,273src_id,274loc,275vehicle.info.heading * 0.01,276vehicle.info.hor_velocity * 0.01,277-vehicle.info.ver_velocity * 0.01); // convert cm-up to m-down278}279}280281float closest_approach_xy(const Location &my_loc,282const Vector3f &my_vel,283const Location &obstacle_loc,284const Vector3f &obstacle_vel,285const uint8_t time_horizon)286{287288Vector2f delta_vel_ne = Vector2f(obstacle_vel[0] - my_vel[0], obstacle_vel[1] - my_vel[1]);289const Vector2f delta_pos_ne = obstacle_loc.get_distance_NE(my_loc);290291Vector2f line_segment_ne = delta_vel_ne * time_horizon;292293float ret = Vector2<float>::closest_distance_between_radial_and_point294(line_segment_ne,295delta_pos_ne);296297debug(" time_horizon: (%d)", time_horizon);298debug(" delta pos: (y=%f,x=%f)", delta_pos_ne[0], delta_pos_ne[1]);299debug(" delta vel: (y=%f,x=%f)", delta_vel_ne[0], delta_vel_ne[1]);300debug(" line segment: (y=%f,x=%f)", line_segment_ne[0], line_segment_ne[1]);301debug(" closest: (%f)", ret);302303return ret;304}305306// returns the closest these objects will get in the body z axis (in metres)307float closest_approach_z(const Location &my_loc,308const Vector3f &my_vel,309const Location &obstacle_loc,310const Vector3f &obstacle_vel,311const uint8_t time_horizon)312{313314float delta_vel_d = obstacle_vel[2] - my_vel[2];315float delta_pos_d = obstacle_loc.alt - my_loc.alt;316317float ret;318if (delta_pos_d >= 0 && delta_vel_d >= 0) {319ret = delta_pos_d;320} else if (delta_pos_d <= 0 && delta_vel_d <= 0) {321ret = fabsf(delta_pos_d);322} else {323ret = fabsf(delta_pos_d - delta_vel_d * time_horizon);324}325326debug(" time_horizon: (%d)", time_horizon);327debug(" delta pos: (%f) metres", delta_pos_d*0.01f);328debug(" delta vel: (%f) m/s", delta_vel_d);329debug(" closest: (%f) metres", ret*0.01f);330331return ret*0.01f;332}333334void AP_Avoidance::update_threat_level(const Location &my_loc,335const Vector3f &my_vel,336AP_Avoidance::Obstacle &obstacle)337{338339Location &obstacle_loc = obstacle._location;340Vector3f &obstacle_vel = obstacle._velocity;341342obstacle.threat_level = MAV_COLLISION_THREAT_LEVEL_NONE;343344const uint32_t obstacle_age = AP_HAL::millis() - obstacle.timestamp_ms;345float closest_xy = closest_approach_xy(my_loc, my_vel, obstacle_loc, obstacle_vel, _fail_time_horizon + obstacle_age/1000);346if (closest_xy < _fail_distance_xy) {347obstacle.threat_level = MAV_COLLISION_THREAT_LEVEL_HIGH;348} else {349closest_xy = closest_approach_xy(my_loc, my_vel, obstacle_loc, obstacle_vel, _warn_time_horizon + obstacle_age/1000);350if (closest_xy < _warn_distance_xy) {351obstacle.threat_level = MAV_COLLISION_THREAT_LEVEL_LOW;352}353}354355// check for vertical separation; our threat level is the minimum356// of vertical and horizontal threat levels357float closest_z = closest_approach_z(my_loc, my_vel, obstacle_loc, obstacle_vel, _warn_time_horizon + obstacle_age/1000);358if (obstacle.threat_level != MAV_COLLISION_THREAT_LEVEL_NONE) {359if (closest_z > _warn_distance_z) {360obstacle.threat_level = MAV_COLLISION_THREAT_LEVEL_NONE;361} else {362closest_z = closest_approach_z(my_loc, my_vel, obstacle_loc, obstacle_vel, _fail_time_horizon + obstacle_age/1000);363if (closest_z > _fail_distance_z) {364obstacle.threat_level = MAV_COLLISION_THREAT_LEVEL_LOW;365}366}367}368369// If we haven't heard from a vehicle then assume it is no threat370if (obstacle_age > MAX_OBSTACLE_AGE_MS) {371obstacle.threat_level = MAV_COLLISION_THREAT_LEVEL_NONE;372}373374// could optimise this to not calculate a lot of this if threat375// level is none - but only *once the GCS has been informed*!376obstacle.closest_approach_xy = closest_xy;377obstacle.closest_approach_z = closest_z;378float current_distance = my_loc.get_distance(obstacle_loc);379obstacle.distance_to_closest_approach = current_distance - closest_xy;380Vector2f net_velocity_ne = Vector2f(my_vel[0] - obstacle_vel[0], my_vel[1] - obstacle_vel[1]);381obstacle.time_to_closest_approach = 0.0f;382if (!is_zero(obstacle.distance_to_closest_approach) &&383! is_zero(net_velocity_ne.length())) {384obstacle.time_to_closest_approach = obstacle.distance_to_closest_approach / net_velocity_ne.length();385}386}387388MAV_COLLISION_THREAT_LEVEL AP_Avoidance::current_threat_level() const {389if (_obstacles == nullptr) {390return MAV_COLLISION_THREAT_LEVEL_NONE;391}392if (_current_most_serious_threat == -1) {393return MAV_COLLISION_THREAT_LEVEL_NONE;394}395return _obstacles[_current_most_serious_threat].threat_level;396}397398#if HAL_GCS_ENABLED399void AP_Avoidance::send_collision_all(const AP_Avoidance::Obstacle &threat, MAV_COLLISION_ACTION behaviour) const400{401const mavlink_collision_t packet{402id: threat.src_id,403time_to_minimum_delta: threat.time_to_closest_approach,404altitude_minimum_delta: threat.closest_approach_z,405horizontal_minimum_delta: threat.closest_approach_xy,406src: MAV_COLLISION_SRC_ADSB,407action: (uint8_t)behaviour,408threat_level: (uint8_t)threat.threat_level,409};410gcs().send_to_active_channels(MAVLINK_MSG_ID_COLLISION, (const char *)&packet);411}412#endif413414void AP_Avoidance::handle_threat_gcs_notify(AP_Avoidance::Obstacle *threat)415{416if (threat == nullptr) {417return;418}419420uint32_t now = AP_HAL::millis();421if (threat->threat_level == MAV_COLLISION_THREAT_LEVEL_NONE) {422// only send cleared messages for a few seconds:423if (_gcs_cleared_messages_first_sent == 0) {424_gcs_cleared_messages_first_sent = now;425}426if (now - _gcs_cleared_messages_first_sent > _gcs_cleared_messages_duration * 1000) {427return;428}429} else {430_gcs_cleared_messages_first_sent = 0;431}432if (now - threat->last_gcs_report_time > _gcs_notify_interval * 1000) {433send_collision_all(*threat, mav_avoidance_action());434threat->last_gcs_report_time = now;435}436437}438439bool AP_Avoidance::obstacle_is_more_serious_threat(const AP_Avoidance::Obstacle &obstacle) const440{441if (_current_most_serious_threat == -1) {442// any threat is more of a threat than no threat443return true;444}445const AP_Avoidance::Obstacle ¤t = _obstacles[_current_most_serious_threat];446if (obstacle.threat_level > current.threat_level) {447// threat_level is updated by update_threat_level448return true;449}450if (obstacle.threat_level == current.threat_level &&451obstacle.time_to_closest_approach < current.time_to_closest_approach) {452return true;453}454return false;455}456457void AP_Avoidance::check_for_threats()458{459const AP_AHRS &_ahrs = AP::ahrs();460461Location my_loc;462if (!_ahrs.get_location(my_loc)) {463// if we don't know our own location we can't determine any threat level464return;465}466467Vector3f my_vel;468if (!_ahrs.get_velocity_NED(my_vel)) {469// assuming our own velocity to be zero here may cause us to470// fly into something. Better not to attempt to avoid in this471// case.472return;473}474475// we always check all obstacles to see if they are threats since it476// is most likely our own position and/or velocity have changed477// determine the current most-serious-threat478_current_most_serious_threat = -1;479for (uint8_t i=0; i<_obstacle_count; i++) {480481AP_Avoidance::Obstacle &obstacle = _obstacles[i];482const uint32_t obstacle_age = AP_HAL::millis() - obstacle.timestamp_ms;483debug("i=%d src_id=%d timestamp=%u age=%d", i, obstacle.src_id, obstacle.timestamp_ms, obstacle_age);484485update_threat_level(my_loc, my_vel, obstacle);486debug(" threat-level=%d", obstacle.threat_level);487488// ignore any really old data:489if (obstacle_age > MAX_OBSTACLE_AGE_MS) {490// shrink list if this is the last entry:491if (i == _obstacle_count-1) {492_obstacle_count -= 1;493}494continue;495}496497if (obstacle_is_more_serious_threat(obstacle)) {498_current_most_serious_threat = i;499}500}501if (_current_most_serious_threat != -1) {502debug("Current most serious threat: %d level=%d", _current_most_serious_threat, _obstacles[_current_most_serious_threat].threat_level);503}504}505506507AP_Avoidance::Obstacle *AP_Avoidance::most_serious_threat()508{509if (_current_most_serious_threat < 0) {510// we *really_ should not have been called!511return nullptr;512}513return &_obstacles[_current_most_serious_threat];514}515516517void AP_Avoidance::update()518{519if (!check_startup()) {520return;521}522523if (_adsb.enabled()) {524get_adsb_samples();525}526527check_for_threats();528529// avoid object (if necessary)530handle_avoidance_local(most_serious_threat());531532// notify GCS of most serious thread533handle_threat_gcs_notify(most_serious_threat());534}535536void AP_Avoidance::handle_avoidance_local(AP_Avoidance::Obstacle *threat)537{538MAV_COLLISION_THREAT_LEVEL new_threat_level = MAV_COLLISION_THREAT_LEVEL_NONE;539MAV_COLLISION_ACTION action = MAV_COLLISION_ACTION_NONE;540541if (threat != nullptr) {542new_threat_level = threat->threat_level;543if (new_threat_level == MAV_COLLISION_THREAT_LEVEL_HIGH) {544action = (MAV_COLLISION_ACTION)_fail_action.get();545Location my_loc;546if (action != MAV_COLLISION_ACTION_NONE && _fail_altitude_minimum > 0 &&547AP::ahrs().get_location(my_loc) && ((my_loc.alt*0.01f) < _fail_altitude_minimum)) {548// disable avoidance when close to ground, report only549action = MAV_COLLISION_ACTION_REPORT;550}551}552}553554uint32_t now = AP_HAL::millis();555556if (new_threat_level != _threat_level) {557// transition to higher states immediately, recovery to lower states more slowly558if (((now - _last_state_change_ms) > AP_AVOIDANCE_STATE_RECOVERY_TIME_MS) || (new_threat_level > _threat_level)) {559// handle recovery from high threat level560if (_threat_level == MAV_COLLISION_THREAT_LEVEL_HIGH) {561handle_recovery(RecoveryAction(_fail_recovery.get()));562_latest_action = MAV_COLLISION_ACTION_NONE;563}564565// update state566_last_state_change_ms = now;567_threat_level = new_threat_level;568}569}570571// handle ongoing threat by calling vehicle specific handler572if ((threat != nullptr) && (_threat_level == MAV_COLLISION_THREAT_LEVEL_HIGH) && (action > MAV_COLLISION_ACTION_REPORT)) {573_latest_action = handle_avoidance(threat, action);574}575}576577578void AP_Avoidance::handle_msg(const mavlink_message_t &msg)579{580if (!check_startup()) {581// avoidance is not active / allocated582return;583}584585if (msg.msgid != MAVLINK_MSG_ID_GLOBAL_POSITION_INT) {586// we only take position from GLOBAL_POSITION_INT587return;588}589590if (msg.sysid == mavlink_system.sysid) {591// we do not obstruct ourselves....592return;593}594595// inform AP_Avoidance we have a new player596mavlink_global_position_int_t packet;597mavlink_msg_global_position_int_decode(&msg, &packet);598const Location loc {599packet.lat,600packet.lon,601int32_t(packet.alt * 0.1), // mm -> cm602Location::AltFrame::ABSOLUTE603};604const Vector3f vel {605packet.vx * 0.01f, // cm to m606packet.vy * 0.01f,607packet.vz * 0.01f608};609add_obstacle(AP_HAL::millis(),610MAV_COLLISION_SRC_MAVLINK_GPS_GLOBAL_INT,611msg.sysid,612loc,613vel);614}615616// get unit vector away from the nearest obstacle617bool AP_Avoidance::get_vector_perpendicular(const AP_Avoidance::Obstacle *obstacle, Vector3f &vec_neu) const618{619if (obstacle == nullptr) {620// why where we called?!621return false;622}623624Location my_abs_pos;625if (!AP::ahrs().get_location(my_abs_pos)) {626// we should not get to here! If we don't know our position627// we can't know if there are any threats, for starters!628return false;629}630631// if their velocity is moving around close to zero then flying632// perpendicular to that velocity may mean we do weird things.633// Instead, we will fly directly away from them634if (obstacle->_velocity.length() < _low_velocity_threshold) {635const Vector2f delta_pos_xy = obstacle->_location.get_distance_NE(my_abs_pos);636const float delta_pos_z = my_abs_pos.alt - obstacle->_location.alt;637Vector3f delta_pos_xyz = Vector3f(delta_pos_xy.x, delta_pos_xy.y, delta_pos_z);638// avoid div by zero639if (delta_pos_xyz.is_zero()) {640return false;641}642delta_pos_xyz.normalize();643vec_neu = delta_pos_xyz;644return true;645} else {646vec_neu = perpendicular_xyz(obstacle->_location, obstacle->_velocity, my_abs_pos);647// avoid div by zero648if (vec_neu.is_zero()) {649return false;650}651vec_neu.normalize();652return true;653}654}655656// helper functions to calculate 3D destination to get us away from obstacle657// v1 is NED658Vector3f AP_Avoidance::perpendicular_xyz(const Location &p1, const Vector3f &v1, const Location &p2)659{660const Vector2f delta_p_2d = p1.get_distance_NE(p2);661Vector3f delta_p_xyz = Vector3f(delta_p_2d[0],delta_p_2d[1],(p2.alt-p1.alt)*0.01f); //check this line662Vector3f v1_xyz = Vector3f(v1[0], v1[1], -v1[2]);663Vector3f ret = Vector3f::perpendicular(delta_p_xyz, v1_xyz);664return ret;665}666667// helper functions to calculate horizontal destination to get us away from obstacle668// v1 is NED669Vector2f AP_Avoidance::perpendicular_xy(const Location &p1, const Vector3f &v1, const Location &p2)670{671const Vector2f delta_p = p1.get_distance_NE(p2);672Vector2f delta_p_n = Vector2f(delta_p[0],delta_p[1]);673Vector2f v1n(v1[0],v1[1]);674Vector2f ret_xy = Vector2f::perpendicular(delta_p_n, v1n);675return ret_xy;676}677678679// singleton instance680AP_Avoidance *AP_Avoidance::_singleton;681682namespace AP {683684AP_Avoidance *ap_avoidance()685{686return AP_Avoidance::get_singleton();687}688689}690691#endif // HAL_ADSB_ENABLED692693694