mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Rover: make rangefinder ranges m rather than cm
This commit is contained in:
parent
013de11916
commit
2f56ac45ab
@ -81,7 +81,7 @@ void Rover::Log_Write_Depth()
|
|||||||
i,
|
i,
|
||||||
loc.lat,
|
loc.lat,
|
||||||
loc.lng,
|
loc.lng,
|
||||||
(double)(s->distance_cm() * 0.01f),
|
(double)(s->distance()),
|
||||||
temp_C);
|
temp_C);
|
||||||
}
|
}
|
||||||
// send water depth and temp to ground station
|
// send water depth and temp to ground station
|
||||||
|
Loading…
Reference in New Issue
Block a user