ardupilot/libraries/AC_Avoidance/AP_OAPathPlanner.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

91 lines
3.4 KiB
C++

#pragma once
#include <AP_Common/AP_Common.h>
#include <AP_Common/Location.h>
#include <AP_Param/AP_Param.h>
#include <AP_HAL/AP_HAL.h>
#include "AP_OABendyRuler.h"
#include "AP_OADijkstra.h"
/*
* This class provides path planning around fence, stay-out zones and moving obstacles
*/
class AP_OAPathPlanner {
public:
AP_OAPathPlanner();
/* Do not allow copies */
AP_OAPathPlanner(const AP_OAPathPlanner &other) = delete;
AP_OAPathPlanner &operator=(const AP_OAPathPlanner&) = delete;
// get singleton instance
static AP_OAPathPlanner *get_singleton() {
return _singleton;
}
// perform any required initialisation
void init();
/// returns true if all pre-takeoff checks have completed successfully
bool pre_arm_check(char *failure_msg, uint8_t failure_msg_len) const;
// provides an alternative target location if path planning around obstacles is required
// returns true and updates result_origin and result_destination with an intermediate path
bool mission_avoidance(const Location &current_loc,
const Location &origin,
const Location &destination,
Location &result_origin,
Location &result_destination) WARN_IF_UNUSED;
// enumerations for _TYPE parameter
enum OAPathPlanTypes {
OA_PATHPLAN_DISABLED = 0,
OA_PATHPLAN_BENDYRULER = 1,
OA_PATHPLAN_DIJKSTRA = 2
};
static const struct AP_Param::GroupInfo var_info[];
private:
// avoidance thread that continually updates the avoidance_result structure based on avoidance_request
void avoidance_thread();
// an avoidance request from the navigation code
struct avoidance_info {
Location current_loc;
Location origin;
Location destination;
Vector2f ground_speed_vec;
uint32_t request_time_ms;
} avoidance_request, avoidance_request2;
// an avoidance result from the avoidance thread
struct {
Location destination; // destination vehicle is trying to get to (also used to verify the result matches a recent request)
Location origin_new; // intermediate origin. The start of line segment that vehicle should follow
Location destination_new; // intermediate destination vehicle should move towards
uint32_t result_time_ms; // system time the result was calculated (used to verify the result is recent)
bool avoidance_needed; // true if the vehicle should move along the path from origin_new to destination_new
} avoidance_result;
// parameters
AP_Int8 _type; // avoidance algorith to be used
AP_Float _lookahead; // object avoidance will look this many meters ahead of vehicle
AP_Float _margin_max; // object avoidance will ignore objects more than this many meters from vehicle
// internal variables used by front end
HAL_Semaphore_Recursive _rsem; // semaphore for multi-thread use of avoidance_request and avoidance_result
bool _thread_created; // true once background thread has been created
AP_OABendyRuler *_oabendyruler; // Bendy Ruler algorithm
AP_OADijkstra *_oadijkstra; // Dijkstra's algorithm
uint32_t _logged_time_ms; // result_time_ms of last result logged (triggers logging of new results)
static AP_OAPathPlanner *_singleton;
};
namespace AP {
AP_OAPathPlanner *ap_oapathplanner();
};