mirror of https://github.com/ArduPilot/ardupilot
Rover: call send-water-depth
This commit is contained in:
parent
3900a4f14a
commit
8c5eecf84e
|
@ -76,6 +76,9 @@ void Rover::Log_Write_Depth()
|
|||
loc.lng,
|
||||
(double)(rangefinder.distance_cm_orient(ROTATION_PITCH_270) * 0.01f),
|
||||
temp_C);
|
||||
|
||||
// send water depth and temp to ground station
|
||||
gcs().send_message(MSG_WATER_DEPTH);
|
||||
}
|
||||
|
||||
// guided mode logging
|
||||
|
|
Loading…
Reference in New Issue