mirror of https://github.com/ArduPilot/ardupilot
AP_Proximity: Change min and max range to support both 60m and 600Hz
This commit is contained in:
parent
f6dc6edc04
commit
5a5fdf9c79
|
@ -74,11 +74,11 @@ void AP_Proximity_TeraRangerTowerEvo::update(void)
|
|||
// get maximum and minimum distances (in meters) of primary sensor
|
||||
float AP_Proximity_TeraRangerTowerEvo::distance_max() const
|
||||
{
|
||||
return 8.0f;
|
||||
return 60.0f;
|
||||
}
|
||||
float AP_Proximity_TeraRangerTowerEvo::distance_min() const
|
||||
{
|
||||
return 0.75f;
|
||||
return 0.50f;
|
||||
}
|
||||
|
||||
void AP_Proximity_TeraRangerTowerEvo::initialise_modes()
|
||||
|
|
Loading…
Reference in New Issue