Path: blob/master/libraries/AC_Avoidance/AP_OADijkstra.h
4182 views
#pragma once12#include "AC_Avoidance_config.h"34#if AP_OAPATHPLANNER_DIJKSTRA_ENABLED56#include <AP_Common/AP_Common.h>7#include <AP_Common/Location.h>8#include <AP_Math/AP_Math.h>9#include "AP_OAVisGraph.h"10#include <AP_Logger/AP_Logger_config.h>1112/*13* Dijkstra's algorithm for path planning around polygon fence14*/1516class AP_OADijkstra {17public:1819AP_OADijkstra(AP_Int16 &options);2021CLASS_NO_COPY(AP_OADijkstra); /* Do not allow copies */2223// set fence margin (in meters) used when creating "safe positions" within the polygon fence24void set_fence_margin(float margin) { _polyfence_margin = MAX(margin, 0.0f); }2526// trigger Dijkstra's to recalculate shortest path based on current location27void recalculate_path() { _shortest_path_ok = false; }2829// update return status enum30enum AP_OADijkstra_State : uint8_t {31DIJKSTRA_STATE_NOT_REQUIRED = 0,32DIJKSTRA_STATE_ERROR,33DIJKSTRA_STATE_SUCCESS34};3536// calculate a destination to avoid the polygon fence37// returns DIJKSTRA_STATE_SUCCESS and populates origin_new, destination_new and next_destination_new if avoidance is required38// next_destination_new will be non-zero if there is a next destination39// dest_to_next_dest_clear will be set to true if the path from (the input) destination to (input) next_destination is clear40AP_OADijkstra_State update(const Location ¤t_loc,41const Location &destination,42const Location &next_destination,43Location& origin_new,44Location& destination_new,45Location& next_destination_new,46bool& dest_to_next_dest_clear);4748private:4950// returns true if at least one inclusion or exclusion zone is enabled51bool some_fences_enabled() const;5253enum class AP_OADijkstra_Error : uint8_t {54DIJKSTRA_ERROR_NONE = 0,55DIJKSTRA_ERROR_OUT_OF_MEMORY,56DIJKSTRA_ERROR_OVERLAPPING_POLYGON_POINTS,57DIJKSTRA_ERROR_FAILED_TO_BUILD_INNER_POLYGON,58DIJKSTRA_ERROR_OVERLAPPING_POLYGON_LINES,59DIJKSTRA_ERROR_FENCE_DISABLED,60DIJKSTRA_ERROR_TOO_MANY_FENCE_POINTS,61DIJKSTRA_ERROR_NO_POSITION_ESTIMATE,62DIJKSTRA_ERROR_COULD_NOT_FIND_PATH63} _error_id;6465// return error message for a given error id66const char* get_error_msg(AP_OADijkstra_Error error_id) const;6768// report error to ground station69void report_error(AP_OADijkstra_Error error_id);7071//72// inclusion polygon methods73//7475// check if inclusion polygons have been updated since create_inclusion_polygon_with_margin was run76// returns true if changed77bool check_inclusion_polygon_updated() const;7879// create polygons inside the existing inclusion polygons80// returns true on success. returns false on failure and err_id is updated81bool create_inclusion_polygon_with_margin(float margin_cm, AP_OADijkstra_Error &err_id);8283//84// exclusion polygon methods85//8687// check if exclusion polygons have been updated since create_exclusion_polygon_with_margin was run88// returns true if changed89bool check_exclusion_polygon_updated() const;9091// create polygons around existing exclusion polygons92// returns true on success. returns false on failure and err_id is updated93bool create_exclusion_polygon_with_margin(float margin_cm, AP_OADijkstra_Error &err_id);9495//96// exclusion circle methods97//9899// check if exclusion circles have been updated since create_exclusion_circle_with_margin was run100// returns true if changed101bool check_exclusion_circle_updated() const;102103// create polygons around existing exclusion circles104// returns true on success. returns false on failure and err_id is updated105bool create_exclusion_circle_with_margin(float margin_cm, AP_OADijkstra_Error &err_id);106107//108// other methods109//110111// returns total number of points across all fence types112uint16_t total_numpoints() const;113114// get a single point across the total list of points from all fence types115// also returns the type of point116bool get_point(uint16_t index, Vector2f& point) const;117118// returns true if line segment intersects polygon or circular fence119bool intersects_fence(const Vector2f &seg_start, const Vector2f &seg_end) const;120121// create visibility graph for all fence (with margin) points122// returns true on success. returns false on failure and err_id is updated123bool create_fence_visgraph(AP_OADijkstra_Error &err_id);124125// calculate shortest path from origin to destination126// returns true on success. returns false on failure and err_id is updated127// requires create_polygon_fence_with_margin and create_polygon_fence_visgraph to have been run128// resulting path is stored in _shortest_path array as vector offsets from EKF origin129bool calc_shortest_path(const Location &origin, const Location &destination, AP_OADijkstra_Error &err_id);130131// shortest path state variables132bool _inclusion_polygon_with_margin_ok;133bool _exclusion_polygon_with_margin_ok;134bool _exclusion_circle_with_margin_ok;135bool _polyfence_visgraph_ok;136bool _shortest_path_ok;137138Location _destination_prev; // destination of previous iterations (used to determine if path should be re-calculated)139Location _next_destination_prev;// next_destination of previous iterations (used to determine if path should be re-calculated)140uint8_t _path_idx_returned; // index into _path array which gives location vehicle should be currently moving towards141bool _dest_to_next_dest_clear; // true if path from dest to next_dest is clear (i.e. does not intersects a fence)142143// inclusion polygon (with margin) related variables144float _polyfence_margin = 10; // margin around polygon defaults to 10m but is overriden with set_fence_margin145AP_ExpandingArray<Vector2f> _inclusion_polygon_pts; // array of nodes corresponding to inclusion polygon points plus a margin146uint8_t _inclusion_polygon_numpoints; // number of points held in above array147uint32_t _inclusion_polygon_update_ms; // system time of boundary update from AC_Fence (used to detect changes to polygon fence)148149// exclusion polygon related variables150AP_ExpandingArray<Vector2f> _exclusion_polygon_pts; // array of nodes corresponding to exclusion polygon points plus a margin151uint8_t _exclusion_polygon_numpoints; // number of points held in above array152uint32_t _exclusion_polygon_update_ms; // system time exclusion polygon was updated (used to detect changes)153154// exclusion circle related variables155AP_ExpandingArray<Vector2f> _exclusion_circle_pts; // array of nodes surrounding exclusion circles plus a margin156uint8_t _exclusion_circle_numpoints; // number of points held in above array157uint32_t _exclusion_circle_update_ms; // system time exclusion circles were updated (used to detect changes)158159// visibility graphs160AP_OAVisGraph _fence_visgraph; // holds distances between all inclusion/exclusion fence points (with margin)161AP_OAVisGraph _source_visgraph; // holds distances from source point to all other nodes162AP_OAVisGraph _destination_visgraph; // holds distances from the destination to all other nodes163164// updates visibility graph for a given position which is an offset (in cm) from the ekf origin165// to add an additional position (i.e. the destination) set add_extra_position = true and provide the position in the extra_position argument166// requires create_polygon_fence_with_margin to have been run167// returns true on success168bool update_visgraph(AP_OAVisGraph& visgraph, const AP_OAVisGraph::OAItemID& oaid, const Vector2f &position, bool add_extra_position = false, Vector2f extra_position = Vector2f(0,0));169170typedef uint8_t node_index; // indices into short path data171struct ShortPathNode {172AP_OAVisGraph::OAItemID id; // unique id for node (combination of type and id number)173bool visited; // true if all this node's neighbour's distances have been updated174node_index distance_from_idx; // index into _short_path_data from where distance was updated (or 255 if not set)175float distance_cm; // distance from source (number is tentative until this node is the current node and/or visited = true)176};177AP_ExpandingArray<ShortPathNode> _short_path_data;178node_index _short_path_data_numpoints; // number of elements in _short_path_data array179180// update total distance for all nodes visible from current node181// curr_node_idx is an index into the _short_path_data array182void update_visible_node_distances(node_index curr_node_idx);183184// find a node's index into _short_path_data array from it's id (i.e. id type and id number)185// returns true if successful and node_idx is updated186bool find_node_from_id(const AP_OAVisGraph::OAItemID &id, node_index &node_idx) const;187188// find index of node with lowest tentative distance (ignore visited nodes)189// returns true if successful and node_idx argument is updated190bool find_closest_node_idx(node_index &node_idx) const;191192// final path variables and functions193AP_ExpandingArray<AP_OAVisGraph::OAItemID> _path; // ids of points on return path in reverse order (i.e. destination is first element)194uint8_t _path_numpoints; // number of points on return path195Vector2f _path_source; // source point used in shortest path calculations (offset in cm from EKF origin)196Vector2f _path_destination; // destination position used in shortest path calculations (offset in cm from EKF origin)197198// return number of points on path199uint8_t get_shortest_path_numpoints() const { return _path_numpoints; }200201// return point from final path as an offset (in cm) from the ekf origin202bool get_shortest_path_point(uint8_t point_num, Vector2f& pos) const;203204// find the position of a node as an offset (in cm) from the ekf origin205// returns true if successful and pos is updated206bool convert_node_to_point(const AP_OAVisGraph::OAItemID& id, Vector2f& pos) const;207208AP_OADijkstra_Error _error_last_id; // last error id sent to GCS209uint32_t _error_last_report_ms; // last time an error message was sent to GCS210211#if HAL_LOGGING_ENABLED212// Logging functions213void Write_OADijkstra(const uint8_t state, const uint8_t error_id, const uint8_t curr_point, const uint8_t tot_points, const Location &final_dest, const Location &oa_dest) const;214void Write_Visgraph_point(const uint8_t version, const uint8_t point_num, const int32_t Lat, const int32_t Lon) const;215#else216void Write_OADijkstra(const uint8_t state, const uint8_t error_id, const uint8_t curr_point, const uint8_t tot_points, const Location &final_dest, const Location &oa_dest) const {}217void Write_Visgraph_point(const uint8_t version, const uint8_t point_num, const int32_t Lat, const int32_t Lon) const {}218#endif219uint8_t _log_num_points;220uint8_t _log_visgraph_version;221222// reference to AP_OAPathPlanner options param223AP_Int16 &_options;224};225226#endif // AP_OAPATHPLANNER_DIJKSTRA_ENABLED227228229