mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
AP_Compass: change fixed point format for more range
This commit is contained in:
parent
0652d71a72
commit
419f1bc00e
@ -686,8 +686,8 @@ uint16_t CompassCalibrator::get_random(void)
|
||||
//////////// CompassSample public interface //////////////
|
||||
//////////////////////////////////////////////////////////
|
||||
|
||||
#define COMPASS_CAL_SAMPLE_SCALE_TO_FIXED(__X) ((int16_t)constrain_float(roundf(__X*16.0f), INT16_MIN, INT16_MAX))
|
||||
#define COMPASS_CAL_SAMPLE_SCALE_TO_FLOAT(__X) (__X/16.0f)
|
||||
#define COMPASS_CAL_SAMPLE_SCALE_TO_FIXED(__X) ((int16_t)constrain_float(roundf(__X*8.0f), INT16_MIN, INT16_MAX))
|
||||
#define COMPASS_CAL_SAMPLE_SCALE_TO_FLOAT(__X) (__X/8.0f)
|
||||
|
||||
Vector3f CompassCalibrator::CompassSample::get() const {
|
||||
return Vector3f(COMPASS_CAL_SAMPLE_SCALE_TO_FLOAT(x),
|
||||
|
Loading…
Reference in New Issue
Block a user