Path: blob/master/libraries/AC_Avoidance/AP_OADijkstra.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_DIJKSTRA_ENABLED1819#include "AP_OADijkstra.h"20#include "AP_OAPathPlanner.h"2122#include <AC_Fence/AC_Fence.h>2324#if AP_FENCE_ENABLED2526#include <AP_AHRS/AP_AHRS.h>27#include <AP_Logger/AP_Logger.h>28#include <GCS_MAVLink/GCS.h>2930#define OA_DIJKSTRA_EXPANDING_ARRAY_ELEMENTS_PER_CHUNK 32 // expanding arrays for fence points and paths to destination will grow in increments of 20 elements31#define OA_DIJKSTRA_POLYGON_SHORTPATH_NOTSET_IDX 255 // index use to indicate we do not have a tentative short path for a node32#define OA_DIJKSTRA_ERROR_REPORTING_INTERVAL_MS 5000 // failure messages sent to GCS every 5 seconds3334/// Constructor35AP_OADijkstra::AP_OADijkstra(AP_Int16 &options) :36_inclusion_polygon_pts(OA_DIJKSTRA_EXPANDING_ARRAY_ELEMENTS_PER_CHUNK),37_exclusion_polygon_pts(OA_DIJKSTRA_EXPANDING_ARRAY_ELEMENTS_PER_CHUNK),38_exclusion_circle_pts(OA_DIJKSTRA_EXPANDING_ARRAY_ELEMENTS_PER_CHUNK),39_short_path_data(OA_DIJKSTRA_EXPANDING_ARRAY_ELEMENTS_PER_CHUNK),40_path(OA_DIJKSTRA_EXPANDING_ARRAY_ELEMENTS_PER_CHUNK),41_options(options)42{43}4445// calculate a destination to avoid fences46// returns DIJKSTRA_STATE_SUCCESS and populates origin_new, destination_new and next_destination_new if avoidance is required47// next_destination_new will be non-zero if there is a next destination48// dest_to_next_dest_clear will be set to true if the path from (the input) destination to (input) next_destination is clear49AP_OADijkstra::AP_OADijkstra_State AP_OADijkstra::update(const Location ¤t_loc,50const Location &destination,51const Location &next_destination,52Location& origin_new,53Location& destination_new,54Location& next_destination_new,55bool& dest_to_next_dest_clear)56{57WITH_SEMAPHORE(AP::fence()->polyfence().get_loaded_fence_semaphore());5859// avoidance is not required if no fences60if (!some_fences_enabled()) {61dest_to_next_dest_clear = _dest_to_next_dest_clear = true;62Write_OADijkstra(DIJKSTRA_STATE_NOT_REQUIRED, 0, 0, 0, destination, destination);63return DIJKSTRA_STATE_NOT_REQUIRED;64}6566// no avoidance required if destination is same as current location67if (current_loc.same_latlon_as(destination)) {68// we do not check path to next destination so conservatively set to false69dest_to_next_dest_clear = _dest_to_next_dest_clear = false;70Write_OADijkstra(DIJKSTRA_STATE_NOT_REQUIRED, 0, 0, 0, destination, destination);71return DIJKSTRA_STATE_NOT_REQUIRED;72}7374// check for inclusion polygon updates75if (check_inclusion_polygon_updated()) {76_inclusion_polygon_with_margin_ok = false;77_polyfence_visgraph_ok = false;78_shortest_path_ok = false;79}8081// check for exclusion polygon updates82if (check_exclusion_polygon_updated()) {83_exclusion_polygon_with_margin_ok = false;84_polyfence_visgraph_ok = false;85_shortest_path_ok = false;86}8788// check for exclusion circle updates89if (check_exclusion_circle_updated()) {90_exclusion_circle_with_margin_ok = false;91_polyfence_visgraph_ok = false;92_shortest_path_ok = false;93}9495// create inner polygon fence96if (!_inclusion_polygon_with_margin_ok) {97_inclusion_polygon_with_margin_ok = create_inclusion_polygon_with_margin(_polyfence_margin * 100.0f, _error_id);98if (!_inclusion_polygon_with_margin_ok) {99dest_to_next_dest_clear = _dest_to_next_dest_clear = false;100report_error(_error_id);101Write_OADijkstra(DIJKSTRA_STATE_ERROR, (uint8_t)_error_id, 0, 0, destination, destination);102return DIJKSTRA_STATE_ERROR;103}104}105106// create exclusion polygon outer fence107if (!_exclusion_polygon_with_margin_ok) {108_exclusion_polygon_with_margin_ok = create_exclusion_polygon_with_margin(_polyfence_margin * 100.0f, _error_id);109if (!_exclusion_polygon_with_margin_ok) {110dest_to_next_dest_clear = _dest_to_next_dest_clear = false;111report_error(_error_id);112Write_OADijkstra(DIJKSTRA_STATE_ERROR, (uint8_t)_error_id, 0, 0, destination, destination);113return DIJKSTRA_STATE_ERROR;114}115}116117// create exclusion circle points118if (!_exclusion_circle_with_margin_ok) {119_exclusion_circle_with_margin_ok = create_exclusion_circle_with_margin(_polyfence_margin * 100.0f, _error_id);120if (!_exclusion_circle_with_margin_ok) {121dest_to_next_dest_clear = _dest_to_next_dest_clear = false;122report_error(_error_id);123Write_OADijkstra(DIJKSTRA_STATE_ERROR, (uint8_t)_error_id, 0, 0, destination, destination);124return DIJKSTRA_STATE_ERROR;125}126}127128// create visgraph for all fence (with margin) points129if (!_polyfence_visgraph_ok) {130_polyfence_visgraph_ok = create_fence_visgraph(_error_id);131if (!_polyfence_visgraph_ok) {132_shortest_path_ok = false;133dest_to_next_dest_clear = _dest_to_next_dest_clear = false;134report_error(_error_id);135Write_OADijkstra(DIJKSTRA_STATE_ERROR, (uint8_t)_error_id, 0, 0, destination, destination);136return DIJKSTRA_STATE_ERROR;137}138// reset logging count to restart logging updated graph139_log_num_points = 0;140_log_visgraph_version++;141}142143// Log one visgraph point per loop144if (_polyfence_visgraph_ok && (_log_num_points < total_numpoints()) && (_options & AP_OAPathPlanner::OARecoveryOptions::OA_OPTION_LOG_DIJKSTRA_POINTS) ) {145Vector2f vis_point;146if (get_point(_log_num_points, vis_point)) {147Location log_location(Vector3f{vis_point.x, vis_point.y, 0.0}, Location::AltFrame::ABOVE_ORIGIN);148Write_Visgraph_point(_log_visgraph_version, _log_num_points, log_location.lat, log_location.lng);149_log_num_points++;150}151}152153// rebuild path if destination or next_destination has changed154if (!destination.same_latlon_as(_destination_prev) || !next_destination.same_latlon_as(_next_destination_prev)) {155_destination_prev = destination;156_next_destination_prev = next_destination;157_shortest_path_ok = false;158}159160// calculate shortest path from current_loc to destination161if (!_shortest_path_ok) {162_shortest_path_ok = calc_shortest_path(current_loc, destination, _error_id);163if (!_shortest_path_ok) {164dest_to_next_dest_clear = _dest_to_next_dest_clear = false;165report_error(_error_id);166Write_OADijkstra(DIJKSTRA_STATE_ERROR, (uint8_t)_error_id, 0, 0, destination, destination);167return DIJKSTRA_STATE_ERROR;168}169// start from 2nd point on path (first is the original origin)170_path_idx_returned = 1;171172// check if path from destination to next_destination intersects with a fence173_dest_to_next_dest_clear = false;174if (!next_destination.is_zero()) {175Vector2f seg_start, seg_end;176if (destination.get_vector_xy_from_origin_NE_cm(seg_start) &&177next_destination.get_vector_xy_from_origin_NE_cm(seg_end)) {178_dest_to_next_dest_clear = !intersects_fence(seg_start, seg_end);179}180}181}182183// path has been created, return latest point184Vector2f dest_pos;185const uint8_t path_length = get_shortest_path_numpoints() > 0 ? (get_shortest_path_numpoints() - 1) : 0;186if ((_path_idx_returned < path_length) && get_shortest_path_point(_path_idx_returned, dest_pos)) {187188// for the first point return origin as current_loc189Vector2f origin_pos;190if ((_path_idx_returned > 0) && get_shortest_path_point(_path_idx_returned-1, origin_pos)) {191// convert offset from ekf origin to Location192Location temp_loc(Vector3f{origin_pos.x, origin_pos.y, 0.0}, Location::AltFrame::ABOVE_ORIGIN);193origin_new = temp_loc;194} else {195// for first point use current loc as origin196origin_new = current_loc;197}198199// convert offset from ekf origin to Location200Location temp_loc(Vector3f{dest_pos.x, dest_pos.y, 0.0}, Location::AltFrame::ABOVE_ORIGIN);201destination_new = destination;202destination_new.lat = temp_loc.lat;203destination_new.lng = temp_loc.lng;204205// provide next destination to allow smooth cornering206next_destination_new.zero();207Vector2f next_dest_pos;208if ((_path_idx_returned + 1 < path_length) && get_shortest_path_point(_path_idx_returned + 1, next_dest_pos)) {209// convert offset from ekf origin to Location210Location next_loc(Vector3f{next_dest_pos.x, next_dest_pos.y, 0.0}, Location::AltFrame::ABOVE_ORIGIN);211next_destination_new = destination;212next_destination_new.lat = next_loc.lat;213next_destination_new.lng = next_loc.lng;214} else {215// return destination as next_destination216next_destination_new = destination;217}218219// path to next destination clear state is still valid from previous calcs (was calced along with shortest path)220dest_to_next_dest_clear = _dest_to_next_dest_clear;221222// check if we should advance to next point for next iteration223const bool near_oa_wp = current_loc.get_distance(destination_new) <= 2.0f;224const bool past_oa_wp = current_loc.past_interval_finish_line(origin_new, destination_new);225if (near_oa_wp || past_oa_wp) {226_path_idx_returned++;227}228// log success229Write_OADijkstra(DIJKSTRA_STATE_SUCCESS, 0, _path_idx_returned, get_shortest_path_numpoints(), destination, destination_new);230return DIJKSTRA_STATE_SUCCESS;231}232233// we have reached the destination so avoidance is no longer required234// path to next destination clear state is still valid from previous calcs235dest_to_next_dest_clear = _dest_to_next_dest_clear;236Write_OADijkstra(DIJKSTRA_STATE_NOT_REQUIRED, 0, 0, 0, destination, destination);237return DIJKSTRA_STATE_NOT_REQUIRED;238}239240// returns true if at least one inclusion or exclusion zone is enabled241bool AP_OADijkstra::some_fences_enabled() const242{243const AC_Fence *fence = AC_Fence::get_singleton();244if (fence == nullptr) {245return false;246}247if ((fence->polyfence().get_inclusion_polygon_count() == 0) &&248(fence->polyfence().get_exclusion_polygon_count() == 0) &&249(fence->polyfence().get_exclusion_circle_count() == 0)) {250return false;251}252return ((fence->get_enabled_fences() & AC_FENCE_TYPE_POLYGON) > 0);253}254255// return error message for a given error id256const char* AP_OADijkstra::get_error_msg(AP_OADijkstra_Error error_id) const257{258switch (error_id) {259case AP_OADijkstra_Error::DIJKSTRA_ERROR_NONE:260return "no error";261break;262case AP_OADijkstra_Error::DIJKSTRA_ERROR_OUT_OF_MEMORY:263return "out of memory";264break;265case AP_OADijkstra_Error::DIJKSTRA_ERROR_OVERLAPPING_POLYGON_POINTS:266return "overlapping polygon points";267break;268case AP_OADijkstra_Error::DIJKSTRA_ERROR_FAILED_TO_BUILD_INNER_POLYGON:269return "failed to build inner polygon";270break;271case AP_OADijkstra_Error::DIJKSTRA_ERROR_OVERLAPPING_POLYGON_LINES:272return "overlapping polygon lines";273break;274case AP_OADijkstra_Error::DIJKSTRA_ERROR_FENCE_DISABLED:275return "fence disabled";276break;277case AP_OADijkstra_Error::DIJKSTRA_ERROR_TOO_MANY_FENCE_POINTS:278return "too many fence points";279break;280case AP_OADijkstra_Error::DIJKSTRA_ERROR_NO_POSITION_ESTIMATE:281return "no position estimate";282break;283case AP_OADijkstra_Error::DIJKSTRA_ERROR_COULD_NOT_FIND_PATH:284return "could not find path";285break;286}287288// we should never reach here but just in case289return "unknown error";290}291292void AP_OADijkstra::report_error(AP_OADijkstra_Error error_id)293{294// report errors to GCS every 5 seconds295uint32_t now_ms = AP_HAL::millis();296if ((error_id != AP_OADijkstra_Error::DIJKSTRA_ERROR_NONE) &&297((error_id != _error_last_id) || ((now_ms - _error_last_report_ms) > OA_DIJKSTRA_ERROR_REPORTING_INTERVAL_MS))) {298const char* error_msg = get_error_msg(error_id);299(void)error_msg; // in case !HAL_GCS_ENABLED300GCS_SEND_TEXT(MAV_SEVERITY_CRITICAL, "Dijkstra: %s", error_msg);301_error_last_id = error_id;302_error_last_report_ms = now_ms;303}304}305306// check if polygon fence has been updated since we created the inner fence. returns true if changed307bool AP_OADijkstra::check_inclusion_polygon_updated() const308{309// exit immediately if polygon fence is not enabled310const AC_Fence *fence = AC_Fence::get_singleton();311if (fence == nullptr) {312return false;313}314return (_inclusion_polygon_update_ms != fence->polyfence().get_inclusion_polygon_update_ms());315}316317// create polygons inside the existing inclusion polygons318// returns true on success. returns false on failure and err_id is updated319bool AP_OADijkstra::create_inclusion_polygon_with_margin(float margin_cm, AP_OADijkstra_Error &err_id)320{321const AC_Fence *fence = AC_Fence::get_singleton();322323if (fence == nullptr) {324err_id = AP_OADijkstra_Error::DIJKSTRA_ERROR_FENCE_DISABLED;325return false;326}327328// skip unnecessary retry to build inclusion polygon if previous fence points have not changed329if (_inclusion_polygon_update_ms == fence->polyfence().get_inclusion_polygon_update_ms()) {330return false;331}332333_inclusion_polygon_update_ms = fence->polyfence().get_inclusion_polygon_update_ms();334335// clear all points336_inclusion_polygon_numpoints = 0;337338// return immediately if no polygons339const uint8_t num_inclusion_polygons = fence->polyfence().get_inclusion_polygon_count();340341// iterate through polygons and create inner points342for (uint8_t i = 0; i < num_inclusion_polygons; i++) {343uint16_t num_points;344const Vector2f* boundary = fence->polyfence().get_inclusion_polygon(i, num_points);345346// for each point in inclusion polygon347// Note: boundary is "unclosed" meaning the last point is *not* the same as the first348uint16_t new_points = 0;349for (uint16_t j = 0; j < num_points; j++) {350351// find points before and after current point (relative to current point)352const uint16_t before_idx = (j == 0) ? num_points-1 : j-1;353const uint16_t after_idx = (j == num_points-1) ? 0 : j+1;354Vector2f before_pt = boundary[before_idx] - boundary[j];355Vector2f after_pt = boundary[after_idx] - boundary[j];356357// if points are overlapping fail358if (before_pt.is_zero() || after_pt.is_zero() || (before_pt == after_pt)) {359err_id = AP_OADijkstra_Error::DIJKSTRA_ERROR_OVERLAPPING_POLYGON_POINTS;360return false;361}362363// scale points to be unit vectors364before_pt.normalize();365after_pt.normalize();366367// calculate intermediate point and scale to margin368Vector2f intermediate_pt = after_pt + before_pt;369intermediate_pt.normalize();370intermediate_pt *= margin_cm;371372// find final point which is outside the inside polygon373Vector2f temp_point = boundary[j] + intermediate_pt;374if (Polygon_outside(temp_point, boundary, num_points)) {375intermediate_pt *= -1.0;376temp_point = boundary[j] + intermediate_pt;377if (Polygon_outside(temp_point, boundary, num_points)) {378// could not find a point on either side that was outside the exclusion polygon so fail379// this may happen if the exclusion polygon has overlapping lines380err_id = AP_OADijkstra_Error::DIJKSTRA_ERROR_OVERLAPPING_POLYGON_LINES;381return false;382}383}384385// don't add points in corners386if (fabsf(wrap_PI(intermediate_pt.angle() - before_pt.angle())) < M_PI_2) {387continue;388}389390// expand array if required391if (!_inclusion_polygon_pts.expand_to_hold(_inclusion_polygon_numpoints + new_points + 1)) {392err_id = AP_OADijkstra_Error::DIJKSTRA_ERROR_OUT_OF_MEMORY;393return false;394}395// add point396_inclusion_polygon_pts[_inclusion_polygon_numpoints + new_points] = temp_point;397new_points++;398}399400// update total number of points401_inclusion_polygon_numpoints += new_points;402}403return true;404}405406// check if exclusion polygons have been updated since create_exclusion_polygon_with_margin was run407// returns true if changed408bool AP_OADijkstra::check_exclusion_polygon_updated() const409{410const AC_Fence *fence = AC_Fence::get_singleton();411if (fence == nullptr) {412return false;413}414return (_exclusion_polygon_update_ms != fence->polyfence().get_exclusion_polygon_update_ms());415}416417// create polygons around existing exclusion polygons418// returns true on success. returns false on failure and err_id is updated419bool AP_OADijkstra::create_exclusion_polygon_with_margin(float margin_cm, AP_OADijkstra_Error &err_id)420{421const AC_Fence *fence = AC_Fence::get_singleton();422423if (fence == nullptr) {424err_id = AP_OADijkstra_Error::DIJKSTRA_ERROR_FENCE_DISABLED;425return false;426}427428// skip unnecessary retry to build exclusion polygon if previous fence points have not changed429if (_exclusion_polygon_update_ms == fence->polyfence().get_exclusion_polygon_update_ms()) {430return false;431}432433_exclusion_polygon_update_ms = fence->polyfence().get_exclusion_polygon_update_ms();434435436// clear all points437_exclusion_polygon_numpoints = 0;438439// return immediately if no exclusion polygons440const uint8_t num_exclusion_polygons = fence->polyfence().get_exclusion_polygon_count();441442// iterate through exclusion polygons and create outer points443for (uint8_t i = 0; i < num_exclusion_polygons; i++) {444uint16_t num_points;445const Vector2f* boundary = fence->polyfence().get_exclusion_polygon(i, num_points);446447// for each point in exclusion polygon448// Note: boundary is "unclosed" meaning the last point is *not* the same as the first449uint16_t new_points = 0;450for (uint16_t j = 0; j < num_points; j++) {451452// find points before and after current point (relative to current point)453const uint16_t before_idx = (j == 0) ? num_points-1 : j-1;454const uint16_t after_idx = (j == num_points-1) ? 0 : j+1;455Vector2f before_pt = boundary[before_idx] - boundary[j];456Vector2f after_pt = boundary[after_idx] - boundary[j];457458// if points are overlapping fail459if (before_pt.is_zero() || after_pt.is_zero() || (before_pt == after_pt)) {460err_id = AP_OADijkstra_Error::DIJKSTRA_ERROR_OVERLAPPING_POLYGON_POINTS;461return false;462}463464// scale points to be unit vectors465before_pt.normalize();466after_pt.normalize();467468// calculate intermediate point and scale to margin469Vector2f intermediate_pt = after_pt + before_pt;470intermediate_pt.normalize();471intermediate_pt *= margin_cm;472473// find final point which is outside the original polygon474Vector2f temp_point = boundary[j] + intermediate_pt;475if (!Polygon_outside(temp_point, boundary, num_points)) {476intermediate_pt *= -1;477temp_point = boundary[j] + intermediate_pt;478if (!Polygon_outside(temp_point, boundary, num_points)) {479// could not find a point on either side that was outside the exclusion polygon so fail480// this may happen if the exclusion polygon has overlapping lines481err_id = AP_OADijkstra_Error::DIJKSTRA_ERROR_OVERLAPPING_POLYGON_LINES;482return false;483}484}485486// don't add points in corners487if (fabsf(wrap_PI(intermediate_pt.angle() - before_pt.angle())) < M_PI_2) {488continue;489}490491// expand array if required492if (!_exclusion_polygon_pts.expand_to_hold(_exclusion_polygon_numpoints + new_points + 1)) {493err_id = AP_OADijkstra_Error::DIJKSTRA_ERROR_OUT_OF_MEMORY;494return false;495}496// add point497_exclusion_polygon_pts[_exclusion_polygon_numpoints + new_points] = temp_point;498new_points++;499}500501// update total number of points502_exclusion_polygon_numpoints += new_points;503}504return true;505}506507// check if exclusion circles have been updated since create_exclusion_circle_with_margin was run508// returns true if changed509bool AP_OADijkstra::check_exclusion_circle_updated() const510{511// exit immediately if fence is not enabled512const AC_Fence *fence = AC_Fence::get_singleton();513if (fence == nullptr) {514return false;515}516return (_exclusion_circle_update_ms != fence->polyfence().get_exclusion_circle_update_ms());517}518519// create polygons around existing exclusion circles520// returns true on success. returns false on failure and err_id is updated521bool AP_OADijkstra::create_exclusion_circle_with_margin(float margin_cm, AP_OADijkstra_Error &err_id)522{523// exit immediately if fence is not enabled524const AC_Fence *fence = AC_Fence::get_singleton();525if (fence == nullptr) {526err_id = AP_OADijkstra_Error::DIJKSTRA_ERROR_FENCE_DISABLED;527return false;528}529530// clear all points531_exclusion_circle_numpoints = 0;532533// unit length offsets for polygon points around circles534const Vector2f unit_offsets[] = {535{cosf(radians(30)), cosf(radians(30-90))}, // north-east536{cosf(radians(90)), cosf(radians(90-90))}, // east537{cosf(radians(150)), cosf(radians(150-90))},// south-east538{cosf(radians(210)), cosf(radians(210-90))},// south-west539{cosf(radians(270)), cosf(radians(270-90))},// west540{cosf(radians(330)), cosf(radians(330-90))},// north-west541};542const uint8_t num_points_per_circle = ARRAY_SIZE(unit_offsets);543544// expand polygon point array if required545const uint8_t num_exclusion_circles = fence->polyfence().get_exclusion_circle_count();546if (!_exclusion_circle_pts.expand_to_hold(num_exclusion_circles * num_points_per_circle)) {547err_id = AP_OADijkstra_Error::DIJKSTRA_ERROR_OUT_OF_MEMORY;548return false;549}550551// iterate through exclusion circles and create outer polygon points552for (uint8_t i = 0; i < num_exclusion_circles; i++) {553Vector2f circle_pos_cm;554float radius;555if (fence->polyfence().get_exclusion_circle(i, circle_pos_cm, radius)) {556// scaler to ensure lines between points do not intersect circle557const float scaler = (1.0f / cosf(radians(180.0f / (float)num_points_per_circle))) * ((radius * 100.0f) + margin_cm);558559// add points to array560for (uint8_t j = 0; j < num_points_per_circle; j++) {561_exclusion_circle_pts[_exclusion_circle_numpoints] = circle_pos_cm + (unit_offsets[j] * scaler);562_exclusion_circle_numpoints++;563}564}565}566567// record fence update time so we don't process these exclusion circles again568_exclusion_circle_update_ms = fence->polyfence().get_exclusion_circle_update_ms();569570return true;571}572573// returns total number of points across all fence types574uint16_t AP_OADijkstra::total_numpoints() const575{576return _inclusion_polygon_numpoints + _exclusion_polygon_numpoints + _exclusion_circle_numpoints;577}578579// get a single point across the total list of points from all fence types580bool AP_OADijkstra::get_point(uint16_t index, Vector2f &point) const581{582// sanity check index583if (index >= total_numpoints()) {584return false;585}586587// return an inclusion polygon point588if (index < _inclusion_polygon_numpoints) {589point = _inclusion_polygon_pts[index];590return true;591}592index -= _inclusion_polygon_numpoints;593594// return an exclusion polygon point595if (index < _exclusion_polygon_numpoints) {596point = _exclusion_polygon_pts[index];597return true;598}599index -= _exclusion_polygon_numpoints;600601// return an exclusion circle point602if (index < _exclusion_circle_numpoints) {603point = _exclusion_circle_pts[index];604return true;605}606607// we should never get here but just in case608return false;609}610611// returns true if line segment intersects polygon or circular fence612bool AP_OADijkstra::intersects_fence(const Vector2f &seg_start, const Vector2f &seg_end) const613{614// return immediately if fence is not enabled615const AC_Fence *fence = AC_Fence::get_singleton();616if (fence == nullptr) {617return false;618}619620// determine if segment crosses any of the inclusion polygons621uint16_t num_points = 0;622for (uint8_t i = 0; i < fence->polyfence().get_inclusion_polygon_count(); i++) {623const Vector2f* boundary = fence->polyfence().get_inclusion_polygon(i, num_points);624if (boundary != nullptr) {625Vector2f intersection;626if (Polygon_intersects(boundary, num_points, seg_start, seg_end, intersection)) {627return true;628}629}630}631632// determine if segment crosses any of the exclusion polygons633for (uint8_t i = 0; i < fence->polyfence().get_exclusion_polygon_count(); i++) {634const Vector2f* boundary = fence->polyfence().get_exclusion_polygon(i, num_points);635if (boundary != nullptr) {636Vector2f intersection;637if (Polygon_intersects(boundary, num_points, seg_start, seg_end, intersection)) {638return true;639}640}641}642643// determine if segment crosses any of the inclusion circles644for (uint8_t i = 0; i < fence->polyfence().get_inclusion_circle_count(); i++) {645Vector2f center_pos_cm;646float radius;647if (fence->polyfence().get_inclusion_circle(i, center_pos_cm, radius)) {648// intersects circle if either start or end is further from the center than the radius649const float radius_cm_sq = sq(radius * 100.0f) ;650if ((seg_start - center_pos_cm).length_squared() > radius_cm_sq) {651return true;652}653if ((seg_end - center_pos_cm).length_squared() > radius_cm_sq) {654return true;655}656}657}658659// determine if segment crosses any of the exclusion circles660for (uint8_t i = 0; i < fence->polyfence().get_exclusion_circle_count(); i++) {661Vector2f center_pos_cm;662float radius;663if (fence->polyfence().get_exclusion_circle(i, center_pos_cm, radius)) {664// calculate distance between circle's center and segment665const float dist_cm = Vector2f::closest_distance_between_line_and_point(seg_start, seg_end, center_pos_cm);666667// intersects if distance is less than radius668if (dist_cm <= (radius * 100.0f)) {669return true;670}671}672}673674// if we got this far then no intersection675return false;676}677678// create visibility graph for all fence (with margin) points679// returns true on success. returns false on failure and err_id is updated680// requires these functions to have been run create_inclusion_polygon_with_margin, create_exclusion_polygon_with_margin, create_exclusion_circle_with_margin681bool AP_OADijkstra::create_fence_visgraph(AP_OADijkstra_Error &err_id)682{683// exit immediately if fence is not enabled684const AC_Fence *fence = AC_Fence::get_singleton();685if (fence == nullptr) {686err_id = AP_OADijkstra_Error::DIJKSTRA_ERROR_FENCE_DISABLED;687return false;688}689690// fail if more fence points than algorithm can handle691if (total_numpoints() >= OA_DIJKSTRA_POLYGON_SHORTPATH_NOTSET_IDX) {692err_id = AP_OADijkstra_Error::DIJKSTRA_ERROR_TOO_MANY_FENCE_POINTS;693return false;694}695696// clear fence points visibility graph697_fence_visgraph.clear();698699// calculate distance from each point to all other points700for (uint8_t i = 0; i < total_numpoints() - 1; i++) {701Vector2f start_seg;702if (get_point(i, start_seg)) {703for (uint8_t j = i + 1; j < total_numpoints(); j++) {704Vector2f end_seg;705if (get_point(j, end_seg)) {706// if line segment does not intersect with any inclusion or exclusion zones add to visgraph707if (!intersects_fence(start_seg, end_seg)) {708if (!_fence_visgraph.add_item({AP_OAVisGraph::OATYPE_INTERMEDIATE_POINT, i},709{AP_OAVisGraph::OATYPE_INTERMEDIATE_POINT, j},710(start_seg - end_seg).length())) {711// failure to add a point can only be caused by out-of-memory712err_id = AP_OADijkstra_Error::DIJKSTRA_ERROR_OUT_OF_MEMORY;713return false;714}715}716}717}718}719}720721return true;722}723724// updates visibility graph for a given position which is an offset (in cm) from the ekf origin725// to add an additional position (i.e. the destination) set add_extra_position = true and provide the position in the extra_position argument726// requires create_inclusion_polygon_with_margin to have been run727// returns true on success728bool AP_OADijkstra::update_visgraph(AP_OAVisGraph& visgraph, const AP_OAVisGraph::OAItemID& oaid, const Vector2f &position, bool add_extra_position, Vector2f extra_position)729{730// clear visibility graph731visgraph.clear();732733// calculate distance from position to all inclusion/exclusion fence points734for (uint8_t i = 0; i < total_numpoints(); i++) {735Vector2f seg_end;736if (get_point(i, seg_end)) {737if (!intersects_fence(position, seg_end)) {738// line segment does not intersect with fences so add to visgraph739if (!visgraph.add_item(oaid, {AP_OAVisGraph::OATYPE_INTERMEDIATE_POINT, i}, (position - seg_end).length())) {740return false;741}742}743}744}745746// add extra point to visibility graph if it doesn't intersect with polygon fence or exclusion polygons747if (add_extra_position) {748if (!intersects_fence(position, extra_position)) {749if (!visgraph.add_item(oaid, {AP_OAVisGraph::OATYPE_DESTINATION, 0}, (position - extra_position).length())) {750return false;751}752}753}754755return true;756}757758// update total distance for all nodes visible from current node759// curr_node_idx is an index into the _short_path_data array760void AP_OADijkstra::update_visible_node_distances(node_index curr_node_idx)761{762// sanity check763if (curr_node_idx >= _short_path_data_numpoints) {764return;765}766767// get current node for convenience768const ShortPathNode &curr_node = _short_path_data[curr_node_idx];769770// for each visibility graph771const AP_OAVisGraph* visgraphs[] = {&_fence_visgraph, &_destination_visgraph};772for (uint8_t v=0; v<ARRAY_SIZE(visgraphs); v++) {773774// skip if empty775const AP_OAVisGraph &curr_visgraph = *visgraphs[v];776if (curr_visgraph.num_items() == 0) {777continue;778}779780// search visibility graph for items visible from current_node781for (uint16_t i = 0; i < curr_visgraph.num_items(); i++) {782const AP_OAVisGraph::VisGraphItem &item = curr_visgraph[i];783// match if current node's id matches either of the id's in the graph (i.e. either end of the vector)784if ((curr_node.id == item.id1) || (curr_node.id == item.id2)) {785AP_OAVisGraph::OAItemID matching_id = (curr_node.id == item.id1) ? item.id2 : item.id1;786// find item's id in node array787node_index item_node_idx;788if (find_node_from_id(matching_id, item_node_idx)) {789// if current node's distance + distance to item is less than item's current distance, update item's distance790const float dist_to_item_via_current_node = _short_path_data[curr_node_idx].distance_cm + item.distance_cm;791if (dist_to_item_via_current_node < _short_path_data[item_node_idx].distance_cm) {792// update item's distance and set "distance_from_idx" to current node's index793_short_path_data[item_node_idx].distance_cm = dist_to_item_via_current_node;794_short_path_data[item_node_idx].distance_from_idx = curr_node_idx;795}796}797}798}799}800}801802// find a node's index into _short_path_data array from it's id (i.e. id type and id number)803// returns true if successful and node_idx is updated804bool AP_OADijkstra::find_node_from_id(const AP_OAVisGraph::OAItemID &id, node_index &node_idx) const805{806switch (id.id_type) {807case AP_OAVisGraph::OATYPE_SOURCE:808// source node is always the first node809if (_short_path_data_numpoints > 0) {810node_idx = 0;811return true;812}813break;814case AP_OAVisGraph::OATYPE_DESTINATION:815// destination is always the 2nd node816if (_short_path_data_numpoints > 1) {817node_idx = 1;818return true;819}820break;821case AP_OAVisGraph::OATYPE_INTERMEDIATE_POINT:822// intermediate nodes start from 3rd node823if (_short_path_data_numpoints > id.id_num + 2) {824node_idx = id.id_num + 2;825return true;826}827break;828}829830// could not find node831return false;832}833834// find index of node with lowest tentative distance (ignore visited nodes)835// returns true if successful and node_idx argument is updated836bool AP_OADijkstra::find_closest_node_idx(node_index &node_idx) const837{838node_index lowest_idx = 0;839float lowest_dist = FLT_MAX;840841// scan through all nodes looking for closest842for (node_index i=0; i<_short_path_data_numpoints; i++) {843const ShortPathNode &node = _short_path_data[i];844if (node.visited || is_equal(_short_path_data[i].distance_cm, FLT_MAX)) {845// if node is already visited OR cannot be reached yet, we can't use it846continue;847}848// figure out the pos of this node849Vector2f node_pos;850float dist_with_heuristics = FLT_MAX;851if (convert_node_to_point(node.id, node_pos)) {852// heuristics is is simple Euclidean distance from the node to the destination853// This should be admissible, therefore optimal path is guaranteed854const float heuristics = (node_pos-_path_destination).length();855dist_with_heuristics = node.distance_cm + heuristics;856} else {857// shouldn't happen858return false;859}860if (dist_with_heuristics < lowest_dist) {861// for NOW, this is the closest node862lowest_idx = i;863lowest_dist = dist_with_heuristics;864}865}866867if (lowest_dist < FLT_MAX) {868// found the closest node869node_idx = lowest_idx;870return true;871}872return false;873}874875// calculate shortest path from origin to destination876// returns true on success. returns false on failure and err_id is updated877// requires these functions to have been run: create_inclusion_polygon_with_margin, create_exclusion_polygon_with_margin, create_exclusion_circle_with_margin, create_polygon_fence_visgraph878// resulting path is stored in _shortest_path array as vector offsets from EKF origin879bool AP_OADijkstra::calc_shortest_path(const Location &origin, const Location &destination, AP_OADijkstra_Error &err_id)880{881// convert origin and destination to offsets from EKF origin882if (!origin.get_vector_xy_from_origin_NE_cm(_path_source) ||883!destination.get_vector_xy_from_origin_NE_cm(_path_destination)) {884err_id = AP_OADijkstra_Error::DIJKSTRA_ERROR_NO_POSITION_ESTIMATE;885return false;886}887888// create visgraphs of origin and destination to fence points889if (!update_visgraph(_source_visgraph, {AP_OAVisGraph::OATYPE_SOURCE, 0}, _path_source, true, _path_destination)) {890err_id = AP_OADijkstra_Error::DIJKSTRA_ERROR_OUT_OF_MEMORY;891return false;892}893if (!update_visgraph(_destination_visgraph, {AP_OAVisGraph::OATYPE_DESTINATION, 0}, _path_destination)) {894err_id = AP_OADijkstra_Error::DIJKSTRA_ERROR_OUT_OF_MEMORY;895return false;896}897898// expand _short_path_data if necessary899if (!_short_path_data.expand_to_hold(2 + total_numpoints())) {900err_id = AP_OADijkstra_Error::DIJKSTRA_ERROR_OUT_OF_MEMORY;901return false;902}903904// add origin and destination (node_type, id, visited, distance_from_idx, distance_cm) to short_path_data array905_short_path_data[0] = {{AP_OAVisGraph::OATYPE_SOURCE, 0}, false, 0, 0};906_short_path_data[1] = {{AP_OAVisGraph::OATYPE_DESTINATION, 0}, false, OA_DIJKSTRA_POLYGON_SHORTPATH_NOTSET_IDX, FLT_MAX};907_short_path_data_numpoints = 2;908909// add all inclusion and exclusion fence points to short_path_data array (node_type, id, visited, distance_from_idx, distance_cm)910for (uint8_t i=0; i<total_numpoints(); i++) {911_short_path_data[_short_path_data_numpoints++] = {{AP_OAVisGraph::OATYPE_INTERMEDIATE_POINT, i}, false, OA_DIJKSTRA_POLYGON_SHORTPATH_NOTSET_IDX, FLT_MAX};912}913914// start algorithm from source point915node_index current_node_idx = 0;916917// update nodes visible from source point918for (uint16_t i = 0; i < _source_visgraph.num_items(); i++) {919node_index node_idx;920if (find_node_from_id(_source_visgraph[i].id2, node_idx)) {921_short_path_data[node_idx].distance_cm = _source_visgraph[i].distance_cm;922_short_path_data[node_idx].distance_from_idx = current_node_idx;923} else {924err_id = AP_OADijkstra_Error::DIJKSTRA_ERROR_COULD_NOT_FIND_PATH;925return false;926}927}928// mark source node as visited929_short_path_data[current_node_idx].visited = true;930931// move current_node_idx to node with lowest distance932while (find_closest_node_idx(current_node_idx)) {933node_index dest_node;934// See if this next "closest" node is actually the destination935if (find_node_from_id({AP_OAVisGraph::OATYPE_DESTINATION,0}, dest_node) && current_node_idx == dest_node) {936// We have discovered destination.. Don't bother with the rest of the graph937break;938}939// update distances to all neighbours of current node940update_visible_node_distances(current_node_idx);941942// mark current node as visited943_short_path_data[current_node_idx].visited = true;944}945946// extract path starting from destination947bool success = false;948node_index nidx;949if (!find_node_from_id({AP_OAVisGraph::OATYPE_DESTINATION,0}, nidx)) {950err_id = AP_OADijkstra_Error::DIJKSTRA_ERROR_COULD_NOT_FIND_PATH;951return false;952}953_path_numpoints = 0;954while (true) {955if (!_path.expand_to_hold(_path_numpoints + 1)) {956err_id = AP_OADijkstra_Error::DIJKSTRA_ERROR_OUT_OF_MEMORY;957return false;958}959// fail if newest node has invalid distance_from_index960if ((_short_path_data[nidx].distance_from_idx == OA_DIJKSTRA_POLYGON_SHORTPATH_NOTSET_IDX) ||961(_short_path_data[nidx].distance_cm >= FLT_MAX)) {962break;963} else {964// add node's id to path array965_path[_path_numpoints] = _short_path_data[nidx].id;966_path_numpoints++;967968// we are done if node is the source969if (_short_path_data[nidx].id.id_type == AP_OAVisGraph::OATYPE_SOURCE) {970success = true;971break;972} else {973// follow node's "distance_from_idx" to previous node on path974nidx = _short_path_data[nidx].distance_from_idx;975}976}977}978// report error in case path not found979if (!success) {980err_id = AP_OADijkstra_Error::DIJKSTRA_ERROR_COULD_NOT_FIND_PATH;981}982983return success;984}985986// return point from final path as an offset (in cm) from the ekf origin987bool AP_OADijkstra::get_shortest_path_point(uint8_t point_num, Vector2f& pos) const988{989if ((_path_numpoints == 0) || (point_num >= _path_numpoints)) {990return false;991}992993// get id from path994AP_OAVisGraph::OAItemID id = _path[_path_numpoints - point_num - 1];995996return convert_node_to_point(id, pos);997}998999// find the position of a node as an offset (in cm) from the ekf origin1000bool AP_OADijkstra::convert_node_to_point(const AP_OAVisGraph::OAItemID& id, Vector2f& pos) const1001{1002// convert id to a position offset from EKF origin1003switch (id.id_type) {1004case AP_OAVisGraph::OATYPE_SOURCE:1005pos = _path_source;1006return true;1007case AP_OAVisGraph::OATYPE_DESTINATION:1008pos = _path_destination;1009return true;1010case AP_OAVisGraph::OATYPE_INTERMEDIATE_POINT:1011return get_point(id.id_num, pos);1012}10131014// we should never reach here but just in case1015return false;1016}1017#endif // AP_FENCE_ENABLED101810191020#endif // AP_OAPATHPLANNER_DIJKSTRA_ENABLED102110221023