AHRS: removed constrain() defines

This commit is contained in:
Andrew Tridgell 2012-12-07 12:33:50 +11:00
parent 09e7b0b592
commit 5840ded767
3 changed files with 0 additions and 4 deletions

View File

@ -87,7 +87,6 @@ bool AP_AHRS::airspeed_estimate(float *airspeed_ret)
if (_wind_max > 0 && _gps && _gps->status() == GPS::GPS_OK) {
// constrain the airspeed by the ground speed
// and AHRS_WIND_MAX
#define constrain(amt,low,high) ((amt)<(low)?(low):((amt)>(high)?(high):(amt)))
*airspeed_ret = constrain(*airspeed_ret,
_gps->ground_speed*0.01 - _wind_max,
_gps->ground_speed*0.01 + _wind_max);

View File

@ -18,8 +18,6 @@
extern const AP_HAL::HAL& hal;
#define constrain(amt,low,high) ((amt)<(low)?(low):((amt)>(high)?(high):(amt)))
// this is the speed in cm/s above which we first get a yaw lock with
// the GPS
#define GPS_SPEED_MIN 300

View File

@ -122,7 +122,6 @@ void AP_AHRS_MPU6000::drift_correction( float deltat )
// 0.65*0.04 / 0.005 = 5.2
float drift_limit = _mpu6000->get_gyro_drift_rate() * deltat
/ _gyro_bias_from_gravity_gain;
#define constrain(amt,low,high) ((amt)<(low)?(low):((amt)>(high)?(high):(amt)))
errorRollPitch[0] = constrain(errorRollPitch[0],
-drift_limit, drift_limit);
errorRollPitch[1] = constrain(errorRollPitch[1],