Path: blob/master/libraries/AC_Avoidance/AP_OABendyRuler.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_OAPATHPLANNER_BENDYRULER_ENABLED1819#include "AP_OABendyRuler.h"20#include <AC_Avoidance/AP_OADatabase.h>21#include <AC_Fence/AC_Fence.h>22#include <AP_AHRS/AP_AHRS.h>23#include <AP_Logger/AP_Logger.h>24#include <AP_Vehicle/AP_Vehicle_Type.h>2526// parameter defaults27const float OA_BENDYRULER_LOOKAHEAD_DEFAULT = 15.0f;28const float OA_BENDYRULER_RATIO_DEFAULT = 1.5f;29const int16_t OA_BENDYRULER_ANGLE_DEFAULT = 75;30const int16_t OA_BENDYRULER_TYPE_DEFAULT = 1;3132const int16_t OA_BENDYRULER_BEARING_INC_XY = 5; // check every 5 degrees around vehicle33const int16_t OA_BENDYRULER_BEARING_INC_VERTICAL = 90;34const float OA_BENDYRULER_LOOKAHEAD_STEP2_RATIO = 1.0f; // step2's lookahead length as a ratio of step1's lookahead length35const float OA_BENDYRULER_LOOKAHEAD_STEP2_MIN = 2.0f; // step2 checks at least this many meters past step1's location36const float OA_BENDYRULER_LOOKAHEAD_PAST_DEST = 2.0f; // lookahead length will be at least this many meters past the destination37const float OA_BENDYRULER_LOW_SPEED_SQUARED = (0.2f * 0.2f); // when ground course is below this speed squared, vehicle's heading will be used3839#define VERTICAL_ENABLED APM_BUILD_COPTER_OR_HELI4041const AP_Param::GroupInfo AP_OABendyRuler::var_info[] = {4243// @Param: LOOKAHEAD44// @DisplayName: Object Avoidance look ahead distance maximum45// @Description: Object Avoidance will look this many meters ahead of vehicle46// @Units: m47// @Range: 1 10048// @Increment: 149// @User: Standard50AP_GROUPINFO("LOOKAHEAD", 1, AP_OABendyRuler, _lookahead, OA_BENDYRULER_LOOKAHEAD_DEFAULT),5152// @Param: CONT_RATIO53// @DisplayName: Obstacle Avoidance margin ratio for BendyRuler to change bearing significantly54// @Description: BendyRuler will avoid changing bearing unless ratio of previous margin from obstacle (or fence) to present calculated margin is atleast this much.55// @Range: 1.1 256// @Increment: 0.157// @User: Standard58AP_GROUPINFO("CONT_RATIO", 2, AP_OABendyRuler, _bendy_ratio, OA_BENDYRULER_RATIO_DEFAULT),5960// @Param: CONT_ANGLE61// @DisplayName: BendyRuler's bearing change resistance threshold angle62// @Description: BendyRuler will resist changing current bearing if the change in bearing is over this angle63// @Range: 20 18064// @Increment: 565// @User: Standard66AP_GROUPINFO("CONT_ANGLE", 3, AP_OABendyRuler, _bendy_angle, OA_BENDYRULER_ANGLE_DEFAULT),6768// @Param{Copter}: TYPE69// @DisplayName: Type of BendyRuler70// @Description: BendyRuler will search for clear path along the direction defined by this parameter71// @Values: 1:Horizontal search, 2:Vertical search72// @User: Standard73AP_GROUPINFO_FRAME("TYPE", 4, AP_OABendyRuler, _bendy_type, OA_BENDYRULER_TYPE_DEFAULT, AP_PARAM_FRAME_COPTER | AP_PARAM_FRAME_HELI | AP_PARAM_FRAME_TRICOPTER),7475AP_GROUPEND76};7778AP_OABendyRuler::AP_OABendyRuler()79{80AP_Param::setup_object_defaults(this, var_info);81_bearing_prev = FLT_MAX;82}8384// run background task to find best path85// returns true and updates origin_new and destination_new if a best path has been found. returns false if OA is not required86// bendy_type is set to the type of BendyRuler used87bool AP_OABendyRuler::update(const Location& current_loc, const Location& destination, const Vector2f &ground_speed_vec, Location &origin_new, Location &destination_new, OABendyType &bendy_type, bool proximity_only)88{89// bendy ruler always sets origin to current_loc90origin_new = current_loc;9192// init bendy_type returned93bendy_type = OABendyType::OA_BENDY_DISABLED;9495// calculate bearing and distance to final destination96const float bearing_to_dest = current_loc.get_bearing_to(destination) * 0.01f;97const float distance_to_dest = current_loc.get_distance(destination);9899// make sure user has set a meaningful value for _lookahead100_lookahead.set(MAX(_lookahead,1.0f));101102// lookahead distance is adjusted dynamically based on avoidance results103_current_lookahead = constrain_float(_current_lookahead, _lookahead * 0.5f, _lookahead);104105// calculate lookahead dist and time for step1. distance can be slightly longer than106// the distance to the destination to allow room to dodge after reaching the destination107const float lookahead_step1_dist = MIN(_current_lookahead, distance_to_dest + OA_BENDYRULER_LOOKAHEAD_PAST_DEST);108109// calculate lookahead dist for step2110const float lookahead_step2_dist = _current_lookahead * OA_BENDYRULER_LOOKAHEAD_STEP2_RATIO;111112// get ground course113float ground_course_deg;114if (ground_speed_vec.length_squared() < OA_BENDYRULER_LOW_SPEED_SQUARED) {115// with zero ground speed use vehicle's heading116ground_course_deg = AP::ahrs().get_yaw_deg();117} else {118ground_course_deg = degrees(ground_speed_vec.angle());119}120121bool ret;122switch (get_type()) {123case OABendyType::OA_BENDY_VERTICAL:124#if VERTICAL_ENABLED125ret = search_vertical_path(current_loc, destination, destination_new, lookahead_step1_dist, lookahead_step2_dist, bearing_to_dest, distance_to_dest, proximity_only);126bendy_type = OABendyType::OA_BENDY_VERTICAL;127break;128#endif129130case OABendyType::OA_BENDY_HORIZONTAL:131default:132ret = search_xy_path(current_loc, destination, ground_course_deg, destination_new, lookahead_step1_dist, lookahead_step2_dist, bearing_to_dest, distance_to_dest, proximity_only);133bendy_type = OABendyType::OA_BENDY_HORIZONTAL;134}135136return ret;137}138139// Search for path in the horizontal directions140bool AP_OABendyRuler::search_xy_path(const Location& current_loc, const Location& destination, float ground_course_deg, Location &destination_new, float lookahead_step1_dist, float lookahead_step2_dist, float bearing_to_dest, float distance_to_dest, bool proximity_only)141{142// check OA_BEARING_INC definition allows checking in all directions143static_assert(360 % OA_BENDYRULER_BEARING_INC_XY == 0, "check 360 is a multiple of OA_BEARING_INC");144145// search in OA_BENDYRULER_BEARING_INC degree increments around the vehicle alternating left146// and right. For each direction check if vehicle would avoid all obstacles147float best_bearing = bearing_to_dest;148float best_bearing_margin = -FLT_MAX;149bool have_best_bearing = false;150float best_margin = -FLT_MAX;151float best_margin_bearing = best_bearing;152153for (uint8_t i = 0; i <= (170 / OA_BENDYRULER_BEARING_INC_XY); i++) {154for (uint8_t bdir = 0; bdir <= 1; bdir++) {155// skip duplicate check of bearing straight towards destination156if ((i==0) && (bdir > 0)) {157continue;158}159// bearing that we are probing160const float bearing_delta = i * OA_BENDYRULER_BEARING_INC_XY * (bdir == 0 ? -1.0f : 1.0f);161const float bearing_test = wrap_180(bearing_to_dest + bearing_delta);162163// ToDo: add effective groundspeed calculations using airspeed164// ToDo: add prediction of vehicle's position change as part of turn to desired heading165166// test location is projected from current location at test bearing167Location test_loc = current_loc;168test_loc.offset_bearing(bearing_test, lookahead_step1_dist);169170// calculate margin from obstacles for this scenario171float margin = calc_avoidance_margin(current_loc, test_loc, proximity_only);172if (margin > best_margin) {173best_margin_bearing = bearing_test;174best_margin = margin;175}176if (margin > _margin_max) {177// this bearing avoids obstacles out to the lookahead_step1_dist178// now check in there is a clear path in three directions towards the destination179if (!have_best_bearing) {180best_bearing = bearing_test;181best_bearing_margin = margin;182have_best_bearing = true;183} else if (fabsf(wrap_180(ground_course_deg - bearing_test)) <184fabsf(wrap_180(ground_course_deg - best_bearing))) {185// replace bearing with one that is closer to our current ground course186best_bearing = bearing_test;187best_bearing_margin = margin;188}189190// perform second stage test in three directions looking for obstacles191const float test_bearings[] { 0.0f, 45.0f, -45.0f };192const float bearing_to_dest2 = test_loc.get_bearing_to(destination) * 0.01f;193float distance2 = constrain_float(lookahead_step2_dist, OA_BENDYRULER_LOOKAHEAD_STEP2_MIN, test_loc.get_distance(destination));194for (uint8_t j = 0; j < ARRAY_SIZE(test_bearings); j++) {195float bearing_test2 = wrap_180(bearing_to_dest2 + test_bearings[j]);196Location test_loc2 = test_loc;197test_loc2.offset_bearing(bearing_test2, distance2);198199// calculate minimum margin to fence and obstacles for this scenario200float margin2 = calc_avoidance_margin(test_loc, test_loc2, proximity_only);201if (margin2 > _margin_max) {202// if the chosen direction is directly towards the destination avoidance can be turned off203// i == 0 && j == 0 implies no deviation from bearing to destination204const bool active = (i != 0 || j != 0);205float final_bearing = bearing_test;206float final_margin = margin;207// check if we need ignore test_bearing and continue on previous bearing208const bool ignore_bearing_change = resist_bearing_change(destination, current_loc, active, bearing_test, lookahead_step1_dist, margin, _destination_prev,_bearing_prev, final_bearing, final_margin, proximity_only);209210// all good, now project in the chosen direction by the full distance211destination_new = current_loc;212destination_new.offset_bearing(final_bearing, MIN(distance_to_dest, lookahead_step1_dist));213_current_lookahead = MIN(_lookahead, _current_lookahead * 1.1f);214Write_OABendyRuler((uint8_t)OABendyType::OA_BENDY_HORIZONTAL, active, bearing_to_dest, 0.0f, ignore_bearing_change, final_margin, destination, destination_new);215return active;216}217}218}219}220}221222float chosen_bearing;223float chosen_distance;224if (have_best_bearing) {225// none of the directions tested were OK for 2-step checks. Choose the direction226// that was best for the first step227chosen_bearing = best_bearing;228chosen_distance = MAX(lookahead_step1_dist + MIN(best_bearing_margin, 0), 0);229_current_lookahead = MIN(_lookahead, _current_lookahead * 1.05f);230} else {231// none of the possible paths had a positive margin. Choose232// the one with the highest margin233chosen_bearing = best_margin_bearing;234chosen_distance = MAX(lookahead_step1_dist + MIN(best_margin, 0), 0);235_current_lookahead = MAX(_lookahead * 0.5f, _current_lookahead * 0.9f);236}237238// calculate new target based on best effort239destination_new = current_loc;240destination_new.offset_bearing(chosen_bearing, chosen_distance);241242// log results243Write_OABendyRuler((uint8_t)OABendyType::OA_BENDY_HORIZONTAL, true, chosen_bearing, 0.0f, false, best_margin, destination, destination_new);244245return true;246}247248// Search for path in the vertical directions249bool AP_OABendyRuler::search_vertical_path(const Location ¤t_loc, const Location &destination, Location &destination_new, float lookahead_step1_dist, float lookahead_step2_dist, float bearing_to_dest, float distance_to_dest, bool proximity_only)250{251// check OA_BEARING_INC_VERTICAL definition allows checking in all directions252static_assert(360 % OA_BENDYRULER_BEARING_INC_VERTICAL == 0, "check 360 is a multiple of OA_BEARING_INC_VERTICAL");253float best_pitch = 0.0f;254bool have_best_pitch = false;255float best_margin = -FLT_MAX;256float best_margin_pitch = best_pitch;257const uint8_t angular_limit = 180 / OA_BENDYRULER_BEARING_INC_VERTICAL;258259for (uint8_t i = 0; i <= angular_limit; i++) {260for (uint8_t bdir = 0; bdir <= 1; bdir++) {261// skip duplicate check of bearing straight towards destination or 180 degrees behind262if (((i==0) && (bdir > 0)) || ((i == angular_limit) && (bdir > 0))) {263continue;264}265266// bearing that we are probing267const float pitch_delta = i * OA_BENDYRULER_BEARING_INC_VERTICAL * (bdir == 0 ? 1.0f : -1.0f);268269Location test_loc = current_loc;270test_loc.offset_bearing_and_pitch(bearing_to_dest, pitch_delta, lookahead_step1_dist);271272// calculate margin from obstacles for this scenario273float margin = calc_avoidance_margin(current_loc, test_loc, proximity_only);274275if (margin > best_margin) {276best_margin_pitch = pitch_delta;277best_margin = margin;278}279280if (margin > _margin_max) {281// this path avoids the obstacles with the required margin, now check for the path ahead282if (!have_best_pitch) {283best_pitch = pitch_delta;284have_best_pitch = true;285}286const float test_pitch_step2[] { 0.0f, 90.0f, -90.0f, 180.0f};287float bearing_to_dest2;288if (is_equal(fabsf(pitch_delta), 90.0f)) {289bearing_to_dest2 = bearing_to_dest;290} else {291bearing_to_dest2 = test_loc.get_bearing_to(destination) * 0.01f;292}293float distance2 = constrain_float(lookahead_step2_dist, OA_BENDYRULER_LOOKAHEAD_STEP2_MIN, test_loc.get_distance(destination));294295for (uint8_t j = 0; j < ARRAY_SIZE(test_pitch_step2); j++) {296float bearing_test2 = wrap_180(test_pitch_step2[j]);297Location test_loc2 = test_loc;298test_loc2.offset_bearing_and_pitch(bearing_to_dest2, bearing_test2, distance2);299300// calculate minimum margin to fence and obstacles for this scenario301float margin2 = calc_avoidance_margin(test_loc, test_loc2, proximity_only);302if (margin2 > _margin_max) {303// if the chosen direction is directly towards the destination we might turn off avoidance304// i == 0 && j == 0 implies no deviation from bearing to destination305bool active = (i != 0 || j != 0);306if (!active) {307// do a sub test for proximity obstacles to confirm if we should really turn of BendyRuler308const float sub_test_pitch_step2[] {-90.0f, 90.0f};309for (uint8_t k = 0; k < ARRAY_SIZE(sub_test_pitch_step2); k++) {310Location test_loc_sub_test = test_loc;311test_loc_sub_test.offset_bearing_and_pitch(bearing_to_dest2, sub_test_pitch_step2[k], _margin_max);312float margin_sub_test = calc_avoidance_margin(test_loc, test_loc_sub_test, true);313if (margin_sub_test < _margin_max) {314// BendyRuler will remain active315active = true;316break;317}318}319}320// project in the chosen direction by the full distance321destination_new = current_loc;322destination_new.offset_bearing_and_pitch(bearing_to_dest, pitch_delta, distance_to_dest);323_current_lookahead = MIN(_lookahead, _current_lookahead * 1.1f);324325Write_OABendyRuler((uint8_t)OABendyType::OA_BENDY_VERTICAL, active, bearing_to_dest, pitch_delta, false, margin, destination, destination_new);326return active;327}328}329}330}331}332333float chosen_pitch;334if (have_best_pitch) {335// none of the directions tested were OK for 2-step checks. Choose the direction336// that was best for the first step337chosen_pitch = best_pitch;338_current_lookahead = MIN(_lookahead, _current_lookahead * 1.05f);339} else {340// none of the possible paths had a positive margin. Choose341// the one with the highest margin342chosen_pitch = best_margin_pitch;343_current_lookahead = MAX(_lookahead * 0.5f, _current_lookahead * 0.9f);344}345346// calculate new target based on best effort347destination_new = current_loc;348destination_new.offset_bearing_and_pitch(bearing_to_dest, chosen_pitch, distance_to_dest);349350// log results351Write_OABendyRuler((uint8_t)OABendyType::OA_BENDY_VERTICAL, true, bearing_to_dest, chosen_pitch,false, best_margin, destination, destination_new);352353return true;354}355356AP_OABendyRuler::OABendyType AP_OABendyRuler::get_type() const357{358switch (_bendy_type) {359case (uint8_t)OABendyType::OA_BENDY_VERTICAL:360#if VERTICAL_ENABLED361return OABendyType::OA_BENDY_VERTICAL;362#endif363364case (uint8_t)OABendyType::OA_BENDY_HORIZONTAL:365default:366return OABendyType::OA_BENDY_HORIZONTAL;367}368// should never reach here369return OABendyType::OA_BENDY_HORIZONTAL;370}371372/*373This function is called when BendyRuler has found a bearing which is obstacles free at atleast lookahead_step1_dist and then lookahead_step2_dist from the present location374In many situations, this new bearing can be either left or right of the obstacle, and BendyRuler can have a tough time deciding between the two.375It has the tendency to move the vehicle back and forth, if the margin obtained is even slightly better in the newer iteration.376Therefore, this method attempts to avoid changing direction of the vehicle by more than _bendy_angle degrees,377unless the new margin is atleast _bendy_ratio times better than the margin with previously calculated bearing.378We return true if we have resisted the change and will follow the last calculated bearing.379*/380bool AP_OABendyRuler::resist_bearing_change(const Location &destination, const Location ¤t_loc, bool active, float bearing_test, float lookahead_step1_dist, float margin, Location &prev_dest, float &prev_bearing, float &final_bearing, float &final_margin, bool proximity_only) const381{382bool resisted_change = false;383// see if there was a change in destination, if so, do not resist changing bearing384bool dest_change = false;385if (!destination.same_latlon_as(prev_dest)) {386dest_change = true;387prev_dest = destination;388}389390// check if we need to resist the change in direction of the vehicle. If we have a clear path to destination, go there any how391if (active && !dest_change && is_positive(_bendy_ratio)) {392// check the change in bearing between freshly calculated and previous stored BendyRuler bearing393if ((fabsf(wrap_180(prev_bearing-bearing_test)) > _bendy_angle) && (!is_equal(prev_bearing,FLT_MAX))) {394// check margin in last bearing's direction395Location test_loc_previous_bearing = current_loc;396test_loc_previous_bearing.offset_bearing(wrap_180(prev_bearing), lookahead_step1_dist);397float previous_bearing_margin = calc_avoidance_margin(current_loc,test_loc_previous_bearing, proximity_only);398399if (margin < (_bendy_ratio * previous_bearing_margin)) {400// don't change direction abruptly. If margin difference is not significant, follow the last direction401final_bearing = prev_bearing;402final_margin = previous_bearing_margin;403resisted_change = true;404}405}406} else {407// reset stored bearing if BendyRuler is not active or if WP has changed for unnecessary resistance to path change408prev_bearing = FLT_MAX;409}410if (!resisted_change) {411// we are not resisting the change, hence store BendyRuler's presently calculated bearing for future iterations412prev_bearing = bearing_test;413}414415return resisted_change;416}417418// calculate minimum distance between a segment and any obstacle419float AP_OABendyRuler::calc_avoidance_margin(const Location &start, const Location &end, bool proximity_only) const420{421float margin_min = FLT_MAX;422423float latest_margin;424425if (calc_margin_from_object_database(start, end, latest_margin)) {426margin_min = MIN(margin_min, latest_margin);427}428429if (proximity_only) {430// only need margin from proximity data431return margin_min;432}433434if (calc_margin_from_circular_fence(start, end, latest_margin)) {435margin_min = MIN(margin_min, latest_margin);436}437438#if VERTICAL_ENABLED439// alt fence only is only needed in vertical avoidance440if (get_type() == OABendyType::OA_BENDY_VERTICAL) {441if (calc_margin_from_alt_fence(start, end, latest_margin)) {442margin_min = MIN(margin_min, latest_margin);443}444}445#endif446447if (calc_margin_from_inclusion_and_exclusion_polygons(start, end, latest_margin)) {448margin_min = MIN(margin_min, latest_margin);449}450451if (calc_margin_from_inclusion_and_exclusion_circles(start, end, latest_margin)) {452margin_min = MIN(margin_min, latest_margin);453}454455// return smallest margin from any obstacle456return margin_min;457}458459// calculate minimum distance between a path and the circular fence (centered on home)460// on success returns true and updates margin461bool AP_OABendyRuler::calc_margin_from_circular_fence(const Location &start, const Location &end, float &margin) const462{463#if AP_FENCE_ENABLED464// exit immediately if polygon fence is not enabled465const AC_Fence *fence = AC_Fence::get_singleton();466if (fence == nullptr) {467return false;468}469if ((fence->get_enabled_fences() & AC_FENCE_TYPE_CIRCLE) == 0) {470return false;471}472473// calculate start and end point's distance from home474const Location &ahrs_home = AP::ahrs().get_home();475const float start_dist_sq = ahrs_home.get_distance_NE(start).length_squared();476const float end_dist_sq = ahrs_home.get_distance_NE(end).length_squared();477478// get circular fence radius + margin479const float fence_radius_plus_margin = fence->get_radius() - fence->get_margin();480481// margin is fence radius minus the longer of start or end distance482margin = fence_radius_plus_margin - sqrtf(MAX(start_dist_sq, end_dist_sq));483return true;484#else485return false;486#endif // AP_FENCE_ENABLED487}488489// calculate minimum distance between a path and the altitude fence490// on success returns true and updates margin491bool AP_OABendyRuler::calc_margin_from_alt_fence(const Location &start, const Location &end, float &margin) const492{493#if AP_FENCE_ENABLED494// exit immediately if polygon fence is not enabled495const AC_Fence *fence = AC_Fence::get_singleton();496if (fence == nullptr) {497return false;498}499if ((fence->get_enabled_fences() & AC_FENCE_TYPE_ALT_MAX) == 0) {500return false;501}502503int32_t alt_above_home_cm_start, alt_above_home_cm_end;504if (!start.get_alt_cm(Location::AltFrame::ABOVE_HOME, alt_above_home_cm_start)) {505return false;506}507if (!end.get_alt_cm(Location::AltFrame::ABOVE_HOME, alt_above_home_cm_end )) {508return false;509}510511// safe max alt = fence alt - fence margin512const float max_fence_alt = fence->get_safe_alt_max();513const float margin_start = max_fence_alt - alt_above_home_cm_start * 0.01f;514const float margin_end = max_fence_alt - alt_above_home_cm_end * 0.01f;515516// margin is minimum distance to fence from either start or end location517margin = MIN(margin_start,margin_end);518519return true;520#else521return false;522#endif // AP_FENCE_ENABLED523}524525// calculate minimum distance between a path and all inclusion and exclusion polygons526// on success returns true and updates margin527bool AP_OABendyRuler::calc_margin_from_inclusion_and_exclusion_polygons(const Location &start, const Location &end, float &margin) const528{529#if AP_FENCE_ENABLED530const AC_Fence *fence = AC_Fence::get_singleton();531if (fence == nullptr) {532return false;533}534535// exclusion polygons enabled along with polygon fences536if ((fence->get_enabled_fences() & AC_FENCE_TYPE_POLYGON) == 0) {537return false;538}539540// return immediately if no inclusion nor exclusion polygons541const uint8_t num_inclusion_polygons = fence->polyfence().get_inclusion_polygon_count();542const uint8_t num_exclusion_polygons = fence->polyfence().get_exclusion_polygon_count();543if ((num_inclusion_polygons == 0) && (num_exclusion_polygons == 0)) {544return false;545}546547// convert start and end to offsets from EKF origin548Vector2f start_NE, end_NE;549if (!start.get_vector_xy_from_origin_NE_cm(start_NE) ||550!end.get_vector_xy_from_origin_NE_cm(end_NE)) {551return false;552}553554// get fence margin555const float fence_margin = fence->get_margin();556557// iterate through inclusion polygons and calculate minimum margin558bool margin_updated = false;559for (uint8_t i = 0; i < num_inclusion_polygons; i++) {560uint16_t num_points;561const Vector2f* boundary = fence->polyfence().get_inclusion_polygon(i, num_points);562563// if outside the fence margin is the closest distance but with negative sign564const float sign = Polygon_outside(start_NE, boundary, num_points) ? -1.0f : 1.0f;565566// calculate min distance (in meters) from line to polygon567float margin_new = (sign * Polygon_closest_distance_line(boundary, num_points, start_NE, end_NE) * 0.01f) - fence_margin;568if (!margin_updated || (margin_new < margin)) {569margin_updated = true;570margin = margin_new;571}572}573574// iterate through exclusion polygons and calculate minimum margin575for (uint8_t i = 0; i < num_exclusion_polygons; i++) {576uint16_t num_points;577const Vector2f* boundary = fence->polyfence().get_exclusion_polygon(i, num_points);578579// if start is inside the polygon the margin's sign is reversed580const float sign = Polygon_outside(start_NE, boundary, num_points) ? 1.0f : -1.0f;581582// calculate min distance (in meters) from line to polygon583float margin_new = (sign * Polygon_closest_distance_line(boundary, num_points, start_NE, end_NE) * 0.01f) - fence_margin;584if (!margin_updated || (margin_new < margin)) {585margin_updated = true;586margin = margin_new;587}588}589590return margin_updated;591#else592return false;593#endif // AP_FENCE_ENABLED594}595596// calculate minimum distance between a path and all inclusion and exclusion circles597// on success returns true and updates margin598bool AP_OABendyRuler::calc_margin_from_inclusion_and_exclusion_circles(const Location &start, const Location &end, float &margin) const599{600#if AP_FENCE_ENABLED601// exit immediately if fence is not enabled602const AC_Fence *fence = AC_Fence::get_singleton();603if (fence == nullptr) {604return false;605}606607// inclusion/exclusion circles enabled along with polygon fences608if ((fence->get_enabled_fences() & AC_FENCE_TYPE_POLYGON) == 0) {609return false;610}611612// return immediately if no inclusion nor exclusion circles613const uint8_t num_inclusion_circles = fence->polyfence().get_inclusion_circle_count();614const uint8_t num_exclusion_circles = fence->polyfence().get_exclusion_circle_count();615if ((num_inclusion_circles == 0) && (num_exclusion_circles == 0)) {616return false;617}618619// convert start and end to offsets from EKF origin620Vector2f start_NE, end_NE;621if (!start.get_vector_xy_from_origin_NE_cm(start_NE) ||622!end.get_vector_xy_from_origin_NE_cm(end_NE)) {623return false;624}625626// get fence margin627const float fence_margin = fence->get_margin();628629// iterate through inclusion circles and calculate minimum margin630bool margin_updated = false;631for (uint8_t i = 0; i < num_inclusion_circles; i++) {632Vector2f center_pos_cm;633float radius;634if (fence->polyfence().get_inclusion_circle(i, center_pos_cm, radius)) {635636// calculate start and ends distance from the center of the circle637const float start_dist_sq = (start_NE - center_pos_cm).length_squared();638const float end_dist_sq = (end_NE - center_pos_cm).length_squared();639640// margin is fence radius minus the longer of start or end distance641const float margin_new = (radius + fence_margin) - (sqrtf(MAX(start_dist_sq, end_dist_sq)) * 0.01f);642643// update margin with lowest value so far644if (!margin_updated || (margin_new < margin)) {645margin_updated = true;646margin = margin_new;647}648}649}650651// iterate through exclusion circles and calculate minimum margin652for (uint8_t i = 0; i < num_exclusion_circles; i++) {653Vector2f center_pos_cm;654float radius;655if (fence->polyfence().get_exclusion_circle(i, center_pos_cm, radius)) {656657// first calculate distance between circle's center and segment658const float dist_cm = Vector2f::closest_distance_between_line_and_point(start_NE, end_NE, center_pos_cm);659660// margin is distance to the center minus the radius661const float margin_new = (dist_cm * 0.01f) - (radius + fence_margin);662663// update margin with lowest value so far664if (!margin_updated || (margin_new < margin)) {665margin_updated = true;666margin = margin_new;667}668}669}670671return margin_updated;672#else673return false;674#endif // AP_FENCE_ENABLED675}676677// calculate minimum distance between a path and proximity sensor obstacles678// on success returns true and updates margin679bool AP_OABendyRuler::calc_margin_from_object_database(const Location &start, const Location &end, float &margin) const680{681// exit immediately if db is empty682AP_OADatabase *oaDb = AP::oadatabase();683if (oaDb == nullptr || !oaDb->healthy()) {684return false;685}686687// convert start and end to offsets (in cm) from EKF origin688Vector3f start_NEU,end_NEU;689if (!start.get_vector_from_origin_NEU_cm(start_NEU) ||690!end.get_vector_from_origin_NEU_cm(end_NEU)) {691return false;692}693if (start_NEU == end_NEU) {694return false;695}696697// check each obstacle's distance from segment698float smallest_margin = FLT_MAX;699for (uint16_t i=0; i<oaDb->database_count(); i++) {700const AP_OADatabase::OA_DbItem& item = oaDb->get_item(i);701const Vector3f point_cm = item.pos * 100.0f;702// margin is distance between line segment and obstacle minus obstacle's radius703const float m = Vector3f::closest_distance_between_line_and_point(start_NEU, end_NEU, point_cm) * 0.01f - item.radius;704if (m < smallest_margin) {705smallest_margin = m;706}707}708709// return smallest margin710if (smallest_margin < FLT_MAX) {711margin = smallest_margin;712return true;713}714715return false;716}717718#endif // AP_OAPATHPLANNER_BENDYRULER_ENABLED719720721