diff --git a/ArduPlane/setup.pde b/ArduPlane/setup.pde index ec9613c969..e5c69636e1 100644 --- a/ArduPlane/setup.pde +++ b/ArduPlane/setup.pde @@ -22,7 +22,9 @@ static const struct Menu::command setup_menu_commands[] PROGMEM = { {"radio", setup_radio}, {"modes", setup_flightmodes}, {"level", setup_level}, +#if !defined( __AVR_ATmega1280__ ) {"accel", setup_accel_scale}, +#endif {"compass", setup_compass}, {"declination", setup_declination}, {"battery", setup_batt_monitor}, @@ -299,6 +301,7 @@ setup_level(uint8_t argc, const Menu::arg *argv) return 0; } +#if !defined( __AVR_ATmega1280__ ) static int8_t setup_accel_scale(uint8_t argc, const Menu::arg *argv) { @@ -307,6 +310,7 @@ setup_accel_scale(uint8_t argc, const Menu::arg *argv) report_ins(); return(0); } +#endif static int8_t setup_compass(uint8_t argc, const Menu::arg *argv) diff --git a/libraries/AP_InertialSensor/AP_InertialSensor.cpp b/libraries/AP_InertialSensor/AP_InertialSensor.cpp index c08e4e8dd9..40a34f0eb8 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor.cpp +++ b/libraries/AP_InertialSensor/AP_InertialSensor.cpp @@ -231,6 +231,7 @@ AP_InertialSensor::_init_accel(void (*delay_cb)(unsigned long t), void (*flash_l } +#if !defined( __AVR_ATmega1280__ ) // perform accelerometer calibration including providing user instructions and feedback bool AP_InertialSensor::calibrate_accel(void (*delay_cb)(unsigned long t), void (*flash_leds_cb)(bool on), void (*send_msg)(const prog_char_t *, ...)) { @@ -472,3 +473,6 @@ void AP_InertialSensor::_calibrate_find_delta(float dS[6], float JS[6][6], float delta[i] = dS[i]; } } + +#endif // __AVR_ATmega1280__ + diff --git a/libraries/AP_InertialSensor/AP_InertialSensor.h b/libraries/AP_InertialSensor/AP_InertialSensor.h index 0a11616b9b..67666eafdc 100644 --- a/libraries/AP_InertialSensor/AP_InertialSensor.h +++ b/libraries/AP_InertialSensor/AP_InertialSensor.h @@ -49,10 +49,12 @@ public: /// virtual void init_accel(void (*delay_cb)(unsigned long t), void (*flash_leds_cb)(bool on)); +#if !defined( __AVR_ATmega1280__ ) // perform accelerometer calibration including providing user instructions and feedback virtual bool calibrate_accel(void (*delay_cb)(unsigned long t), void (*flash_leds_cb)(bool on) = NULL, void (*send_msg)(const prog_char_t *, ...) = NULL); +#endif /// Perform cold-start initialisation for just the gyros. /// @@ -140,11 +142,13 @@ protected: virtual void _init_gyro(void (*delay_cb)(unsigned long t), void (*flash_leds_cb)(bool on) = NULL); +#if !defined( __AVR_ATmega1280__ ) // _calibrate_accel - perform low level accel calibration virtual bool _calibrate_accel(Vector3f accel_sample[6], Vector3f& accel_offsets, Vector3f& accel_scale); virtual void _calibrate_update_matrices(float dS[6], float JS[6][6], float beta[6], float data[3]); virtual void _calibrate_reset_matrices(float dS[6], float JS[6][6]); virtual void _calibrate_find_delta(float dS[6], float JS[6][6], float delta[6]); +#endif // save parameters to eeprom void _save_parameters();