mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_WheelEncoder: Fix integer division limiting wheel encoder accuracy
CID: 318646
This commit is contained in:
parent
c712e926d7
commit
b38200a960
@ -269,7 +269,7 @@ float AP_WheelEncoder::get_rate(uint8_t instance) const
|
|||||||
}
|
}
|
||||||
|
|
||||||
// calculate delta_angle (in radians) per second
|
// calculate delta_angle (in radians) per second
|
||||||
return M_2PI * (state[instance].dist_count_change / _counts_per_revolution[instance]) / (state[instance].dt_ms / 1000.0f);
|
return M_2PI * (state[instance].dist_count_change / ((float)_counts_per_revolution[instance])) / (state[instance].dt_ms * 1e-3f);
|
||||||
}
|
}
|
||||||
|
|
||||||
// get the total number of sensor reading from the encoder
|
// get the total number of sensor reading from the encoder
|
||||||
|
Loading…
Reference in New Issue
Block a user