Path: blob/master/libraries/AP_Avoidance/AP_Avoidance.cpp
9405 views
#include "AP_Avoidance_config.h"12#if AP_ADSB_AVOIDANCE_ENABLED34#include "AP_Avoidance.h"56extern const AP_HAL::HAL& hal;78#include <limits>9#include <AP_AHRS/AP_AHRS.h>10#include <GCS_MAVLink/GCS.h>11#include <AP_Vehicle/AP_Vehicle_Type.h>1213#define AVOIDANCE_DEBUGGING 01415#if APM_BUILD_TYPE(APM_BUILD_ArduPlane)16#define AP_AVOIDANCE_WARN_TIME_DEFAULT 3017#define AP_AVOIDANCE_FAIL_TIME_DEFAULT 3018#define AP_AVOIDANCE_WARN_DISTANCE_XY_DEFAULT 100019#define AP_AVOIDANCE_WARN_DISTANCE_Z_DEFAULT 30020#define AP_AVOIDANCE_FAIL_DISTANCE_XY_DEFAULT 30021#define AP_AVOIDANCE_FAIL_DISTANCE_Z_DEFAULT 10022#define AP_AVOIDANCE_RECOVERY_DEFAULT RecoveryAction::RESUME_IF_AUTO_ELSE_LOITER23#define AP_AVOIDANCE_FAIL_ACTION_DEFAULT MAV_COLLISION_ACTION_REPORT24#else // APM_BUILD_TYPE(APM_BUILD_ArduCopter),Heli, Rover, Boat25#define AP_AVOIDANCE_WARN_TIME_DEFAULT 3026#define AP_AVOIDANCE_FAIL_TIME_DEFAULT 3027#define AP_AVOIDANCE_WARN_DISTANCE_XY_DEFAULT 30028#define AP_AVOIDANCE_WARN_DISTANCE_Z_DEFAULT 30029#define AP_AVOIDANCE_FAIL_DISTANCE_XY_DEFAULT 10030#define AP_AVOIDANCE_FAIL_DISTANCE_Z_DEFAULT 10031#define AP_AVOIDANCE_RECOVERY_DEFAULT RecoveryAction::RTL32#define AP_AVOIDANCE_FAIL_ACTION_DEFAULT MAV_COLLISION_ACTION_REPORT33#endif3435#if AVOIDANCE_DEBUGGING36#include <stdio.h>37#define debug(fmt, args ...) do {::fprintf(stderr,"%s:%d: " fmt "\n", __FUNCTION__, __LINE__, ## args); } while(0)38#else39#define debug(fmt, args ...)40#endif4142// table of user settable parameters43const AP_Param::GroupInfo AP_Avoidance::var_info[] = {4445// @Param: ENABLE46// @DisplayName: Enable Avoidance using ADSB47// @Description: Enable Avoidance using ADSB48// @Values: 0:Disabled,1:Enabled49// @User: Advanced50AP_GROUPINFO_FLAGS("ENABLE", 1, AP_Avoidance, _enabled, 0, AP_PARAM_FLAG_ENABLE),5152// @Param: F_ACTION53// @DisplayName: Collision Avoidance Behavior54// @Description: Specifies aircraft behaviour when a collision is imminent55// @Values: 0:None,1:Report,2:Climb Or Descend,3:Move Horizontally,4:Move Perpendicularly in 3D,5:RTL,6:Hover56// @User: Advanced57AP_GROUPINFO("F_ACTION", 2, AP_Avoidance, _fail_action, AP_AVOIDANCE_FAIL_ACTION_DEFAULT),5859// @Param: W_ACTION60// @DisplayName: Collision Avoidance Behavior - Warn61// @Description: Specifies aircraft behaviour when a collision may occur62// @Values: 0:None,1:Report63// @User: Advanced64AP_GROUPINFO("W_ACTION", 3, AP_Avoidance, _warn_action, MAV_COLLISION_ACTION_REPORT),6566// @Param: F_RCVRY67// @DisplayName: Recovery behaviour after a fail event68// @Description: Determines what the aircraft will do after a fail event is resolved69// @Values: 0:Remain in AVOID_ADSB,1:Resume previous flight mode,2:RTL,3:Resume if AUTO else Loiter70// @User: Advanced71AP_GROUPINFO("F_RCVRY", 4, AP_Avoidance, _fail_recovery, uint8_t(AP_AVOIDANCE_RECOVERY_DEFAULT)),7273// @Param: OBS_MAX74// @DisplayName: Maximum number of obstacles to track75// @Description: Maximum number of obstacles to track76// @User: Advanced77AP_GROUPINFO("OBS_MAX", 5, AP_Avoidance, _obstacles_max, 20),7879// @Param: W_TIME80// @DisplayName: Time Horizon Warn81// @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)82// @Units: s83// @User: Advanced84AP_GROUPINFO("W_TIME", 6, AP_Avoidance, _warn_time_horizon_s, AP_AVOIDANCE_WARN_TIME_DEFAULT),8586// @Param: F_TIME87// @DisplayName: Time Horizon Fail88// @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 undertaken89// @Units: s90// @User: Advanced91AP_GROUPINFO("F_TIME", 7, AP_Avoidance, _fail_time_horizon_s, AP_AVOIDANCE_FAIL_TIME_DEFAULT),9293// @Param: W_DIST_XY94// @DisplayName: Distance Warn XY95// @Description: Closest allowed projected distance before W_ACTION is undertaken96// @Units: m97// @User: Advanced98AP_GROUPINFO("W_DIST_XY", 8, AP_Avoidance, _warn_distance_ne_m, AP_AVOIDANCE_WARN_DISTANCE_XY_DEFAULT),99100// @Param: F_DIST_XY101// @DisplayName: Distance Fail XY102// @Description: Closest allowed projected distance before F_ACTION is undertaken103// @Units: m104// @User: Advanced105AP_GROUPINFO("F_DIST_XY", 9, AP_Avoidance, _fail_distance_ne_m, AP_AVOIDANCE_FAIL_DISTANCE_XY_DEFAULT),106107// @Param: W_DIST_Z108// @DisplayName: Distance Warn Z109// @Description: Closest allowed projected distance before BEHAVIOUR_W is undertaken110// @Units: m111// @User: Advanced112AP_GROUPINFO("W_DIST_Z", 10, AP_Avoidance, _warn_distance_d_m, AP_AVOIDANCE_WARN_DISTANCE_Z_DEFAULT),113114// @Param: F_DIST_Z115// @DisplayName: Distance Fail Z116// @Description: Closest allowed projected distance before BEHAVIOUR_F is undertaken117// @Units: m118// @User: Advanced119AP_GROUPINFO("F_DIST_Z", 11, AP_Avoidance, _fail_distance_d_m, AP_AVOIDANCE_FAIL_DISTANCE_Z_DEFAULT),120121// @Param: F_ALT_MIN122// @DisplayName: ADS-B avoidance minimum altitude123// @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.124// @Units: m125// @User: Advanced126AP_GROUPINFO("F_ALT_MIN", 12, AP_Avoidance, _fail_altitude_min_m, 0),127128AP_GROUPEND129};130131AP_Avoidance::AP_Avoidance(AP_ADSB &adsb) :132_adsb(adsb)133{134AP_Param::setup_object_defaults(this, var_info);135if (_singleton != nullptr) {136AP_HAL::panic("AP_Avoidance must be singleton");137}138_singleton = this;139}140141/*142* Initialize variables and allocate memory for array143*/144void AP_Avoidance::init(void)145{146debug("ADSB initialisation: %d obstacles", _obstacles_max.get());147if (_obstacles == nullptr) {148_obstacles = NEW_NOTHROW AP_Avoidance::Obstacle[_obstacles_max];149150if (_obstacles == nullptr) {151// dynamic RAM allocation of _obstacles[] failed, disable gracefully152DEV_PRINTF("Unable to initialize Avoidance obstacle list\n");153// disable ourselves to avoid repeated allocation attempts154_enabled.set(0);155return;156}157_obstacles_allocated = _obstacles_max;158}159_obstacle_count = 0;160_last_state_change_ms = 0;161_threat_level = MAV_COLLISION_THREAT_LEVEL_NONE;162_gcs_cleared_messages_first_sent = std::numeric_limits<uint32_t>::max();163_current_most_serious_threat = -1;164}165166/*167* de-initialize and free up some memory168*/169void AP_Avoidance::deinit(void)170{171if (_obstacles != nullptr) {172delete [] _obstacles;173_obstacles = nullptr;174_obstacles_allocated = 0;175handle_recovery(RecoveryAction::RTL);176}177_obstacle_count = 0;178}179180bool AP_Avoidance::check_startup()181{182if (!_enabled) {183if (_obstacles != nullptr) {184deinit();185}186// nothing to do187return false;188}189if (_obstacles == nullptr) {190init();191}192return _obstacles != nullptr;193}194195// vel_ned_ms is north/east/down196void AP_Avoidance::add_obstacle(const uint32_t obstacle_timestamp_ms,197const MAV_COLLISION_SRC src,198const uint32_t src_id,199const Location &loc,200const Vector3f &vel_ned_ms)201{202if (! check_startup()) {203return;204}205uint32_t oldest_timestamp = std::numeric_limits<uint32_t>::max();206uint8_t oldest_index = 255; // avoid compiler warning with initialisation207int16_t index = -1;208uint8_t i;209for (i=0; i<_obstacle_count; i++) {210if (_obstacles[i].src_id == src_id &&211_obstacles[i].src == src) {212// pre-existing obstacle found; we will update its information213index = i;214break;215}216if (_obstacles[i].timestamp_ms < oldest_timestamp) {217oldest_timestamp = _obstacles[i].timestamp_ms;218oldest_index = i;219}220}221WITH_SEMAPHORE(_rsem);222223if (index == -1) {224// existing obstacle not found. See if we can store it anyway:225if (i <_obstacles_allocated) {226// have room to store more vehicles...227index = _obstacle_count++;228} else if (oldest_timestamp < obstacle_timestamp_ms) {229// replace this very old entry with this new data230index = oldest_index;231} else {232// no room for this (old?!) data233return;234}235236_obstacles[index].src = src;237_obstacles[index].src_id = src_id;238}239240_obstacles[index]._location = loc;241_obstacles[index]._velocity_ned_ms = vel_ned_ms;242_obstacles[index].timestamp_ms = obstacle_timestamp_ms;243}244245void AP_Avoidance::add_obstacle(const uint32_t obstacle_timestamp_ms,246const MAV_COLLISION_SRC src,247const uint32_t src_id,248const Location &loc,249const float cog,250const float speed_ne_ms,251const float speed_d_ms)252{253Vector3f vel_ned_ms;254vel_ned_ms[0] = speed_ne_ms * cosf(radians(cog));255vel_ned_ms[1] = speed_ne_ms * sinf(radians(cog));256vel_ned_ms[2] = speed_d_ms;257// debug("cog=%f speed_ne_ms=%f veln=%f vele=%f", cog, speed_ne_ms, vel_ned_ms[0], vel[1]);258return add_obstacle(obstacle_timestamp_ms, src, src_id, loc, vel_ned_ms);259}260261uint32_t AP_Avoidance::src_id_for_adsb_vehicle(const AP_ADSB::adsb_vehicle_t &vehicle) const262{263// TODO: need to include squawk code and callsign264return vehicle.info.ICAO_address;265}266267void AP_Avoidance::get_adsb_samples()268{269AP_ADSB::adsb_vehicle_t vehicle;270while (_adsb.next_sample(vehicle)) {271uint32_t src_id = src_id_for_adsb_vehicle(vehicle);272Location loc = _adsb.get_location(vehicle);273add_obstacle(vehicle.last_update_ms,274MAV_COLLISION_SRC_ADSB,275src_id,276loc,277vehicle.info.heading * 0.01,278vehicle.info.hor_velocity * 0.01,279-vehicle.info.ver_velocity * 0.01); // convert cm-up to m-down280}281}282283float closest_approach_NE_m(const Location &loc,284const Vector3f &vel_ned_ms,285const Location &obstacle_loc,286const Vector3f &obstacle_vel_ned_ms,287const uint8_t time_horizon_s)288{289290Vector2f delta_vel_ne_ms = Vector2f(obstacle_vel_ned_ms[0] - vel_ned_ms[0], obstacle_vel_ned_ms[1] - vel_ned_ms[1]);291const Vector2f delta_pos_ne_m = obstacle_loc.get_distance_NE(loc);292293Vector2f line_segment_ne_m = delta_vel_ne_ms * time_horizon_s;294295float dist_ne_m = Vector2<float>::closest_distance_between_radial_and_point296(line_segment_ne_m,297delta_pos_ne_m);298299debug(" time_horizon: (%d)", time_horizon_s);300debug(" delta pos: (y=%f,x=%f)", delta_pos_ne_m[0], delta_pos_ne_m[1]);301debug(" delta vel: (y=%f,x=%f)", delta_vel_ne_ms[0], delta_vel_ne_ms[1]);302debug(" line segment: (y=%f,x=%f)", line_segment_ne_m[0], line_segment_ne_m[1]);303debug(" closest: (%f)", dist_ne_m);304305return dist_ne_m;306}307308// returns the closest these objects will get in the body z axis (in metres)309float closest_approach_D_m(const Location &loc,310const Vector3f &vel_ned_ms,311const Location &obstacle_loc,312const Vector3f &obstacle_vel_ned_ms,313const uint8_t time_horizon_s)314{315316float delta_vel_d_ms = obstacle_vel_ned_ms[2] - vel_ned_ms[2];317float delta_pos_d_cm = obstacle_loc.alt - loc.alt;318319float dist_d_cm;320if (delta_pos_d_cm >= 0 && delta_vel_d_ms >= 0) {321dist_d_cm = delta_pos_d_cm;322} else if (delta_pos_d_cm <= 0 && delta_vel_d_ms <= 0) {323dist_d_cm = fabsf(delta_pos_d_cm);324} else {325dist_d_cm = fabsf(delta_pos_d_cm - delta_vel_d_ms * time_horizon_s * 100.0);326}327328debug(" time_horizon: (%d)", time_horizon_s);329debug(" delta pos: (%f) metres", delta_pos_d_cm*0.01f);330debug(" delta vel: (%f) m/s", delta_vel_d_ms);331debug(" closest: (%f) metres", dist_d_cm*0.01f);332333return dist_d_cm * 0.01f;334}335336void AP_Avoidance::update_threat_level(const Location &loc,337const Vector3f &vel_ned_ms,338AP_Avoidance::Obstacle &obstacle)339{340341Location &obstacle_loc = obstacle._location;342Vector3f &obstacle_vel_ned_ms = obstacle._velocity_ned_ms;343344obstacle.threat_level = MAV_COLLISION_THREAT_LEVEL_NONE;345346const uint32_t obstacle_age_ms = AP_HAL::millis() - obstacle.timestamp_ms;347float closest_ne_m = closest_approach_NE_m(loc, vel_ned_ms, obstacle_loc, obstacle_vel_ned_ms, _fail_time_horizon_s + obstacle_age_ms/1000);348if (closest_ne_m < _fail_distance_ne_m) {349obstacle.threat_level = MAV_COLLISION_THREAT_LEVEL_HIGH;350} else {351closest_ne_m = closest_approach_NE_m(loc, vel_ned_ms, obstacle_loc, obstacle_vel_ned_ms, _warn_time_horizon_s + obstacle_age_ms/1000);352if (closest_ne_m < _warn_distance_ne_m) {353obstacle.threat_level = MAV_COLLISION_THREAT_LEVEL_LOW;354}355}356357// check for vertical separation; our threat level is the minimum358// of vertical and horizontal threat levels359float closest_d_m = closest_approach_D_m(loc, vel_ned_ms, obstacle_loc, obstacle_vel_ned_ms, _warn_time_horizon_s + obstacle_age_ms/1000);360if (obstacle.threat_level != MAV_COLLISION_THREAT_LEVEL_NONE) {361if (closest_d_m > _warn_distance_d_m) {362obstacle.threat_level = MAV_COLLISION_THREAT_LEVEL_NONE;363} else {364closest_d_m = closest_approach_D_m(loc, vel_ned_ms, obstacle_loc, obstacle_vel_ned_ms, _fail_time_horizon_s + obstacle_age_ms/1000);365if (closest_d_m > _fail_distance_d_m) {366obstacle.threat_level = MAV_COLLISION_THREAT_LEVEL_LOW;367}368}369}370371// If we haven't heard from a vehicle then assume it is no threat372if (obstacle_age_ms > MAX_OBSTACLE_AGE_MS) {373obstacle.threat_level = MAV_COLLISION_THREAT_LEVEL_NONE;374}375376// could optimise this to not calculate a lot of this if threat377// level is none - but only *once the GCS has been informed*!378obstacle.closest_approach_ne_m = closest_ne_m;379obstacle.closest_approach_d_m = closest_d_m;380float current_distance_ne_m = loc.get_distance(obstacle_loc);381obstacle.distance_to_closest_approach_ned_m = current_distance_ne_m - closest_ne_m;382Vector2f net_velocity_ne_ms = Vector2f(vel_ned_ms[0] - obstacle_vel_ned_ms[0], vel_ned_ms[1] - obstacle_vel_ned_ms[1]);383obstacle.time_to_closest_approach_s = 0.0f;384if (!is_zero(obstacle.distance_to_closest_approach_ned_m) &&385! is_zero(net_velocity_ne_ms.length())) {386obstacle.time_to_closest_approach_s = obstacle.distance_to_closest_approach_ned_m / net_velocity_ne_ms.length();387}388}389390MAV_COLLISION_THREAT_LEVEL AP_Avoidance::current_threat_level() const {391if (_obstacles == nullptr) {392return MAV_COLLISION_THREAT_LEVEL_NONE;393}394if (_current_most_serious_threat == -1) {395return MAV_COLLISION_THREAT_LEVEL_NONE;396}397return _obstacles[_current_most_serious_threat].threat_level;398}399400#if HAL_GCS_ENABLED401void AP_Avoidance::send_collision_all(const AP_Avoidance::Obstacle &threat, MAV_COLLISION_ACTION behaviour) const402{403const mavlink_collision_t packet{404id: threat.src_id,405time_to_minimum_delta: threat.time_to_closest_approach_s,406altitude_minimum_delta: threat.closest_approach_d_m,407horizontal_minimum_delta: threat.closest_approach_ne_m,408src: MAV_COLLISION_SRC_ADSB,409action: (uint8_t)behaviour,410threat_level: (uint8_t)threat.threat_level,411};412gcs().send_to_active_channels(MAVLINK_MSG_ID_COLLISION, (const char *)&packet);413}414#endif415416void AP_Avoidance::handle_threat_gcs_notify(AP_Avoidance::Obstacle *threat)417{418if (threat == nullptr) {419return;420}421422uint32_t now = AP_HAL::millis();423if (threat->threat_level == MAV_COLLISION_THREAT_LEVEL_NONE) {424// only send cleared messages for a few seconds:425if (_gcs_cleared_messages_first_sent == 0) {426_gcs_cleared_messages_first_sent = now;427}428if (now - _gcs_cleared_messages_first_sent > _gcs_cleared_messages_duration * 1000) {429return;430}431} else {432_gcs_cleared_messages_first_sent = 0;433}434if (now - threat->last_gcs_report_time > _gcs_notify_interval * 1000) {435send_collision_all(*threat, mav_avoidance_action());436threat->last_gcs_report_time = now;437}438439}440441bool AP_Avoidance::obstacle_is_more_serious_threat(const AP_Avoidance::Obstacle &obstacle) const442{443if (_current_most_serious_threat == -1) {444// any threat is more of a threat than no threat445return true;446}447const AP_Avoidance::Obstacle ¤t = _obstacles[_current_most_serious_threat];448if (obstacle.threat_level > current.threat_level) {449// threat_level is updated by update_threat_level450return true;451}452if (obstacle.threat_level == current.threat_level &&453obstacle.time_to_closest_approach_s < current.time_to_closest_approach_s) {454return true;455}456return false;457}458459void AP_Avoidance::check_for_threats()460{461const AP_AHRS &_ahrs = AP::ahrs();462463Location loc;464if (!_ahrs.get_location(loc)) {465// if we don't know our own location we can't determine any threat level466return;467}468469Vector3f vel_ned_ms;470if (!_ahrs.get_velocity_NED(vel_ned_ms)) {471// assuming our own velocity to be zero here may cause us to472// fly into something. Better not to attempt to avoid in this473// case.474return;475}476477// we always check all obstacles to see if they are threats since it478// is most likely our own position and/or velocity have changed479// determine the current most-serious-threat480_current_most_serious_threat = -1;481for (uint8_t i=0; i<_obstacle_count; i++) {482483AP_Avoidance::Obstacle &obstacle = _obstacles[i];484const uint32_t obstacle_age_ms = AP_HAL::millis() - obstacle.timestamp_ms;485debug("i=%d src_id=%d timestamp=%u age=%d", i, obstacle.src_id, obstacle.timestamp_ms, obstacle_age_ms);486487update_threat_level(loc, vel_ned_ms, obstacle);488debug(" threat-level=%d", obstacle.threat_level);489490// ignore any really old data:491if (obstacle_age_ms > MAX_OBSTACLE_AGE_MS) {492// shrink list if this is the last entry:493if (i == _obstacle_count-1) {494_obstacle_count -= 1;495}496continue;497}498499if (obstacle_is_more_serious_threat(obstacle)) {500_current_most_serious_threat = i;501}502}503if (_current_most_serious_threat != -1) {504debug("Current most serious threat: %d level=%d", _current_most_serious_threat, _obstacles[_current_most_serious_threat].threat_level);505}506}507508509AP_Avoidance::Obstacle *AP_Avoidance::most_serious_threat()510{511if (_current_most_serious_threat < 0) {512// we *really_ should not have been called!513return nullptr;514}515return &_obstacles[_current_most_serious_threat];516}517518519void AP_Avoidance::update()520{521if (!check_startup()) {522return;523}524525if (_adsb.enabled()) {526get_adsb_samples();527}528529check_for_threats();530531// avoid object (if necessary)532handle_avoidance_local(most_serious_threat());533534// notify GCS of most serious thread535handle_threat_gcs_notify(most_serious_threat());536}537538void AP_Avoidance::handle_avoidance_local(AP_Avoidance::Obstacle *threat)539{540MAV_COLLISION_THREAT_LEVEL new_threat_level = MAV_COLLISION_THREAT_LEVEL_NONE;541MAV_COLLISION_ACTION action = MAV_COLLISION_ACTION_NONE;542543if (threat != nullptr) {544new_threat_level = threat->threat_level;545if (new_threat_level == MAV_COLLISION_THREAT_LEVEL_HIGH) {546action = (MAV_COLLISION_ACTION)_fail_action.get();547Location loc;548if (action != MAV_COLLISION_ACTION_NONE && _fail_altitude_min_m > 0 &&549AP::ahrs().get_location(loc) && ((loc.alt * 0.01f) < _fail_altitude_min_m)) {550// disable avoidance when close to ground, report only551action = MAV_COLLISION_ACTION_REPORT;552}553}554}555556uint32_t now = AP_HAL::millis();557558if (new_threat_level != _threat_level) {559// transition to higher states immediately, recovery to lower states more slowly560if (((now - _last_state_change_ms) > AP_AVOIDANCE_STATE_RECOVERY_TIME_MS) || (new_threat_level > _threat_level)) {561// handle recovery from high threat level562if (_threat_level == MAV_COLLISION_THREAT_LEVEL_HIGH) {563handle_recovery(RecoveryAction(_fail_recovery.get()));564_latest_action = MAV_COLLISION_ACTION_NONE;565}566567// update state568_last_state_change_ms = now;569_threat_level = new_threat_level;570}571}572573// handle ongoing threat by calling vehicle specific handler574if ((threat != nullptr) && (_threat_level == MAV_COLLISION_THREAT_LEVEL_HIGH) && (action > MAV_COLLISION_ACTION_REPORT)) {575_latest_action = handle_avoidance(threat, action);576}577}578579580void AP_Avoidance::handle_msg(const mavlink_message_t &msg)581{582if (!check_startup()) {583// avoidance is not active / allocated584return;585}586587if (msg.msgid != MAVLINK_MSG_ID_GLOBAL_POSITION_INT) {588// we only take position from GLOBAL_POSITION_INT589return;590}591592if (msg.sysid == mavlink_system.sysid) {593// we do not obstruct ourselves....594return;595}596597// inform AP_Avoidance we have a new player598mavlink_global_position_int_t packet;599mavlink_msg_global_position_int_decode(&msg, &packet);600const Location loc {601packet.lat,602packet.lon,603int32_t(packet.alt * 0.1), // mm -> cm604Location::AltFrame::ABSOLUTE605};606const Vector3f vel_ned_ms {607packet.vx * 0.01f, // cm to m608packet.vy * 0.01f,609packet.vz * 0.01f610};611add_obstacle(AP_HAL::millis(),612MAV_COLLISION_SRC_MAVLINK_GPS_GLOBAL_INT,613msg.sysid,614loc,615vel_ned_ms);616}617618// get unit vector away from the nearest obstacle619bool AP_Avoidance::get_vector_perpendicular(const AP_Avoidance::Obstacle *obstacle, Vector3f &vec_neu_unit) const620{621if (obstacle == nullptr) {622// why where we called?!623return false;624}625626Location current_loc;627if (!AP::ahrs().get_location(current_loc)) {628// we should not get to here! If we don't know our position629// we can't know if there are any threats, for starters!630return false;631}632633// if their velocity is moving around close to zero then flying634// perpendicular to that velocity may mean we do weird things.635// Instead, we will fly directly away from them636if (obstacle->_velocity_ned_ms.length() < _low_velocity_threshold) {637const Vector2f delta_pos_ne_m = obstacle->_location.get_distance_NE(current_loc);638const float delta_pos_u_cm = current_loc.alt - obstacle->_location.alt;639Vector3f delta_pos_neu_m = Vector3f{delta_pos_ne_m.x, delta_pos_ne_m.y, delta_pos_u_cm * 0.01};640// avoid div by zero641if (delta_pos_neu_m.is_zero()) {642return false;643}644delta_pos_neu_m.normalize();645vec_neu_unit = delta_pos_neu_m;646return true;647} else {648vec_neu_unit = perpendicular_neu_m(obstacle->_location, obstacle->_velocity_ned_ms, current_loc);649// avoid div by zero650if (vec_neu_unit.is_zero()) {651return false;652}653vec_neu_unit.normalize();654return true;655}656}657658// helper functions to calculate 3D destination to get us away from obstacle659// v1_ned is NED660Vector3f AP_Avoidance::perpendicular_neu_m(const Location &p1, const Vector3f &v1_ned, const Location &p2)661{662const Vector2f delta_p_ne_m = p1.get_distance_NE(p2);663Vector3f delta_p_neu_m = Vector3f(delta_p_ne_m[0], delta_p_ne_m[1], (p2.alt - p1.alt) * 0.01f); //check this line664Vector3f v1_neu = Vector3f(v1_ned[0], v1_ned[1], -v1_ned[2]);665Vector3f ret_neu_m = Vector3f::perpendicular(delta_p_neu_m, v1_neu);666return ret_neu_m;667}668669// singleton instance670AP_Avoidance *AP_Avoidance::_singleton;671672namespace AP {673674AP_Avoidance *ap_avoidance()675{676return AP_Avoidance::get_singleton();677}678679}680681#endif // AP_ADSB_AVOIDANCE_ENABLED682683684