Path: blob/master/libraries/AC_Avoidance/AC_Avoid.cpp
4182 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, 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, 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_xy_max, 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, 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, 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, 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_z_max, 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_cms, Vector3f &backup_vel, float kP_z, float accel_cmss_z, float dt)137{138// Only horizontal component needed for most fences, since fences are 2D139Vector2f desired_velocity_xy_cms{desired_vel_cms.x, desired_vel_cms.y};140141#if AP_FENCE_ENABLED || AP_BEACON_ENABLED142// limit acceleration143const float accel_cmss_limited = MIN(accel_cmss, AC_AVOID_ACCEL_CMSS_MAX);144#endif145146// maximum component of desired backup velocity in each quadrant147Vector2f quad_1_back_vel, quad_2_back_vel, quad_3_back_vel, quad_4_back_vel;148149#if AP_FENCE_ENABLED150if ((_enabled & AC_AVOID_STOP_AT_FENCE) > 0) {151// Store velocity needed to back away from fence152Vector2f backup_vel_fence;153154adjust_velocity_circle_fence(kP, accel_cmss_limited, desired_velocity_xy_cms, backup_vel_fence, dt);155find_max_quadrant_velocity(backup_vel_fence, quad_1_back_vel, quad_2_back_vel, quad_3_back_vel, quad_4_back_vel);156157// backup_vel_fence is set to zero after each fence in case the velocity is unset from previous methods158backup_vel_fence.zero();159adjust_velocity_inclusion_and_exclusion_polygons(kP, accel_cmss_limited, desired_velocity_xy_cms, backup_vel_fence, dt);160find_max_quadrant_velocity(backup_vel_fence, quad_1_back_vel, quad_2_back_vel, quad_3_back_vel, quad_4_back_vel);161162backup_vel_fence.zero();163adjust_velocity_inclusion_circles(kP, accel_cmss_limited, desired_velocity_xy_cms, backup_vel_fence, dt);164find_max_quadrant_velocity(backup_vel_fence, quad_1_back_vel, quad_2_back_vel, quad_3_back_vel, quad_4_back_vel);165166backup_vel_fence.zero();167adjust_velocity_exclusion_circles(kP, accel_cmss_limited, desired_velocity_xy_cms, backup_vel_fence, dt);168find_max_quadrant_velocity(backup_vel_fence, quad_1_back_vel, quad_2_back_vel, quad_3_back_vel, quad_4_back_vel);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;176adjust_velocity_beacon_fence(kP, accel_cmss_limited, desired_velocity_xy_cms, backup_vel_beacon, dt);177find_max_quadrant_velocity(backup_vel_beacon, quad_1_back_vel, quad_2_back_vel, quad_3_back_vel, quad_4_back_vel);178}179#endif // AP_BEACON_ENABLED180181// check for vertical fence182float desired_velocity_z_cms = desired_vel_cms.z;183float desired_backup_vel_z = 0.0f;184adjust_velocity_z(kP_z, accel_cmss_z, desired_velocity_z_cms, desired_backup_vel_z, dt);185186// Desired backup velocity is sum of maximum velocity component in each quadrant187const Vector2f desired_backup_vel_xy = quad_1_back_vel + quad_2_back_vel + quad_3_back_vel + quad_4_back_vel;188backup_vel = Vector3f{desired_backup_vel_xy.x, desired_backup_vel_xy.y, desired_backup_vel_z};189desired_vel_cms = Vector3f{desired_velocity_xy_cms.x, desired_velocity_xy_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_cmss_z are for vertical axis197*/198void AC_Avoid::adjust_velocity(Vector3f &desired_vel_cms, bool &backing_up, float kP, float accel_cmss, float kP_z, float accel_cmss_z, float dt)199{200// exit immediately if disabled201if (_enabled == AC_AVOID_DISABLED) {202return;203}204205// make a copy of input velocity, because desired_vel_cms might be changed206const Vector3f desired_vel_cms_original = desired_vel_cms;207208// limit acceleration209const float accel_cmss_limited = MIN(accel_cmss, AC_AVOID_ACCEL_CMSS_MAX);210211// maximum component of horizontal desired backup velocity in each quadrant212Vector2f quad_1_back_vel, quad_2_back_vel, quad_3_back_vel, quad_4_back_vel;213float back_vel_up = 0.0f;214float back_vel_down = 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;220adjust_velocity_proximity(kP, accel_cmss_limited, desired_vel_cms, backup_vel_proximity, kP_z,accel_cmss_z, dt);221find_max_quadrant_velocity_3D(backup_vel_proximity, quad_1_back_vel, quad_2_back_vel, quad_3_back_vel, quad_4_back_vel, back_vel_up, back_vel_down);222}223224// Avoidance in response to various fences225Vector3f backup_vel_fence;226adjust_velocity_fence(kP, accel_cmss, desired_vel_cms, backup_vel_fence, kP_z, accel_cmss_z, dt);227find_max_quadrant_velocity_3D(backup_vel_fence , quad_1_back_vel, quad_2_back_vel, quad_3_back_vel, quad_4_back_vel, back_vel_up, back_vel_down);228229// Desired backup velocity is sum of maximum velocity component in each quadrant230const Vector2f desired_backup_vel_xy = quad_1_back_vel + quad_2_back_vel + quad_3_back_vel + quad_4_back_vel;231const float desired_backup_vel_z = back_vel_down + back_vel_up;232Vector3f desired_backup_vel{desired_backup_vel_xy.x, desired_backup_vel_xy.y, desired_backup_vel_z};233234const float max_back_spd_xy_cms = _backup_speed_xy_max * 100.0;235if (!desired_backup_vel.xy().is_zero() && is_positive(max_back_spd_xy_cms)) {236backing_up = true;237// Constrain horizontal backing away speed238desired_backup_vel.xy().limit_length(max_back_spd_xy_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.x)) {243if (is_positive(desired_backup_vel.x)) {244desired_vel_cms.x = MAX(desired_vel_cms.x, desired_backup_vel.x);245} else {246desired_vel_cms.x = MIN(desired_vel_cms.x, desired_backup_vel.x);247}248}249if (!is_zero(desired_backup_vel.y)) {250if (is_positive(desired_backup_vel.y)) {251desired_vel_cms.y = MAX(desired_vel_cms.y, desired_backup_vel.y);252} else {253desired_vel_cms.y = MIN(desired_vel_cms.y, desired_backup_vel.y);254}255}256}257258const float max_back_spd_z_cms = _backup_speed_z_max * 100.0;259if (!is_zero(desired_backup_vel.z) && is_positive(max_back_spd_z_cms)) {260backing_up = true;261262// Constrain vertical backing away speed263desired_backup_vel.z = constrain_float(desired_backup_vel.z, -max_back_spd_z_cms, max_back_spd_z_cms);264265if (!is_zero(desired_backup_vel.z)) {266if (is_positive(desired_backup_vel.z)) {267desired_vel_cms.z = MAX(desired_vel_cms.z, desired_backup_vel.z);268} else {269desired_vel_cms.z = MIN(desired_vel_cms.z, desired_backup_vel.z);270}271}272}273274// limit acceleration275limit_accel(desired_vel_cms_original, desired_vel_cms, dt);276277if (desired_vel_cms_original != desired_vel_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_cms_original, desired_vel_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_cms_original, desired_vel_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(const Vector3f &original_vel, Vector3f &modified_vel, float dt)306{307if (original_vel == modified_vel || is_zero(_accel_max) || !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 = original_vel;315}316317// acceleration demanded by avoidance318const Vector3f accel = (modified_vel - _prev_avoid_vel)/dt;319320// max accel in cm321const float max_accel_cm = _accel_max * 100.0f;322323if (accel.length() > max_accel_cm) {324// pull back on the acceleration325const Vector3f accel_direction = accel.normalized();326modified_vel = (accel_direction * max_accel_cm) * dt + _prev_avoid_vel;327}328329_prev_avoid_vel = modified_vel;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, float heading, float &speed, float dt)340{341// convert heading and speed into velocity vector342Vector3f vel{343cosf(heading) * speed * 100.0f,344sinf(heading) * speed * 100.0f,3450.0f346};347348bool backing_up = false;349adjust_velocity(vel, backing_up, kP, accel * 100.0f, 0, 0, dt);350const Vector2f vel_xy{vel.x, vel.y};351352if (backing_up) {353// back up354if (fabsf(wrap_180(degrees(vel_xy.angle())) - degrees(heading)) > 90.0f) {355// Big difference between the direction of velocity vector and actual heading therefore we need to reverse the direction356speed = -vel_xy.length() * 0.01f;357} else {358speed = vel_xy.length() * 0.01f;359}360return;361}362363// No need to back up so adjust speed towards zero if needed364if (is_negative(speed)) {365speed = -vel_xy.length() * 0.01f;366} else {367speed = vel_xy.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 = 0.0f;374adjust_velocity_z(kP, accel_cmss, climb_rate_cms, backup_speed, dt);375if (!is_zero(backup_speed)) {376if (is_negative(backup_speed)) {377climb_rate_cms = MIN(climb_rate_cms, backup_speed);378} else {379climb_rate_cms = MAX(climb_rate_cms, backup_speed);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, 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_cmss_limited = MIN(accel_cmss, AC_AVOID_ACCEL_CMSS_MAX);402403bool limit_min_alt = false;404bool limit_max_alt = false;405float max_alt_diff = 0.0f; // distance from altitude limit to vehicle in metres (positive means vehicle is below limit)406float min_alt_diff = 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;413_ahrs.get_relative_position_D_home(veh_alt);414if ((fence->get_enabled_fences() & AC_FENCE_TYPE_ALT_MIN) > 0) {415// fence.get_safe_alt_max() is UP, veh_alt is DOWN:416min_alt_diff = -(fence->get_safe_alt_min() + veh_alt);417limit_min_alt = true;418}419if ((fence->get_enabled_fences() & AC_FENCE_TYPE_ALT_MAX) > 0) {420// fence.get_safe_alt_max() is UP, veh_alt is DOWN:421max_alt_diff = fence->get_safe_alt_max() + veh_alt;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;430float curr_alt;431if (_ahrs.get_hgt_ctrl_limit(alt_limit) &&432_ahrs.get_relative_position_D_origin_float(curr_alt)) {433// alt_limit is UP, curr_alt is DOWN:434const float ctrl_alt_diff = alt_limit + curr_alt;435if (!limit_max_alt || ctrl_alt_diff < max_alt_diff) {436max_alt_diff = ctrl_alt_diff;437limit_max_alt = true;438}439}440441#if HAL_PROXIMITY_ENABLED442// get distance from proximity sensor443float proximity_alt_diff;444AP_Proximity *proximity = AP::proximity();445if (proximity && proximity_avoidance_enabled() && proximity->get_upward_distance(proximity_alt_diff)) {446proximity_alt_diff -= _margin;447if (!limit_max_alt || proximity_alt_diff < max_alt_diff) {448max_alt_diff = proximity_alt_diff;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_z_max * 100.0;457// do not allow climbing if we've breached the safe altitude458if (max_alt_diff <= 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 = -1*(get_max_speed(kP, accel_cmss_limited, -max_alt_diff*100.0f, dt));463464// Constrain to max backup speed465backup_speed = MAX(backup_speed, -max_back_spd_cms);466}467return;468// do not allow descending if we've breached the safe altitude469} else if (min_alt_diff <= 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 = get_max_speed(kP, accel_cmss_limited, -min_alt_diff*100.0f, dt);474475// Constrain to max backup speed476backup_speed = MIN(backup_speed, max_back_spd_cms);477}478return;479}480481// limit climb rate482if (limit_max_alt) {483const float max_alt_max_speed = get_max_speed(kP, accel_cmss_limited, max_alt_diff*100.0f, dt);484climb_rate_cms = MIN(max_alt_max_speed, climb_rate_cms);485}486487if (limit_min_alt) {488const float max_alt_min_speed = get_max_speed(kP, accel_cmss_limited, min_alt_diff*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)499{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 = 0.0f; // maximum positive roll value511float roll_negative = 0.0f; // minimum negative roll value512float pitch_positive = 0.0f; // maximum positive pitch value513float pitch_negative = 0.0f; // minimum negative pitch value514515// get maximum positive and negative roll and pitch percentages from proximity sensor516get_proximity_roll_pitch_norm(roll_positive, roll_negative, pitch_positive, pitch_negative);517518// add maximum positive and negative percentages together for roll and pitch, convert to radians519Vector2f rp_out_rad((roll_positive + roll_negative) * radians(45.0), (pitch_positive + pitch_negative) * 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_cms in the direction of the unit vector547* limit_direction to be at most the maximum speed permitted by the limit_distance_cm.548*549* Uses velocity adjustment idea from Randy's second email on this thread:550* https://groups.google.com/forum/#!searchin/drones-discuss/obstacle/drones-discuss/QwUXz__WuqY/qo3G8iTLSJAJ551*/552void AC_Avoid::limit_velocity_2D(float kP, float accel_cmss, Vector2f &desired_vel_cms, const Vector2f& limit_direction, float limit_distance_cm, float dt)553{554const float max_speed = get_max_speed(kP, accel_cmss, limit_distance_cm, dt);555// project onto limit direction556const float speed = desired_vel_cms * limit_direction;557if (speed > max_speed) {558// subtract difference between desired speed and maximum acceptable speed559desired_vel_cms += limit_direction*(max_speed - speed);560}561}562563/*564* Note: This method is used to limit velocity horizontally and vertically given a 3D desired velocity vector565* Limits the component of desired_vel_cms in the direction of the obstacle_vector based on the passed value of "margin"566*/567void AC_Avoid::limit_velocity_3D(float kP, float accel_cmss, Vector3f &desired_vel_cms, const Vector3f& obstacle_vector, float margin_cm, float kP_z, float accel_cmss_z, float dt)568{569if (desired_vel_cms.is_zero()) {570// nothing to limit571return;572}573// create a margin_cm length vector in the direction of desired_vel_cms574// this will create larger margin towards the direction vehicle is travelling in575const Vector3f margin_vector = desired_vel_cms.normalized() * margin_cm;576const Vector2f limit_direction_xy{obstacle_vector.x, obstacle_vector.y};577578if (!limit_direction_xy.is_zero()) {579const float distance_from_fence_xy = MAX((limit_direction_xy.length() - Vector2f{margin_vector.x, margin_vector.y}.length()), 0.0f);580Vector2f velocity_xy{desired_vel_cms.x, desired_vel_cms.y};581limit_velocity_2D(kP, accel_cmss, velocity_xy, limit_direction_xy.normalized(), distance_from_fence_xy, dt);582desired_vel_cms.x = velocity_xy.x;583desired_vel_cms.y = velocity_xy.y;584}585586if (is_zero(desired_vel_cms.z) || is_zero(obstacle_vector.z)) {587// nothing to limit vertically if desired_vel_cms.z is zero588// if obstacle_vector.z is zero then the obstacle is probably horizontally located, and we can move vertically589return;590}591592if (is_positive(desired_vel_cms.z) != is_positive(obstacle_vector.z)) {593// why limit velocity vertically when we are going the opposite direction594return;595}596597// to check if Z velocity changes598const float velocity_z_original = desired_vel_cms.z;599const float z_speed = fabsf(desired_vel_cms.z);600601// obstacle_vector.z and margin_vector.z should be in same direction as checked above602const float dist_z = MAX(fabsf(obstacle_vector.z) - fabsf(margin_vector.z), 0.0f);603if (is_zero(dist_z)) {604// eliminate any vertical velocity605desired_vel_cms.z = 0.0f;606} else {607const float max_z_speed = get_max_speed(kP_z, accel_cmss_z, dist_z, dt);608desired_vel_cms.z = MIN(max_z_speed, z_speed);609}610611// make sure the direction of the Z velocity did not change612// we are only limiting speed here, not changing directions613// check if original z velocity is positive or negative614if (is_negative(velocity_z_original)) {615desired_vel_cms.z = desired_vel_cms.z * -1.0f;616}617}618619/*620* Compute the back away horizontal velocity required to avoid breaching margin621* INPUT: This method requires the breach in margin distance (back_distance_cm), direction towards the breach (limit_direction)622* It then calculates the desired backup velocity and passes it on to "find_max_quadrant_velocity" method to distribute the velocity vectors into respective quadrants623* 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 quadrant624*/625void 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)626{627if (limit_direction.is_zero()) {628// protect against divide by zero629return;630}631// speed required to move away the exact distance that we have breached the margin with632const float back_speed = get_max_speed(kP, 0.4f * accel_cmss, fabsf(back_distance_cm), dt);633634// direction to the obstacle635limit_direction.normalize();636637// move in the opposite direction with the required speed638Vector2f back_direction_vel = limit_direction * (-back_speed);639// divide the vector into quadrants, find maximum velocity component in each quadrant640find_max_quadrant_velocity(back_direction_vel, quad1_back_vel_cms, quad2_back_vel_cms, quad3_back_vel_cms, quad4_back_vel_cms);641}642643/*644* Compute the back away velocity required to avoid breaching margin, including vertical component645* min_z_vel is <= 0, and stores the greatest velocity in the downwards direction646* max_z_vel is >= 0, and stores the greatest velocity in the upwards direction647* eventually max_z_vel + min_z_vel will give the final desired Z backaway velocity648*/649void 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, float back_distance_cms, Vector3f limit_direction, float kp_z, float accel_cmss_z, float back_distance_z, float& min_z_vel, float& max_z_vel, float dt)650{651// backup horizontally652if (is_positive(back_distance_cms)) {653Vector2f limit_direction_2d{limit_direction.x, limit_direction.y};654calc_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_2d, dt);655}656657// backup vertically658if (!is_zero(back_distance_z)) {659float back_speed_z = get_max_speed(kp_z, 0.4f * accel_cmss_z, fabsf(back_distance_z), dt);660// Down is positive661if (is_positive(back_distance_z)) {662back_speed_z *= -1.0f;663}664665// store the z backup speed into min or max z if possible666if (back_speed_z < min_z_vel) {667min_z_vel = back_speed_z;668}669if (back_speed_z > max_z_vel) {670max_z_vel = back_speed_z;671}672}673}674675/*676* Calculate maximum velocity vector that can be formed in each quadrant677* This method takes the desired backup velocity, and four other velocities corresponding to each quadrant678* The desired velocity is then fit into one of the 4 quadrant velocities as per the sign of its components679* This ensures that if we have multiple backup velocities, we can get the maximum of all of those velocities in each quadrant680*/681void AC_Avoid::find_max_quadrant_velocity(Vector2f &desired_vel, Vector2f &quad1_vel, Vector2f &quad2_vel, Vector2f &quad3_vel, Vector2f &quad4_vel)682{683if (desired_vel.is_zero()) {684return;685}686// first quadrant: +ve x, +ve y direction687if (is_positive(desired_vel.x) && is_positive(desired_vel.y)) {688quad1_vel = Vector2f{MAX(quad1_vel.x, desired_vel.x), MAX(quad1_vel.y,desired_vel.y)};689}690// second quadrant: -ve x, +ve y direction691if (is_negative(desired_vel.x) && is_positive(desired_vel.y)) {692quad2_vel = Vector2f{MIN(quad2_vel.x, desired_vel.x), MAX(quad2_vel.y,desired_vel.y)};693}694// third quadrant: -ve x, -ve y direction695if (is_negative(desired_vel.x) && is_negative(desired_vel.y)) {696quad3_vel = Vector2f{MIN(quad3_vel.x, desired_vel.x), MIN(quad3_vel.y,desired_vel.y)};697}698// fourth quadrant: +ve x, -ve y direction699if (is_positive(desired_vel.x) && is_negative(desired_vel.y)) {700quad4_vel = Vector2f{MAX(quad4_vel.x, desired_vel.x), MIN(quad4_vel.y,desired_vel.y)};701}702}703704/*705Calculate maximum velocity vector that can be formed in each quadrant and separately store max & min of vertical components706*/707void 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)708{709// split into horizontal and vertical components710Vector2f velocity_xy{desired_vel.x, desired_vel.y};711find_max_quadrant_velocity(velocity_xy, quad1_vel, quad2_vel, quad3_vel, quad4_vel);712713// store maximum and minimum of z714if (is_positive(desired_vel.z) && (desired_vel.z > max_z_vel)) {715max_z_vel = desired_vel.z;716}717if (is_negative(desired_vel.z) && (desired_vel.z < min_z_vel)) {718min_z_vel = desired_vel.z;719}720}721722/*723* Computes the speed such that the stopping distance724* of the vehicle will be exactly the input distance.725*/726float AC_Avoid::get_max_speed(float kP, float accel_cmss, float distance_cm, float dt) const727{728if (is_zero(kP)) {729return safe_sqrt(2.0f * distance_cm * accel_cmss);730} else {731return sqrt_controller(distance_cm, kP, accel_cmss, dt);732}733}734735#if AP_FENCE_ENABLED736737/*738* Adjusts the desired velocity for the circular fence.739*/740void AC_Avoid::adjust_velocity_circle_fence(float kP, float accel_cmss, Vector2f &desired_vel_cms, Vector2f &backup_vel, float dt)741{742AC_Fence *fence = AP::fence();743if (fence == nullptr) {744return;745}746747AC_Fence &_fence = *fence;748749// exit if circular fence is not enabled750if ((_fence.get_enabled_fences() & AC_FENCE_TYPE_CIRCLE) == 0) {751return;752}753754// exit if the circular fence has already been breached755if ((_fence.get_breaches() & AC_FENCE_TYPE_CIRCLE) != 0) {756return;757}758759// get desired speed760const float desired_speed = desired_vel_cms.length();761if (is_zero(desired_speed)) {762// no avoidance necessary when desired speed is zero763return;764}765766const AP_AHRS &_ahrs = AP::ahrs();767768// get position as a 2D offset from ahrs home769Vector2f position_xy;770if (!_ahrs.get_relative_position_NE_home(position_xy)) {771// we have no idea where we are....772return;773}774position_xy *= 100.0f; // m -> cm775776// get the fence radius in cm777const float fence_radius = _fence.get_radius() * 100.0f;778// get the margin to the fence in cm779const float margin_cm = _fence.get_margin() * 100.0f;780781if (margin_cm > fence_radius) {782return;783}784785// get vehicle distance from home786const float dist_from_home = position_xy.length();787if (dist_from_home > fence_radius) {788// outside of circular fence, no velocity adjustments789return;790}791const float distance_to_boundary = fence_radius - dist_from_home;792793// for backing away794Vector2f quad_1_back_vel, quad_2_back_vel, quad_3_back_vel, quad_4_back_vel;795796// back away if vehicle has breached margin797if (is_negative(distance_to_boundary - margin_cm)) {798calc_backup_velocity_2D(kP, accel_cmss, quad_1_back_vel, quad_2_back_vel, quad_3_back_vel, quad_4_back_vel, margin_cm - distance_to_boundary, position_xy, dt);799}800// desired backup velocity is sum of maximum velocity component in each quadrant801backup_vel = quad_1_back_vel + quad_2_back_vel + quad_3_back_vel + quad_4_back_vel;802803// vehicle is inside the circular fence804switch (_behavior) {805case BEHAVIOR_SLIDE: {806// implement sliding behaviour807const Vector2f stopping_point = position_xy + desired_vel_cms*(get_stopping_distance(kP, accel_cmss, desired_speed)/desired_speed);808const float stopping_point_dist_from_home = stopping_point.length();809if (stopping_point_dist_from_home <= fence_radius - margin_cm) {810// stopping before before fence so no need to adjust811return;812}813// unsafe desired velocity - will not be able to stop before reaching margin from fence814// Project stopping point radially onto fence boundary815// Adjusted velocity will point towards this projected point at a safe speed816const Vector2f target_offset = stopping_point * ((fence_radius - margin_cm) / stopping_point_dist_from_home);817const Vector2f target_direction = target_offset - position_xy;818const float distance_to_target = target_direction.length();819if (is_positive(distance_to_target)) {820const float max_speed = get_max_speed(kP, accel_cmss, distance_to_target, dt);821desired_vel_cms = target_direction * (MIN(desired_speed,max_speed) / distance_to_target);822}823break;824}825826case (BEHAVIOR_STOP): {827// implement stopping behaviour828// calculate stopping point plus a margin so we look forward far enough to intersect with circular fence829const Vector2f stopping_point_plus_margin = position_xy + desired_vel_cms*((2.0f + margin_cm + get_stopping_distance(kP, accel_cmss, desired_speed))/desired_speed);830const float stopping_point_plus_margin_dist_from_home = stopping_point_plus_margin.length();831if (dist_from_home >= fence_radius - margin_cm) {832// vehicle has already breached margin around fence833// if stopping point is even further from home (i.e. in wrong direction) then adjust speed to zero834// otherwise user is backing away from fence so do not apply limits835if (stopping_point_plus_margin_dist_from_home >= dist_from_home) {836desired_vel_cms.zero();837}838} else {839// shorten vector without adjusting its direction840Vector2f intersection;841if (Vector2f::circle_segment_intersection(position_xy, stopping_point_plus_margin, Vector2f(0.0f,0.0f), fence_radius - margin_cm, intersection)) {842const float distance_to_target = (intersection - position_xy).length();843const float max_speed = get_max_speed(kP, accel_cmss, distance_to_target, dt);844if (max_speed < desired_speed) {845desired_vel_cms *= MAX(max_speed, 0.0f) / desired_speed;846}847}848}849break;850}851}852}853854/*855* Adjusts the desired velocity for the exclusion polygons856*/857void AC_Avoid::adjust_velocity_inclusion_and_exclusion_polygons(float kP, float accel_cmss, Vector2f &desired_vel_cms, Vector2f &backup_vel, float dt)858{859const AC_Fence *fence = AP::fence();860if (fence == nullptr) {861return;862}863864// exit if polygon fences are not enabled865if ((fence->get_enabled_fences() & AC_FENCE_TYPE_POLYGON) == 0) {866return;867}868869// for backing away870Vector2f quad_1_back_vel, quad_2_back_vel, quad_3_back_vel, quad_4_back_vel;871872// iterate through inclusion polygons873const uint8_t num_inclusion_polygons = fence->polyfence().get_inclusion_polygon_count();874for (uint8_t i = 0; i < num_inclusion_polygons; i++) {875uint16_t num_points;876const Vector2f* boundary = fence->polyfence().get_inclusion_polygon(i, num_points);877Vector2f backup_vel_inc;878// adjust velocity879adjust_velocity_polygon(kP, accel_cmss, desired_vel_cms, backup_vel_inc, boundary, num_points, fence->get_margin(), dt, true);880find_max_quadrant_velocity(backup_vel_inc, quad_1_back_vel, quad_2_back_vel, quad_3_back_vel, quad_4_back_vel);881}882883// iterate through exclusion polygons884const uint8_t num_exclusion_polygons = fence->polyfence().get_exclusion_polygon_count();885for (uint8_t i = 0; i < num_exclusion_polygons; i++) {886uint16_t num_points;887const Vector2f* boundary = fence->polyfence().get_exclusion_polygon(i, num_points);888Vector2f backup_vel_exc;889// adjust velocity890adjust_velocity_polygon(kP, accel_cmss, desired_vel_cms, backup_vel_exc, boundary, num_points, fence->get_margin(), dt, false);891find_max_quadrant_velocity(backup_vel_exc, quad_1_back_vel, quad_2_back_vel, quad_3_back_vel, quad_4_back_vel);892}893// desired backup velocity is sum of maximum velocity component in each quadrant894backup_vel = quad_1_back_vel + quad_2_back_vel + quad_3_back_vel + quad_4_back_vel;895}896897/*898* Adjusts the desired velocity for the inclusion circles899*/900void AC_Avoid::adjust_velocity_inclusion_circles(float kP, float accel_cmss, Vector2f &desired_vel_cms, Vector2f &backup_vel, float dt)901{902const AC_Fence *fence = AP::fence();903if (fence == nullptr) {904return;905}906907// return immediately if no inclusion circles908const uint8_t num_circles = fence->polyfence().get_inclusion_circle_count();909if (num_circles == 0) {910return;911}912913// exit if polygon fences are not enabled914if ((fence->get_enabled_fences() & AC_FENCE_TYPE_POLYGON) == 0) {915return;916}917918// get vehicle position919Vector2f position_NE;920if (!AP::ahrs().get_relative_position_NE_origin_float(position_NE)) {921// do not limit velocity if we don't have a position estimate922return;923}924position_NE = position_NE * 100.0f; // m to cm925926// get the margin to the fence in cm927const float margin_cm = fence->get_margin() * 100.0f;928929// get desired speed930const float desired_speed = desired_vel_cms.length();931932// get stopping distance as an offset from the vehicle933Vector2f stopping_offset;934if (!is_zero(desired_speed)) {935switch (_behavior) {936case BEHAVIOR_SLIDE:937stopping_offset = desired_vel_cms*(get_stopping_distance(kP, accel_cmss, desired_speed)/desired_speed);938break;939case BEHAVIOR_STOP:940// calculate stopping point plus a margin so we look forward far enough to intersect with circular fence941stopping_offset = desired_vel_cms*((2.0f + margin_cm + get_stopping_distance(kP, accel_cmss, desired_speed))/desired_speed);942break;943}944}945946// for backing away947Vector2f quad_1_back_vel, quad_2_back_vel, quad_3_back_vel, quad_4_back_vel;948949// iterate through inclusion circles950for (uint8_t i = 0; i < num_circles; i++) {951Vector2f center_pos_cm;952float radius;953if (fence->polyfence().get_inclusion_circle(i, center_pos_cm, radius)) {954// get position relative to circle's center955const Vector2f position_NE_rel = (position_NE - center_pos_cm);956957// if we are outside this circle do not limit velocity for this circle958const float dist_sq_cm = position_NE_rel.length_squared();959const float radius_cm = (radius * 100.0f);960if (dist_sq_cm > sq(radius_cm)) {961continue;962}963964const float radius_with_margin = radius_cm - margin_cm;965if (is_negative(radius_with_margin)) {966return;967}968969const float margin_breach = radius_with_margin - safe_sqrt(dist_sq_cm);970// back away if vehicle has breached margin971if (is_negative(margin_breach)) {972calc_backup_velocity_2D(kP, accel_cmss, quad_1_back_vel, quad_2_back_vel, quad_3_back_vel, quad_4_back_vel, margin_breach, position_NE_rel, dt);973}974if (is_zero(desired_speed)) {975// no avoidance necessary when desired speed is zero976continue;977}978979switch (_behavior) {980case BEHAVIOR_SLIDE: {981// implement sliding behaviour982const Vector2f stopping_point = position_NE_rel + stopping_offset;983const float stopping_point_dist = stopping_point.length();984if (is_zero(stopping_point_dist) || (stopping_point_dist <= (radius_cm - margin_cm))) {985// stopping before before fence so no need to adjust for this circle986continue;987}988// unsafe desired velocity - will not be able to stop before reaching margin from fence989// project stopping point radially onto fence boundary990// adjusted velocity will point towards this projected point at a safe speed991const Vector2f target_offset = stopping_point * ((radius_cm - margin_cm) / stopping_point_dist);992const Vector2f target_direction = target_offset - position_NE_rel;993const float distance_to_target = target_direction.length();994if (is_positive(distance_to_target)) {995const float max_speed = get_max_speed(kP, accel_cmss, distance_to_target, dt);996desired_vel_cms = target_direction * (MIN(desired_speed,max_speed) / distance_to_target);997}998}999break;1000case BEHAVIOR_STOP: {1001// implement stopping behaviour1002const Vector2f stopping_point_plus_margin = position_NE_rel + stopping_offset;1003const float dist_cm = safe_sqrt(dist_sq_cm);1004if (dist_cm >= radius_cm - margin_cm) {1005// vehicle has already breached margin around fence1006// if stopping point is even further from center (i.e. in wrong direction) then adjust speed to zero1007// otherwise user is backing away from fence so do not apply limits1008if (stopping_point_plus_margin.length() >= dist_cm) {1009desired_vel_cms.zero();1010// desired backup velocity is sum of maximum velocity component in each quadrant1011backup_vel = quad_1_back_vel + quad_2_back_vel + quad_3_back_vel + quad_4_back_vel;1012return;1013}1014} else {1015// shorten vector without adjusting its direction1016Vector2f intersection;1017if (Vector2f::circle_segment_intersection(position_NE_rel, stopping_point_plus_margin, Vector2f(0.0f,0.0f), radius_cm - margin_cm, intersection)) {1018const float distance_to_target = (intersection - position_NE_rel).length();1019const float max_speed = get_max_speed(kP, accel_cmss, distance_to_target, dt);1020if (max_speed < desired_speed) {1021desired_vel_cms *= MAX(max_speed, 0.0f) / desired_speed;1022}1023}1024}1025}1026break;1027}1028}1029}1030// desired backup velocity is sum of maximum velocity component in each quadrant1031backup_vel = quad_1_back_vel + quad_2_back_vel + quad_3_back_vel + quad_4_back_vel;1032}10331034/*1035* Adjusts the desired velocity for the exclusion circles1036*/1037void AC_Avoid::adjust_velocity_exclusion_circles(float kP, float accel_cmss, Vector2f &desired_vel_cms, Vector2f &backup_vel, float dt)1038{1039const AC_Fence *fence = AP::fence();1040if (fence == nullptr) {1041return;1042}10431044// return immediately if no inclusion circles1045const uint8_t num_circles = fence->polyfence().get_exclusion_circle_count();1046if (num_circles == 0) {1047return;1048}10491050// exit if polygon fences are not enabled1051if ((fence->get_enabled_fences() & AC_FENCE_TYPE_POLYGON) == 0) {1052return;1053}10541055// get vehicle position1056Vector2f position_NE;1057if (!AP::ahrs().get_relative_position_NE_origin_float(position_NE)) {1058// do not limit velocity if we don't have a position estimate1059return;1060}1061position_NE = position_NE * 100.0f; // m to cm10621063// get the margin to the fence in cm1064const float margin_cm = fence->get_margin() * 100.0f;10651066// for backing away1067Vector2f quad_1_back_vel, quad_2_back_vel, quad_3_back_vel, quad_4_back_vel;10681069// get desired speed1070const float desired_speed = desired_vel_cms.length();10711072// calculate stopping distance as an offset from the vehicle (only used for BEHAVIOR_STOP)1073// add a margin so we look forward far enough to intersect with circular fence1074Vector2f stopping_offset;1075if (!is_zero(desired_speed)) {1076if ((AC_Avoid::BehaviourType)_behavior.get() == BEHAVIOR_STOP) {1077stopping_offset = desired_vel_cms*((2.0f + margin_cm + get_stopping_distance(kP, accel_cmss, desired_speed))/desired_speed);1078}1079}1080// iterate through exclusion circles1081for (uint8_t i = 0; i < num_circles; i++) {1082Vector2f center_pos_cm;1083float radius;1084if (fence->polyfence().get_exclusion_circle(i, center_pos_cm, radius)) {1085// get position relative to circle's center1086const Vector2f position_NE_rel = (position_NE - center_pos_cm);10871088// if we are inside this circle do not limit velocity for this circle1089const float dist_sq_cm = position_NE_rel.length_squared();1090const float radius_cm = (radius * 100.0f);1091if (radius_cm < margin_cm) {1092return;1093}1094if (dist_sq_cm < sq(radius_cm)) {1095continue;1096}10971098const Vector2f vector_to_center = center_pos_cm - position_NE;1099const float dist_to_boundary = vector_to_center.length() - radius_cm;1100// back away if vehicle has breached margin1101if (is_negative(dist_to_boundary - margin_cm)) {1102calc_backup_velocity_2D(kP, accel_cmss, quad_1_back_vel, quad_2_back_vel, quad_3_back_vel, quad_4_back_vel, margin_cm - dist_to_boundary, vector_to_center, dt);1103}1104if (is_zero(desired_speed)) {1105// no avoidance necessary when desired speed is zero1106continue;1107}11081109switch (_behavior) {1110case BEHAVIOR_SLIDE: {1111// vector from current position to circle's center1112Vector2f limit_direction = vector_to_center;1113if (limit_direction.is_zero()) {1114// vehicle is exactly on circle center so do not limit velocity1115continue;1116}1117// calculate distance to edge of circle1118const float limit_distance_cm = limit_direction.length() - radius_cm;1119if (!is_positive(limit_distance_cm)) {1120// vehicle is within circle so do not limit velocity1121continue;1122}1123// vehicle is outside the circle, adjust velocity to stay outside1124limit_direction.normalize();1125limit_velocity_2D(kP, accel_cmss, desired_vel_cms, limit_direction, MAX(limit_distance_cm - margin_cm, 0.0f), dt);1126}1127break;1128case BEHAVIOR_STOP: {1129// implement stopping behaviour1130const Vector2f stopping_point_plus_margin = position_NE_rel + stopping_offset;1131const float dist_cm = safe_sqrt(dist_sq_cm);1132if (dist_cm < radius_cm + margin_cm) {1133// vehicle has already breached margin around fence1134// if stopping point is closer to center (i.e. in wrong direction) then adjust speed to zero1135// otherwise user is backing away from fence so do not apply limits1136if (stopping_point_plus_margin.length() <= dist_cm) {1137desired_vel_cms.zero();1138backup_vel = quad_1_back_vel + quad_2_back_vel + quad_3_back_vel + quad_4_back_vel;1139return;1140}1141} else {1142// shorten vector without adjusting its direction1143Vector2f intersection;1144if (Vector2f::circle_segment_intersection(position_NE_rel, stopping_point_plus_margin, Vector2f(0.0f,0.0f), radius_cm + margin_cm, intersection)) {1145const float distance_to_target = (intersection - position_NE_rel).length();1146const float max_speed = get_max_speed(kP, accel_cmss, distance_to_target, dt);1147if (max_speed < desired_speed) {1148desired_vel_cms *= MAX(max_speed, 0.0f) / desired_speed;1149}1150}1151}1152}1153break;1154}1155}1156}1157// desired backup velocity is sum of maximum velocity component in each quadrant1158backup_vel = quad_1_back_vel + quad_2_back_vel + quad_3_back_vel + quad_4_back_vel;1159}1160#endif // AP_FENCE_ENABLED11611162#if AP_BEACON_ENABLED1163/*1164* Adjusts the desired velocity for the beacon fence.1165*/1166void AC_Avoid::adjust_velocity_beacon_fence(float kP, float accel_cmss, Vector2f &desired_vel_cms, Vector2f &backup_vel, float dt)1167{1168AP_Beacon *_beacon = AP::beacon();11691170// exit if the beacon is not present1171if (_beacon == nullptr) {1172return;1173}11741175// get boundary from beacons1176uint16_t num_points = 0;1177const Vector2f* boundary = _beacon->get_boundary_points(num_points);1178if ((boundary == nullptr) || (num_points == 0)) {1179return;1180}11811182// adjust velocity using beacon1183float margin = 0;1184#if AP_FENCE_ENABLED1185if (AP::fence()) {1186margin = AP::fence()->get_margin();1187}1188#endif1189adjust_velocity_polygon(kP, accel_cmss, desired_vel_cms, backup_vel, boundary, num_points, margin, dt, true);1190}1191#endif // AP_BEACON_ENABLED11921193/*1194* Adjusts the desired velocity based on output from the proximity sensor1195*/1196void AC_Avoid::adjust_velocity_proximity(float kP, float accel_cmss, Vector3f &desired_vel_cms, Vector3f &backup_vel, float kP_z, float accel_cmss_z, float dt)1197{1198#if HAL_PROXIMITY_ENABLED1199// exit immediately if proximity sensor is not present1200AP_Proximity *proximity = AP::proximity();1201if (!proximity) {1202return;1203}12041205AP_Proximity &_proximity = *proximity;1206// get total number of obstacles1207const uint8_t obstacle_num = _proximity.get_obstacle_count();1208if (obstacle_num == 0) {1209// no obstacles1210return;1211}12121213const AP_AHRS &_ahrs = AP::ahrs();12141215// for backing away1216Vector2f quad_1_back_vel, quad_2_back_vel, quad_3_back_vel, quad_4_back_vel;1217float max_back_vel_z = 0.0f;1218float min_back_vel_z = 0.0f;12191220// rotate velocity vector from earth frame to body-frame since obstacles are in body-frame1221const Vector2f desired_vel_body_cms = _ahrs.earth_to_body2D(Vector2f{desired_vel_cms.x, desired_vel_cms.y});12221223// safe_vel will be adjusted to stay away from Proximity Obstacles1224Vector3f safe_vel = Vector3f{desired_vel_body_cms.x, desired_vel_body_cms.y, desired_vel_cms.z};1225const Vector3f safe_vel_orig = safe_vel;12261227// calc margin in cm1228const float margin_cm = MAX(_margin * 100.0f, 0.0f);1229Vector3f stopping_point_plus_margin;1230if (!desired_vel_cms.is_zero()) {1231// only used for "stop mode". Pre-calculating the stopping point here makes sure we do not need to repeat the calculations under iterations.1232const float speed = safe_vel.length();1233stopping_point_plus_margin = safe_vel * ((2.0f + margin_cm + get_stopping_distance(kP, accel_cmss, speed))/speed);1234}12351236for (uint8_t i = 0; i<obstacle_num; i++) {1237// get obstacle from proximity library1238Vector3f vector_to_obstacle;1239if (!_proximity.get_obstacle(i, vector_to_obstacle)) {1240// this one is not valid1241continue;1242}12431244const float dist_to_boundary = vector_to_obstacle.length();1245if (is_zero(dist_to_boundary)) {1246continue;1247}12481249// back away if vehicle has breached margin1250if (is_negative(dist_to_boundary - margin_cm)) {1251const float breach_dist = margin_cm - dist_to_boundary;1252// add a deadzone so that the vehicle doesn't backup and go forward again and again1253const float deadzone = MAX(0.0f, _backup_deadzone) * 100.0f;1254if (breach_dist > deadzone) {1255// this vector will help us decide how much we have to back away horizontally and vertically1256const Vector3f margin_vector = vector_to_obstacle.normalized() * breach_dist;1257const float xy_back_dist = margin_vector.xy().length();1258const float z_back_dist = margin_vector.z;1259calc_backup_velocity_3D(kP, accel_cmss, quad_1_back_vel, quad_2_back_vel, quad_3_back_vel, quad_4_back_vel, xy_back_dist, vector_to_obstacle, kP_z, accel_cmss_z, z_back_dist, min_back_vel_z, max_back_vel_z, dt);1260}1261}12621263if (desired_vel_cms.is_zero()) {1264// cannot limit velocity if there is nothing to limit1265// backing up (if needed) has already been done1266continue;1267}12681269switch (_behavior) {1270case BEHAVIOR_SLIDE: {1271Vector3f limit_direction{vector_to_obstacle};1272// distance to closest point1273const float limit_distance_cm = limit_direction.length();1274if (is_zero(limit_distance_cm)) {1275// We are exactly on the edge, this should ideally never be possible1276// i.e. do not adjust velocity.1277continue;1278}1279// Adjust velocity to not violate margin.1280limit_velocity_3D(kP, accel_cmss, safe_vel, limit_direction, margin_cm, kP_z, accel_cmss_z, dt);12811282break;1283}12841285case BEHAVIOR_STOP: {1286// vector from current position to obstacle1287Vector3f limit_direction;1288// find closest point with line segment1289// also see if the vehicle will "roughly" intersect the boundary with the projected stopping point1290const bool intersect = _proximity.closest_point_from_segment_to_obstacle(i, Vector3f{}, stopping_point_plus_margin, limit_direction);1291if (intersect) {1292// the vehicle is intersecting the plane formed by the boundary1293// distance to the closest point from the stopping point1294float limit_distance_cm = limit_direction.length();1295if (is_zero(limit_distance_cm)) {1296// We are exactly on the edge, this should ideally never be possible1297// i.e. do not adjust velocity.1298return;1299}1300if (limit_distance_cm <= margin_cm) {1301// we are within the margin so stop vehicle1302safe_vel.zero();1303} else {1304// vehicle inside the given edge, adjust velocity to not violate this edge1305limit_velocity_3D(kP, accel_cmss, safe_vel, limit_direction, margin_cm, kP_z, accel_cmss_z, dt);1306}13071308break;1309}1310}1311}1312}13131314// desired backup velocity is sum of maximum velocity component in each quadrant1315const Vector2f desired_back_vel_cms_xy = quad_1_back_vel + quad_2_back_vel + quad_3_back_vel + quad_4_back_vel;1316const float desired_back_vel_cms_z = max_back_vel_z + min_back_vel_z;13171318if (safe_vel == safe_vel_orig && desired_back_vel_cms_xy.is_zero() && is_zero(desired_back_vel_cms_z)) {1319// proximity avoidance did nothing, no point in doing the calculations below. Return early1320backup_vel.zero();1321return;1322}13231324// set modified desired velocity vector and back away velocity vector1325// vectors were in body-frame, rotate resulting vector back to earth-frame1326const Vector2f safe_vel_2d = _ahrs.body_to_earth2D(Vector2f{safe_vel.x, safe_vel.y});1327desired_vel_cms = Vector3f{safe_vel_2d.x, safe_vel_2d.y, safe_vel.z};1328const Vector2f backup_vel_xy = _ahrs.body_to_earth2D(desired_back_vel_cms_xy);1329backup_vel = Vector3f{backup_vel_xy.x, backup_vel_xy.y, desired_back_vel_cms_z};1330#endif // HAL_PROXIMITY_ENABLED1331}13321333/*1334* Adjusts the desired velocity for the polygon fence.1335*/1336void AC_Avoid::adjust_velocity_polygon(float kP, float accel_cmss, Vector2f &desired_vel_cms, Vector2f &backup_vel, const Vector2f* boundary, uint16_t num_points, float margin, float dt, bool stay_inside)1337{1338// exit if there are no points1339if (boundary == nullptr || num_points == 0) {1340return;1341}13421343const AP_AHRS &_ahrs = AP::ahrs();13441345// do not adjust velocity if vehicle is outside the polygon fence1346Vector2f position_xy;1347if (!_ahrs.get_relative_position_NE_origin_float(position_xy)) {1348// boundary is in earth frame but we have no idea1349// where we are1350return;1351}1352position_xy = position_xy * 100.0f; // m to cm135313541355// return if we have already breached polygon1356const bool inside_polygon = !Polygon_outside(position_xy, boundary, num_points);1357if (inside_polygon != stay_inside) {1358return;1359}13601361// Safe_vel will be adjusted to remain within fence.1362// We need a separate vector in case adjustment fails,1363// e.g. if we are exactly on the boundary.1364Vector2f safe_vel(desired_vel_cms);1365Vector2f desired_back_vel_cms;13661367// calc margin in cm1368const float margin_cm = MAX(margin * 100.0f, 0.0f);13691370// for stopping1371const float speed = safe_vel.length();1372Vector2f stopping_point_plus_margin;1373if (!desired_vel_cms.is_zero()) {1374stopping_point_plus_margin = position_xy + safe_vel*((2.0f + margin_cm + get_stopping_distance(kP, accel_cmss, speed))/speed);1375}13761377// for backing away1378Vector2f quad_1_back_vel, quad_2_back_vel, quad_3_back_vel, quad_4_back_vel;13791380for (uint16_t i=0; i<num_points; i++) {1381uint16_t j = i+1;1382if (j >= num_points) {1383j = 0;1384}1385// end points of current edge1386Vector2f start = boundary[j];1387Vector2f end = boundary[i];1388Vector2f vector_to_boundary = Vector2f::closest_point(position_xy, start, end) - position_xy;1389// back away if vehicle has breached margin1390if (is_negative(vector_to_boundary.length() - margin_cm)) {1391calc_backup_velocity_2D(kP, accel_cmss, quad_1_back_vel, quad_2_back_vel, quad_3_back_vel, quad_4_back_vel, margin_cm-vector_to_boundary.length(), vector_to_boundary, dt);1392}13931394// exit immediately if no desired velocity1395if (desired_vel_cms.is_zero()) {1396continue;1397}13981399switch (_behavior) {1400case (BEHAVIOR_SLIDE): {1401// vector from current position to closest point on current edge1402Vector2f limit_direction = vector_to_boundary;1403// distance to closest point1404const float limit_distance_cm = limit_direction.length();1405if (is_zero(limit_distance_cm)) {1406// We are exactly on the edge - treat this as a fence breach.1407// i.e. do not adjust velocity.1408return;1409}1410// We are strictly inside the given edge.1411// Adjust velocity to not violate this edge.1412limit_direction /= limit_distance_cm;1413limit_velocity_2D(kP, accel_cmss, safe_vel, limit_direction, MAX(limit_distance_cm - margin_cm, 0.0f), dt);1414break;1415}14161417case (BEHAVIOR_STOP): {1418// find intersection with line segment1419Vector2f intersection;1420if (Vector2f::segment_intersection(position_xy, stopping_point_plus_margin, start, end, intersection)) {1421// vector from current position to point on current edge1422Vector2f limit_direction = intersection - position_xy;1423const float limit_distance_cm = limit_direction.length();1424if (is_zero(limit_distance_cm)) {1425// We are exactly on the edge - treat this as a fence breach.1426// i.e. do not adjust velocity.1427return;1428}1429if (limit_distance_cm <= margin_cm) {1430// we are within the margin so stop vehicle1431safe_vel.zero();1432} else {1433// vehicle inside the given edge, adjust velocity to not violate this edge1434limit_direction /= limit_distance_cm;1435limit_velocity_2D(kP, accel_cmss, safe_vel, limit_direction, MAX(limit_distance_cm - margin_cm, 0.0f), dt);1436}1437}1438break;1439}1440}1441}1442// desired backup velocity is sum of maximum velocity component in each quadrant1443desired_back_vel_cms = quad_1_back_vel + quad_2_back_vel + quad_3_back_vel + quad_4_back_vel;14441445// set modified desired velocity vector or back away velocity vector1446desired_vel_cms = safe_vel;1447backup_vel = desired_back_vel_cms;1448}14491450/*1451* Computes distance required to stop, given current speed.1452*1453* Implementation copied from AC_PosControl.1454*/1455float AC_Avoid::get_stopping_distance(float kP, float accel_cmss, float speed_cms) const1456{1457// avoid divide by zero by using current position if the velocity is below 10cm/s, kP is very low or acceleration is zero1458if (accel_cmss <= 0.0f || is_zero(speed_cms)) {1459return 0.0f;1460}14611462// handle linear deceleration1463if (kP <= 0.0f) {1464return 0.5f * sq(speed_cms) / accel_cmss;1465}14661467// calculate distance within which we can stop1468// accel_cmss/kP is the point at which velocity switches from linear to sqrt1469if (speed_cms < accel_cmss/kP) {1470return speed_cms/kP;1471} else {1472// accel_cmss/(2.0f*kP*kP) is the distance at which we switch from linear to sqrt response1473return accel_cmss/(2.0f*kP*kP) + (speed_cms*speed_cms)/(2.0f*accel_cmss);1474}1475}14761477// convert distance (in meters) to a lean percentage (in 0~1 range) for use in manual flight modes1478float AC_Avoid::distance_to_lean_norm(float dist_m)1479{1480// ignore objects beyond DIST_MAX1481if (dist_m < 0.0f || dist_m >= _dist_max || _dist_max <= 0.0f) {1482return 0.0f;1483}1484// inverted but linear response1485return 1.0f - (dist_m / _dist_max);1486}14871488// returns the maximum positive and negative roll and pitch percentages (in -1 ~ +1 range) based on the proximity sensor1489void AC_Avoid::get_proximity_roll_pitch_norm(float &roll_positive, float &roll_negative, float &pitch_positive, float &pitch_negative)1490{1491#if HAL_PROXIMITY_ENABLED1492AP_Proximity *proximity = AP::proximity();1493if (proximity == nullptr) {1494return;1495}1496AP_Proximity &_proximity = *proximity;1497const uint8_t obj_count = _proximity.get_object_count();1498// if no objects return1499if (obj_count == 0) {1500return;1501}15021503// calculate maximum roll, pitch values from objects1504for (uint8_t i=0; i<obj_count; i++) {1505float ang_deg, dist_m;1506if (_proximity.get_object_angle_and_distance(i, ang_deg, dist_m)) {1507if (dist_m < _dist_max) {1508// convert distance to lean angle (in 0 to 1 range)1509const float lean_pct = distance_to_lean_norm(dist_m);1510// convert angle to roll and pitch lean percentages1511const float angle_rad = radians(ang_deg);1512const float roll_pct = -sinf(angle_rad) * lean_pct;1513const float pitch_pct = cosf(angle_rad) * lean_pct;1514// update roll, pitch maximums1515if (roll_pct > 0.0f) {1516roll_positive = MAX(roll_positive, roll_pct);1517} else if (roll_pct < 0.0f) {1518roll_negative = MIN(roll_negative, roll_pct);1519}1520if (pitch_pct > 0.0f) {1521pitch_positive = MAX(pitch_positive, pitch_pct);1522} else if (pitch_pct < 0.0f) {1523pitch_negative = MIN(pitch_negative, pitch_pct);1524}1525}1526}1527}1528#endif // HAL_PROXIMITY_ENABLED1529}15301531// singleton instance1532AC_Avoid *AC_Avoid::_singleton;15331534namespace AP {15351536AC_Avoid *ac_avoid()1537{1538return AC_Avoid::get_singleton();1539}15401541}15421543#endif // !APM_BUILD_Arduplane15441545#endif // AP_AVOIDANCE_ENABLED154615471548