mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 15:23:57 -04:00
AP_Proximity: Change parameter defaults
This commit is contained in:
parent
45477f6063
commit
1dc67fb932
@ -157,7 +157,7 @@ const AP_Param::GroupInfo AP_Proximity::var_info[] = {
|
||||
// @Description: Ignore proximity data that is within 1 meter of the ground below the vehicle. This requires a downward facing rangefinder
|
||||
// @Values: 0:Disabled, 1:Enabled
|
||||
// @User: Standard
|
||||
AP_GROUPINFO_FRAME("_IGN_GND", 16, AP_Proximity, _ign_gnd_enable, 1, AP_PARAM_FRAME_COPTER | AP_PARAM_FRAME_HELI | AP_PARAM_FRAME_TRICOPTER),
|
||||
AP_GROUPINFO_FRAME("_IGN_GND", 16, AP_Proximity, _ign_gnd_enable, 0, AP_PARAM_FRAME_COPTER | AP_PARAM_FRAME_HELI | AP_PARAM_FRAME_TRICOPTER),
|
||||
|
||||
// @Param: _LOG_RAW
|
||||
// @DisplayName: Proximity raw distances log
|
||||
|
Loading…
Reference in New Issue
Block a user