Path: blob/master/libraries/AC_Avoidance/AC_Avoid.cpp
9459 views
/*1This program is free software: you can redistribute it and/or modify2it under the terms of the GNU General Public License as published by3the Free Software Foundation, either version 3 of the License, or4(at your option) any later version.56This program is distributed in the hope that it will be useful,7but WITHOUT ANY WARRANTY; without even the implied warranty of8MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the9GNU General Public License for more details.1011You should have received a copy of the GNU General Public License12along with this program. If not, see <http://www.gnu.org/licenses/>.13*/1415#include "AC_Avoidance_config.h"1617#if AP_AVOIDANCE_ENABLED1819#include "AC_Avoid.h"20#include <AP_AHRS/AP_AHRS.h> // AHRS library21#include <AC_Fence/AC_Fence.h> // Failsafe fence library22#include <AP_Proximity/AP_Proximity.h>23#include <AP_Beacon/AP_Beacon.h>24#include <AP_Logger/AP_Logger.h>25#include <AP_Vehicle/AP_Vehicle_Type.h>26#include <stdio.h>2728#if !APM_BUILD_TYPE(APM_BUILD_ArduPlane)2930#if APM_BUILD_TYPE(APM_BUILD_Rover)31# define AP_AVOID_BEHAVE_DEFAULT AC_Avoid::BehaviourType::BEHAVIOR_STOP32#else33# define AP_AVOID_BEHAVE_DEFAULT AC_Avoid::BehaviourType::BEHAVIOR_SLIDE34#endif3536#if APM_BUILD_COPTER_OR_HELI37# define AP_AVOID_ENABLE_Z 138#endif3940const AP_Param::GroupInfo AC_Avoid::var_info[] = {4142// @Param: ENABLE43// @DisplayName: Avoidance control enable/disable44// @Description: Enabled/disable avoidance input sources45// @Bitmask: 0:UseFence,1:UseProximitySensor,2:UseBeaconFence46// @User: Standard47AP_GROUPINFO_FLAGS("ENABLE", 1, AC_Avoid, _enabled, AC_AVOID_DEFAULT, AP_PARAM_FLAG_ENABLE),4849// @Param{Copter}: ANGLE_MAX50// @DisplayName: Avoidance max lean angle in non-GPS flight modes51// @Description: Max lean angle used to avoid obstacles while in non-GPS modes52// @Units: cdeg53// @Increment: 1054// @Range: 0 450055// @User: Standard56AP_GROUPINFO_FRAME("ANGLE_MAX", 2, AC_Avoid, _angle_max_cd, 1000, AP_PARAM_FRAME_COPTER | AP_PARAM_FRAME_HELI | AP_PARAM_FRAME_TRICOPTER),5758// @Param{Copter}: DIST_MAX59// @DisplayName: Avoidance distance maximum in non-GPS flight modes60// @Description: Distance from object at which obstacle avoidance will begin in non-GPS modes61// @Units: m62// @Range: 1 3063// @User: Standard64AP_GROUPINFO_FRAME("DIST_MAX", 3, AC_Avoid, _dist_max_m, AC_AVOID_NONGPS_DIST_MAX_DEFAULT, AP_PARAM_FRAME_COPTER | AP_PARAM_FRAME_HELI | AP_PARAM_FRAME_TRICOPTER),6566// @Param: MARGIN67// @DisplayName: Avoidance distance margin in GPS modes68// @Description: Vehicle will attempt to stay at least this distance (in meters) from objects while in GPS modes69// @Units: m70// @Range: 1 1071// @User: Standard72AP_GROUPINFO("MARGIN", 4, AC_Avoid, _margin_m, 2.0f),7374// @Param{Copter, Rover}: BEHAVE75// @DisplayName: Avoidance behaviour76// @Description: Avoidance behaviour (slide or stop)77// @Values: 0:Slide,1:Stop78// @User: Standard79AP_GROUPINFO_FRAME("BEHAVE", 5, AC_Avoid, _behavior, AP_AVOID_BEHAVE_DEFAULT, AP_PARAM_FRAME_COPTER | AP_PARAM_FRAME_HELI | AP_PARAM_FRAME_TRICOPTER | AP_PARAM_FRAME_ROVER),8081// @Param: BACKUP_SPD82// @DisplayName: Avoidance maximum horizontal backup speed83// @Description: Maximum speed that will be used to back away from obstacles horizontally in position control modes (m/s). Set zero to disable horizontal backup.84// @Units: m/s85// @Range: 0 286// @User: Standard87AP_GROUPINFO("BACKUP_SPD", 6, AC_Avoid, _backup_speed_max_ne_ms, 0.75f),8889// @Param{Copter}: ALT_MIN90// @DisplayName: Avoidance minimum altitude91// @Description: Minimum altitude above which proximity based avoidance will start working. This requires a valid downward facing rangefinder reading to work. Set zero to disable92// @Units: m93// @Range: 0 694// @User: Standard95AP_GROUPINFO_FRAME("ALT_MIN", 7, AC_Avoid, _alt_min_m, 0.0f, AP_PARAM_FRAME_COPTER | AP_PARAM_FRAME_HELI | AP_PARAM_FRAME_TRICOPTER),9697// @Param: ACCEL_MAX98// @DisplayName: Avoidance maximum acceleration99// @Description: Maximum acceleration with which obstacles will be avoided with. Set zero to disable acceleration limits100// @Units: m/s/s101// @Range: 0 9102// @User: Standard103AP_GROUPINFO("ACCEL_MAX", 8, AC_Avoid, _accel_max_mss, 3.0f),104105// @Param: BACKUP_DZ106// @DisplayName: Avoidance deadzone between stopping and backing away from obstacle107// @Description: Distance beyond AVOID_MARGIN parameter, after which vehicle will backaway from obstacles. Increase this parameter if you see vehicle going back and forth in front of obstacle.108// @Units: m109// @Range: 0 2110// @User: Standard111AP_GROUPINFO("BACKUP_DZ", 9, AC_Avoid, _backup_deadzone_m, 0.10f),112113// @Param: BACKZ_SPD114// @DisplayName: Avoidance maximum vertical backup speed115// @Description: Maximum speed that will be used to back away from obstacles vertically in height control modes (m/s). Set zero to disable vertical backup.116// @Units: m/s117// @Range: 0 2118// @User: Standard119AP_GROUPINFO("BACKZ_SPD", 10, AC_Avoid, _backup_speed_max_u_ms, 0.75),120121AP_GROUPEND122};123124/// Constructor125AC_Avoid::AC_Avoid()126{127_singleton = this;128129AP_Param::setup_object_defaults(this, var_info);130}131132/*133* This method limits velocity and calculates backaway velocity from various supported fences134* Also limits vertical velocity using adjust_velocity_z method135*/136void AC_Avoid::adjust_velocity_fence(float kP, float accel_cmss, Vector3f &desired_vel_neu_cms, Vector3f &backup_vel_neu_cms, float kP_z, float accel_z_cmss, float dt)137{138// Only horizontal component needed for most fences, since fences are 2D139Vector2f desired_velocity_ne_cms{desired_vel_neu_cms.x, desired_vel_neu_cms.y};140141#if AP_FENCE_ENABLED || AP_BEACON_ENABLED142// limit acceleration143const float accel_limited_cmss = MIN(accel_cmss, AC_AVOID_ACCEL_CMSS_MAX);144#endif145146// maximum component of desired backup velocity in each quadrant147Vector2f quad_1_back_vel_ne_cms, quad_2_back_vel_ne_cms, quad_3_back_vel_ne_cms, quad_4_back_vel_ne_cms;148149#if AP_FENCE_ENABLED150if ((_enabled & AC_AVOID_STOP_AT_FENCE) > 0) {151// Store velocity needed to back away from fence152Vector2f backup_vel_fence_ne_cms;153154adjust_velocity_circle_fence(kP, accel_limited_cmss, desired_velocity_ne_cms, backup_vel_fence_ne_cms, dt);155find_max_quadrant_velocity(backup_vel_fence_ne_cms, quad_1_back_vel_ne_cms, quad_2_back_vel_ne_cms, quad_3_back_vel_ne_cms, quad_4_back_vel_ne_cms);156157// backup_vel_fence_ne_cms is set to zero after each fence in case the velocity is unset from previous methods158backup_vel_fence_ne_cms.zero();159adjust_velocity_inclusion_and_exclusion_polygons(kP, accel_limited_cmss, desired_velocity_ne_cms, backup_vel_fence_ne_cms, dt);160find_max_quadrant_velocity(backup_vel_fence_ne_cms, quad_1_back_vel_ne_cms, quad_2_back_vel_ne_cms, quad_3_back_vel_ne_cms, quad_4_back_vel_ne_cms);161162backup_vel_fence_ne_cms.zero();163adjust_velocity_inclusion_circles(kP, accel_limited_cmss, desired_velocity_ne_cms, backup_vel_fence_ne_cms, dt);164find_max_quadrant_velocity(backup_vel_fence_ne_cms, quad_1_back_vel_ne_cms, quad_2_back_vel_ne_cms, quad_3_back_vel_ne_cms, quad_4_back_vel_ne_cms);165166backup_vel_fence_ne_cms.zero();167adjust_velocity_exclusion_circles(kP, accel_limited_cmss, desired_velocity_ne_cms, backup_vel_fence_ne_cms, dt);168find_max_quadrant_velocity(backup_vel_fence_ne_cms, quad_1_back_vel_ne_cms, quad_2_back_vel_ne_cms, quad_3_back_vel_ne_cms, quad_4_back_vel_ne_cms);169}170#endif // AP_FENCE_ENABLED171172#if AP_BEACON_ENABLED173if ((_enabled & AC_AVOID_STOP_AT_BEACON_FENCE) > 0) {174// Store velocity needed to back away from beacon fence175Vector2f backup_vel_beacon_ne_cms;176adjust_velocity_beacon_fence(kP, accel_limited_cmss, desired_velocity_ne_cms, backup_vel_beacon_ne_cms, dt);177find_max_quadrant_velocity(backup_vel_beacon_ne_cms, quad_1_back_vel_ne_cms, quad_2_back_vel_ne_cms, quad_3_back_vel_ne_cms, quad_4_back_vel_ne_cms);178}179#endif // AP_BEACON_ENABLED180181// check for vertical fence182float desired_velocity_z_cms = desired_vel_neu_cms.z;183float desired_backup_vel_u_cms = 0.0f;184adjust_velocity_z(kP_z, accel_z_cmss, desired_velocity_z_cms, desired_backup_vel_u_cms, dt);185186// Desired backup velocity is sum of maximum velocity component in each quadrant187const Vector2f desired_backup_vel_ne_cms = quad_1_back_vel_ne_cms + quad_2_back_vel_ne_cms + quad_3_back_vel_ne_cms + quad_4_back_vel_ne_cms;188backup_vel_neu_cms = Vector3f{desired_backup_vel_ne_cms.x, desired_backup_vel_ne_cms.y, desired_backup_vel_u_cms};189desired_vel_neu_cms = Vector3f{desired_velocity_ne_cms.x, desired_velocity_ne_cms.y, desired_velocity_z_cms};190}191192/*193* Adjusts the desired velocity so that the vehicle can stop194* before the fence/object.195* kP, accel_cmss are for the horizontal axis196* kP_z, accel_z_cmss are for vertical axis197*/198void AC_Avoid::adjust_velocity(Vector3f &desired_vel_neu_cms, bool &backing_up, float kP, float accel_cmss, float kP_z, float accel_z_cmss, float dt)199{200// exit immediately if disabled201if (_enabled == AC_AVOID_DISABLED) {202return;203}204205// make a copy of input velocity, because desired_vel_neu_cms might be changed206const Vector3f desired_vel_original_neu_cms = desired_vel_neu_cms;207208// limit acceleration209const float accel_limited_cmss = MIN(accel_cmss, AC_AVOID_ACCEL_CMSS_MAX);210211// maximum component of horizontal desired backup velocity in each quadrant212Vector2f quad_1_back_vel_ne_cms, quad_2_back_vel_ne_cms, quad_3_back_vel_ne_cms, quad_4_back_vel_ne_cms;213float back_vel_up_cms = 0.0f;214float back_vel_down_cms = 0.0f;215216// Avoidance in response to proximity sensor217if (proximity_avoidance_enabled() && _proximity_alt_enabled) {218// Store velocity needed to back away from physical obstacles219Vector3f backup_vel_proximity_neu_cms;220adjust_velocity_proximity(kP, accel_limited_cmss, desired_vel_neu_cms, backup_vel_proximity_neu_cms, kP_z,accel_z_cmss, dt);221find_max_quadrant_velocity_3D(backup_vel_proximity_neu_cms, quad_1_back_vel_ne_cms, quad_2_back_vel_ne_cms, quad_3_back_vel_ne_cms, quad_4_back_vel_ne_cms, back_vel_up_cms, back_vel_down_cms);222}223224// Avoidance in response to various fences225Vector3f backup_vel_fence_neu_cms;226adjust_velocity_fence(kP, accel_cmss, desired_vel_neu_cms, backup_vel_fence_neu_cms, kP_z, accel_z_cmss, dt);227find_max_quadrant_velocity_3D(backup_vel_fence_neu_cms , quad_1_back_vel_ne_cms, quad_2_back_vel_ne_cms, quad_3_back_vel_ne_cms, quad_4_back_vel_ne_cms, back_vel_up_cms, back_vel_down_cms);228229// Desired backup velocity is sum of maximum velocity component in each quadrant230const Vector2f desired_backup_vel_ne_cms = quad_1_back_vel_ne_cms + quad_2_back_vel_ne_cms + quad_3_back_vel_ne_cms + quad_4_back_vel_ne_cms;231const float desired_backup_vel_u_cms = back_vel_down_cms + back_vel_up_cms;232Vector3f desired_backup_vel_neu_cm{desired_backup_vel_ne_cms.x, desired_backup_vel_ne_cms.y, desired_backup_vel_u_cms};233234const float backup_speed_max_ne_cms = _backup_speed_max_ne_ms * 100.0;235if (!desired_backup_vel_neu_cm.xy().is_zero() && is_positive(backup_speed_max_ne_cms)) {236backing_up = true;237// Constrain horizontal backing away speed238desired_backup_vel_neu_cm.xy().limit_length(backup_speed_max_ne_cms);239240// let user take control if they are backing away at a greater speed than what we have calculated241// this has to be done for x,y,z separately. For eg, user is doing fine in "x" direction but might need backing up in "y".242if (!is_zero(desired_backup_vel_neu_cm.x)) {243if (is_positive(desired_backup_vel_neu_cm.x)) {244desired_vel_neu_cms.x = MAX(desired_vel_neu_cms.x, desired_backup_vel_neu_cm.x);245} else {246desired_vel_neu_cms.x = MIN(desired_vel_neu_cms.x, desired_backup_vel_neu_cm.x);247}248}249if (!is_zero(desired_backup_vel_neu_cm.y)) {250if (is_positive(desired_backup_vel_neu_cm.y)) {251desired_vel_neu_cms.y = MAX(desired_vel_neu_cms.y, desired_backup_vel_neu_cm.y);252} else {253desired_vel_neu_cms.y = MIN(desired_vel_neu_cms.y, desired_backup_vel_neu_cm.y);254}255}256}257258const float backup_speed_max_u_cms = _backup_speed_max_u_ms * 100.0;259if (!is_zero(desired_backup_vel_neu_cm.z) && is_positive(backup_speed_max_u_cms)) {260backing_up = true;261262// Constrain vertical backing away speed263desired_backup_vel_neu_cm.z = constrain_float(desired_backup_vel_neu_cm.z, -backup_speed_max_u_cms, backup_speed_max_u_cms);264265if (!is_zero(desired_backup_vel_neu_cm.z)) {266if (is_positive(desired_backup_vel_neu_cm.z)) {267desired_vel_neu_cms.z = MAX(desired_vel_neu_cms.z, desired_backup_vel_neu_cm.z);268} else {269desired_vel_neu_cms.z = MIN(desired_vel_neu_cms.z, desired_backup_vel_neu_cm.z);270}271}272}273274// limit acceleration275limit_accel_NEU_cm(desired_vel_original_neu_cms, desired_vel_neu_cms, dt);276277if (desired_vel_original_neu_cms != desired_vel_neu_cms) {278_last_limit_time = AP_HAL::millis();279}280281#if HAL_LOGGING_ENABLED282if (limits_active()) {283// log at not more than 10hz (adjust_velocity method can be potentially called at 400hz!)284uint32_t now = AP_HAL::millis();285if ((now - _last_log_ms) > 100) {286_last_log_ms = now;287Write_SimpleAvoidance(true, desired_vel_original_neu_cms, desired_vel_neu_cms, backing_up);288}289} else {290// avoidance isn't active anymore291// log once so that it registers in logs292if (_last_log_ms) {293Write_SimpleAvoidance(false, desired_vel_original_neu_cms, desired_vel_neu_cms, backing_up);294// this makes sure logging won't run again till it is active295_last_log_ms = 0;296}297}298#endif299}300301/*302* Limit acceleration so that change of velocity output by avoidance library is controlled303* This helps reduce jerks and sudden movements in the vehicle304*/305void AC_Avoid::limit_accel_NEU_cm(const Vector3f &original_vel_neu_cms, Vector3f &modified_vel_neu_cms, float dt)306{307if (original_vel_neu_cms == modified_vel_neu_cms || is_zero(_accel_max_mss) || !is_positive(dt)) {308// we can't limit accel if any of these conditions are true309return;310}311312if (AP_HAL::millis() - _last_limit_time > AC_AVOID_ACCEL_TIMEOUT_MS) {313// reset this velocity because its been a long time since avoidance was active314_prev_avoid_vel_neu_cms = original_vel_neu_cms;315}316317// acceleration demanded by avoidance318const Vector3f accel_neu_cmss = (modified_vel_neu_cms - _prev_avoid_vel_neu_cms)/dt;319320// max accel in cm321const float accel_max_cmss = _accel_max_mss * 100.0f;322323if (accel_neu_cmss.length() > accel_max_cmss) {324// pull back on the acceleration325const Vector3f accel_direction_neu = accel_neu_cmss.normalized();326modified_vel_neu_cms = (accel_direction_neu * accel_max_cmss) * dt + _prev_avoid_vel_neu_cms;327}328329_prev_avoid_vel_neu_cms = modified_vel_neu_cms;330return;331}332333// This method is used in most Rover modes and not in Copter334// adjust desired horizontal speed so that the vehicle stops before the fence or object335// accel (maximum acceleration/deceleration) is in m/s/s336// heading is in radians337// speed is in m/s338// kP should be zero for linear response, non-zero for non-linear response339void AC_Avoid::adjust_speed(float kP, float accel_mss, float heading_rad, float &speed_ms, float dt)340{341// convert heading and speed into velocity vector342Vector3f vel_neu_cms{343cosf(heading_rad) * speed_ms * 100.0f,344sinf(heading_rad) * speed_ms * 100.0f,3450.0f346};347348bool backing_up = false;349adjust_velocity(vel_neu_cms, backing_up, kP, accel_mss * 100.0f, 0, 0, dt);350const Vector2f vel_ne_cms{vel_neu_cms.x, vel_neu_cms.y};351352if (backing_up) {353// back up354if (fabsf(wrap_180(degrees(vel_ne_cms.angle())) - degrees(heading_rad)) > 90.0f) {355// Big difference between the direction of velocity vector and actual heading therefore we need to reverse the direction356speed_ms = -vel_ne_cms.length() * 0.01f;357} else {358speed_ms = vel_ne_cms.length() * 0.01f;359}360return;361}362363// No need to back up so adjust speed towards zero if needed364if (is_negative(speed_ms)) {365speed_ms = -vel_ne_cms.length() * 0.01f;366} else {367speed_ms = vel_ne_cms.length() * 0.01f;368}369}370371// adjust vertical climb rate so vehicle does not break the vertical fence372void AC_Avoid::adjust_velocity_z(float kP, float accel_cmss, float& climb_rate_cms, float dt) {373float backup_speed_cms = 0.0f;374adjust_velocity_z(kP, accel_cmss, climb_rate_cms, backup_speed_cms, dt);375if (!is_zero(backup_speed_cms)) {376if (is_negative(backup_speed_cms)) {377climb_rate_cms = MIN(climb_rate_cms, backup_speed_cms);378} else {379climb_rate_cms = MAX(climb_rate_cms, backup_speed_cms);380}381}382}383384// adjust vertical climb rate so vehicle does not break the vertical fence385void AC_Avoid::adjust_velocity_z(float kP, float accel_cmss, float& climb_rate_cms, float& backup_speed_cms, float dt)386{387#ifdef AP_AVOID_ENABLE_Z388389// exit immediately if disabled390if (_enabled == AC_AVOID_DISABLED) {391return;392}393394// do not adjust climb_rate if level395if (is_zero(climb_rate_cms)) {396return;397}398399const AP_AHRS &_ahrs = AP::ahrs();400// limit acceleration401const float accel_limited_cmss = MIN(accel_cmss, AC_AVOID_ACCEL_CMSS_MAX);402403bool limit_min_alt = false;404bool limit_max_alt = false;405float max_alt_diff_m = 0.0f; // distance from altitude limit to vehicle in metres (positive means vehicle is below limit)406float min_alt_diff_m = 0.0f;407#if AP_FENCE_ENABLED408// calculate distance below fence409AC_Fence *fence = AP::fence();410if ((_enabled & AC_AVOID_STOP_AT_FENCE) > 0 && fence) {411// calculate distance from vehicle to safe altitude412float veh_alt_m;413_ahrs.get_relative_position_D_home(veh_alt_m);414if ((fence->get_enabled_fences() & AC_FENCE_TYPE_ALT_MIN) > 0) {415// fence.get_safe_alt_max_m() is UP, veh_alt_m is DOWN:416min_alt_diff_m = -(fence->get_safe_alt_min_m() + veh_alt_m);417limit_min_alt = true;418}419if ((fence->get_enabled_fences() & AC_FENCE_TYPE_ALT_MAX) > 0) {420// fence.get_safe_alt_max_m() is UP, veh_alt_m is DOWN:421max_alt_diff_m = fence->get_safe_alt_max_m() + veh_alt_m;422limit_max_alt = true;423}424}425#endif426427// calculate distance to (e.g.) optical flow altitude limit428// AHRS values are always in metres429float alt_limit_m;430float curr_alt_m;431if (_ahrs.get_hgt_ctrl_limit(alt_limit_m) &&432_ahrs.get_relative_position_D_origin_float(curr_alt_m)) {433// alt_limit_m is UP, curr_alt_m is DOWN:434const float ctrl_alt_diff_m = alt_limit_m + curr_alt_m;435if (!limit_max_alt || ctrl_alt_diff_m < max_alt_diff_m) {436max_alt_diff_m = ctrl_alt_diff_m;437limit_max_alt = true;438}439}440441#if HAL_PROXIMITY_ENABLED442// get distance from proximity sensor443float proximity_alt_diff_m;444AP_Proximity *proximity = AP::proximity();445if (proximity && proximity_avoidance_enabled() && proximity->get_upward_distance(proximity_alt_diff_m)) {446proximity_alt_diff_m -= _margin_m;447if (!limit_max_alt || proximity_alt_diff_m < max_alt_diff_m) {448max_alt_diff_m = proximity_alt_diff_m;449limit_max_alt = true;450}451}452#endif453454// limit climb rate455if (limit_max_alt || limit_min_alt) {456const float max_back_spd_cms = _backup_speed_max_u_ms * 100.0;457// do not allow climbing if we've breached the safe altitude458if (max_alt_diff_m <= 0.0f && limit_max_alt) {459climb_rate_cms = MIN(climb_rate_cms, 0.0f);460// also calculate backup speed that will get us back to safe altitude461if (is_positive(max_back_spd_cms)) {462backup_speed_cms = -1*(get_max_speed(kP, accel_limited_cmss, -max_alt_diff_m * 100.0f, dt));463464// Constrain to max backup speed465backup_speed_cms = MAX(backup_speed_cms, -max_back_spd_cms);466}467return;468// do not allow descending if we've breached the safe altitude469} else if (min_alt_diff_m <= 0.0f && limit_min_alt) {470climb_rate_cms = MAX(climb_rate_cms, 0.0f);471// also calculate backup speed that will get us back to safe altitude472if (is_positive(max_back_spd_cms)) {473backup_speed_cms = get_max_speed(kP, accel_limited_cmss, -min_alt_diff_m * 100.0f, dt);474475// Constrain to max backup speed476backup_speed_cms = MIN(backup_speed_cms, max_back_spd_cms);477}478return;479}480481// limit climb rate482if (limit_max_alt) {483const float max_alt_max_speed_cms = get_max_speed(kP, accel_limited_cmss, max_alt_diff_m * 100.0f, dt);484climb_rate_cms = MIN(max_alt_max_speed_cms, climb_rate_cms);485}486487if (limit_min_alt) {488const float max_alt_min_speed = get_max_speed(kP, accel_limited_cmss, min_alt_diff_m * 100.0f, dt);489climb_rate_cms = MAX(-max_alt_min_speed, climb_rate_cms);490}491}492#endif493}494495// adjust roll-pitch to push vehicle away from objects496// roll and pitch value are in radians497// veh_angle_max_rad is the user defined maximum lean angle for the vehicle in radians498void AC_Avoid::adjust_roll_pitch_rad(float &roll_rad, float &pitch_rad, float veh_angle_max_rad) const499{500// exit immediately if proximity based avoidance is disabled501if (!proximity_avoidance_enabled()) {502return;503}504505// exit immediately if angle max is zero506if (_angle_max_cd <= 0.0f || veh_angle_max_rad <= 0.0f) {507return;508}509510float roll_positive_norm = 0.0f; // maximum positive roll value511float roll_negative_norm = 0.0f; // minimum negative roll value512float pitch_positive_norm = 0.0f; // maximum positive pitch value513float pitch_negative_norm = 0.0f; // minimum negative pitch value514515// get maximum positive and negative roll and pitch percentages from proximity sensor516get_proximity_roll_pitch_norm(roll_positive_norm, roll_negative_norm, pitch_positive_norm, pitch_negative_norm);517518// add maximum positive and negative percentages together for roll and pitch, convert to radians519Vector2f rp_out_rad((roll_positive_norm + roll_negative_norm) * radians(45.0), (pitch_positive_norm + pitch_negative_norm) * radians(45.0));520521// apply avoidance angular limits522// the object avoidance lean angle is never more than 75% of the total angle-limit to allow the pilot to override523const float angle_limit_rad = constrain_float(cd_to_rad(_angle_max_cd), 0.0f, veh_angle_max_rad * AC_AVOID_ANGLE_MAX_PERCENT);524float vec_length_rad = rp_out_rad.length();525if (vec_length_rad > angle_limit_rad) {526rp_out_rad *= (angle_limit_rad / vec_length_rad);527}528529// add passed in roll, pitch angles530rp_out_rad.x += roll_rad;531rp_out_rad.y += pitch_rad;532533// apply total angular limits534vec_length_rad = rp_out_rad.length();535if (vec_length_rad > veh_angle_max_rad) {536rp_out_rad *= (veh_angle_max_rad / vec_length_rad);537}538539// return adjusted roll, pitch540roll_rad = rp_out_rad.x;541pitch_rad = rp_out_rad.y;542}543544/*545* Note: This method is used to limit velocity horizontally only546* Limits the component of desired_vel in the direction of the unit vector547* limit_direction_ne to be at most the maximum speed permitted by the limit_distance.548*549* The function is unit-agnostic — accel, desired_vel_ne, and limit_direction_ne550* must all use the same base unit (e.g. m, cm) for correct scaling.551*552* Uses velocity adjustment idea from Randy's second email on this thread:553* https://groups.google.com/forum/#!searchin/drones-discuss/obstacle/drones-discuss/QwUXz__WuqY/qo3G8iTLSJAJ554*/555void AC_Avoid::limit_velocity_NE(float kP, float accel, Vector2f &desired_vel_ne, const Vector2f& limit_direction_ne, float limit_distance, float dt) const556{557const float max_speed = get_max_speed(kP, accel, limit_distance, dt);558// project onto limit direction559const float speed = desired_vel_ne * limit_direction_ne;560if (speed > max_speed) {561// subtract difference between desired speed and maximum acceptable speed562desired_vel_ne += limit_direction_ne * (max_speed - speed);563}564}565566/*567* Note: This method is used to limit velocity horizontally and vertically given a 3D desired velocity vector568* Limits the component of desired_vel_neu in the direction of the obstacle_vector_neu based on the passed value of "margin"569*570* The function is unit-agnostic — accel, desired_vel_neu, obstacle_vector_neu, margin, and accel_u571* must all use the same base unit (e.g. m, cm) for correct scaling.572*/573void AC_Avoid::limit_velocity_NEU(float kP, float accel, Vector3f &desired_vel_neu, const Vector3f& obstacle_vector_neu, float margin, float kP_z, float accel_u, float dt) const574{575if (desired_vel_neu.is_zero()) {576// nothing to limit577return;578}579// create a margin length vector in the direction of desired_vel_cms580// this will create larger margin towards the direction vehicle is travelling in581const Vector3f margin_vector_neu = desired_vel_neu.normalized() * margin;582const Vector2f limit_direction_ne{obstacle_vector_neu.x, obstacle_vector_neu.y};583584if (!limit_direction_ne.is_zero()) {585const float distance_from_fence_xy = MAX((limit_direction_ne.length() - Vector2f{margin_vector_neu.x, margin_vector_neu.y}.length()), 0.0f);586Vector2f velocity_ne{desired_vel_neu.x, desired_vel_neu.y};587limit_velocity_NE(kP, accel, velocity_ne, limit_direction_ne.normalized(), distance_from_fence_xy, dt);588desired_vel_neu.x = velocity_ne.x;589desired_vel_neu.y = velocity_ne.y;590}591592if (is_zero(desired_vel_neu.z) || is_zero(obstacle_vector_neu.z)) {593// nothing to limit vertically if desired_vel_cms.z is zero594// if obstacle_vector_neu.z is zero then the obstacle is probably horizontally located, and we can move vertically595return;596}597598if (is_positive(desired_vel_neu.z) != is_positive(obstacle_vector_neu.z)) {599// why limit velocity vertically when we are going the opposite direction600return;601}602603// to check if Z velocity changes604const float velocity_original_u = desired_vel_neu.z;605const float speed_u = fabsf(desired_vel_neu.z);606607// obstacle_vector_neu.z and margin_vector_neu.z should be in same direction as checked above608const float dist_u = MAX(fabsf(obstacle_vector_neu.z) - fabsf(margin_vector_neu.z), 0.0f);609if (is_zero(dist_u)) {610// eliminate any vertical velocity611desired_vel_neu.z = 0.0f;612} else {613const float max_z_speed = get_max_speed(kP_z, accel_u, dist_u, dt);614desired_vel_neu.z = MIN(max_z_speed, speed_u);615}616617// make sure the direction of the Z velocity did not change618// we are only limiting speed here, not changing directions619// check if original z velocity is positive or negative620if (is_negative(velocity_original_u)) {621desired_vel_neu.z = desired_vel_neu.z * -1.0f;622}623}624625/*626* Compute the back away horizontal velocity required to avoid breaching margin627* INPUT: This method requires the breach in margin distance (back_distance_cm), direction towards the breach (limit_direction)628* It then calculates the desired backup velocity and passes it on to "find_max_quadrant_velocity" method to distribute the velocity vectors into respective quadrants629* OUTPUT: The method then outputs four velocities (quad1/2/3/4_back_vel_cms), which correspond to the maximum horizontal desired backup velocity in each quadrant630*/631void AC_Avoid::calc_backup_velocity_2D(float kP, float accel_cmss, Vector2f &quad1_back_vel_cms, Vector2f &quad2_back_vel_cms, Vector2f &quad3_back_vel_cms, Vector2f &quad4_back_vel_cms, float back_distance_cm, Vector2f limit_direction, float dt) const632{633if (limit_direction.is_zero()) {634// protect against divide by zero635return;636}637// speed required to move away the exact distance that we have breached the margin with638const float back_speed_cms = get_max_speed(kP, 0.4f * accel_cmss, fabsf(back_distance_cm), dt);639640// direction to the obstacle641limit_direction.normalize();642643// move in the opposite direction with the required speed644Vector2f back_direction_vel_cms = limit_direction * (-back_speed_cms);645// divide the vector into quadrants, find maximum velocity component in each quadrant646find_max_quadrant_velocity(back_direction_vel_cms, quad1_back_vel_cms, quad2_back_vel_cms, quad3_back_vel_cms, quad4_back_vel_cms);647}648649/*650* Compute the back away velocity required to avoid breaching margin, including vertical component651* min_z_vel is <= 0, and stores the greatest velocity in the downwards direction652* max_z_vel is >= 0, and stores the greatest velocity in the upwards direction653* eventually max_z_vel + min_z_vel will give the final desired Z backaway velocity654*/655void AC_Avoid::calc_backup_velocity_3D(float kP, float accel_cmss, Vector2f &quad1_back_vel_cms, Vector2f &quad2_back_vel_cms, Vector2f &quad3_back_vel_cms, Vector2f &quad4_back_vel_cms,656float back_distance_cms, Vector3f limit_direction_neu, float kp_z, float accel_z_cmss, float back_distance_u_cm, float& min_vel_u_cms, float& max_vel_u_cms, float dt) const657{658// backup horizontally659if (is_positive(back_distance_cms)) {660Vector2f limit_direction_ne{limit_direction_neu.x, limit_direction_neu.y};661calc_backup_velocity_2D(kP, accel_cmss, quad1_back_vel_cms, quad2_back_vel_cms, quad3_back_vel_cms, quad4_back_vel_cms, back_distance_cms, limit_direction_ne, dt);662}663664// backup vertically665if (!is_zero(back_distance_u_cm)) {666float back_speed_z_cms = get_max_speed(kp_z, 0.4f * accel_z_cmss, fabsf(back_distance_u_cm), dt);667// Down is positive668if (is_positive(back_distance_u_cm)) {669back_speed_z_cms *= -1.0f;670}671672// store the z backup speed into min or max z if possible673if (back_speed_z_cms < min_vel_u_cms) {674min_vel_u_cms = back_speed_z_cms;675}676if (back_speed_z_cms > max_vel_u_cms) {677max_vel_u_cms = back_speed_z_cms;678}679}680}681682/*683* Calculate maximum velocity vector that can be formed in each quadrant684* This method takes the desired backup velocity, and four other velocities corresponding to each quadrant685* The desired velocity is then fit into one of the 4 quadrant velocities as per the sign of its components686* This ensures that if we have multiple backup velocities, we can get the maximum of all of those velocities in each quadrant687*/688void AC_Avoid::find_max_quadrant_velocity(Vector2f &desired_vel, Vector2f &quad1_vel, Vector2f &quad2_vel, Vector2f &quad3_vel, Vector2f &quad4_vel) const689{690if (desired_vel.is_zero()) {691return;692}693// first quadrant: +ve x, +ve y direction694if (is_positive(desired_vel.x) && is_positive(desired_vel.y)) {695quad1_vel = Vector2f{MAX(quad1_vel.x, desired_vel.x), MAX(quad1_vel.y,desired_vel.y)};696}697// second quadrant: -ve x, +ve y direction698if (is_negative(desired_vel.x) && is_positive(desired_vel.y)) {699quad2_vel = Vector2f{MIN(quad2_vel.x, desired_vel.x), MAX(quad2_vel.y,desired_vel.y)};700}701// third quadrant: -ve x, -ve y direction702if (is_negative(desired_vel.x) && is_negative(desired_vel.y)) {703quad3_vel = Vector2f{MIN(quad3_vel.x, desired_vel.x), MIN(quad3_vel.y,desired_vel.y)};704}705// fourth quadrant: +ve x, -ve y direction706if (is_positive(desired_vel.x) && is_negative(desired_vel.y)) {707quad4_vel = Vector2f{MAX(quad4_vel.x, desired_vel.x), MIN(quad4_vel.y,desired_vel.y)};708}709}710711/*712Calculate maximum velocity vector that can be formed in each quadrant and separately store max & min of vertical components713*/714void AC_Avoid::find_max_quadrant_velocity_3D(Vector3f &desired_vel, Vector2f &quad1_vel, Vector2f &quad2_vel, Vector2f &quad3_vel, Vector2f &quad4_vel, float &max_z_vel, float &min_z_vel) const715{716// split into horizontal and vertical components717Vector2f velocity_ne{desired_vel.x, desired_vel.y};718find_max_quadrant_velocity(velocity_ne, quad1_vel, quad2_vel, quad3_vel, quad4_vel);719720// store maximum and minimum of z721if (is_positive(desired_vel.z) && (desired_vel.z > max_z_vel)) {722max_z_vel = desired_vel.z;723}724if (is_negative(desired_vel.z) && (desired_vel.z < min_z_vel)) {725min_z_vel = desired_vel.z;726}727}728729/*730* Computes the speed such that the stopping distance731* of the vehicle will be exactly the input distance.732*/733float AC_Avoid::get_max_speed(float kP, float accel, float distance, float dt) const734{735if (is_zero(kP)) {736return safe_sqrt(2.0f * distance * accel);737} else {738return sqrt_controller(distance, kP, accel, dt);739}740}741742#if AP_FENCE_ENABLED743744/*745* Adjusts the desired velocity for the circular fence.746*/747void AC_Avoid::adjust_velocity_circle_fence(float kP, float accel_cmss, Vector2f &desired_vel_ne_cms, Vector2f &backup_vel_ne_cms, float dt)748{749AC_Fence *fence = AP::fence();750if (fence == nullptr) {751return;752}753754AC_Fence &_fence = *fence;755756// exit if circular fence is not enabled757if ((_fence.get_enabled_fences() & AC_FENCE_TYPE_CIRCLE) == 0) {758return;759}760761// exit if the circular fence has already been breached762if ((_fence.get_breaches() & AC_FENCE_TYPE_CIRCLE) != 0) {763return;764}765766// get desired speed767const float desired_speed_cms = desired_vel_ne_cms.length();768if (is_zero(desired_speed_cms)) {769// no avoidance necessary when desired speed is zero770return;771}772773const AP_AHRS &_ahrs = AP::ahrs();774775// get position as a 2D offset from ahrs home776Vector2f position_ne_cm;777if (!_ahrs.get_relative_position_NE_home(position_ne_cm)) {778// we have no idea where we are....779return;780}781position_ne_cm *= 100.0f; // m -> cm782783// get the fence radius in cm784const float fence_radius_cm = _fence.get_radius_m() * 100.0f;785// get the margin to the fence in cm786const float margin_cm = _fence.get_margin_ne_m() * 100.0f;787788if (margin_cm > fence_radius_cm) {789return;790}791792// get vehicle distance from home793const float dist_from_home_cm = position_ne_cm.length();794if (dist_from_home_cm > fence_radius_cm) {795// outside of circular fence, no velocity adjustments796return;797}798const float distance_to_boundary_cm = fence_radius_cm - dist_from_home_cm;799800// for backing away801Vector2f quad_1_back_vel_ne_cms, quad_2_back_vel_ne_cms, quad_3_back_vel_ne_cms, quad_4_back_vel_ne_cms;802803// back away if vehicle has breached margin804if (is_negative(distance_to_boundary_cm - margin_cm)) {805calc_backup_velocity_2D(kP, accel_cmss, quad_1_back_vel_ne_cms, quad_2_back_vel_ne_cms, quad_3_back_vel_ne_cms, quad_4_back_vel_ne_cms, margin_cm - distance_to_boundary_cm, position_ne_cm, dt);806}807// desired backup velocity is sum of maximum velocity component in each quadrant808backup_vel_ne_cms = quad_1_back_vel_ne_cms + quad_2_back_vel_ne_cms + quad_3_back_vel_ne_cms + quad_4_back_vel_ne_cms;809810// vehicle is inside the circular fence811switch (_behavior) {812case BEHAVIOR_SLIDE: {813// implement sliding behaviour814const Vector2f stopping_point_ne_cm = position_ne_cm + desired_vel_ne_cms * (get_stopping_distance(kP, accel_cmss, desired_speed_cms) / desired_speed_cms);815const float stopping_point_dist_from_home_ne_cm = stopping_point_ne_cm.length();816if (stopping_point_dist_from_home_ne_cm <= fence_radius_cm - margin_cm) {817// stopping before before fence so no need to adjust818return;819}820// unsafe desired velocity - will not be able to stop before reaching margin from fence821// Project stopping point radially onto fence boundary822// Adjusted velocity will point towards this projected point at a safe speed823const Vector2f target_offset_ne_cm = stopping_point_ne_cm * ((fence_radius_cm - margin_cm) / stopping_point_dist_from_home_ne_cm);824const Vector2f target_direction_ne_cm = target_offset_ne_cm - position_ne_cm;825const float distance_to_target_cm = target_direction_ne_cm.length();826if (is_positive(distance_to_target_cm)) {827const float max_speed_cms = get_max_speed(kP, accel_cmss, distance_to_target_cm, dt);828desired_vel_ne_cms = target_direction_ne_cm * (MIN(desired_speed_cms,max_speed_cms) / distance_to_target_cm);829}830break;831}832833case (BEHAVIOR_STOP): {834// implement stopping behaviour835// calculate stopping point plus a margin so we look forward far enough to intersect with circular fence836const Vector2f stopping_point_plus_margin_ne_cm = position_ne_cm + desired_vel_ne_cms*((2.0f + margin_cm + get_stopping_distance(kP, accel_cmss, desired_speed_cms))/desired_speed_cms);837const float stopping_point_plus_margin_dist_from_home_cm = stopping_point_plus_margin_ne_cm.length();838if (dist_from_home_cm >= fence_radius_cm - margin_cm) {839// vehicle has already breached margin around fence840// if stopping point is even further from home (i.e. in wrong direction) then adjust speed to zero841// otherwise user is backing away from fence so do not apply limits842if (stopping_point_plus_margin_dist_from_home_cm >= dist_from_home_cm) {843desired_vel_ne_cms.zero();844}845} else {846// shorten vector without adjusting its direction847Vector2f intersection_ne_cm;848if (Vector2f::circle_segment_intersection(position_ne_cm, stopping_point_plus_margin_ne_cm, Vector2f(0.0f,0.0f), fence_radius_cm - margin_cm, intersection_ne_cm)) {849const float distance_to_target_cm = (intersection_ne_cm - position_ne_cm).length();850const float max_speed_cms = get_max_speed(kP, accel_cmss, distance_to_target_cm, dt);851if (max_speed_cms < desired_speed_cms) {852desired_vel_ne_cms *= MAX(max_speed_cms, 0.0f) / desired_speed_cms;853}854}855}856break;857}858}859}860861/*862* Adjusts the desired velocity for the exclusion polygons863*/864void AC_Avoid::adjust_velocity_inclusion_and_exclusion_polygons(float kP, float accel_cmss, Vector2f &desired_vel_ne_cms, Vector2f &backup_vel_ne_cms, float dt)865{866const AC_Fence *fence = AP::fence();867if (fence == nullptr) {868return;869}870871// exit if polygon fences are not enabled872if ((fence->get_enabled_fences() & AC_FENCE_TYPE_POLYGON) == 0) {873return;874}875876// for backing away877Vector2f quad_1_back_vel_ne_cms, quad_2_back_vel_ne_cms, quad_3_back_vel_ne_cms, quad_4_back_vel_ne_cms;878879// iterate through inclusion polygons880const uint8_t num_inclusion_polygons = fence->polyfence().get_inclusion_polygon_count();881for (uint8_t i = 0; i < num_inclusion_polygons; i++) {882uint16_t num_points;883const Vector2f* boundary = fence->polyfence().get_inclusion_polygon(i, num_points);884Vector2f backup_vel_inc_ne_cms;885// adjust velocity886adjust_velocity_polygon(kP, accel_cmss, desired_vel_ne_cms, backup_vel_inc_ne_cms, boundary, num_points, fence->get_margin_ne_m(), dt, true);887find_max_quadrant_velocity(backup_vel_inc_ne_cms, quad_1_back_vel_ne_cms, quad_2_back_vel_ne_cms, quad_3_back_vel_ne_cms, quad_4_back_vel_ne_cms);888}889890// iterate through exclusion polygons891const uint8_t num_exclusion_polygons = fence->polyfence().get_exclusion_polygon_count();892for (uint8_t i = 0; i < num_exclusion_polygons; i++) {893uint16_t num_points;894const Vector2f* boundary = fence->polyfence().get_exclusion_polygon(i, num_points);895Vector2f backup_vel_exc_ne_cms;896// adjust velocity897adjust_velocity_polygon(kP, accel_cmss, desired_vel_ne_cms, backup_vel_exc_ne_cms, boundary, num_points, fence->get_margin_ne_m(), dt, false);898find_max_quadrant_velocity(backup_vel_exc_ne_cms, quad_1_back_vel_ne_cms, quad_2_back_vel_ne_cms, quad_3_back_vel_ne_cms, quad_4_back_vel_ne_cms);899}900// desired backup velocity is sum of maximum velocity component in each quadrant901backup_vel_ne_cms = quad_1_back_vel_ne_cms + quad_2_back_vel_ne_cms + quad_3_back_vel_ne_cms + quad_4_back_vel_ne_cms;902}903904/*905* Adjusts the desired velocity for the inclusion circles906*/907void AC_Avoid::adjust_velocity_inclusion_circles(float kP, float accel_cmss, Vector2f &desired_vel_ne_cms, Vector2f &backup_vel_ne_cms, float dt)908{909const AC_Fence *fence = AP::fence();910if (fence == nullptr) {911return;912}913914// return immediately if no inclusion circles915const uint8_t num_circles = fence->polyfence().get_inclusion_circle_count();916if (num_circles == 0) {917return;918}919920// exit if polygon fences are not enabled921if ((fence->get_enabled_fences() & AC_FENCE_TYPE_POLYGON) == 0) {922return;923}924925// get vehicle position926Vector2f position_ne_cm;927if (!AP::ahrs().get_relative_position_NE_origin_float(position_ne_cm)) {928// do not limit velocity if we don't have a position estimate929return;930}931position_ne_cm = position_ne_cm * 100.0f; // m to cm932933// get the margin to the fence in cm934const float margin_cm = fence->get_margin_ne_m() * 100.0f;935936// get desired speed937const float desired_speed_cms = desired_vel_ne_cms.length();938939// get stopping distance as an offset from the vehicle940Vector2f stopping_offset_ne_cm;941if (!is_zero(desired_speed_cms)) {942switch (_behavior) {943case BEHAVIOR_SLIDE:944stopping_offset_ne_cm = desired_vel_ne_cms * (get_stopping_distance(kP, accel_cmss, desired_speed_cms) / desired_speed_cms);945break;946case BEHAVIOR_STOP:947// calculate stopping point plus a margin so we look forward far enough to intersect with circular fence948stopping_offset_ne_cm = desired_vel_ne_cms * ((2.0f + margin_cm + get_stopping_distance(kP, accel_cmss, desired_speed_cms)) / desired_speed_cms);949break;950}951}952953// for backing away954Vector2f quad_1_back_vel_ne_cms, quad_2_back_vel_ne_cms, quad_3_back_vel_ne_cms, quad_4_back_vel_ne_cms;955956// iterate through inclusion circles957for (uint8_t i = 0; i < num_circles; i++) {958Vector2f center_pos_ne_cm;959float radius_m;960if (fence->polyfence().get_inclusion_circle(i, center_pos_ne_cm, radius_m)) {961// get position relative to circle's center962const Vector2f position_rel_ne_cm = (position_ne_cm - center_pos_ne_cm);963964// if we are outside this circle do not limit velocity for this circle965const float dist_sq_cm = position_rel_ne_cm.length_squared();966const float radius_cm = (radius_m * 100.0f);967if (dist_sq_cm > sq(radius_cm)) {968continue;969}970971const float radius_with_margin_cm = radius_cm - margin_cm;972if (is_negative(radius_with_margin_cm)) {973return;974}975976const float margin_breach_cm = radius_with_margin_cm - safe_sqrt(dist_sq_cm);977// back away if vehicle has breached margin978if (is_negative(margin_breach_cm)) {979calc_backup_velocity_2D(kP, accel_cmss, quad_1_back_vel_ne_cms, quad_2_back_vel_ne_cms, quad_3_back_vel_ne_cms, quad_4_back_vel_ne_cms, margin_breach_cm, position_rel_ne_cm, dt);980}981if (is_zero(desired_speed_cms)) {982// no avoidance necessary when desired speed is zero983continue;984}985986switch (_behavior) {987case BEHAVIOR_SLIDE: {988// implement sliding behaviour989const Vector2f stopping_point_ne_cm = position_rel_ne_cm + stopping_offset_ne_cm;990const float stopping_point_dist_cm = stopping_point_ne_cm.length();991if (is_zero(stopping_point_dist_cm) || (stopping_point_dist_cm <= (radius_cm - margin_cm))) {992// stopping before before fence so no need to adjust for this circle993continue;994}995// unsafe desired velocity - will not be able to stop before reaching margin from fence996// project stopping point radially onto fence boundary997// adjusted velocity will point towards this projected point at a safe speed998const Vector2f target_offset_ne_cm = stopping_point_ne_cm * ((radius_cm - margin_cm) / stopping_point_dist_cm);999const Vector2f target_direction_ne_cm = target_offset_ne_cm - position_rel_ne_cm;1000const float distance_to_target_cm = target_direction_ne_cm.length();1001if (is_positive(distance_to_target_cm)) {1002const float max_speed_cms = get_max_speed(kP, accel_cmss, distance_to_target_cm, dt);1003desired_vel_ne_cms = target_direction_ne_cm * (MIN(desired_speed_cms, max_speed_cms) / distance_to_target_cm);1004}1005}1006break;1007case BEHAVIOR_STOP: {1008// implement stopping behaviour1009const Vector2f stopping_point_plus_margin_ne_cm = position_rel_ne_cm + stopping_offset_ne_cm;1010const float dist_cm = safe_sqrt(dist_sq_cm);1011if (dist_cm >= radius_cm - margin_cm) {1012// vehicle has already breached margin around fence1013// if stopping point is even further from center (i.e. in wrong direction) then adjust speed to zero1014// otherwise user is backing away from fence so do not apply limits1015if (stopping_point_plus_margin_ne_cm.length() >= dist_cm) {1016desired_vel_ne_cms.zero();1017// desired backup velocity is sum of maximum velocity component in each quadrant1018backup_vel_ne_cms = quad_1_back_vel_ne_cms + quad_2_back_vel_ne_cms + quad_3_back_vel_ne_cms + quad_4_back_vel_ne_cms;1019return;1020}1021} else {1022// shorten vector without adjusting its direction1023Vector2f intersection_ne_cm;1024if (Vector2f::circle_segment_intersection(position_rel_ne_cm, stopping_point_plus_margin_ne_cm, Vector2f(0.0f,0.0f), radius_cm - margin_cm, intersection_ne_cm)) {1025const float distance_to_target_cm = (intersection_ne_cm - position_rel_ne_cm).length();1026const float max_speed_cms = get_max_speed(kP, accel_cmss, distance_to_target_cm, dt);1027if (max_speed_cms < desired_speed_cms) {1028desired_vel_ne_cms *= MAX(max_speed_cms, 0.0f) / desired_speed_cms;1029}1030}1031}1032}1033break;1034}1035}1036}1037// desired backup velocity is sum of maximum velocity component in each quadrant1038backup_vel_ne_cms = quad_1_back_vel_ne_cms + quad_2_back_vel_ne_cms + quad_3_back_vel_ne_cms + quad_4_back_vel_ne_cms;1039}10401041/*1042* Adjusts the desired velocity for the exclusion circles1043*/1044void AC_Avoid::adjust_velocity_exclusion_circles(float kP, float accel_cmss, Vector2f &desired_vel_ne_cms, Vector2f &backup_vel_ne_cms, float dt)1045{1046const AC_Fence *fence = AP::fence();1047if (fence == nullptr) {1048return;1049}10501051// return immediately if no inclusion circles1052const uint8_t num_circles = fence->polyfence().get_exclusion_circle_count();1053if (num_circles == 0) {1054return;1055}10561057// exit if polygon fences are not enabled1058if ((fence->get_enabled_fences() & AC_FENCE_TYPE_POLYGON) == 0) {1059return;1060}10611062// get vehicle position1063Vector2f position_ne_cm;1064if (!AP::ahrs().get_relative_position_NE_origin_float(position_ne_cm)) {1065// do not limit velocity if we don't have a position estimate1066return;1067}1068position_ne_cm = position_ne_cm * 100.0f; // m to cm10691070// get the margin to the fence in cm1071const float margin_cm = fence->get_margin_ne_m() * 100.0f;10721073// for backing away1074Vector2f quad_1_back_vel_ne_cms, quad_2_back_vel_ne_cms, quad_3_back_vel_ne_cms, quad_4_back_vel_ne_cms;10751076// get desired speed1077const float desired_speed_cms = desired_vel_ne_cms.length();10781079// calculate stopping distance as an offset from the vehicle (only used for BEHAVIOR_STOP)1080// add a margin so we look forward far enough to intersect with circular fence1081Vector2f stopping_offset_ne_cm;1082if (!is_zero(desired_speed_cms)) {1083if ((AC_Avoid::BehaviourType)_behavior.get() == BEHAVIOR_STOP) {1084stopping_offset_ne_cm = desired_vel_ne_cms * ((2.0f + margin_cm + get_stopping_distance(kP, accel_cmss, desired_speed_cms)) / desired_speed_cms);1085}1086}1087// iterate through exclusion circles1088for (uint8_t i = 0; i < num_circles; i++) {1089Vector2f center_pos_ne_cm;1090float radius_m;1091if (fence->polyfence().get_exclusion_circle(i, center_pos_ne_cm, radius_m)) {1092// get position relative to circle's center1093const Vector2f position_rel_ne_cm = (position_ne_cm - center_pos_ne_cm);10941095// if we are inside this circle do not limit velocity for this circle1096const float dist_sq_cm = position_rel_ne_cm.length_squared();1097const float radius_cm = (radius_m * 100.0f);1098if (radius_cm < margin_cm) {1099return;1100}1101if (dist_sq_cm < sq(radius_cm)) {1102continue;1103}11041105const Vector2f vector_to_center_ne_cm = center_pos_ne_cm - position_ne_cm;1106const float dist_to_boundary_cm = vector_to_center_ne_cm.length() - radius_cm;1107// back away if vehicle has breached margin1108if (is_negative(dist_to_boundary_cm - margin_cm)) {1109calc_backup_velocity_2D(kP, accel_cmss, quad_1_back_vel_ne_cms, quad_2_back_vel_ne_cms, quad_3_back_vel_ne_cms, quad_4_back_vel_ne_cms, margin_cm - dist_to_boundary_cm, vector_to_center_ne_cm, dt);1110}1111if (is_zero(desired_speed_cms)) {1112// no avoidance necessary when desired speed is zero1113continue;1114}11151116switch (_behavior) {1117case BEHAVIOR_SLIDE: {1118// vector from current position to circle's center1119Vector2f limit_direction_ne_cm = vector_to_center_ne_cm;1120if (limit_direction_ne_cm.is_zero()) {1121// vehicle is exactly on circle center so do not limit velocity1122continue;1123}1124// calculate distance to edge of circle1125const float limit_distance_cm = limit_direction_ne_cm.length() - radius_cm;1126if (!is_positive(limit_distance_cm)) {1127// vehicle is within circle so do not limit velocity1128continue;1129}1130// vehicle is outside the circle, adjust velocity to stay outside1131limit_direction_ne_cm.normalize();1132limit_velocity_NE(kP, accel_cmss, desired_vel_ne_cms, limit_direction_ne_cm, MAX(limit_distance_cm - margin_cm, 0.0f), dt);1133}1134break;1135case BEHAVIOR_STOP: {1136// implement stopping behaviour1137const Vector2f stopping_point_plus_margin_ne_cm = position_rel_ne_cm + stopping_offset_ne_cm;1138const float dist_cm = safe_sqrt(dist_sq_cm);1139if (dist_cm < radius_cm + margin_cm) {1140// vehicle has already breached margin around fence1141// if stopping point is closer to center (i.e. in wrong direction) then adjust speed to zero1142// otherwise user is backing away from fence so do not apply limits1143if (stopping_point_plus_margin_ne_cm.length() <= dist_cm) {1144desired_vel_ne_cms.zero();1145backup_vel_ne_cms = quad_1_back_vel_ne_cms + quad_2_back_vel_ne_cms + quad_3_back_vel_ne_cms + quad_4_back_vel_ne_cms;1146return;1147}1148} else {1149// shorten vector without adjusting its direction1150Vector2f intersection_ne_cm;1151if (Vector2f::circle_segment_intersection(position_rel_ne_cm, stopping_point_plus_margin_ne_cm, Vector2f(0.0f,0.0f), radius_cm + margin_cm, intersection_ne_cm)) {1152const float distance_to_target_cm = (intersection_ne_cm - position_rel_ne_cm).length();1153const float max_speed_cms = get_max_speed(kP, accel_cmss, distance_to_target_cm, dt);1154if (max_speed_cms < desired_speed_cms) {1155desired_vel_ne_cms *= MAX(max_speed_cms, 0.0f) / desired_speed_cms;1156}1157}1158}1159}1160break;1161}1162}1163}1164// desired backup velocity is sum of maximum velocity component in each quadrant1165backup_vel_ne_cms = quad_1_back_vel_ne_cms + quad_2_back_vel_ne_cms + quad_3_back_vel_ne_cms + quad_4_back_vel_ne_cms;1166}1167#endif // AP_FENCE_ENABLED11681169#if AP_BEACON_ENABLED1170/*1171* Adjusts the desired velocity for the beacon fence.1172*/1173void AC_Avoid::adjust_velocity_beacon_fence(float kP, float accel_cmss, Vector2f &desired_vel_ne_cms, Vector2f &backup_vel_ne_cms, float dt)1174{1175AP_Beacon *_beacon = AP::beacon();11761177// exit if the beacon is not present1178if (_beacon == nullptr) {1179return;1180}11811182// get boundary from beacons1183uint16_t num_points = 0;1184const Vector2f* boundary = _beacon->get_boundary_points(num_points);1185if ((boundary == nullptr) || (num_points == 0)) {1186return;1187}11881189// adjust velocity using beacon1190float margin_m = 0;1191#if AP_FENCE_ENABLED1192if (AP::fence()) {1193margin_m = AP::fence()->get_margin_ne_m();1194}1195#endif1196adjust_velocity_polygon(kP, accel_cmss, desired_vel_ne_cms, backup_vel_ne_cms, boundary, num_points, margin_m, dt, true);1197}1198#endif // AP_BEACON_ENABLED11991200/*1201* Adjusts the desired velocity based on output from the proximity sensor1202*/1203void AC_Avoid::adjust_velocity_proximity(float kP, float accel_cmss, Vector3f &desired_vel_neu_cms, Vector3f &backup_vel_neu_cms, float kP_z, float accel_u_cmss, float dt)1204{1205#if HAL_PROXIMITY_ENABLED1206// exit immediately if proximity sensor is not present1207AP_Proximity *proximity = AP::proximity();1208if (!proximity) {1209return;1210}12111212AP_Proximity &_proximity = *proximity;1213// get total number of obstacles1214const uint8_t obstacle_num = _proximity.get_obstacle_count();1215if (obstacle_num == 0) {1216// no obstacles1217return;1218}12191220const AP_AHRS &_ahrs = AP::ahrs();12211222// for backing away1223Vector2f quad_1_back_vel_ne_cms, quad_2_back_vel_ne_cms, quad_3_back_vel_ne_cms, quad_4_back_vel_ne_cms;1224float max_back_vel_u_cms = 0.0f;1225float min_back_vel_u_cms = 0.0f;12261227// rotate velocity vector from earth frame to body-frame since obstacles are in body-frame1228const Vector2f desired_vel_body_ne_cms = _ahrs.earth_to_body2D(Vector2f{desired_vel_neu_cms.x, desired_vel_neu_cms.y});12291230// safe_vel_ne_cms will be adjusted to stay away from Proximity Obstacles1231Vector3f safe_vel_neu_cms = Vector3f{desired_vel_body_ne_cms.x, desired_vel_body_ne_cms.y, desired_vel_neu_cms.z};1232const Vector3f safe_vel_orig_neu_cms = safe_vel_neu_cms;12331234// calc margin in cm1235const float margin_cm = MAX(_margin_m * 100.0f, 0.0f);1236Vector3f stopping_point_plus_margin_neu_cm;1237if (!desired_vel_neu_cms.is_zero()) {1238// only used for "stop mode". Pre-calculating the stopping point here makes sure we do not need to repeat the calculations under iterations.1239const float speed_cms = safe_vel_neu_cms.length();1240stopping_point_plus_margin_neu_cm = safe_vel_neu_cms * ((2.0f + margin_cm + get_stopping_distance(kP, accel_cmss, speed_cms)) / speed_cms);1241}12421243for (uint8_t i = 0; i<obstacle_num; i++) {1244// get obstacle from proximity library1245Vector3f vector_to_obstacle_neu;1246if (!_proximity.get_obstacle(i, vector_to_obstacle_neu)) {1247// this one is not valid1248continue;1249}12501251const float dist_to_boundary_cm = vector_to_obstacle_neu.length();1252if (is_zero(dist_to_boundary_cm)) {1253continue;1254}12551256// back away if vehicle has breached margin1257if (is_negative(dist_to_boundary_cm - margin_cm)) {1258const float breach_dist_cm = margin_cm - dist_to_boundary_cm;1259// add a deadzone so that the vehicle doesn't backup and go forward again and again1260const float deadzone_cm = MAX(0.0f, _backup_deadzone_m) * 100.0f;1261if (breach_dist_cm > deadzone_cm) {1262// this vector will help us decide how much we have to back away horizontally and vertically1263const Vector3f margin_vector_neu_cm = vector_to_obstacle_neu.normalized() * breach_dist_cm;1264const float xy_back_dist = margin_vector_neu_cm.xy().length();1265const float z_back_dist = margin_vector_neu_cm.z;1266calc_backup_velocity_3D(kP, accel_cmss, quad_1_back_vel_ne_cms, quad_2_back_vel_ne_cms, quad_3_back_vel_ne_cms, quad_4_back_vel_ne_cms, xy_back_dist, vector_to_obstacle_neu, kP_z, accel_u_cmss, z_back_dist, min_back_vel_u_cms, max_back_vel_u_cms, dt);1267}1268}12691270if (desired_vel_neu_cms.is_zero()) {1271// cannot limit velocity if there is nothing to limit1272// backing up (if needed) has already been done1273continue;1274}12751276switch (_behavior) {1277case BEHAVIOR_SLIDE: {1278Vector3f limit_direction_neu{vector_to_obstacle_neu};1279// distance to closest point1280const float limit_distance_cm = limit_direction_neu.length();1281if (is_zero(limit_distance_cm)) {1282// We are exactly on the edge, this should ideally never be possible1283// i.e. do not adjust velocity.1284continue;1285}1286// Adjust velocity to not violate margin.1287limit_velocity_NEU(kP, accel_cmss, safe_vel_neu_cms, limit_direction_neu, margin_cm, kP_z, accel_u_cmss, dt);12881289break;1290}12911292case BEHAVIOR_STOP: {1293// vector from current position to obstacle1294Vector3f limit_direction_neu;1295// find closest point with line segment1296// also see if the vehicle will "roughly" intersect the boundary with the projected stopping point1297const bool intersect = _proximity.closest_point_from_segment_to_obstacle(i, Vector3f{}, stopping_point_plus_margin_neu_cm, limit_direction_neu);1298if (intersect) {1299// the vehicle is intersecting the plane formed by the boundary1300// distance to the closest point from the stopping point1301float limit_distance_cm = limit_direction_neu.length();1302if (is_zero(limit_distance_cm)) {1303// We are exactly on the edge, this should ideally never be possible1304// i.e. do not adjust velocity.1305return;1306}1307if (limit_distance_cm <= margin_cm) {1308// we are within the margin so stop vehicle1309safe_vel_neu_cms.zero();1310} else {1311// vehicle inside the given edge, adjust velocity to not violate this edge1312limit_velocity_NEU(kP, accel_cmss, safe_vel_neu_cms, limit_direction_neu, margin_cm, kP_z, accel_u_cmss, dt);1313}13141315break;1316}1317}1318}1319}13201321// desired backup velocity is sum of maximum velocity component in each quadrant1322const Vector2f desired_back_vel_cms_xy = quad_1_back_vel_ne_cms + quad_2_back_vel_ne_cms + quad_3_back_vel_ne_cms + quad_4_back_vel_ne_cms;1323const float desired_back_vel_cms_z = max_back_vel_u_cms + min_back_vel_u_cms;13241325if (safe_vel_neu_cms == safe_vel_orig_neu_cms && desired_back_vel_cms_xy.is_zero() && is_zero(desired_back_vel_cms_z)) {1326// proximity avoidance did nothing, no point in doing the calculations below. Return early1327backup_vel_neu_cms.zero();1328return;1329}13301331// set modified desired velocity vector and back away velocity vector1332// vectors were in body-frame, rotate resulting vector back to earth-frame1333const Vector2f safe_vel_ne_cms = _ahrs.body_to_earth2D(Vector2f{safe_vel_neu_cms.x, safe_vel_neu_cms.y});1334desired_vel_neu_cms = Vector3f{safe_vel_ne_cms.x, safe_vel_ne_cms.y, safe_vel_neu_cms.z};1335const Vector2f backup_vel_ne_cms = _ahrs.body_to_earth2D(desired_back_vel_cms_xy);1336backup_vel_neu_cms = Vector3f{backup_vel_ne_cms.x, backup_vel_ne_cms.y, desired_back_vel_cms_z};1337#endif // HAL_PROXIMITY_ENABLED1338}13391340/*1341* Adjusts the desired velocity for the polygon fence.1342*/1343void AC_Avoid::adjust_velocity_polygon(float kP, float accel_cmss, Vector2f &desired_vel_cms, Vector2f &backup_vel_ne_cms, const Vector2f* boundary, uint16_t num_points, float margin, float dt, bool stay_inside)1344{1345// exit if there are no points1346if (boundary == nullptr || num_points == 0) {1347return;1348}13491350const AP_AHRS &_ahrs = AP::ahrs();13511352// do not adjust velocity if vehicle is outside the polygon fence1353Vector2f position_ne_cm;1354if (!_ahrs.get_relative_position_NE_origin_float(position_ne_cm)) {1355// boundary is in earth frame but we have no idea1356// where we are1357return;1358}1359position_ne_cm = position_ne_cm * 100.0f; // m to cm136013611362// return if we have already breached polygon1363const bool inside_polygon = !Polygon_outside(position_ne_cm, boundary, num_points);1364if (inside_polygon != stay_inside) {1365return;1366}13671368// Safe_vel will be adjusted to remain within fence.1369// We need a separate vector in case adjustment fails,1370// e.g. if we are exactly on the boundary.1371Vector2f safe_vel_ne_cms(desired_vel_cms);1372Vector2f desired_back_vel_cms;13731374// calc margin in cm1375const float margin_cm = MAX(margin * 100.0f, 0.0f);13761377// for stopping1378const float speed = safe_vel_ne_cms.length();1379Vector2f stopping_point_plus_margin_ne_cm;1380if (!desired_vel_cms.is_zero()) {1381stopping_point_plus_margin_ne_cm = position_ne_cm + safe_vel_ne_cms*((2.0f + margin_cm + get_stopping_distance(kP, accel_cmss, speed))/speed);1382}13831384// for backing away1385Vector2f quad_1_back_vel_ne_cms, quad_2_back_vel_ne_cms, quad_3_back_vel_ne_cms, quad_4_back_vel_ne_cms;13861387for (uint16_t i=0; i<num_points; i++) {1388uint16_t j = i+1;1389if (j >= num_points) {1390j = 0;1391}1392// end points of current edge1393Vector2f start = boundary[j];1394Vector2f end = boundary[i];1395Vector2f vector_to_boundary_ne_cm = Vector2f::closest_point(position_ne_cm, start, end) - position_ne_cm;1396// back away if vehicle has breached margin1397if (is_negative(vector_to_boundary_ne_cm.length() - margin_cm)) {1398calc_backup_velocity_2D(kP, accel_cmss, quad_1_back_vel_ne_cms, quad_2_back_vel_ne_cms, quad_3_back_vel_ne_cms, quad_4_back_vel_ne_cms, margin_cm - vector_to_boundary_ne_cm.length(), vector_to_boundary_ne_cm, dt);1399}14001401// exit immediately if no desired velocity1402if (desired_vel_cms.is_zero()) {1403continue;1404}14051406switch (_behavior) {1407case (BEHAVIOR_SLIDE): {1408// vector from current position to closest point on current edge1409Vector2f limit_direction_ne_cm = vector_to_boundary_ne_cm;1410// distance to closest point1411const float limit_distance_cm = limit_direction_ne_cm.length();1412if (is_zero(limit_distance_cm)) {1413// We are exactly on the edge - treat this as a fence breach.1414// i.e. do not adjust velocity.1415return;1416}1417// We are strictly inside the given edge.1418// Adjust velocity to not violate this edge.1419limit_direction_ne_cm /= limit_distance_cm;1420limit_velocity_NE(kP, accel_cmss, safe_vel_ne_cms, limit_direction_ne_cm, MAX(limit_distance_cm - margin_cm, 0.0f), dt);1421break;1422}14231424case (BEHAVIOR_STOP): {1425// find intersection_ne_cm with line segment1426Vector2f intersection_ne_cm;1427if (Vector2f::segment_intersection(position_ne_cm, stopping_point_plus_margin_ne_cm, start, end, intersection_ne_cm)) {1428// vector from current position to point on current edge1429Vector2f limit_direction_ne_cm = intersection_ne_cm - position_ne_cm;1430const float limit_distance_cm = limit_direction_ne_cm.length();1431if (is_zero(limit_distance_cm)) {1432// We are exactly on the edge - treat this as a fence breach.1433// i.e. do not adjust velocity.1434return;1435}1436if (limit_distance_cm <= margin_cm) {1437// we are within the margin so stop vehicle1438safe_vel_ne_cms.zero();1439} else {1440// vehicle inside the given edge, adjust velocity to not violate this edge1441limit_direction_ne_cm /= limit_distance_cm;1442limit_velocity_NE(kP, accel_cmss, safe_vel_ne_cms, limit_direction_ne_cm, MAX(limit_distance_cm - margin_cm, 0.0f), dt);1443}1444}1445break;1446}1447}1448}1449// desired backup velocity is sum of maximum velocity component in each quadrant1450desired_back_vel_cms = quad_1_back_vel_ne_cms + quad_2_back_vel_ne_cms + quad_3_back_vel_ne_cms + quad_4_back_vel_ne_cms;14511452// set modified desired velocity vector or back away velocity vector1453desired_vel_cms = safe_vel_ne_cms;1454backup_vel_ne_cms = desired_back_vel_cms;1455}14561457/*1458* Computes distance required to stop, given current speed.1459*1460* Implementation copied from AC_PosControl.1461*/1462float AC_Avoid::get_stopping_distance(float kP, float accel_cmss, float speed_cms) const1463{1464// avoid divide by zero by using current position if the velocity is below 10cm/s, kP is very low or acceleration is zero1465if (accel_cmss <= 0.0f || is_zero(speed_cms)) {1466return 0.0f;1467}14681469// handle linear deceleration1470if (kP <= 0.0f) {1471return 0.5f * sq(speed_cms) / accel_cmss;1472}14731474// calculate distance within which we can stop1475// accel_cmss/kP is the point at which velocity switches from linear to sqrt1476if (speed_cms < accel_cmss/kP) {1477return speed_cms/kP;1478} else {1479// accel_cmss/(2.0f*kP*kP) is the distance at which we switch from linear to sqrt response1480return accel_cmss/(2.0f*kP*kP) + (speed_cms*speed_cms)/(2.0f*accel_cmss);1481}1482}14831484// convert distance (in meters) to a lean percentage (in 0~1 range) for use in manual flight modes1485float AC_Avoid::distance_m_to_lean_norm(float dist_m) const1486{1487// ignore objects beyond DIST_MAX1488if (dist_m < 0.0f || dist_m >= _dist_max_m || _dist_max_m <= 0.0f) {1489return 0.0f;1490}1491// inverted but linear response1492return 1.0f - (dist_m / _dist_max_m);1493}14941495// returns the maximum positive and negative roll and pitch percentages (in -1 ~ +1 range) based on the proximity sensor1496void AC_Avoid::get_proximity_roll_pitch_norm(float &roll_positive_norm, float &roll_negative_norm, float &pitch_positive_norm, float &pitch_negative_norm) const1497{1498#if HAL_PROXIMITY_ENABLED1499AP_Proximity *proximity = AP::proximity();1500if (proximity == nullptr) {1501return;1502}1503AP_Proximity &_proximity = *proximity;1504const uint8_t obj_count = _proximity.get_object_count();1505// if no objects return1506if (obj_count == 0) {1507return;1508}15091510// calculate maximum roll, pitch values from objects1511for (uint8_t i=0; i<obj_count; i++) {1512float ang_deg, dist_m;1513if (_proximity.get_object_angle_and_distance(i, ang_deg, dist_m)) {1514if (dist_m < _dist_max_m) {1515// convert distance to lean angle (in 0 to 1 range)1516const float lean_norm = distance_m_to_lean_norm(dist_m);1517// convert angle to roll and pitch lean percentages1518const float angle_rad = radians(ang_deg);1519const float roll_norm = -sinf(angle_rad) * lean_norm;1520const float pitch_norm = cosf(angle_rad) * lean_norm;1521// update roll, pitch maximums1522if (roll_norm > 0.0f) {1523roll_positive_norm = MAX(roll_positive_norm, roll_norm);1524} else if (roll_norm < 0.0f) {1525roll_negative_norm = MIN(roll_negative_norm, roll_norm);1526}1527if (pitch_norm > 0.0f) {1528pitch_positive_norm = MAX(pitch_positive_norm, pitch_norm);1529} else if (pitch_norm < 0.0f) {1530pitch_negative_norm = MIN(pitch_negative_norm, pitch_norm);1531}1532}1533}1534}1535#endif // HAL_PROXIMITY_ENABLED1536}15371538// singleton instance1539AC_Avoid *AC_Avoid::_singleton;15401541namespace AP {15421543AC_Avoid *ac_avoid()1544{1545return AC_Avoid::get_singleton();1546}15471548}15491550#endif // !APM_BUILD_Arduplane15511552#endif // AP_AVOIDANCE_ENABLED155315541555