mirror of https://github.com/ArduPilot/ardupilot
AP_WheelEncoder: fix WheelEncoder_Quadrature timestamp.
Convert timestamp to ms from us.
This commit is contained in:
parent
38bbb2361e
commit
6f7abab036
|
@ -138,5 +138,5 @@ void AP_WheelEncoder_Quadrature::irq_handler(uint8_t pin,
|
||||||
update_phase_and_error_count();
|
update_phase_and_error_count();
|
||||||
|
|
||||||
// record update time
|
// record update time
|
||||||
irq_state.last_reading_ms = timestamp;
|
irq_state.last_reading_ms = timestamp * 1e-3f;
|
||||||
}
|
}
|
||||||
|
|
Loading…
Reference in New Issue