diff --git a/ArduPlane/GCS_Mavlink.pde b/ArduPlane/GCS_Mavlink.pde index 4b43f97669..e246e29d3f 100644 --- a/ArduPlane/GCS_Mavlink.pde +++ b/ArduPlane/GCS_Mavlink.pde @@ -1045,7 +1045,6 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg) } else if (packet.param4 == 1) { trim_radio(); } -#if !defined( __AVR_ATmega1280__ ) else if (packet.param5 == 1) { float trim_roll, trim_pitch; AP_InertialSensor_UserInteract_MAVLink interact(chan); @@ -1059,7 +1058,6 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg) ahrs.set_trim(Vector3f(trim_roll, trim_pitch, 0)); } } -#endif else { send_text_P(SEVERITY_LOW, PSTR("Unsupported preflight calibration")); } diff --git a/ArduPlane/config.h b/ArduPlane/config.h index 6d814ab735..573407f741 100644 --- a/ArduPlane/config.h +++ b/ArduPlane/config.h @@ -54,34 +54,6 @@ #error CONFIG_APM_HARDWARE option is depreated! use CONFIG_HAL_BOARD instead. #endif -////////////////////////////////////////////////////////////////////////////// -// APM HARDWARE -// - -#if defined( __AVR_ATmega1280__ ) - // default choices for a 1280. We can't fit everything in, so we - // make some popular choices by default - #define LOGGING_ENABLED DISABLED - #ifndef GEOFENCE_ENABLED - # define GEOFENCE_ENABLED DISABLED - #endif - #ifndef CLI_ENABLED - # define CLI_ENABLED DISABLED - #endif - #ifndef MOUNT2 - # define MOUNT2 DISABLED - #endif - #ifndef MOUNT - # define MOUNT DISABLED - #endif - #ifndef CAMERA - # define CAMERA DISABLED - #endif - #ifndef FRSKY_TELEM_ENABLED - # define FRSKY_TELEM_ENABLED DISABLED - #endif -#endif - ////////////////////////////////////////////////////////////////////////////// // sensor types @@ -305,7 +277,6 @@ ////////////////////////////////////////////////////////////////////////////// // MOUNT (ANTENNA OR CAMERA) // -// uses 4174 bytes of memory on 1280 chips (MNT_JSTICK_SPD_OPTION, MNT_RETRACT_OPTION, MNT_STABILIZE_OPTION and MNT_MOUNT2_OPTION disabled) // uses 7726 bytes of memory on 2560 chips (all options are enabled) #ifndef MOUNT # define MOUNT ENABLED diff --git a/ArduPlane/setup.pde b/ArduPlane/setup.pde index 9f12acb172..341f1e136e 100644 --- a/ArduPlane/setup.pde +++ b/ArduPlane/setup.pde @@ -7,10 +7,8 @@ static int8_t setup_radio (uint8_t argc, const Men static int8_t setup_show (uint8_t argc, const Menu::arg *argv); static int8_t setup_factory (uint8_t argc, const Menu::arg *argv); static int8_t setup_level (uint8_t argc, const Menu::arg *argv); -#if !defined( __AVR_ATmega1280__ ) static int8_t setup_accel_scale (uint8_t argc, const Menu::arg *argv); static int8_t setup_set (uint8_t argc, const Menu::arg *argv); -#endif static int8_t setup_erase (uint8_t argc, const Menu::arg *argv); static int8_t setup_compass (uint8_t argc, const Menu::arg *argv); @@ -22,14 +20,10 @@ static const struct Menu::command setup_menu_commands[] PROGMEM = { {"reset", setup_factory}, {"radio", setup_radio}, {"level", setup_level}, -#if !defined( __AVR_ATmega1280__ ) {"accel", setup_accel_scale}, -#endif {"compass", setup_compass}, {"show", setup_show}, -#if !defined( __AVR_ATmega1280__ ) {"set", setup_set}, -#endif {"erase", setup_erase}, }; @@ -58,8 +52,6 @@ setup_mode(uint8_t argc, const Menu::arg *argv) static int8_t setup_show(uint8_t argc, const Menu::arg *argv) { - -#if !defined( __AVR_ATmega1280__ ) AP_Param *param; ap_var_type type; @@ -77,16 +69,12 @@ setup_show(uint8_t argc, const Menu::arg *argv) AP_Param::show(param, argv[1].str, type, cliSerial); return 0; } -#endif AP_Param::show_all(cliSerial); return(0); } - -#if !defined( __AVR_ATmega1280__ ) - //Set a parameter to a specified value. It will cast the value to the current type of the //parameter and make sure it fits in case of INT8 and INT16 static int8_t setup_set(uint8_t argc, const Menu::arg *argv) @@ -145,7 +133,6 @@ static int8_t setup_set(uint8_t argc, const Menu::arg *argv) return 0; } -#endif // Initialise the EEPROM to 'factory' settings (mostly defined in APM_Config.h or via defaults). // Called by the setup menu 'factoryreset' command. @@ -285,7 +272,6 @@ setup_level(uint8_t argc, const Menu::arg *argv) return 0; } -#if !defined( __AVR_ATmega1280__ ) /* handle full accelerometer calibration via user dialog */ @@ -310,7 +296,6 @@ 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)