AP_InertialSensor: return floats from raw-sample-rate getters

The underlying type changed at some stage but the getters did not
This commit is contained in:
Peter Barker 2019-04-04 16:00:04 +11:00 committed by Andrew Tridgell
parent 4f29d2e5a6
commit e0fc73776c
1 changed files with 7 additions and 5 deletions

View File

@ -183,22 +183,24 @@ protected:
// set accelerometer max absolute offset for calibration
void _set_accel_max_abs_offset(uint8_t instance, float offset);
// get accelerometer raw sample rate
uint32_t _accel_raw_sample_rate(uint8_t instance) const {
// get accelerometer raw sample rate.
float _accel_raw_sample_rate(uint8_t instance) const {
return _imu._accel_raw_sample_rates[instance];
}
// set accelerometer raw sample rate
// set accelerometer raw sample rate; note that the storage type
// is actually float!
void _set_accel_raw_sample_rate(uint8_t instance, uint16_t rate_hz) {
_imu._accel_raw_sample_rates[instance] = rate_hz;
}
// get gyroscope raw sample rate
uint32_t _gyro_raw_sample_rate(uint8_t instance) const {
float _gyro_raw_sample_rate(uint8_t instance) const {
return _imu._gyro_raw_sample_rates[instance];
}
// set gyro raw sample rate
// set gyro raw sample rate; note that the storage type is
// actually float!
void _set_gyro_raw_sample_rate(uint8_t instance, uint16_t rate_hz) {
_imu._gyro_raw_sample_rates[instance] = rate_hz;
}