mirror of https://github.com/ArduPilot/ardupilot
AC_Avoidance: oapathplanner gets fast-waypoint option
This commit is contained in:
parent
607fa40431
commit
58b6429893
|
@ -59,7 +59,7 @@ const AP_Param::GroupInfo AP_OAPathPlanner::var_info[] = {
|
||||||
// @DisplayName: Options while recovering from Object Avoidance
|
// @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).
|
// @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{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
|
// @User: Standard
|
||||||
AP_GROUPINFO("OPTIONS", 5, AP_OAPathPlanner, _options, OA_OPTIONS_DEFAULT),
|
AP_GROUPINFO("OPTIONS", 5, AP_OAPathPlanner, _options, OA_OPTIONS_DEFAULT),
|
||||||
|
|
||||||
|
|
|
@ -74,6 +74,7 @@ public:
|
||||||
OA_OPTION_DISABLED = 0,
|
OA_OPTION_DISABLED = 0,
|
||||||
OA_OPTION_WP_RESET = (1 << 0),
|
OA_OPTION_WP_RESET = (1 << 0),
|
||||||
OA_OPTION_LOG_DIJKSTRA_POINTS = (1 << 1),
|
OA_OPTION_LOG_DIJKSTRA_POINTS = (1 << 1),
|
||||||
|
OA_OPTION_FAST_WAYPOINTS = (1 << 2),
|
||||||
};
|
};
|
||||||
|
|
||||||
uint16_t get_options() const { return _options;}
|
uint16_t get_options() const { return _options;}
|
||||||
|
|
Loading…
Reference in New Issue