From 77822acbbf20c6594bc187a5b804ed8dc283b059 Mon Sep 17 00:00:00 2001 From: jphelirc Date: Thu, 23 Dec 2010 14:05:59 +0000 Subject: [PATCH] preparing for addon features git-svn-id: https://arducopter.googlecode.com/svn/trunk@1235 f9c3cf11-9bcb-44bc-f272-b75c42450872 --- ArduCopterMega/APM_Config.h | 34 ++++++++++++-------- ArduCopterMega/ArduCopterMega.pde | 53 ++++++++++++++++++++++++++++++- ArduCopterMega/control_modes.pde | 2 +- 3 files changed, 74 insertions(+), 15 deletions(-) diff --git a/ArduCopterMega/APM_Config.h b/ArduCopterMega/APM_Config.h index 0facb1e8ce..3b8a354fdb 100644 --- a/ArduCopterMega/APM_Config.h +++ b/ArduCopterMega/APM_Config.h @@ -1,13 +1,21 @@ -// Example config file. Use APM_Config.h.reference and the wiki to find additional defines to setup your plane. -// Once you upload the code, run the factory "reset" to save all config values to EEPROM. -// After reset, use the setup mode to set your radio limits for CH1-4, and to set your flight modes. - -#define GPS_PROTOCOL GPS_PROTOCOL_MTK -#define GCS_PROTOCOL GCS_PROTOCOL_NONE - -#define MAGORIENTATION AP_COMPASS_COMPONENTS_UP_PINS_BACK -#define ARM_AT_STARTUP 0 -//#define MAGOFFSET 30.50,15.00,47.00 -//#define DECLINATION 14.2 - - +// Example config file. Use APM_Config.h.reference and the wiki to find additional defines to setup your plane. +// Once you upload the code, run the factory "reset" to save all config values to EEPROM. +// After reset, use the setup mode to set your radio limits for CH1-4, and to set your flight modes. + +#define GPS_PROTOCOL GPS_PROTOCOL_MTK +#define GCS_PROTOCOL GCS_PROTOCOL_NONE + +#define MAGORIENTATION AP_COMPASS_COMPONENTS_UP_PINS_BACK +#define ARM_AT_STARTUP 0 +//#define MAGOFFSET 30.50,15.00,47.00 +//#define DECLINATION 14.2 + + +// For future development, don't enable unless you know them +// These are all experimental and underwork, jp 23-12-10 +//#define ENABLE_EXTRAS ENABLED +//#define ENABLE_EXTRAINIT ENABLED +//#define ENABLE_CAM ENABLED +//#define ENABLE_AM ENABLED +//#define ENABLE_xx ENABLED + diff --git a/ArduCopterMega/ArduCopterMega.pde b/ArduCopterMega/ArduCopterMega.pde index da1399054b..0c28c18760 100644 --- a/ArduCopterMega/ArduCopterMega.pde +++ b/ArduCopterMega/ArduCopterMega.pde @@ -364,10 +364,49 @@ float load; // % MCU cycles used byte FastLoopGate = 9; + + +// AC generic variables for future use +byte gled_status = HIGH; +long gled_timer; +int gled_speed = 200; + +long cli_timer; +byte cli_status = LOW; +byte cli_step; + +byte fled_status; +byte res1; +byte res2; +byte res3; +byte res4; +byte res5; +byte cam_mode; +byte cam1; +byte cam2; +byte cam3; + +int ires1; +int ires2; +int ires3; +int ires4; + +boolean SW_DIP1; // closest to SW2 slider switch +boolean SW_DIP2; +boolean SW_DIP3; +boolean SW_DIP4; // closest to header pins + + + // Basic Initialization //--------------------- void setup() { init_ardupilot(); + + #if ENABLE_EXTRAINIT + init_extras(); + #endif + } void loop() @@ -544,6 +583,18 @@ void medium_loop() #if ENABLE_HIL output_HIL(); #endif + + #if ENABLE_CAM + camera_stabilization(); + #endif + + #if ENABLE_AM + flight_lights(); + #endif + + #if ENABLE_xx + do_something_usefull(); + #endif if (millis() - perf_mon_timer > 20000) { @@ -835,4 +886,4 @@ void read_AHRS(void) roll_sensor = dcm.roll_sensor; pitch_sensor = dcm.pitch_sensor; yaw_sensor = dcm.yaw_sensor; -} \ No newline at end of file +} diff --git a/ArduCopterMega/control_modes.pde b/ArduCopterMega/control_modes.pde index 5688885075..d9524d0d3c 100644 --- a/ArduCopterMega/control_modes.pde +++ b/ArduCopterMega/control_modes.pde @@ -99,4 +99,4 @@ void read_trim_switch() trim_flag = false; } } -} \ No newline at end of file +}