Copter: remove #ifdef checks for Atmega1280

This commit is contained in:
Randy Mackay 2013-04-05 22:48:10 +09:00
parent 1dcd46bffc
commit fc0c451b69
2 changed files with 7 additions and 115 deletions

View File

@ -40,7 +40,6 @@
//////////////////////////////////////////////////////////////////////////////
//////////////////////////////////////////////////////////////////////////////
#ifdef CONFIG_APM_HARDWARE
#error CONFIG_APM_HARDWARE option is deprecated! use CONFIG_HAL_BOARD instead
#endif
@ -48,6 +47,10 @@
#ifndef CONFIG_HAL_BOARD
#error CONFIG_HAL_BOARD must be defined to build ArduCopter
#endif
#ifdef __AVR_ATmega1280__
#error ATmega1280 is not supported
#endif
//////////////////////////////////////////////////////////////////////////////
// APM2 HARDWARE DEFAULTS
//
@ -517,71 +520,25 @@
# define GROUND_START_DELAY 3
#endif
//////////////////////////////////////////////////////////////////////////////
//////////////////////////////////////////////////////////////////////////////
// FLIGHT AND NAVIGATION CONTROL
//////////////////////////////////////////////////////////////////////////////
//////////////////////////////////////////////////////////////////////////////
//////////////////////////////////////////////////////////////////////////////
// Y6 Support
#ifndef TOP_BOTTOM_RATIO
# define TOP_BOTTOM_RATIO 1.00f
#endif
//////////////////////////////////////////////////////////////////////////////
// CAMERA TRIGGER AND CONTROL
//
#ifndef CAMERA
# if defined( __AVR_ATmega1280__ )
# define CAMERA DISABLED
# else
# define CAMERA ENABLED
# endif
# define CAMERA ENABLED
#endif
//////////////////////////////////////////////////////////////////////////////
// MOUNT (ANTENNA OR CAMERA)
//
#ifndef MOUNT
# if defined( __AVR_ATmega1280__ )
# define MOUNT DISABLED
# else
# define MOUNT ENABLED
# endif
# define MOUNT ENABLED
#endif
#ifndef MOUNT2
# define MOUNT2 DISABLED
#endif
#if defined( __AVR_ATmega1280__ ) && (MOUNT == ENABLED || MOUNT2 == ENABLED)
# warning "You choose to enable MOUNT on a small ATmega1280, CLI, CAMERA and AP_LIMITS will be disabled to free some space for it"
// The small ATmega1280 chip does not have enough memory for mount support
// so disable CLI, this will allow mount support and other improvements to fit.
// This should almost have no side effects, because the APM planner can now do a complete board setup.
# define CLI_ENABLED DISABLED
// The small ATmega1280 chip does not have enough memory for mount support
// so disable AUTO GPS support, this will allow mount support and other improvements to fit.
// This should almost have no side effects, because the most users use MTK anyways.
// If the user defined a GPS protocol, than we will NOT overwrite it
# if GPS_PROTOCOL == GPS_PROTOCOL_AUTO
# undef GPS_PROTOCOL
# define GPS_PROTOCOL GPS_PROTOCOL_MTK
# endif
// To save some more space
# undef CAMERA
# define CAMERA DISABLED
# define AP_LIMITS DISABLED
#endif
//////////////////////////////////////////////////////////////////////////////
// Attitude Control
@ -1062,18 +1019,7 @@
//////////////////////////////////////////////////////////////////////////////
// Dataflash logging control
//
// Logging must be disabled for 1280 build.
#if defined( __AVR_ATmega1280__ )
# if LOGGING_ENABLED == ENABLED
// If logging was enabled in APM_Config or command line, warn the user.
# warning "Logging is not supported on ATmega1280"
# undef LOGGING_ENABLED
# endif
# ifndef LOGGING_ENABLED
# define LOGGING_ENABLED DISABLED
# endif
#elif !defined(LOGGING_ENABLED)
// Logging is enabled by default for all other builds.
#ifndef LOGGING_ENABLED
# define LOGGING_ENABLED ENABLED
#endif
@ -1215,12 +1161,7 @@
// use this to completely disable the CLI
#ifndef CLI_ENABLED
// Sorry the chip is just too small to let this fit
# if defined( __AVR_ATmega1280__ )
# define CLI_ENABLED DISABLED
# else
# define CLI_ENABLED ENABLED
# endif
#endif
// experimental mpu6000 DMP code

View File

@ -127,10 +127,6 @@ test_eedump(uint8_t argc, const Menu::arg *argv)
static int8_t
test_radio_pwm(uint8_t argc, const Menu::arg *argv)
{
#if defined( __AVR_ATmega1280__ ) // test disabled to save code size for 1280
print_test_disabled();
return (0);
#else
print_hit_enter();
delay(1000);
@ -158,7 +154,6 @@ test_radio_pwm(uint8_t argc, const Menu::arg *argv)
return (0);
}
}
#endif
}
/*
@ -457,10 +452,6 @@ test_radio(uint8_t argc, const Menu::arg *argv)
static int8_t
test_ins(uint8_t argc, const Menu::arg *argv)
{
#if defined( __AVR_ATmega1280__ ) // test disabled to save code size for 1280
print_test_disabled();
return (0);
#else
Vector3f gyro, accel;
print_hit_enter();
cliSerial->printf_P(PSTR("INS\n"));
@ -490,17 +481,11 @@ test_ins(uint8_t argc, const Menu::arg *argv)
return (0);
}
}
#endif
}
static int8_t
test_gps(uint8_t argc, const Menu::arg *argv)
{
// test disabled to save code size for 1280
#if defined( __AVR_ATmega1280__ ) || HIL_MODE != HIL_MODE_DISABLED
print_test_disabled();
return (0);
#else
print_hit_enter();
delay(1000);
@ -530,7 +515,6 @@ test_gps(uint8_t argc, const Menu::arg *argv)
}
}
return 0;
#endif
}
/*
@ -666,10 +650,6 @@ test_tuning(uint8_t argc, const Menu::arg *argv)
static int8_t
test_battery(uint8_t argc, const Menu::arg *argv)
{
#if defined( __AVR_ATmega1280__ ) // disable this test if we are using 1280
print_test_disabled();
return (0);
#else
cliSerial->printf_P(PSTR("\nCareful! Motors will spin! Press Enter to start.\n"));
while (cliSerial->read() != -1); /* flush */
while(!cliSerial->available()) { /* wait for input */
@ -706,16 +686,10 @@ test_battery(uint8_t argc, const Menu::arg *argv)
}
motors.armed(false);
return (0);
#endif
}
static int8_t test_relay(uint8_t argc, const Menu::arg *argv)
{
#if defined( __AVR_ATmega1280__ ) // test disabled to save code size for 1280
print_test_disabled();
return (0);
#else
print_hit_enter();
delay(1000);
@ -734,7 +708,6 @@ static int8_t test_relay(uint8_t argc, const Menu::arg *argv)
return (0);
}
}
#endif
}
@ -804,10 +777,6 @@ test_wp(uint8_t argc, const Menu::arg *argv)
static int8_t
test_baro(uint8_t argc, const Menu::arg *argv)
{
#if defined( __AVR_ATmega1280__ ) // test disabled to save code size for 1280
print_test_disabled();
return (0);
#else
print_hit_enter();
init_barometer();
@ -827,7 +796,6 @@ test_baro(uint8_t argc, const Menu::arg *argv)
}
}
return 0;
#endif
}
#endif
@ -835,10 +803,6 @@ test_baro(uint8_t argc, const Menu::arg *argv)
static int8_t
test_mag(uint8_t argc, const Menu::arg *argv)
{
#if defined( __AVR_ATmega1280__ ) // test disabled to save code size for 1280
print_test_disabled();
return (0);
#else
if(g.compass_enabled) {
print_hit_enter();
@ -865,7 +829,6 @@ test_mag(uint8_t argc, const Menu::arg *argv)
return (0);
}
return (0);
#endif
}
/*
@ -998,14 +961,9 @@ test_wp_nav(uint8_t argc, const Menu::arg *argv)
static int8_t
test_logging(uint8_t argc, const Menu::arg *argv)
{
#if defined( __AVR_ATmega1280__ ) // test disabled to save code size for 1280
print_test_disabled();
return (0);
#else
cliSerial->println_P(PSTR("Testing dataflash logging"));
DataFlash.ShowDeviceInfo(cliSerial);
return 0;
#endif
}
@ -1088,13 +1046,6 @@ static void print_hit_enter()
cliSerial->printf_P(PSTR("Hit Enter to exit.\n\n"));
}
#if defined( __AVR_ATmega1280__ )
static void print_test_disabled()
{
cliSerial->printf_P(PSTR("Sorry, not 1280 compat.\n"));
}
#endif
/*
* //static void fake_out_gps()
* {