diff --git a/libraries/AC_Avoidance/AP_OAPathPlanner.cpp b/libraries/AC_Avoidance/AP_OAPathPlanner.cpp index 81ee6b49a7f370..b81d28248a0326 100644 --- a/libraries/AC_Avoidance/AP_OAPathPlanner.cpp +++ b/libraries/AC_Avoidance/AP_OAPathPlanner.cpp @@ -59,7 +59,7 @@ const AP_Param::GroupInfo AP_OAPathPlanner::var_info[] = { // @DisplayName: Options while recovering from Object Avoidance // @Description: Bitmask which will govern vehicles behaviour while recovering from Obstacle Avoidance (i.e Avoidance is turned off after the path ahead is clear). // @Bitmask{Rover}: 0: Reset the origin of the waypoint to the present location, 1: log Dijkstra points - // @Bitmask{Copter}: 1: log Dijkstra points + // @Bitmask{Copter}: 1:log Dijkstra points, 2:Allow fast waypoints (Dijkastras only) // @User: Standard AP_GROUPINFO("OPTIONS", 5, AP_OAPathPlanner, _options, OA_OPTIONS_DEFAULT), diff --git a/libraries/AC_Avoidance/AP_OAPathPlanner.h b/libraries/AC_Avoidance/AP_OAPathPlanner.h index 21c3530fd3b90a..a8e813d5acae7e 100644 --- a/libraries/AC_Avoidance/AP_OAPathPlanner.h +++ b/libraries/AC_Avoidance/AP_OAPathPlanner.h @@ -74,6 +74,7 @@ class AP_OAPathPlanner { OA_OPTION_DISABLED = 0, OA_OPTION_WP_RESET = (1 << 0), OA_OPTION_LOG_DIJKSTRA_POINTS = (1 << 1), + OA_OPTION_FAST_WAYPOINTS = (1 << 2), }; uint16_t get_options() const { return _options;}