AP_InertialSensor: removed AVR1280 specific ifdef

This commit is contained in:
Andrew Tridgell 2015-08-11 16:47:56 +10:00 committed by Randy Mackay
parent fbcacbd1d4
commit a7bd3d1c54
3 changed files with 0 additions and 14 deletions

View File

@ -450,7 +450,6 @@ bool AP_InertialSensor::_calculate_trim(const Vector3f &accel_sample, float& tri
return true; return true;
} }
#if !defined( __AVR_ATmega1280__ )
// calibrate_accel - perform accelerometer calibration including providing user // calibrate_accel - perform accelerometer calibration including providing user
// instructions and feedback Gauss-Newton accel calibration routines borrowed // instructions and feedback Gauss-Newton accel calibration routines borrowed
// from Rolfe Schmidt blog post describing the method: // from Rolfe Schmidt blog post describing the method:
@ -635,7 +634,6 @@ failed:
_calibrating = false; _calibrating = false;
return false; return false;
} }
#endif
void void
AP_InertialSensor::init_gyro() AP_InertialSensor::init_gyro()
@ -921,8 +919,6 @@ AP_InertialSensor::_init_gyro()
AP_Notify::flags.initialising = false; AP_Notify::flags.initialising = false;
} }
#if !defined( __AVR_ATmega1280__ )
/* /*
check that the samples used for accel calibration have a sufficient check that the samples used for accel calibration have a sufficient
range on each axis. The sphere fit in _calibrate_accel() can produce range on each axis. The sphere fit in _calibrate_accel() can produce
@ -1122,8 +1118,6 @@ void AP_InertialSensor::_calibrate_find_delta(float dS[6], float JS[6][6], float
} }
} }
#endif // __AVR_ATmega1280__
// save parameters to eeprom // save parameters to eeprom
void AP_InertialSensor::_save_parameters() void AP_InertialSensor::_save_parameters()
{ {

View File

@ -87,13 +87,11 @@ public:
uint8_t register_gyro(void); uint8_t register_gyro(void);
uint8_t register_accel(void); uint8_t register_accel(void);
#if !defined( __AVR_ATmega1280__ )
// perform accelerometer calibration including providing user instructions // perform accelerometer calibration including providing user instructions
// and feedback // and feedback
bool calibrate_accel(AP_InertialSensor_UserInteract *interact, bool calibrate_accel(AP_InertialSensor_UserInteract *interact,
float& trim_roll, float& trim_roll,
float& trim_pitch); float& trim_pitch);
#endif
bool calibrate_trim(float &trim_roll, float &trim_pitch); bool calibrate_trim(float &trim_roll, float &trim_pitch);
/// calibrating - returns true if the gyros or accels are currently being calibrated /// calibrating - returns true if the gyros or accels are currently being calibrated
@ -242,7 +240,6 @@ private:
// gyro initialisation // gyro initialisation
void _init_gyro(); void _init_gyro();
#if !defined( __AVR_ATmega1280__ )
// Calibration routines borrowed from Rolfe Schmidt // Calibration routines borrowed from Rolfe Schmidt
// blog post describing the method: http://chionophilous.wordpress.com/2011/10/24/accelerometer-calibration-iv-1-implementing-gauss-newton-on-an-atmega/ // blog post describing the method: http://chionophilous.wordpress.com/2011/10/24/accelerometer-calibration-iv-1-implementing-gauss-newton-on-an-atmega/
// original sketch available at http://rolfeschmidt.com/mathtools/skimetrics/adxl_gn_calibration.pde // original sketch available at http://rolfeschmidt.com/mathtools/skimetrics/adxl_gn_calibration.pde
@ -259,7 +256,6 @@ private:
void _calibrate_reset_matrices(float dS[6], float JS[6][6]); void _calibrate_reset_matrices(float dS[6], float JS[6][6]);
void _calibrate_find_delta(float dS[6], float JS[6][6], float delta[6]); void _calibrate_find_delta(float dS[6], float JS[6][6], float delta[6]);
bool _calculate_trim(const Vector3f &accel_sample, float& trim_roll, float& trim_pitch); bool _calculate_trim(const Vector3f &accel_sample, float& trim_roll, float& trim_pitch);
#endif
// save parameters to eeprom // save parameters to eeprom
void _save_parameters(); void _save_parameters();

View File

@ -121,12 +121,8 @@ static void run_calibration()
} }
#if !defined( __AVR_ATmega1280__ )
AP_InertialSensor_UserInteractStream interact(hal.console); AP_InertialSensor_UserInteractStream interact(hal.console);
ins.calibrate_accel(&interact, roll_trim, pitch_trim); ins.calibrate_accel(&interact, roll_trim, pitch_trim);
#else
hal.console->println_P(PSTR("calibrate_accel not available on 1280"));
#endif
} }
static void display_offsets_and_scaling() static void display_offsets_and_scaling()