ardupilot/libraries/AC_Avoidance/AP_OABendyRuler.h

88 lines
4.8 KiB
C
Raw Normal View History

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-05-10 02:59:31 -03:00
#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>
/*
* BendyRuler avoidance algorithm for avoiding the polygon and circular fence and dynamic objects detected by the proximity sensor
*/
class AP_OABendyRuler {
public:
AP_OABendyRuler();
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-05-10 02:59:31 -03:00
/* Do not allow copies */
AP_OABendyRuler(const AP_OABendyRuler &other) = delete;
AP_OABendyRuler &operator=(const AP_OABendyRuler&) = delete;
// send configuration info stored in front end parameters
void set_config(float margin_max) { _margin_max = MAX(margin_max, 0.0f); }
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-05-10 02:59:31 -03:00
// run background task to find best path and update avoidance_results
// returns true and populates origin_new and destination_new if OA is required. returns false if OA is not required
bool update(const Location& current_loc, const Location& destination, const Vector2f &ground_speed_vec, Location &origin_new, Location &destination_new, bool proximity_only);
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-05-10 02:59:31 -03:00
enum class OABendyType {
OA_BENDY_DISABLED = 0,
OA_BENDY_HORIZONTAL = 1,
OA_BENDY_VERTICAL = 2,
};
// return type of BendyRuler in use
OABendyType get_type() const;
// search for path in XY direction
bool search_xy_path(const Location& current_loc, const Location& destination, float ground_course_deg, Location &destination_new, float lookahead_step_1_dist, float lookahead_step_2_dist, float bearing_to_dest, float distance_to_dest, bool proximity_only);
// search for path in the Vertical directions
bool search_vertical_path(const Location& current_loc, const Location& destination,Location &destination_new, const float &lookahead_step1_dist, const float &lookahead_step2_dist, const float &bearing_to_dest, const float &distance_to_dest, bool proximity_only);
static const struct AP_Param::GroupInfo var_info[];
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-05-10 02:59:31 -03:00
private:
// calculate minimum distance between a path and any obstacle
float calc_avoidance_margin(const Location &start, const Location &end, bool proximity_only) const;
// determine if BendyRuler should accept the new bearing or try and resist it. Returns true if bearing is not changed
bool resist_bearing_change(const Location &destination, const Location &current_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) const;
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-05-10 02:59:31 -03:00
// calculate minimum distance between a path and the circular fence (centered on home)
// on success returns true and updates margin
bool calc_margin_from_circular_fence(const Location &start, const Location &end, float &margin) const;
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-05-10 02:59:31 -03:00
// calculate minimum distance between a path and the altitude fence
// on success returns true and updates margin
bool calc_margin_from_alt_fence(const Location &start, const Location &end, float &margin) const;
// calculate minimum distance between a path and all inclusion and exclusion polygons
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-05-10 02:59:31 -03:00
// on success returns true and updates margin
bool calc_margin_from_inclusion_and_exclusion_polygons(const Location &start, const Location &end, float &margin) const;
// calculate minimum distance between a path and all inclusion and exclusion circles
// on success returns true and updates margin
bool calc_margin_from_inclusion_and_exclusion_circles(const Location &start, const Location &end, float &margin) const;
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-05-10 02:59:31 -03:00
// calculate minimum distance between a path and proximity sensor obstacles
// on success returns true and updates margin
bool calc_margin_from_object_database(const Location &start, const Location &end, float &margin) const;
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-05-10 02:59:31 -03:00
2021-01-22 03:23:53 -04:00
// Logging function
void Write_OABendyRuler(const uint8_t type, const bool active, const float target_yaw, const float target_pitch, const bool resist_chg, const float margin, const Location &final_dest, const Location &oa_dest) const;
// OA common parameters
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-05-10 02:59:31 -03:00
float _margin_max; // object avoidance will ignore objects more than this many meters from vehicle
// BendyRuler parameters
AP_Float _lookahead; // object avoidance will look this many meters ahead of vehicle
AP_Float _bendy_ratio; // object avoidance will avoid major directional change if change in margin ratio is less than this param
AP_Int16 _bendy_angle; // object avoidance will try avoding change in direction over this much angle
AP_Int8 _bendy_type; // Type of BendyRuler to run
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-05-10 02:59:31 -03:00
// internal variables used by background thread
float _current_lookahead; // distance (in meters) ahead of the vehicle we are looking for obstacles
float _bearing_prev; // stored bearing in degrees
Location _destination_prev; // previous destination, to check if there has been a change in destination
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-05-10 02:59:31 -03:00
};