mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-02 14:08:45 -04:00
Rover: DPTH message only written if range finder last read time changed
This commit is contained in:
parent
1b0f0a7559
commit
88a230e897
@ -60,6 +60,13 @@ void Rover::Log_Write_Depth()
|
||||
return;
|
||||
}
|
||||
|
||||
// check if new sensor reading has arrived
|
||||
uint32_t reading_ms = rangefinder.last_reading_ms(ROTATION_PITCH_270);
|
||||
if (reading_ms == rangefinder_last_reading_ms) {
|
||||
return;
|
||||
}
|
||||
rangefinder_last_reading_ms = reading_ms;
|
||||
|
||||
DataFlash.Log_Write("DPTH", "TimeUS,Lat,Lng,Depth",
|
||||
"sDUm", "FGG0", "QLLf",
|
||||
AP_HAL::micros64(),
|
||||
|
@ -280,6 +280,9 @@ private:
|
||||
uint32_t detected_time_ms;
|
||||
} obstacle;
|
||||
|
||||
// range finder last update (used for DPTH logging)
|
||||
uint32_t rangefinder_last_reading_ms;
|
||||
|
||||
// Ground speed
|
||||
// The amount current ground speed is below min ground speed. meters per second
|
||||
float ground_speed;
|
||||
|
Loading…
Reference in New Issue
Block a user