AC_Avoid: Change parameter defaults

This commit is contained in:
Rishabh 2021-04-04 12:16:42 +05:30 committed by Randy Mackay
parent 1dc67fb932
commit e31ea2f3ee
2 changed files with 3 additions and 3 deletions

View File

@ -78,7 +78,7 @@ const AP_Param::GroupInfo AC_Avoid::var_info[] = {
// @Units: m/s // @Units: m/s
// @Range: 0 2 // @Range: 0 2
// @User: Standard // @User: Standard
AP_GROUPINFO("BACKUP_SPD", 6, AC_Avoid, _backup_speed_max, 0.5f), AP_GROUPINFO("BACKUP_SPD", 6, AC_Avoid, _backup_speed_max, 0.75f),
// @Param: ALT_MIN // @Param: ALT_MIN
// @DisplayName: Avoidance minimum altitude // @DisplayName: Avoidance minimum altitude
@ -86,7 +86,7 @@ const AP_Param::GroupInfo AC_Avoid::var_info[] = {
// @Units: m // @Units: m
// @Range: 0 6 // @Range: 0 6
// @User: Standard // @User: Standard
AP_GROUPINFO("ALT_MIN", 7, AC_Avoid, _alt_min, 2.0f), AP_GROUPINFO("ALT_MIN", 7, AC_Avoid, _alt_min, 0.0f),
// @Param: ACCEL_MAX // @Param: ACCEL_MAX
// @DisplayName: Avoidance maximum acceleration // @DisplayName: Avoidance maximum acceleration

View File

@ -100,7 +100,7 @@ const AP_Param::GroupInfo AP_OADatabase::var_info[] = {
// @Units: m // @Units: m
// @Range: 0 4 // @Range: 0 4
// @User: Advanced // @User: Advanced
AP_GROUPINFO_FRAME("ALT_MIN", 8, AP_OADatabase, _min_alt, 2.0f, AP_PARAM_FRAME_COPTER | AP_PARAM_FRAME_HELI | AP_PARAM_FRAME_TRICOPTER), AP_GROUPINFO_FRAME("ALT_MIN", 8, AP_OADatabase, _min_alt, 0.0f, AP_PARAM_FRAME_COPTER | AP_PARAM_FRAME_HELI | AP_PARAM_FRAME_TRICOPTER),
AP_GROUPEND AP_GROUPEND
}; };