ardupilot/libraries/AC_Avoidance/AP_OADijkstra.h
Randy Mackay af80070ed9 AP_OAPathPlanner: path planning around obstacles
implements both bendy ruler and dijkstra's algorithms

includes many changes after peer review including:
removed unused airspeed and turn-rate arguments
renamed constants to start with OA_BENDYRULER_
removed fence_ptr check from update function that could cause bendy ruler to fail when fences were disabled
AC_Fence's fence-margin is not used and instead we always use a hard-coded 2m limit
vehicle's heading is used instead of ground-course when speed is below 0.2m/s
static assert added to ensure OA_BENDYRULER_BERAING_INC constant is defined correctly
replace BAD_MARGIN/GOOD_MARGIN with FLT_MAX/-FLT_MAX
use calc_margin_from_xxx function's return values
calc-margin-from-proximity-sensors fails if copy-locations fails
remove debug
remove unused singletons

and other changes including:
integrate fence rename to get_boundary_points
adapt to fence return point and duplicate final point from not being returned
create bendyrule and dijkstra objects on init
add pre-arm-check to ensure they've been created successfully
Dijkstra's detects polygon fence changes
minor fix to Dijkstra's return path
allow update_visgraph to accept 0,0 as extra point

and these fixes from peer reviews:
remove unused methods
add note about dangers of operator[]
reduce memory consuption of ShortPathNode
remove unused methods including print_all_nodes and print_shortest_path
replace OA_DIJKSTRA_POLYGON_VISGRAPH_INFINITY_CM with FLT_MAX
update method gets check that ekf origin has been set
fix indexing bug in inner fence creation
fix whitespace error
find-node-from-id uses switch statement instead of 3 IF statements
update_visgraph comments added to clarify usage of extra_position argument
find-closest-node-idx always uses node_index instead of int16_t
static assert that OA_DIJKSTRA_POLYGON_FENCE_PTS < 255
some looping style changes
AP_OABendyRuler: fix to ground course calculation
AP_OAPathPlanner: pre_arm_check writes to caller's buffer
remove unnecessary hal and stdio.h includes
rename fence_ptr local variable to fence
add sanity check to OADijkstra's set_fence_margin
add sanity check to OABendyRuler's set_config
BendyRuler's test_bearing local constants changed to be float constants
BendyRuler's ahrs_home made local constant
BendyRuler's proximity margin calcs lose margin_found local variable (use FLT_MAX instead)
BendyRuler's calc-margin-from-circular-fence performance improvement by removing one sqrt
AP_OABendyRuler: fix probe directions to be 5deg offsets from dir to destination
AP_OADijkstra: fixes after peer review
remove unnecesary initialisations
replace safe_sqrt(sq()) with length()
remove unnecessary block
comment fixes
AP_OAPathPlanner: add logging of final an intermediate location
2019-06-11 13:13:22 +09:00

107 lines
5.4 KiB
C++

#pragma once
#include <AP_Common/AP_Common.h>
#include <AP_Common/Location.h>
#include <AP_Math/AP_Math.h>
#include <AP_HAL/AP_HAL.h>
#include "AP_OAVisGraph.h"
#define OA_DIJKSTRA_POLYGON_FENCE_PTS 20 // algorithm can handle up to this many polygon fence points
#define OA_DIJKSTRA_POLYGON_SHORTPATH_PTS OA_DIJKSTRA_POLYGON_FENCE_PTS+1 // return path can have up to this many destinations
/*
* Dijkstra's algorithm for path planning around polygon fence
*/
class AP_OADijkstra {
public:
AP_OADijkstra();
/* Do not allow copies */
AP_OADijkstra(const AP_OADijkstra &other) = delete;
AP_OADijkstra &operator=(const AP_OADijkstra&) = delete;
// set fence margin (in meters) used when creating "safe positions" within the polygon fence
void set_fence_margin(float margin) { _polyfence_margin = MAX(margin, 0.0f); }
// calculate a destination to avoid the polygon fence
// returns true if avoidance is required and target destination is placed in result_loc
bool update(const Location &current_loc, const Location &destination, Location& origin_new, Location& destination_new);
private:
// check if polygon fence has been updated since we created the inner fence. returns true if changed
bool check_polygon_fence_updated() const;
// create a smaller polygon fence within the existing polygon fence
// returns true on success
bool create_polygon_fence_with_margin(float margin_cm);
// create a visibility graph of the polygon fence
// returns true on success
// requires create_polygon_fence_with_margin to have been run
bool create_polygon_fence_visgraph();
// calculate shortest path from origin to destination
// returns true on success
// requires create_polygon_fence_with_margin and create_polygon_fence_visgraph to have been run
// resulting path is stored in _shortest_path array as vector offsets from EKF origin
bool calc_shortest_path(const Location &origin, const Location &destination);
// shortest path state variables
bool _polyfence_with_margin_ok;
bool _polyfence_visgraph_ok;
bool _shortest_path_ok;
Location _destination_prev; // destination of previous iterations (used to determine if path should be re-calculated)
uint8_t _path_idx_returned; // index into _path array which gives location vehicle should be currently moving towards
// polygon fence (with margin) related variables
float _polyfence_margin = 10;
Vector2f _polyfence_pts[OA_DIJKSTRA_POLYGON_FENCE_PTS];
uint8_t _polyfence_numpoints;
uint32_t _polyfence_update_ms; // system time of boundary update from AC_Fence (used to detect changes to polygon fence)
// visibility graphs
AP_OAVisGraph _polyfence_visgraph;
AP_OAVisGraph _source_visgraph;
AP_OAVisGraph _destination_visgraph;
// updates visibility graph for a given position which is an offset (in cm) from the ekf origin
// to add an additional position (i.e. the destination) set add_extra_position = true and provide the position in the extra_position argument
// requires create_polygon_fence_with_margin to have been run
// returns true on success
bool update_visgraph(AP_OAVisGraph& visgraph, const AP_OAVisGraph::OAItemID& oaid, const Vector2f &position, bool add_extra_position = false, Vector2f extra_position = Vector2f(0,0));
typedef uint8_t node_index; // indices into short path data
struct ShortPathNode {
AP_OAVisGraph::OAItemID id; // unique id for node (combination of type and id number)
bool visited; // true if all this node's neighbour's distances have been updated
node_index distance_from_idx; // index into _short_path_data from where distance was updated (or 255 if not set)
float distance_cm; // distance from source (number is tentative until this node is the current node and/or visited = true)
} _short_path_data[OA_DIJKSTRA_POLYGON_SHORTPATH_PTS];
node_index _short_path_data_numpoints; // number of elements in _short_path_data array
// update total distance for all nodes visible from current node
// curr_node_idx is an index into the _short_path_data array
void update_visible_node_distances(node_index curr_node_idx);
// find a node's index into _short_path_data array from it's id (i.e. id type and id number)
// returns true if successful and node_idx is updated
bool find_node_from_id(const AP_OAVisGraph::OAItemID &id, node_index &node_idx) const;
// find index of node with lowest tentative distance (ignore visited nodes)
// returns true if successful and node_idx argument is updated
bool find_closest_node_idx(node_index &node_idx) const;
// final path variables and functions
AP_OAVisGraph::OAItemID _path[OA_DIJKSTRA_POLYGON_SHORTPATH_PTS]; // ids of points on return path in reverse order (i.e. destination is first element)
uint8_t _path_numpoints; // number of points on return path
Vector2f _path_source; // source point used in shortest path calculations (offset in cm from EKF origin)
Vector2f _path_destination; // destination position used in shortest path calculations (offset in cm from EKF origin)
// return point from final path as an offset (in cm) from the ekf origin
bool get_shortest_path_point(uint8_t point_num, Vector2f& pos);
};