mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-30 20:48:33 -04:00
AC_Avoid: Mark OA_OPTIONS as a Rover-Only param
This commit is contained in:
parent
cb034c50a7
commit
68b6ecc59c
@ -25,9 +25,7 @@ extern const AP_HAL::HAL &hal;
|
||||
|
||||
// parameter defaults
|
||||
const float OA_MARGIN_MAX_DEFAULT = 5;
|
||||
#if APM_BUILD_TYPE(APM_BUILD_Rover)
|
||||
const int16_t OA_OPTIONS_DEFAULT = 1;
|
||||
#endif
|
||||
const int16_t OA_OPTIONS_DEFAULT = 1;
|
||||
|
||||
const int16_t OA_UPDATE_MS = 1000; // path planning updates run at 1hz
|
||||
const int16_t OA_TIMEOUT_MS = 3000; // results over 3 seconds old are ignored
|
||||
@ -57,15 +55,13 @@ const AP_Param::GroupInfo AP_OAPathPlanner::var_info[] = {
|
||||
// @Path: AP_OADatabase.cpp
|
||||
AP_SUBGROUPINFO(_oadatabase, "DB_", 4, AP_OAPathPlanner, AP_OADatabase),
|
||||
|
||||
#if APM_BUILD_TYPE(APM_BUILD_Rover)
|
||||
// @Param: OPTIONS
|
||||
// @Param{Rover}: OPTIONS
|
||||
// @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).
|
||||
// @Values: 0:Vehicle will return to its original waypoint trajectory, 1:Reset the origin of the waypoint to the present location
|
||||
// @Bitmask: 0: Reset the origin of the waypoint to the present location
|
||||
// @User: Standard
|
||||
AP_GROUPINFO("OPTIONS", 5, AP_OAPathPlanner, _options, OA_OPTIONS_DEFAULT),
|
||||
#endif
|
||||
AP_GROUPINFO_FRAME("OPTIONS", 5, AP_OAPathPlanner, _options, OA_OPTIONS_DEFAULT, AP_PARAM_FRAME_ROVER),
|
||||
|
||||
// @Group: BR_
|
||||
// @Path: AP_OABendyRuler.cpp
|
||||
|
Loading…
Reference in New Issue
Block a user