ArduPlane: rename purple to APM2

This commit is contained in:
Andrew Tridgell 2011-11-26 10:11:36 +11:00 committed by Pat Hickey
parent 1d66b075b0
commit 7467bf649c
7 changed files with 17 additions and 17 deletions

View File

@ -79,8 +79,8 @@ Arduino_Mega_ISR_Registry isr_registry;
//////////////////////////////////////////////////////////////////////////////// ////////////////////////////////////////////////////////////////////////////////
// APM_RC_Class Instance // APM_RC_Class Instance
//////////////////////////////////////////////////////////////////////////////// ////////////////////////////////////////////////////////////////////////////////
#if CONFIG_APM_HARDWARE == APM_HARDWARE_PURPLE #if CONFIG_APM_HARDWARE == APM_HARDWARE_APM2
APM_RC_Purple APM_RC; APM_RC_APM2 APM_RC;
#else #else
APM_RC_APM1 APM_RC; APM_RC_APM1 APM_RC;
#endif #endif
@ -88,8 +88,8 @@ Arduino_Mega_ISR_Registry isr_registry;
//////////////////////////////////////////////////////////////////////////////// ////////////////////////////////////////////////////////////////////////////////
// Dataflash // Dataflash
//////////////////////////////////////////////////////////////////////////////// ////////////////////////////////////////////////////////////////////////////////
#if CONFIG_APM_HARDWARE == APM_HARDWARE_PURPLE #if CONFIG_APM_HARDWARE == APM_HARDWARE_APM2
DataFlash_Purple DataFlash; DataFlash_APM2 DataFlash;
#else #else
DataFlash_APM1 DataFlash; DataFlash_APM1 DataFlash;
#endif #endif

View File

@ -18,8 +18,8 @@ hilnocli:
heli: heli:
make -f Makefile EXTRAFLAGS="-DFRAME_CONFIG=HELI_FRAME" make -f Makefile EXTRAFLAGS="-DFRAME_CONFIG=HELI_FRAME"
purple: apm2:
make -f Makefile EXTRAFLAGS="-DCONFIG_APM_HARDWARE=APM_HARDWARE_PURPLE -DCLI_SLIDER_ENABLED=DISABLED" make -f Makefile EXTRAFLAGS="-DCONFIG_APM_HARDWARE=APM_HARDWARE_APM2 -DCLI_SLIDER_ENABLED=DISABLED"
mavlink10: mavlink10:
make -f Makefile EXTRAFLAGS="-DHIL_MODE=HIL_MODE_ATTITUDE -DMAVLINK10 -DCLI_ENABLED=DISABLED -DLOGGING_ENABLED=DISABLED" make -f Makefile EXTRAFLAGS="-DHIL_MODE=HIL_MODE_ATTITUDE -DMAVLINK10 -DCLI_ENABLED=DISABLED -DLOGGING_ENABLED=DISABLED"

View File

@ -51,10 +51,10 @@
#endif #endif
////////////////////////////////////////////////////////////////////////////// //////////////////////////////////////////////////////////////////////////////
// PURPLE HARDWARE DEFAULTS // APM2 HARDWARE DEFAULTS
// //
#if CONFIG_APM_HARDWARE == APM_HARDWARE_PURPLE #if CONFIG_APM_HARDWARE == APM_HARDWARE_APM2
# define CONFIG_IMU_TYPE CONFIG_IMU_MPU6000 # define CONFIG_IMU_TYPE CONFIG_IMU_MPU6000
# define CONFIG_PUSHBUTTON DISABLED # define CONFIG_PUSHBUTTON DISABLED
# define CONFIG_RELAY DISABLED # define CONFIG_RELAY DISABLED
@ -73,7 +73,7 @@
# define SLIDE_SWITCH_PIN 40 # define SLIDE_SWITCH_PIN 40
# define PUSHBUTTON_PIN 41 # define PUSHBUTTON_PIN 41
# define USB_MUX_PIN -1 # define USB_MUX_PIN -1
#elif CONFIG_APM_HARDWARE == APM_HARDWARE_PURPLE #elif CONFIG_APM_HARDWARE == APM_HARDWARE_APM2
# define A_LED_PIN 27 # define A_LED_PIN 27
# define B_LED_PIN 26 # define B_LED_PIN 26
# define C_LED_PIN 25 # define C_LED_PIN 25

View File

@ -40,7 +40,7 @@ static void reset_control_switch()
static void update_servo_switches() static void update_servo_switches()
{ {
#if CONFIG_APM_HARDWARE != APM_HARDWARE_PURPLE #if CONFIG_APM_HARDWARE != APM_HARDWARE_APM2
if (!g.switch_enable) { if (!g.switch_enable) {
// switches are disabled in EEPROM (see SWITCH_ENABLE option) // switches are disabled in EEPROM (see SWITCH_ENABLE option)
// this means the EEPROM control of all channel reversal is enabled // this means the EEPROM control of all channel reversal is enabled

View File

@ -226,6 +226,6 @@ enum gcs_severity {
#define CONFIG_IMU_MPU6000 2 #define CONFIG_IMU_MPU6000 2
#define APM_HARDWARE_APM1 1 #define APM_HARDWARE_APM1 1
#define APM_HARDWARE_PURPLE 2 #define APM_HARDWARE_APM2 2
#endif // _DEFINES_H #endif // _DEFINES_H

View File

@ -56,7 +56,7 @@ static void run_cli(void)
static void init_ardupilot() static void init_ardupilot()
{ {
#if USB_MUX_PIN > 0 #if USB_MUX_PIN > 0
// on the purple board we have a mux thet switches UART0 between // on the APM2 board we have a mux thet switches UART0 between
// USB and the board header. If the right ArduPPM firmware is // USB and the board header. If the right ArduPPM firmware is
// installed we can detect if USB is connected using the // installed we can detect if USB is connected using the
// USB_MUX_PIN // USB_MUX_PIN
@ -176,7 +176,7 @@ static void init_ardupilot()
adc.Init(&timer_scheduler); // APM ADC library initialization adc.Init(&timer_scheduler); // APM ADC library initialization
#if CONFIG_APM_HARDWARE == APM_HARDWARE_PURPLE #if CONFIG_APM_HARDWARE == APM_HARDWARE_APM2
barometer.Init(1, true); barometer.Init(1, true);
#else #else
barometer.Init(1, false); barometer.Init(1, false);

View File

@ -25,7 +25,7 @@ static int8_t test_xbee(uint8_t argc, const Menu::arg *argv);
static int8_t test_eedump(uint8_t argc, const Menu::arg *argv); static int8_t test_eedump(uint8_t argc, const Menu::arg *argv);
static int8_t test_rawgps(uint8_t argc, const Menu::arg *argv); static int8_t test_rawgps(uint8_t argc, const Menu::arg *argv);
static int8_t test_modeswitch(uint8_t argc, const Menu::arg *argv); static int8_t test_modeswitch(uint8_t argc, const Menu::arg *argv);
#if CONFIG_APM_HARDWARE != APM_HARDWARE_PURPLE #if CONFIG_APM_HARDWARE != APM_HARDWARE_APM2
static int8_t test_dipswitches(uint8_t argc, const Menu::arg *argv); static int8_t test_dipswitches(uint8_t argc, const Menu::arg *argv);
#endif #endif
@ -44,7 +44,7 @@ static const struct Menu::command test_menu_commands[] PROGMEM = {
{"xbee", test_xbee}, {"xbee", test_xbee},
{"eedump", test_eedump}, {"eedump", test_eedump},
{"modeswitch", test_modeswitch}, {"modeswitch", test_modeswitch},
#if CONFIG_APM_HARDWARE != APM_HARDWARE_PURPLE #if CONFIG_APM_HARDWARE != APM_HARDWARE_APM2
{"dipswitches", test_dipswitches}, {"dipswitches", test_dipswitches},
#endif #endif
@ -410,7 +410,7 @@ test_modeswitch(uint8_t argc, const Menu::arg *argv)
} }
} }
#if CONFIG_APM_HARDWARE != APM_HARDWARE_PURPLE #if CONFIG_APM_HARDWARE != APM_HARDWARE_APM2
static int8_t static int8_t
test_dipswitches(uint8_t argc, const Menu::arg *argv) test_dipswitches(uint8_t argc, const Menu::arg *argv)
{ {
@ -441,7 +441,7 @@ test_dipswitches(uint8_t argc, const Menu::arg *argv)
} }
} }
} }
#endif // CONFIG_APM_HARDWARE != APM_HARDWARE_PURPLE #endif // CONFIG_APM_HARDWARE != APM_HARDWARE_APM2
//------------------------------------------------------------------------------------------- //-------------------------------------------------------------------------------------------