diff --git a/ArduCopter/ArduCopter.pde b/ArduCopter/ArduCopter.pde index 9d86beab8b..6e9037014d 100644 --- a/ArduCopter/ArduCopter.pde +++ b/ArduCopter/ArduCopter.pde @@ -418,6 +418,7 @@ static byte led_mode = NORMAL_LEDS; static const float t7 = 10000000.0; // We use atan2 and other trig techniques to calaculate angles // We need to scale the longitude up to make these calcs work +// to account for decreasing distance between lines of longitude away from the equator static float scaleLongUp = 1; // Sometimes we need to remove the scaling for distance calcs static float scaleLongDown = 1; @@ -529,20 +530,12 @@ static int8_t CH7_wp_index; //////////////////////////////////////////////////////////////////////////////// // Battery Sensors //////////////////////////////////////////////////////////////////////////////// -// Battery Voltage of total battery, initialized above threshold for filter -static float battery_voltage = LOW_VOLTAGE * 1.05; -// Battery Voltage of cell 1, initialized above threshold for filter -static float battery_voltage1 = LOW_VOLTAGE * 1.05; -// Battery Voltage of cells 1 + 2, initialized above threshold for filter -static float battery_voltage2 = LOW_VOLTAGE * 1.05; -// Battery Voltage of cells 1 + 2+3, initialized above threshold for filter -static float battery_voltage3 = LOW_VOLTAGE * 1.05; -// Battery Voltage of cells 1 + 2+3 + 4, initialized above threshold for filter -static float battery_voltage4 = LOW_VOLTAGE * 1.05; +// Battery Voltage of battery, initialized above threshold for filter +static float battery_voltage1 = LOW_VOLTAGE * 1.05; // refers to the instant amp draw – based on an Attopilot Current sensor -static float current_amps; +static float current_amps1; // refers to the total amps drawn – based on an Attopilot Current sensor -static float current_total; +static float current_total1; // Used to track if the battery is low - LED output flashes when the batt is low static bool low_batt = false; diff --git a/ArduCopter/GCS_Mavlink.pde b/ArduCopter/GCS_Mavlink.pde index 195c9b40c2..6e2e6715dc 100644 --- a/ArduCopter/GCS_Mavlink.pde +++ b/ArduCopter/GCS_Mavlink.pde @@ -78,7 +78,7 @@ static NOINLINE void send_extended_status1(mavlink_channel_t chan, uint16_t pack status = MAV_STATE_STANDBY; } - uint16_t battery_remaining = 1000.0 * (float)(g.pack_capacity - current_total)/(float)g.pack_capacity; //Mavlink scaling 100% = 1000 + uint16_t battery_remaining = 1000.0 * (float)(g.pack_capacity - current_total1)/(float)g.pack_capacity; //Mavlink scaling 100% = 1000 mavlink_msg_sys_status_send( chan, @@ -86,7 +86,7 @@ static NOINLINE void send_extended_status1(mavlink_channel_t chan, uint16_t pack nav_mode, status, 0, - battery_voltage * 1000, + battery_voltage1 * 1000, battery_remaining, packet_drops); } diff --git a/ArduCopter/Log.pde b/ArduCopter/Log.pde index e0d2acab55..57b2136ff0 100644 --- a/ArduCopter/Log.pde +++ b/ArduCopter/Log.pde @@ -321,9 +321,9 @@ static void Log_Write_Current() DataFlash.WriteInt(g.rc_3.control_in); // 1 DataFlash.WriteLong(throttle_integrator); // 2 - DataFlash.WriteInt(battery_voltage * 100.0); // 3 - DataFlash.WriteInt(current_amps * 100.0); // 4 - DataFlash.WriteInt(current_total); // 5 + DataFlash.WriteInt(battery_voltage1 * 100.0); // 3 + DataFlash.WriteInt(current_amps1 * 100.0); // 4 + DataFlash.WriteInt(current_total1); // 5 DataFlash.WriteByte(END_BYTE); } diff --git a/ArduCopter/Parameters.h b/ArduCopter/Parameters.h index 4895a39b52..80147e64ea 100644 --- a/ArduCopter/Parameters.h +++ b/ArduCopter/Parameters.h @@ -198,7 +198,7 @@ public: AP_Int16 RTL_altitude; AP_Int8 sonar_enabled; AP_Int8 sonar_type; // 0 = XL, 1 = LV, 2 = XLL (XL with 10m range) - AP_Int8 battery_monitoring; // 0=disabled, 1=3 cell lipo, 2=4 cell lipo, 3=total voltage only, 4=total voltage and current + AP_Int8 battery_monitoring; // 0=disabled, 3=voltage only, 4=voltage and current AP_Int16 pack_capacity; // Battery pack capacity less reserve AP_Int8 compass_enabled; AP_Int8 optflow_enabled; diff --git a/ArduCopter/config.h b/ArduCopter/config.h index c662b0baa0..bcf285fd51 100644 --- a/ArduCopter/config.h +++ b/ArduCopter/config.h @@ -118,6 +118,8 @@ # define USB_MUX_PIN -1 # define CLI_SLIDER_ENABLED DISABLED # define OPTFLOW_CS_PIN 34 +# define BATTERY_PIN_1 0 +# define CURRENT_PIN_1 1 #elif CONFIG_APM_HARDWARE == APM_HARDWARE_APM2 # define A_LED_PIN 27 # define B_LED_PIN 26 @@ -129,6 +131,8 @@ # define CLI_SLIDER_ENABLED DISABLED # define USB_MUX_PIN 23 # define OPTFLOW_CS_PIN A6 +# define BATTERY_PIN_1 1 +# define CURRENT_PIN_1 2 #endif ////////////////////////////////////////////////////////////////////////////// diff --git a/ArduCopter/config_channels.h b/ArduCopter/config_channels.h index 5429b273de..fe6677e42a 100644 --- a/ArduCopter/config_channels.h +++ b/ArduCopter/config_channels.h @@ -61,10 +61,10 @@ // // #if CONFIG_APM_HARDWARE == APM_HARDWARE_APM2 -/* Camera Pitch and Camera Roll: Not yet defined for APM2 +/* Camera Pitch and Camera Roll: Not yet defined for APM2 * They will likely be dependent on the frame config */ -# define CH_CAM_PITCH (-1) -# define CH_CAM_ROLL (-1) +# define CH_CAM_PITCH CH_11 +# define CH_CAM_ROLL CH_10 #elif CONFIG_APM_HARDWARE == APM_HARDWARE_APM1 # define CH_CAM_PITCH CH_5 # define CH_CAM_ROLL CH_6 diff --git a/ArduCopter/defines.h b/ArduCopter/defines.h index ff8f628bf9..a9927a105c 100644 --- a/ArduCopter/defines.h +++ b/ArduCopter/defines.h @@ -325,15 +325,8 @@ enum gcs_severity { #define AN14 68 // NC #define AN15 69 // NC -#define VOLTAGE_PIN_0 0 // These are the pins for current sensor: voltage -#define CURRENT_PIN_1 1 // and current - #define RELAY_PIN 47 -#define BATTERY_PIN1 0 // These are the pins for the voltage dividers -#define BATTERY_PIN2 1 -#define BATTERY_PIN3 2 -#define BATTERY_PIN4 3 #define PIEZO_PIN AN5 //Last pin on the back ADC connector diff --git a/ArduCopter/sensors.pde b/ArduCopter/sensors.pde index 21692965bd..2837ccd1c9 100644 --- a/ArduCopter/sensors.pde +++ b/ArduCopter/sensors.pde @@ -100,30 +100,25 @@ static void init_optflow() static void read_battery(void) { - battery_voltage1 = BATTERY_VOLTAGE(analogRead(BATTERY_PIN1)) * .1 + battery_voltage1 * .9; - battery_voltage2 = BATTERY_VOLTAGE(analogRead(BATTERY_PIN2)) * .1 + battery_voltage2 * .9; - battery_voltage3 = BATTERY_VOLTAGE(analogRead(BATTERY_PIN3)) * .1 + battery_voltage3 * .9; - battery_voltage4 = BATTERY_VOLTAGE(analogRead(BATTERY_PIN4)) * .1 + battery_voltage4 * .9; - if(g.battery_monitoring == 1) - battery_voltage = battery_voltage3; // set total battery voltage, for telemetry stream - - if(g.battery_monitoring == 2) - battery_voltage = battery_voltage4; - - if(g.battery_monitoring == 3 || g.battery_monitoring == 4) - battery_voltage = battery_voltage1; + if(g.battery_monitoring == 0){ + battery_voltage1 = 0; + return; + } + if(g.battery_monitoring == 3 || g.battery_monitoring == 4) { + battery_voltage1 = BATTERY_VOLTAGE(analogRead(BATTERY_PIN_1)) * .1 + battery_voltage1 * .9; + } if(g.battery_monitoring == 4) { - current_amps = CURRENT_AMPS(analogRead(CURRENT_PIN_1)) * .1 + current_amps * .9; //reads power sensor current pin - current_total += current_amps * 0.0278; // called at 100ms on average + current_amps1 = CURRENT_AMPS(analogRead(CURRENT_PIN_1)) * .1 + current_amps1 * .9; //reads power sensor current pin + current_total1 += current_amps1 * 0.02778; // called at 100ms on average, .0002778 is 1/3600 (conversion to hours) } #if BATTERY_EVENT == 1 //if(battery_voltage < g.low_voltage) // low_battery_event(); - if((battery_voltage < g.low_voltage) || (g.battery_monitoring == 4 && current_total > g.pack_capacity)){ + if((battery_voltage1 < g.low_voltage) || (g.battery_monitoring == 4 && current_total1 > g.pack_capacity)){ low_battery_event(); #if PIEZO_LOW_VOLTAGE == 1 diff --git a/ArduCopter/setup.pde b/ArduCopter/setup.pde index 0d714d62b2..3b7ed57455 100644 --- a/ArduCopter/setup.pde +++ b/ArduCopter/setup.pde @@ -395,7 +395,7 @@ setup_batt_monitor(uint8_t argc, const Menu::arg *argv) g.battery_monitoring.set_and_save(argv[1].i); } else { - Serial.printf_P(PSTR("\nOp: off, 1-4")); + Serial.printf_P(PSTR("\nOp: off, 3-4")); } report_batt_monitor(); @@ -778,8 +778,6 @@ static void report_batt_monitor() Serial.printf_P(PSTR("\nBatt Mon:\n")); print_divider(); if(g.battery_monitoring == 0) print_enabled(false); - if(g.battery_monitoring == 1) Serial.printf_P(PSTR("3c")); - if(g.battery_monitoring == 2) Serial.printf_P(PSTR("4c")); if(g.battery_monitoring == 3) Serial.printf_P(PSTR("volts")); if(g.battery_monitoring == 4) Serial.printf_P(PSTR("volts and cur")); print_blanks(2); diff --git a/ArduCopter/test.pde b/ArduCopter/test.pde index b965847a89..e1fc53df4d 100644 --- a/ArduCopter/test.pde +++ b/ArduCopter/test.pde @@ -21,7 +21,6 @@ static int8_t test_battery(uint8_t argc, const Menu::arg *argv); //static int8_t test_wp_nav(uint8_t argc, const Menu::arg *argv); //static int8_t test_reverse(uint8_t argc, const Menu::arg *argv); static int8_t test_tuning(uint8_t argc, const Menu::arg *argv); -static int8_t test_current(uint8_t argc, const Menu::arg *argv); static int8_t test_relay(uint8_t argc, const Menu::arg *argv); static int8_t test_wp(uint8_t argc, const Menu::arg *argv); #if HIL_MODE != HIL_MODE_ATTITUDE @@ -69,7 +68,6 @@ const struct Menu::command test_menu_commands[] PROGMEM = { {"battery", test_battery}, {"tune", test_tuning}, //{"tri", test_tri}, - {"current", test_current}, {"relay", test_relay}, {"wp", test_wp}, //{"nav", test_nav}, @@ -713,26 +711,6 @@ test_gps(uint8_t argc, const Menu::arg *argv) } //*/ -static int8_t -test_battery(uint8_t argc, const Menu::arg *argv) -{ -#if BATTERY_EVENT == 1 - for (int i = 0; i < 20; i++){ - delay(20); - read_battery(); - } - Serial.printf_P(PSTR("Volts: 1:%2.2f, 2:%2.2f, 3:%2.2f, 4:%2.2f\n"), - battery_voltage1, - battery_voltage2, - battery_voltage3, - battery_voltage4); -#else - Serial.printf_P(PSTR("Not enabled\n")); - -#endif - return (0); -} - static int8_t test_tuning(uint8_t argc, const Menu::arg *argv) { @@ -751,7 +729,7 @@ test_tuning(uint8_t argc, const Menu::arg *argv) } static int8_t -test_current(uint8_t argc, const Menu::arg *argv) +test_battery(uint8_t argc, const Menu::arg *argv) { print_hit_enter(); //delta_ms_medium_loop = 100; @@ -760,11 +738,17 @@ test_current(uint8_t argc, const Menu::arg *argv) delay(100); read_radio(); read_battery(); - Serial.printf_P(PSTR("V: %4.4f, A: %4.4f, mAh: %4.4f\n"), - battery_voltage, - current_amps, - current_total); - + if (g.battery_monitoring == 3){ + Serial.printf_P(PSTR("V: %4.4f\n"), + battery_voltage1, + current_amps1, + current_total1); + } else { + Serial.printf_P(PSTR("V: %4.4f, A: %4.4f, Ah: %4.4f\n"), + battery_voltage1, + current_amps1, + current_total1); + } APM_RC.OutputCh(MOT_1, g.rc_3.radio_in); APM_RC.OutputCh(MOT_2, g.rc_3.radio_in); APM_RC.OutputCh(MOT_3, g.rc_3.radio_in); diff --git a/ArduPlane/ArduPlane.pde b/ArduPlane/ArduPlane.pde index 6e45378b47..f2dbcb7bbb 100644 --- a/ArduPlane/ArduPlane.pde +++ b/ArduPlane/ArduPlane.pde @@ -1,6 +1,6 @@ /// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- -#define THISFIRMWARE "ArduPlane V2.27" +#define THISFIRMWARE "ArduPlane V2.28" /* Authors: Doug Weibel, Jose Julio, Jordi Munoz, Jason Short, Andrew Tridgell, Randy Mackay, Pat Hickey, John Arne Birkeland, Olivier Adler Thanks to: Chris Anderson, Michael Oborne, Paul Mather, Bill Premerlani, James Cohen, JB from rotorFX, Automatik, Fefenin, Peter Meister, Remzibi, Yury Smirnov, Sandro Benigno, Max Levine, Roberto Navoni, Lorenz Meier @@ -240,6 +240,15 @@ AP_AnalogSource_Arduino pitot_analog_source(CONFIG_PITOT_SOURCE_ANALOG_PIN, 4.0) AP_RangeFinder_MaxsonarXL sonar(&pitot_analog_source, &sonar_mode_filter); #endif +AP_Relay relay; + +// Camera/Antenna mount tracking and stabilisation stuff +// -------------------------------------- +#if MOUNT == ENABLED +AP_Mount camera_mount(g_gps, &dcm); +#endif + + //////////////////////////////////////////////////////////////////////////////// // Global variables //////////////////////////////////////////////////////////////////////////////// @@ -354,162 +363,263 @@ static int ground_start_avg; // If we do not detect GPS at startup, we stop trying and assume GPS is not connected static bool GPS_enabled = false; +//////////////////////////////////////////////////////////////////////////////// // Location & Navigation -// --------------------- +//////////////////////////////////////////////////////////////////////////////// +// Constants const float radius_of_earth = 6378100; // meters const float gravity = 9.81; // meters/ sec^2 -static long nav_bearing; // deg * 100 : 0 to 360 current desired bearing to navigate -static long target_bearing; // deg * 100 : 0 to 360 location of the plane to the target -static long crosstrack_bearing; // deg * 100 : 0 to 360 desired angle of plane to target -static float nav_gain_scaler = 1; // Gain scaling for headwind/tailwind TODO: why does this variable need to be initialized to 1? +// This is the currently calculated direction to fly. +// deg * 100 : 0 to 360 +static long nav_bearing; +// This is the direction to the next waypoint or loiter center +// deg * 100 : 0 to 360 +static long target_bearing; +//This is the direction from the last waypoint to the next waypoint +// deg * 100 : 0 to 360 +static long crosstrack_bearing; +// A gain scaler to account for ground speed/headwind/tailwind +static float nav_gain_scaler = 1; +// Direction held during phases of takeoff and landing +// deg * 100 dir of plane, A value of -1 indicates the course has not been set/is not in use static long hold_course = -1; // deg * 100 dir of plane -static byte nav_command_index; // active nav command memory location -static byte non_nav_command_index; // active non-nav command memory location -static byte nav_command_ID = NO_COMMAND; // active nav command ID -static byte non_nav_command_ID = NO_COMMAND; // active non-nav command ID +// There may be two active commands in Auto mode. +// This indicates the active navigation command by index number +static byte nav_command_index; +// This indicates the active non-navigation command by index number +static byte non_nav_command_index; +// This is the command type (eg navigate to waypoint) of the active navigation command +static byte nav_command_ID = NO_COMMAND; +static byte non_nav_command_ID = NO_COMMAND; +//////////////////////////////////////////////////////////////////////////////// // Airspeed -// -------- -static int airspeed; // m/s * 100 -static int airspeed_nudge; // m/s * 100 : additional airspeed based on throttle stick position in top 1/2 of range -static long target_airspeed; // m/s * 100 (used for Auto-flap deployment in FBW_B mode) -static float airspeed_error; // m/s * 100 -static long energy_error; // energy state error (kinetic + potential) for altitude hold -static long airspeed_energy_error; // kinetic portion of energy error (m^2/s^2) +//////////////////////////////////////////////////////////////////////////////// +// The current airspeed estimate/measurement in centimeters per second +static int airspeed; +// The calculated airspeed to use in FBW-B. Also used in higher modes for insuring min ground speed is met. +// Also used for flap deployment criteria. Centimeters per second.static long target_airspeed; +static long target_airspeed; +// The difference between current and desired airspeed. Used in the pitch controller. Centimeters per second. +static float airspeed_error; +// The calculated total energy error (kinetic (altitude) plus potential (airspeed)). +// Used by the throttle controller +static long energy_error; +// kinetic portion of energy error (m^2/s^2) +static long airspeed_energy_error; +// An amount that the airspeed should be increased in auto modes based on the user positioning the +// throttle stick in the top half of the range. Centimeters per second. +static int airspeed_nudge; +// Similar to airspeed_nudge, but used when no airspeed sensor. +// 0-(throttle_max - throttle_cruise) : throttle nudge in Auto mode using top 1/2 of throttle stick travel +static int throttle_nudge = 0; +//////////////////////////////////////////////////////////////////////////////// // Ground speed -static long groundspeed_undershoot = 0; // m/s * 100 (>=0, where > 0 => amount below min ground speed) - +//////////////////////////////////////////////////////////////////////////////// +// The amount current ground speed is below min ground speed. Centimeters per second +static long groundspeed_undershoot = 0; +//////////////////////////////////////////////////////////////////////////////// // Location Errors -// --------------- -static long bearing_error; // deg * 100 : 0 to 36000 -static long altitude_error; // meters * 100 we are off in altitude -static float crosstrack_error; // meters we are off trackline +//////////////////////////////////////////////////////////////////////////////// +// Difference between current bearing and desired bearing. Hundredths of a degree +static long bearing_error; +// Difference between current altitude and desired altitude. Centimeters +static long altitude_error; +// Distance perpandicular to the course line that we are off trackline. Meters +static float crosstrack_error; +//////////////////////////////////////////////////////////////////////////////// // Battery Sensors -// --------------- -static float battery_voltage = LOW_VOLTAGE * 1.05; // Battery Voltage of total battery, initialized above threshold for filter -static float battery_voltage1 = LOW_VOLTAGE * 1.05; // Battery Voltage of cell 1, initialized above threshold for filter -static float battery_voltage2 = LOW_VOLTAGE * 1.05; // Battery Voltage of cells 1 + 2, initialized above threshold for filter -static float battery_voltage3 = LOW_VOLTAGE * 1.05; // Battery Voltage of cells 1 + 2+3, initialized above threshold for filter -static float battery_voltage4 = LOW_VOLTAGE * 1.05; // Battery Voltage of cells 1 + 2+3 + 4, initialized above threshold for filter +//////////////////////////////////////////////////////////////////////////////// +// Battery pack 1 voltage. Initialized above the low voltage threshold to pre-load the filter and prevent low voltage events at startup. +static float battery_voltage1 = LOW_VOLTAGE * 1.05; +// Battery pack 1 instantaneous currrent draw. Amperes +static float current_amps1; +// Totalized current (Amp-hours) from battery 1 +static float current_total1; -static float current_amps; -static float current_total; +// To Do - Add support for second battery pack +//static float battery_voltage2 = LOW_VOLTAGE * 1.05; // Battery 2 Voltage, initialized above threshold for filter +//static float current_amps2; // Current (Amperes) draw from battery 2 +//static float current_total2; // Totalized current (Amp-hours) from battery 2 +//////////////////////////////////////////////////////////////////////////////// // Airspeed Sensors -// ---------------- -static float airspeed_raw; // Airspeed Sensor - is a float to better handle filtering -static float airspeed_pressure; // airspeed as a pressure value - -// Barometer Sensor variables -// -------------------------- -static unsigned long abs_pressure; +//////////////////////////////////////////////////////////////////////////////// +// Raw differential pressure measurement (filtered). ADC units +static float airspeed_raw; +// Raw differential pressure less the zero pressure offset. ADC units +static float airspeed_pressure; +//////////////////////////////////////////////////////////////////////////////// // Altitude Sensor variables -// ---------------------- +//////////////////////////////////////////////////////////////////////////////// +// Raw absolute pressure measurement (filtered). ADC units +static unsigned long abs_pressure; +// Altitude from the sonar sensor. Meters. Not yet implemented. static int sonar_alt; +//////////////////////////////////////////////////////////////////////////////// // flight mode specific -// -------------------- -static bool takeoff_complete = true; // Flag for using gps ground course instead of IMU yaw. Set false when takeoff command processes. +//////////////////////////////////////////////////////////////////////////////// +// Flag for using gps ground course instead of IMU yaw. Set false when takeoff command in process. +static bool takeoff_complete = true; +// Flag to indicate if we have landed. +//Set land_complete if we are within 2 seconds distance or within 3 meters altitude of touchdown static bool land_complete; +// Altitude threshold to complete a takeoff command in autonomous modes. Centimeters static long takeoff_altitude; -// static int landing_distance; // meters; -static int landing_pitch; // pitch for landing set by commands +// Pitch to hold during landing command in the no airspeed sensor case. Hundredths of a degree +static int landing_pitch; +// Minimum pitch to hold during takeoff command execution. Hundredths of a degree static int takeoff_pitch; +//////////////////////////////////////////////////////////////////////////////// // Loiter management -// ----------------- -static long old_target_bearing; // deg * 100 -static int loiter_total; // deg : how many times to loiter * 360 -static int loiter_delta; // deg : how far we just turned -static int loiter_sum; // deg : how far we have turned around a waypoint -static long loiter_time; // millis : when we started LOITER mode -static int loiter_time_max; // millis : how long to stay in LOITER mode +//////////////////////////////////////////////////////////////////////////////// +// Previous target bearing. Used to calculate loiter rotations. Hundredths of a degree +static long old_target_bearing; +// Total desired rotation in a loiter. Used for Loiter Turns commands. Degrees +static int loiter_total; +// The amount in degrees we have turned since recording old_target_bearing +static int loiter_delta; +// Total rotation in a loiter. Used for Loiter Turns commands and to check for missed waypoints. Degrees +static int loiter_sum; +// The amount of time we have been in a Loiter. Used for the Loiter Time command. Milliseconds. +static long loiter_time; +// The amount of time we should stay in a loiter for the Loiter Time command. Milliseconds. +static int loiter_time_max; -// these are the values for navigation control functions -// ---------------------------------------------------- -static long nav_roll; // deg * 100 : target roll angle -static long nav_pitch; // deg * 100 : target pitch angle -static int throttle_nudge = 0; // 0-(throttle_max - throttle_cruise) : throttle nudge in Auto mode using top 1/2 of throttle stick travel +//////////////////////////////////////////////////////////////////////////////// +// Navigation control variables +//////////////////////////////////////////////////////////////////////////////// +// The instantaneous desired bank angle. Hundredths of a degree +static long nav_roll; +// The instantaneous desired pitch angle. Hundredths of a degree +static long nav_pitch; -// Waypoints -// --------- -static long wp_distance; // meters - distance between plane and next waypoint -static long wp_totalDistance; // meters - distance between old and next waypoint +//////////////////////////////////////////////////////////////////////////////// +// Waypoint distances +//////////////////////////////////////////////////////////////////////////////// +// Distance between plane and next waypoint. Meters +static long wp_distance; +// Distance between previous and next waypoint. Meters +static long wp_totalDistance; +//////////////////////////////////////////////////////////////////////////////// // repeating event control -// ----------------------- -static byte event_id; // what to do - see defines -static long event_timer; // when the event was asked for in ms -static uint16_t event_delay; // how long to delay the next firing of event in millis -static int event_repeat = 0; // how many times to cycle : -1 (or -2) = forever, 2 = do one cycle, 4 = do two cycles -static int event_value; // per command value, such as PWM for servos -static int event_undo_value; // the value used to cycle events (alternate value to event_value) +//////////////////////////////////////////////////////////////////////////////// +// Flag indicating current event type +static byte event_id; +// when the event was started in ms +static long event_timer; +// how long to delay the next firing of event in millis +static uint16_t event_delay; +// how many times to cycle : -1 (or -2) = forever, 2 = do one cycle, 4 = do two cycles +static int event_repeat = 0; +// per command value, such as PWM for servos +static int event_value; +// the value used to cycle events (alternate value to event_value) +static int event_undo_value; -// delay command -// -------------- -static long condition_value; // used in condition commands (eg delay, change alt, etc.) +//////////////////////////////////////////////////////////////////////////////// +// Conditional command +//////////////////////////////////////////////////////////////////////////////// +// A value used in condition commands (eg delay, change alt, etc.) +// For example in a change altitude command, it is the altitude to change to. +static long condition_value; +// A starting value used to check the status of a conditional command. +// For example in a delay command the condition_start records that start time for the delay static long condition_start; -static int condition_rate; +// A value used in condition commands. For example the rate at which to change altitude. +static int condition_rate; +//////////////////////////////////////////////////////////////////////////////// // 3D Location vectors -// ------------------- -static struct Location home; // home location -static struct Location prev_WP; // last waypoint -static struct Location current_loc; // current location -static struct Location next_WP; // next waypoint -static struct Location guided_WP; // guided mode waypoint -static struct Location next_nav_command; // command preloaded -static struct Location next_nonnav_command; // command preloaded -static long target_altitude; // used for altitude management between waypoints -static long offset_altitude; // used for altitude management between waypoints -static bool home_is_set; // Flag for if we have g_gps lock and have set the home location +// Location structure defined in AP_Common +//////////////////////////////////////////////////////////////////////////////// +// The home location used for RTL. The location is set when we first get stable GPS lock +static struct Location home; +// Flag for if we have g_gps lock and have set the home location +static bool home_is_set; +// The location of the previous waypoint. Used for track following and altitude ramp calculations +static struct Location prev_WP; +// The plane's current location +static struct Location current_loc; +// The location of the current/active waypoint. Used for altitude ramp, track following and loiter calculations. +static struct Location next_WP; +// The location of the active waypoint in Guided mode. +static struct Location guided_WP; +// The location structure information from the Nav command being processed +static struct Location next_nav_command; +// The location structure information from the Non-Nav command being processed +static struct Location next_nonnav_command; +//////////////////////////////////////////////////////////////////////////////// +// Altitude / Climb rate control +//////////////////////////////////////////////////////////////////////////////// +// The current desired altitude. Altitude is linearly ramped between waypoints. Centimeters +static long target_altitude; +// Altitude difference between previous and current waypoint. Centimeters +static long offset_altitude; +//////////////////////////////////////////////////////////////////////////////// // IMU variables -// ------------- -static float G_Dt = 0.02; // Integration time for the gyros (DCM algorithm) - +//////////////////////////////////////////////////////////////////////////////// +// The main loop execution time. Seconds +//This is the time between calls to the DCM algorithm and is the Integration time for the gyros. +static float G_Dt = 0.02; +//////////////////////////////////////////////////////////////////////////////// // Performance monitoring -// ---------------------- -static long perf_mon_timer; // Metric based on accel gain deweighting -static int G_Dt_max = 0; // Max main loop cycle time in milliseconds +//////////////////////////////////////////////////////////////////////////////// +// Timer used to accrue data and trigger recording of the performanc monitoring log message +static long perf_mon_timer; +// The maximum main loop execution time recorded in the current performance monitoring interval +static int G_Dt_max = 0; +// The number of gps fixes recorded in the current performance monitoring interval static int gps_fix_count = 0; +// A variable used by developers to track performanc metrics. +// Currently used to record the number of GCS heartbeat messages received static int pmTest1 = 0; +//////////////////////////////////////////////////////////////////////////////// // System Timers -// -------------- -static unsigned long fast_loopTimer; // Time in miliseconds of main control loop -static unsigned long fast_loopTimeStamp; // Time Stamp when fast loop was complete -static uint8_t delta_ms_fast_loop; // Delta Time in miliseconds +//////////////////////////////////////////////////////////////////////////////// +// Time in miliseconds of start of main control loop. Milliseconds +static unsigned long fast_loopTimer; +// Time Stamp when fast loop was complete. Milliseconds +static unsigned long fast_loopTimeStamp; +// Number of milliseconds used in last main loop cycle +static uint8_t delta_ms_fast_loop; +// Counter of main loop executions. Used for performance monitoring and failsafe processing static uint16_t mainLoop_count; -static unsigned long medium_loopTimer; // Time in miliseconds of medium loop -static byte medium_loopCounter; // Counters for branching from main control loop to slower loops +// Time in miliseconds of start of medium control loop. Milliseconds +static unsigned long medium_loopTimer; +// Counters for branching from main control loop to slower loops +static byte medium_loopCounter; +// Number of milliseconds used in last medium loop cycle static uint8_t delta_ms_medium_loop; +// Counters for branching from medium control loop to slower loops static byte slow_loopCounter; +// Counter to trigger execution of very low rate processes static byte superslow_loopCounter; -static byte counter_one_herz; +// Counter to trigger execution of 1 Hz processes +static byte counter_one_herz; -static unsigned long nav_loopTimer; // used to track the elapsed time for GPS nav +// used to track the elapsed time for navigation PID integral terms +static unsigned long nav_loopTimer; +// Elapsed time since last call to navigation pid functions +static unsigned long dTnav; +// % MCU cycles used +static float load; -static unsigned long dTnav; // Delta Time in milliseconds for navigation computations -static float load; // % MCU cycles used - -AP_Relay relay; - -// Camera/Antenna mount tracking and stabilisation stuff -// -------------------------------------- -#if MOUNT == ENABLED -AP_Mount camera_mount(g_gps, &dcm); -#endif //////////////////////////////////////////////////////////////////////////////// diff --git a/ArduPlane/GCS_Mavlink.pde b/ArduPlane/GCS_Mavlink.pde index ee4810e14d..3bf8642db8 100644 --- a/ArduPlane/GCS_Mavlink.pde +++ b/ArduPlane/GCS_Mavlink.pde @@ -206,11 +206,11 @@ static NOINLINE void send_extended_status1(mavlink_channel_t chan, uint16_t pack uint16_t battery_current = -1; uint8_t battery_remaining = -1; - if (current_total != 0 && g.pack_capacity != 0) { - battery_remaining = (100.0 * (g.pack_capacity - current_total) / g.pack_capacity); + if (current_total1 != 0 && g.pack_capacity != 0) { + battery_remaining = (100.0 * (g.pack_capacity - current_total1) / g.pack_capacity); } - if (current_total != 0) { - battery_current = current_amps * 100; + if (current_total1 != 0) { + battery_current = current_amps1 * 100; } mavlink_msg_sys_status_send( @@ -219,7 +219,7 @@ static NOINLINE void send_extended_status1(mavlink_channel_t chan, uint16_t pack control_sensors_enabled, control_sensors_health, (uint16_t)(load * 1000), - battery_voltage * 1000, // mV + battery_voltage1 * 1000, // mV battery_current, // in 10mA units battery_remaining, // in % 0, // comm drops %, @@ -270,7 +270,7 @@ static NOINLINE void send_extended_status1(mavlink_channel_t chan, uint16_t pack } uint8_t status = MAV_STATE_ACTIVE; - uint16_t battery_remaining = 1000.0 * (float)(g.pack_capacity - current_total)/(float)g.pack_capacity; //Mavlink scaling 100% = 1000 + uint16_t battery_remaining = 1000.0 * (float)(g.pack_capacity - current_total1)/(float)g.pack_capacity; //Mavlink scaling 100% = 1000 mavlink_msg_sys_status_send( chan, @@ -278,7 +278,7 @@ static NOINLINE void send_extended_status1(mavlink_channel_t chan, uint16_t pack nav_mode, status, load * 1000, - battery_voltage * 1000, + battery_voltage1 * 1000, battery_remaining, packet_drops); #endif // MAVLINK10 diff --git a/ArduPlane/Log.pde b/ArduPlane/Log.pde index 6b9887c076..da073b0873 100644 --- a/ArduPlane/Log.pde +++ b/ArduPlane/Log.pde @@ -386,9 +386,9 @@ static void Log_Write_Current() DataFlash.WriteByte(HEAD_BYTE2); DataFlash.WriteByte(LOG_CURRENT_MSG); DataFlash.WriteInt(g.channel_throttle.control_in); - DataFlash.WriteInt((int)(battery_voltage * 100.0)); - DataFlash.WriteInt((int)(current_amps * 100.0)); - DataFlash.WriteInt((int)current_total); + DataFlash.WriteInt((int)(battery_voltage1 * 100.0)); + DataFlash.WriteInt((int)(current_amps1 * 100.0)); + DataFlash.WriteInt((int)current_total1); DataFlash.WriteByte(END_BYTE); } diff --git a/ArduPlane/Parameters.h b/ArduPlane/Parameters.h index 9277351bf9..c618b634c1 100644 --- a/ArduPlane/Parameters.h +++ b/ArduPlane/Parameters.h @@ -330,7 +330,7 @@ public: AP_Int32 ground_pressure; AP_Int8 compass_enabled; AP_Int16 angle_of_attack; - AP_Int8 battery_monitoring; // 0=disabled, 1=3 cell lipo, 2=4 cell lipo, 3=total voltage only, 4=total voltage and current + AP_Int8 battery_monitoring; // 0=disabled, 3=voltage only, 4=voltage and current AP_Float volt_div_ratio; AP_Float curr_amp_per_volt; AP_Float input_voltage; diff --git a/ArduPlane/commands_logic.pde b/ArduPlane/commands_logic.pde index b1ae83b171..0dff0191d4 100644 --- a/ArduPlane/commands_logic.pde +++ b/ArduPlane/commands_logic.pde @@ -64,20 +64,6 @@ handle_process_condition_command() do_change_alt(); break; - /* case MAV_CMD_NAV_LAND_OPTIONS: // TODO - Add the command or equiv to MAVLink (repair in verify_condition() also) - gcs_send_text_P(SEVERITY_LOW,PSTR("Landing options set")); - - // pitch in deg, airspeed m/s, throttle %, track WP 1 or 0 - landing_pitch = next_nav_command.lng * 100; - g.airspeed_cruise = next_nav_command.alt * 100; - g.throttle_cruise = next_nav_command.lat; - landing_distance = next_nav_command.p1; - - SendDebug_P("MSG: throttle_cruise = "); - SendDebugln(g.throttle_cruise,DEC); - break; - */ - default: break; } diff --git a/ArduPlane/config.h b/ArduPlane/config.h index 0d599e4d43..87bf4d639c 100644 --- a/ArduPlane/config.h +++ b/ArduPlane/config.h @@ -87,6 +87,8 @@ # define PUSHBUTTON_PIN 41 # define USB_MUX_PIN -1 # define CONFIG_RELAY ENABLED +# define BATTERY_PIN_1 0 +# define CURRENT_PIN_1 1 #elif CONFIG_APM_HARDWARE == APM_HARDWARE_APM2 # define A_LED_PIN 27 # define B_LED_PIN 26 @@ -97,6 +99,8 @@ # define PUSHBUTTON_PIN (-1) # define CLI_SLIDER_ENABLED DISABLED # define USB_MUX_PIN 23 +# define BATTERY_PIN_1 1 +# define CURRENT_PIN_1 2 #endif ////////////////////////////////////////////////////////////////////////////// @@ -161,10 +165,10 @@ # endif #elif CONFIG_PITOT_SOURCE == PITOT_SOURCE_ANALOG_PIN # ifndef CONFIG_PITOT_SOURCE_ANALOG_PIN -# define CONFIG_PITOT_SOURCE_ANALOG_PIN AN4 +# define CONFIG_PITOT_SOURCE_ANALOG_PIN 0 # endif #else -# warning Invalid value for CONFIG_PITOT_SOURCE, disabling sonar +# warning Invalid value for CONFIG_PITOT_SOURCE, disabling airspeed # undef PITOT_ENABLED # define PITOT_ENABLED DISABLED #endif @@ -173,10 +177,9 @@ # define SONAR_TYPE MAX_SONAR_LV // MAX_SONAR_XL, #endif -/* In ArduPlane PITOT usually takes the place of SONAR, but some bits - * still depend on SONAR. - */ -#define SONAR_ENABLED PITOT_ENABLED +#ifndef SONAR_ENABLED +#define SONAR_ENABLED DISABLED +#endif ////////////////////////////////////////////////////////////////////////////// // HIL_MODE OPTIONAL @@ -225,12 +228,17 @@ # define LOW_VOLTAGE 9.6 #endif #ifndef VOLT_DIV_RATIO -# define VOLT_DIV_RATIO 3.56 +# define VOLT_DIV_RATIO 3.56 // This is the proper value for an on-board APM1 voltage divider with a 3.9kOhm resistor +//# define VOLT_DIV_RATIO 15.70 // This is the proper value for the AttoPilot 50V/90A sensor +//# define VOLT_DIV_RATIO 4.127 // This is the proper value for the AttoPilot 13.6V/45A sensor + #endif #ifndef CURR_AMP_PER_VOLT -# define CURR_AMP_PER_VOLT 27.32 +# define CURR_AMP_PER_VOLT 27.32 // This is the proper value for the AttoPilot 50V/90A sensor +//# define CURR_AMP_PER_VOLT 13.66 // This is the proper value for the AttoPilot 13.6V/45A sensor #endif + #ifndef CURR_AMPS_OFFSET # define CURR_AMPS_OFFSET 0.0 #endif diff --git a/ArduPlane/defines.h b/ArduPlane/defines.h index 3c365f68eb..67afa10cb2 100644 --- a/ArduPlane/defines.h +++ b/ArduPlane/defines.h @@ -183,18 +183,8 @@ enum gcs_severity { #define BATTERY_VOLTAGE(x) (x*(g.input_voltage/1024.0))*g.volt_div_ratio - #define CURRENT_AMPS(x) ((x*(g.input_voltage/1024.0))-CURR_AMPS_OFFSET)*g.curr_amp_per_volt -#define AIRSPEED_CH 7 // The external ADC channel for the airspeed sensor -#define BATTERY_PIN1 0 // These are the pins for the voltage dividers -#define BATTERY_PIN2 1 -#define BATTERY_PIN3 2 -#define BATTERY_PIN4 3 - -#define VOLTAGE_PIN_0 0 // These are the pins for current sensor: voltage -#define CURRENT_PIN_1 1 // and current - #define RELAY_PIN 47 diff --git a/ArduPlane/sensors.pde b/ArduPlane/sensors.pde index cb96f16e2b..c31c3ab69f 100644 --- a/ArduPlane/sensors.pde +++ b/ArduPlane/sensors.pde @@ -106,25 +106,21 @@ static void zero_airspeed(void) static void read_battery(void) { - battery_voltage1 = BATTERY_VOLTAGE(analogRead(BATTERY_PIN1)) * .1 + battery_voltage1 * .9; - battery_voltage2 = BATTERY_VOLTAGE(analogRead(BATTERY_PIN2)) * .1 + battery_voltage2 * .9; - battery_voltage3 = BATTERY_VOLTAGE(analogRead(BATTERY_PIN3)) * .1 + battery_voltage3 * .9; - battery_voltage4 = BATTERY_VOLTAGE(analogRead(BATTERY_PIN4)) * .1 + battery_voltage4 * .9; - - if(g.battery_monitoring == 1) - battery_voltage = battery_voltage3; // set total battery voltage, for telemetry stream - if(g.battery_monitoring == 2) - battery_voltage = battery_voltage4; + if(g.battery_monitoring == 0) { + battery_voltage1 = 0; + return; + } + if(g.battery_monitoring == 3 || g.battery_monitoring == 4) - battery_voltage = battery_voltage1; + battery_voltage1 = BATTERY_VOLTAGE(analogRead(BATTERY_PIN_1)) * .1 + battery_voltage1 * .9; if(g.battery_monitoring == 4) { - current_amps = CURRENT_AMPS(analogRead(CURRENT_PIN_1)) * .1 + current_amps * .9; //reads power sensor current pin - current_total += current_amps * (float)delta_ms_medium_loop * 0.000278; + current_amps1 = CURRENT_AMPS(analogRead(CURRENT_PIN_1)) * .1 + current_amps1 * .9; //reads power sensor current pin + current_total1 += current_amps1 * (float)delta_ms_medium_loop * 0.0002778; // .0002778 is 1/3600 (conversion to hours) } #if BATTERY_EVENT == ENABLED - if(battery_voltage < LOW_VOLTAGE) low_battery_event(); - if(g.battery_monitoring == 4 && current_total > g.pack_capacity) low_battery_event(); + if(battery_voltage1 < LOW_VOLTAGE) low_battery_event(); + if(g.battery_monitoring == 4 && current_total1 > g.pack_capacity) low_battery_event(); #endif } diff --git a/ArduPlane/setup.pde b/ArduPlane/setup.pde index 2841e8b787..49dd6f9ca7 100644 --- a/ArduPlane/setup.pde +++ b/ArduPlane/setup.pde @@ -301,8 +301,11 @@ setup_compass(uint8_t argc, const Menu::arg *argv) } else if (!strcmp_P(argv[1].str, PSTR("off"))) { g.compass_enabled = false; + } else if (!strcmp_P(argv[1].str, PSTR("reset"))) { + compass.set_offsets(0,0,0); + } else { - Serial.printf_P(PSTR("\nOptions:[on,off]\n")); + Serial.printf_P(PSTR("\nOptions:[on,off,reset]\n")); report_compass(); return 0; } @@ -319,7 +322,7 @@ setup_batt_monitor(uint8_t argc, const Menu::arg *argv) g.battery_monitoring.set_and_save(argv[1].i); } else { - Serial.printf_P(PSTR("\nOptions: 0-4")); + Serial.printf_P(PSTR("\nOptions: 3-4")); } report_batt_monitor(); @@ -336,8 +339,6 @@ static void report_batt_monitor() Serial.printf_P(PSTR("Batt Mointor\n")); print_divider(); if(g.battery_monitoring == 0) Serial.printf_P(PSTR("Batt monitoring disabled")); - if(g.battery_monitoring == 1) Serial.printf_P(PSTR("Monitoring 3 cell")); - if(g.battery_monitoring == 2) Serial.printf_P(PSTR("Monitoring 4 cell")); if(g.battery_monitoring == 3) Serial.printf_P(PSTR("Monitoring batt volts")); if(g.battery_monitoring == 4) Serial.printf_P(PSTR("Monitoring volts and current")); print_blanks(2); diff --git a/ArduPlane/test.pde b/ArduPlane/test.pde index ebe7d76091..105d343ea1 100644 --- a/ArduPlane/test.pde +++ b/ArduPlane/test.pde @@ -14,7 +14,6 @@ static int8_t test_adc(uint8_t argc, const Menu::arg *argv); #endif static int8_t test_imu(uint8_t argc, const Menu::arg *argv); static int8_t test_battery(uint8_t argc, const Menu::arg *argv); -static int8_t test_current(uint8_t argc, const Menu::arg *argv); static int8_t test_relay(uint8_t argc, const Menu::arg *argv); static int8_t test_wp(uint8_t argc, const Menu::arg *argv); static int8_t test_airspeed(uint8_t argc, const Menu::arg *argv); @@ -34,18 +33,18 @@ static int8_t test_logging(uint8_t argc, const Menu::arg *argv); // User enters the string in the console to call the functions on the right. // See class Menu in AP_Common for implementation details static const struct Menu::command test_menu_commands[] PROGMEM = { - {"pwm", test_radio_pwm}, - {"radio", test_radio}, - {"passthru", test_passthru}, - {"failsafe", test_failsafe}, - {"battery", test_battery}, - {"relay", test_relay}, - {"waypoints", test_wp}, - {"xbee", test_xbee}, - {"eedump", test_eedump}, - {"modeswitch", test_modeswitch}, + {"pwm", test_radio_pwm}, + {"radio", test_radio}, + {"passthru", test_passthru}, + {"failsafe", test_failsafe}, + {"battery", test_battery}, + {"relay", test_relay}, + {"waypoints", test_wp}, + {"xbee", test_xbee}, + {"eedump", test_eedump}, + {"modeswitch", test_modeswitch}, #if CONFIG_APM_HARDWARE != APM_HARDWARE_APM2 - {"dipswitches", test_dipswitches}, + {"dipswitches", test_dipswitches}, #endif // Tests below here are for hardware sensors only present @@ -60,7 +59,6 @@ static const struct Menu::command test_menu_commands[] PROGMEM = { {"airspeed", test_airspeed}, {"airpressure", test_pressure}, {"compass", test_mag}, - {"current", test_current}, #elif HIL_MODE == HIL_MODE_SENSORS {"adc", test_adc}, {"gps", test_gps}, @@ -260,26 +258,7 @@ test_failsafe(uint8_t argc, const Menu::arg *argv) static int8_t test_battery(uint8_t argc, const Menu::arg *argv) { -if (g.battery_monitoring >=1 && g.battery_monitoring < 4) { - for (int i = 0; i < 80; i++){ // Need to get many samples for filter to stabilize - delay(20); - read_battery(); - } - Serial.printf_P(PSTR("Volts: 1:%2.2f, 2:%2.2f, 3:%2.2f, 4:%2.2f\n"), - battery_voltage1, - battery_voltage2, - battery_voltage3, - battery_voltage4); -} else { - Serial.printf_P(PSTR("Not enabled\n")); -} - return (0); -} - -static int8_t -test_current(uint8_t argc, const Menu::arg *argv) -{ -if (g.battery_monitoring == 4) { +if (g.battery_monitoring == 3 || g.battery_monitoring == 4) { print_hit_enter(); delta_ms_medium_loop = 100; @@ -287,10 +266,17 @@ if (g.battery_monitoring == 4) { delay(100); read_radio(); read_battery(); - Serial.printf_P(PSTR("V: %4.4f, A: %4.4f, mAh: %4.4f\n"), - battery_voltage, - current_amps, - current_total); + if (g.battery_monitoring == 3){ + Serial.printf_P(PSTR("V: %4.4f\n"), + battery_voltage1, + current_amps1, + current_total1); + } else { + Serial.printf_P(PSTR("V: %4.4f, A: %4.4f, mAh: %4.4f\n"), + battery_voltage1, + current_amps1, + current_total1); + } // write out the servo PWM values // ------------------------------ diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/Jetibox/JetiBox.cpp b/Tools/ArduPPM/WorkBasket/Jeti_Duplex/Jetibox/JetiBox.cpp similarity index 100% rename from Tools/ArduPPM/WorkBasket/Jeti Duplex/Jetibox/JetiBox.cpp rename to Tools/ArduPPM/WorkBasket/Jeti_Duplex/Jetibox/JetiBox.cpp diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/Jetibox/JetiBox.h b/Tools/ArduPPM/WorkBasket/Jeti_Duplex/Jetibox/JetiBox.h similarity index 100% rename from Tools/ArduPPM/WorkBasket/Jeti Duplex/Jetibox/JetiBox.h rename to Tools/ArduPPM/WorkBasket/Jeti_Duplex/Jetibox/JetiBox.h diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/X-DIY/APM_Config.h b/Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/X-DIY/APM_Config.h similarity index 100% rename from Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/X-DIY/APM_Config.h rename to Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/X-DIY/APM_Config.h diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/X-DIY/APM_Config.h.reference b/Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/X-DIY/APM_Config.h.reference similarity index 100% rename from Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/X-DIY/APM_Config.h.reference rename to Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/X-DIY/APM_Config.h.reference diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/X-DIY/APM_Config_xplane.h b/Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/X-DIY/APM_Config_xplane.h similarity index 100% rename from Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/X-DIY/APM_Config_xplane.h rename to Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/X-DIY/APM_Config_xplane.h diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/X-DIY/ArduPilotMega.pde b/Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/X-DIY/ArduPilotMega.pde similarity index 100% rename from Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/X-DIY/ArduPilotMega.pde rename to Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/X-DIY/ArduPilotMega.pde diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/X-DIY/Attitude.pde b/Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/X-DIY/Attitude.pde similarity index 100% rename from Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/X-DIY/Attitude.pde rename to Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/X-DIY/Attitude.pde diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/X-DIY/DCM.pde b/Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/X-DIY/DCM.pde similarity index 100% rename from Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/X-DIY/DCM.pde rename to Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/X-DIY/DCM.pde diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/X-DIY/EEPROM map.txt b/Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/X-DIY/EEPROM map.txt similarity index 100% rename from Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/X-DIY/EEPROM map.txt rename to Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/X-DIY/EEPROM map.txt diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/X-DIY/EEPROM.pde b/Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/X-DIY/EEPROM.pde similarity index 100% rename from Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/X-DIY/EEPROM.pde rename to Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/X-DIY/EEPROM.pde diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/X-DIY/GCS_Ardupilot.pde b/Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/X-DIY/GCS_Ardupilot.pde similarity index 100% rename from Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/X-DIY/GCS_Ardupilot.pde rename to Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/X-DIY/GCS_Ardupilot.pde diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/X-DIY/GCS_DebugTerminal.pde b/Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/X-DIY/GCS_DebugTerminal.pde similarity index 100% rename from Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/X-DIY/GCS_DebugTerminal.pde rename to Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/X-DIY/GCS_DebugTerminal.pde diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/X-DIY/GCS_IMU_ouput.pde b/Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/X-DIY/GCS_IMU_ouput.pde similarity index 100% rename from Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/X-DIY/GCS_IMU_ouput.pde rename to Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/X-DIY/GCS_IMU_ouput.pde diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/X-DIY/GCS_Jason_text.pde b/Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/X-DIY/GCS_Jason_text.pde similarity index 100% rename from Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/X-DIY/GCS_Jason_text.pde rename to Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/X-DIY/GCS_Jason_text.pde diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/X-DIY/GCS_Standard.pde b/Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/X-DIY/GCS_Standard.pde similarity index 100% rename from Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/X-DIY/GCS_Standard.pde rename to Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/X-DIY/GCS_Standard.pde diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/X-DIY/GCS_XDIY.pde b/Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/X-DIY/GCS_XDIY.pde similarity index 100% rename from Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/X-DIY/GCS_XDIY.pde rename to Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/X-DIY/GCS_XDIY.pde diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/X-DIY/GCS_Xplane.pde b/Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/X-DIY/GCS_Xplane.pde similarity index 100% rename from Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/X-DIY/GCS_Xplane.pde rename to Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/X-DIY/GCS_Xplane.pde diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/X-DIY/HIL_output.pde b/Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/X-DIY/HIL_output.pde similarity index 100% rename from Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/X-DIY/HIL_output.pde rename to Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/X-DIY/HIL_output.pde diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/X-DIY/Jeti.pde b/Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/X-DIY/Jeti.pde similarity index 100% rename from Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/X-DIY/Jeti.pde rename to Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/X-DIY/Jeti.pde diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/X-DIY/Log.pde b/Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/X-DIY/Log.pde similarity index 100% rename from Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/X-DIY/Log.pde rename to Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/X-DIY/Log.pde diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/X-DIY/command description.txt b/Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/X-DIY/command description.txt similarity index 100% rename from Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/X-DIY/command description.txt rename to Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/X-DIY/command description.txt diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/X-DIY/commands.pde b/Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/X-DIY/commands.pde similarity index 100% rename from Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/X-DIY/commands.pde rename to Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/X-DIY/commands.pde diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/X-DIY/commands_process.pde b/Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/X-DIY/commands_process.pde similarity index 100% rename from Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/X-DIY/commands_process.pde rename to Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/X-DIY/commands_process.pde diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/X-DIY/config.h b/Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/X-DIY/config.h similarity index 100% rename from Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/X-DIY/config.h rename to Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/X-DIY/config.h diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/X-DIY/control_modes.pde b/Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/X-DIY/control_modes.pde similarity index 100% rename from Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/X-DIY/control_modes.pde rename to Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/X-DIY/control_modes.pde diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/X-DIY/debug.pde b/Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/X-DIY/debug.pde similarity index 100% rename from Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/X-DIY/debug.pde rename to Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/X-DIY/debug.pde diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/X-DIY/defines.h b/Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/X-DIY/defines.h similarity index 100% rename from Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/X-DIY/defines.h rename to Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/X-DIY/defines.h diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/X-DIY/events.pde b/Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/X-DIY/events.pde similarity index 100% rename from Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/X-DIY/events.pde rename to Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/X-DIY/events.pde diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/X-DIY/navigation.pde b/Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/X-DIY/navigation.pde similarity index 100% rename from Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/X-DIY/navigation.pde rename to Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/X-DIY/navigation.pde diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/X-DIY/radio.pde b/Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/X-DIY/radio.pde similarity index 100% rename from Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/X-DIY/radio.pde rename to Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/X-DIY/radio.pde diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/X-DIY/sensors.pde b/Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/X-DIY/sensors.pde similarity index 100% rename from Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/X-DIY/sensors.pde rename to Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/X-DIY/sensors.pde diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/X-DIY/setup.pde b/Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/X-DIY/setup.pde similarity index 100% rename from Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/X-DIY/setup.pde rename to Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/X-DIY/setup.pde diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/X-DIY/system.pde b/Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/X-DIY/system.pde similarity index 100% rename from Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/X-DIY/system.pde rename to Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/X-DIY/system.pde diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/X-DIY/test.pde b/Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/X-DIY/test.pde similarity index 100% rename from Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/X-DIY/test.pde rename to Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/X-DIY/test.pde diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/APM_ADC/APM_ADC.cpp b/Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/APM_ADC/APM_ADC.cpp similarity index 100% rename from Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/APM_ADC/APM_ADC.cpp rename to Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/APM_ADC/APM_ADC.cpp diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/APM_ADC/APM_ADC.h b/Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/APM_ADC/APM_ADC.h similarity index 100% rename from Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/APM_ADC/APM_ADC.h rename to Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/APM_ADC/APM_ADC.h diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/APM_ADC/examples/APM_ADC_test/APM_ADC_test.pde b/Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/APM_ADC/examples/APM_ADC_test/APM_ADC_test.pde similarity index 100% rename from Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/APM_ADC/examples/APM_ADC_test/APM_ADC_test.pde rename to Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/APM_ADC/examples/APM_ADC_test/APM_ADC_test.pde diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/APM_ADC/keywords.txt b/Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/APM_ADC/keywords.txt similarity index 100% rename from Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/APM_ADC/keywords.txt rename to Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/APM_ADC/keywords.txt diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/APM_BMP085/APM_BMP085.cpp b/Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/APM_BMP085/APM_BMP085.cpp similarity index 100% rename from Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/APM_BMP085/APM_BMP085.cpp rename to Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/APM_BMP085/APM_BMP085.cpp diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/APM_BMP085/APM_BMP085.h b/Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/APM_BMP085/APM_BMP085.h similarity index 100% rename from Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/APM_BMP085/APM_BMP085.h rename to Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/APM_BMP085/APM_BMP085.h diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/APM_BMP085/examples/APM_BMP085_test/APM_BMP085_test.pde b/Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/APM_BMP085/examples/APM_BMP085_test/APM_BMP085_test.pde similarity index 100% rename from Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/APM_BMP085/examples/APM_BMP085_test/APM_BMP085_test.pde rename to Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/APM_BMP085/examples/APM_BMP085_test/APM_BMP085_test.pde diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/APM_BMP085/keywords.txt b/Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/APM_BMP085/keywords.txt similarity index 100% rename from Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/APM_BMP085/keywords.txt rename to Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/APM_BMP085/keywords.txt diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/APM_BinComm/APM_BinComm.cpp b/Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/APM_BinComm/APM_BinComm.cpp similarity index 100% rename from Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/APM_BinComm/APM_BinComm.cpp rename to Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/APM_BinComm/APM_BinComm.cpp diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/APM_BinComm/APM_BinComm.h b/Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/APM_BinComm/APM_BinComm.h similarity index 100% rename from Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/APM_BinComm/APM_BinComm.h rename to Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/APM_BinComm/APM_BinComm.h diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/APM_BinComm/keywords.txt b/Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/APM_BinComm/keywords.txt similarity index 100% rename from Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/APM_BinComm/keywords.txt rename to Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/APM_BinComm/keywords.txt diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/APM_BinComm/protocol/protocol.def b/Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/APM_BinComm/protocol/protocol.def similarity index 100% rename from Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/APM_BinComm/protocol/protocol.def rename to Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/APM_BinComm/protocol/protocol.def diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/APM_BinComm/protocol/protocol.h b/Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/APM_BinComm/protocol/protocol.h similarity index 100% rename from Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/APM_BinComm/protocol/protocol.h rename to Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/APM_BinComm/protocol/protocol.h diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/APM_BinComm/protocol/protogen.awk b/Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/APM_BinComm/protocol/protogen.awk similarity index 100% rename from Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/APM_BinComm/protocol/protogen.awk rename to Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/APM_BinComm/protocol/protogen.awk diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/APM_BinComm/test/Makefile b/Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/APM_BinComm/test/Makefile similarity index 100% rename from Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/APM_BinComm/test/Makefile rename to Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/APM_BinComm/test/Makefile diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/APM_BinComm/test/WProgram.h b/Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/APM_BinComm/test/WProgram.h similarity index 100% rename from Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/APM_BinComm/test/WProgram.h rename to Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/APM_BinComm/test/WProgram.h diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/APM_BinComm/test/test.cpp b/Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/APM_BinComm/test/test.cpp similarity index 100% rename from Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/APM_BinComm/test/test.cpp rename to Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/APM_BinComm/test/test.cpp diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/APM_Compass/APM_Compass.cpp b/Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/APM_Compass/APM_Compass.cpp similarity index 100% rename from Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/APM_Compass/APM_Compass.cpp rename to Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/APM_Compass/APM_Compass.cpp diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/APM_Compass/APM_Compass.h b/Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/APM_Compass/APM_Compass.h similarity index 100% rename from Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/APM_Compass/APM_Compass.h rename to Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/APM_Compass/APM_Compass.h diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/APM_Compass/examples/APM_Compass_test/APM_Compass_test.pde b/Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/APM_Compass/examples/APM_Compass_test/APM_Compass_test.pde similarity index 100% rename from Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/APM_Compass/examples/APM_Compass_test/APM_Compass_test.pde rename to Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/APM_Compass/examples/APM_Compass_test/APM_Compass_test.pde diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/APM_Compass/keywords.txt b/Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/APM_Compass/keywords.txt similarity index 100% rename from Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/APM_Compass/keywords.txt rename to Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/APM_Compass/keywords.txt diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/APM_FastSerial/APM_FastSerial.cpp b/Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/APM_FastSerial/APM_FastSerial.cpp similarity index 100% rename from Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/APM_FastSerial/APM_FastSerial.cpp rename to Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/APM_FastSerial/APM_FastSerial.cpp diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/APM_FastSerial/APM_FastSerial.h b/Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/APM_FastSerial/APM_FastSerial.h similarity index 100% rename from Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/APM_FastSerial/APM_FastSerial.h rename to Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/APM_FastSerial/APM_FastSerial.h diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/APM_FastSerial/examples/APM_FastSerial/APM_FastSerial.pde b/Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/APM_FastSerial/examples/APM_FastSerial/APM_FastSerial.pde similarity index 100% rename from Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/APM_FastSerial/examples/APM_FastSerial/APM_FastSerial.pde rename to Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/APM_FastSerial/examples/APM_FastSerial/APM_FastSerial.pde diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/APM_FastSerial/keywords.txt b/Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/APM_FastSerial/keywords.txt similarity index 100% rename from Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/APM_FastSerial/keywords.txt rename to Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/APM_FastSerial/keywords.txt diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/APM_RC/APM_RC.cpp b/Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/APM_RC/APM_RC.cpp similarity index 100% rename from Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/APM_RC/APM_RC.cpp rename to Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/APM_RC/APM_RC.cpp diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/APM_RC/APM_RC.h b/Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/APM_RC/APM_RC.h similarity index 100% rename from Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/APM_RC/APM_RC.h rename to Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/APM_RC/APM_RC.h diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/APM_RC/examples/APM_radio/APM_radio.pde b/Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/APM_RC/examples/APM_radio/APM_radio.pde similarity index 100% rename from Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/APM_RC/examples/APM_radio/APM_radio.pde rename to Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/APM_RC/examples/APM_radio/APM_radio.pde diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/APM_RC/keywords.txt b/Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/APM_RC/keywords.txt similarity index 100% rename from Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/APM_RC/keywords.txt rename to Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/APM_RC/keywords.txt diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/APM_RC_QUAD/APM_RC_QUAD.cpp b/Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/APM_RC_QUAD/APM_RC_QUAD.cpp similarity index 100% rename from Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/APM_RC_QUAD/APM_RC_QUAD.cpp rename to Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/APM_RC_QUAD/APM_RC_QUAD.cpp diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/APM_RC_QUAD/APM_RC_QUAD.h b/Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/APM_RC_QUAD/APM_RC_QUAD.h similarity index 100% rename from Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/APM_RC_QUAD/APM_RC_QUAD.h rename to Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/APM_RC_QUAD/APM_RC_QUAD.h diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/APM_RC_QUAD/examples/APM_radio_quad/APM_radio_quad.pde b/Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/APM_RC_QUAD/examples/APM_radio_quad/APM_radio_quad.pde similarity index 100% rename from Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/APM_RC_QUAD/examples/APM_radio_quad/APM_radio_quad.pde rename to Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/APM_RC_QUAD/examples/APM_radio_quad/APM_radio_quad.pde diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/APM_RC_QUAD/keywords.txt b/Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/APM_RC_QUAD/keywords.txt similarity index 100% rename from Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/APM_RC_QUAD/keywords.txt rename to Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/APM_RC_QUAD/keywords.txt diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_Common/AP_Common.cpp b/Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/AP_Common/AP_Common.cpp similarity index 100% rename from Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_Common/AP_Common.cpp rename to Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/AP_Common/AP_Common.cpp diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_Common/AP_Common.h b/Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/AP_Common/AP_Common.h similarity index 100% rename from Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_Common/AP_Common.h rename to Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/AP_Common/AP_Common.h diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_Common/c++.cpp b/Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/AP_Common/c++.cpp similarity index 100% rename from Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_Common/c++.cpp rename to Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/AP_Common/c++.cpp diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_Common/examples/menu/menu.pde b/Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/AP_Common/examples/menu/menu.pde similarity index 100% rename from Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_Common/examples/menu/menu.pde rename to Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/AP_Common/examples/menu/menu.pde diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_Common/include/menu.h b/Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/AP_Common/include/menu.h similarity index 100% rename from Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_Common/include/menu.h rename to Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/AP_Common/include/menu.h diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_Common/keywords.txt b/Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/AP_Common/keywords.txt similarity index 100% rename from Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_Common/keywords.txt rename to Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/AP_Common/keywords.txt diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_Common/menu.cpp b/Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/AP_Common/menu.cpp similarity index 100% rename from Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_Common/menu.cpp rename to Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/AP_Common/menu.cpp diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_Compass/AP_Compass.cpp b/Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/AP_Compass/AP_Compass.cpp similarity index 100% rename from Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_Compass/AP_Compass.cpp rename to Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/AP_Compass/AP_Compass.cpp diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_Compass/AP_Compass.h b/Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/AP_Compass/AP_Compass.h similarity index 100% rename from Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_Compass/AP_Compass.h rename to Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/AP_Compass/AP_Compass.h diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_Compass/Compass.h b/Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/AP_Compass/Compass.h similarity index 100% rename from Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_Compass/Compass.h rename to Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/AP_Compass/Compass.h diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_Compass/examples/AP_Compass_test/AP_Compass_test.pde b/Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/AP_Compass/examples/AP_Compass_test/AP_Compass_test.pde similarity index 100% rename from Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_Compass/examples/AP_Compass_test/AP_Compass_test.pde rename to Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/AP_Compass/examples/AP_Compass_test/AP_Compass_test.pde diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_Compass/keywords.txt b/Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/AP_Compass/keywords.txt similarity index 100% rename from Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_Compass/keywords.txt rename to Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/AP_Compass/keywords.txt diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_GPS/AP_GPS.h b/Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/AP_GPS/AP_GPS.h similarity index 100% rename from Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_GPS/AP_GPS.h rename to Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/AP_GPS/AP_GPS.h diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_GPS/AP_GPS_406.cpp b/Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/AP_GPS/AP_GPS_406.cpp similarity index 100% rename from Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_GPS/AP_GPS_406.cpp rename to Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/AP_GPS/AP_GPS_406.cpp diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_GPS/AP_GPS_406.h b/Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/AP_GPS/AP_GPS_406.h similarity index 100% rename from Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_GPS/AP_GPS_406.h rename to Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/AP_GPS/AP_GPS_406.h diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_GPS/AP_GPS_Auto.cpp b/Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/AP_GPS/AP_GPS_Auto.cpp similarity index 100% rename from Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_GPS/AP_GPS_Auto.cpp rename to Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/AP_GPS/AP_GPS_Auto.cpp diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_GPS/AP_GPS_Auto.h b/Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/AP_GPS/AP_GPS_Auto.h similarity index 100% rename from Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_GPS/AP_GPS_Auto.h rename to Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/AP_GPS/AP_GPS_Auto.h diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_GPS/AP_GPS_IMU.cpp b/Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/AP_GPS/AP_GPS_IMU.cpp similarity index 100% rename from Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_GPS/AP_GPS_IMU.cpp rename to Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/AP_GPS/AP_GPS_IMU.cpp diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_GPS/AP_GPS_IMU.h b/Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/AP_GPS/AP_GPS_IMU.h similarity index 100% rename from Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_GPS/AP_GPS_IMU.h rename to Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/AP_GPS/AP_GPS_IMU.h diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_GPS/AP_GPS_MTK.cpp b/Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/AP_GPS/AP_GPS_MTK.cpp similarity index 100% rename from Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_GPS/AP_GPS_MTK.cpp rename to Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/AP_GPS/AP_GPS_MTK.cpp diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_GPS/AP_GPS_MTK.h b/Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/AP_GPS/AP_GPS_MTK.h similarity index 100% rename from Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_GPS/AP_GPS_MTK.h rename to Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/AP_GPS/AP_GPS_MTK.h diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_GPS/AP_GPS_NMEA.cpp b/Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/AP_GPS/AP_GPS_NMEA.cpp similarity index 100% rename from Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_GPS/AP_GPS_NMEA.cpp rename to Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/AP_GPS/AP_GPS_NMEA.cpp diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_GPS/AP_GPS_NMEA.h b/Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/AP_GPS/AP_GPS_NMEA.h similarity index 100% rename from Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_GPS/AP_GPS_NMEA.h rename to Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/AP_GPS/AP_GPS_NMEA.h diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_GPS/AP_GPS_None.h b/Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/AP_GPS/AP_GPS_None.h similarity index 100% rename from Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_GPS/AP_GPS_None.h rename to Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/AP_GPS/AP_GPS_None.h diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_GPS/AP_GPS_SIRF.cpp b/Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/AP_GPS/AP_GPS_SIRF.cpp similarity index 100% rename from Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_GPS/AP_GPS_SIRF.cpp rename to Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/AP_GPS/AP_GPS_SIRF.cpp diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_GPS/AP_GPS_SIRF.h b/Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/AP_GPS/AP_GPS_SIRF.h similarity index 100% rename from Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_GPS/AP_GPS_SIRF.h rename to Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/AP_GPS/AP_GPS_SIRF.h diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_GPS/AP_GPS_UBLOX.cpp b/Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/AP_GPS/AP_GPS_UBLOX.cpp similarity index 100% rename from Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_GPS/AP_GPS_UBLOX.cpp rename to Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/AP_GPS/AP_GPS_UBLOX.cpp diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_GPS/AP_GPS_UBLOX.h b/Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/AP_GPS/AP_GPS_UBLOX.h similarity index 100% rename from Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_GPS/AP_GPS_UBLOX.h rename to Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/AP_GPS/AP_GPS_UBLOX.h diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_GPS/GPS.cpp b/Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/AP_GPS/GPS.cpp similarity index 100% rename from Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_GPS/GPS.cpp rename to Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/AP_GPS/GPS.cpp diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_GPS/GPS.h b/Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/AP_GPS/GPS.h similarity index 100% rename from Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_GPS/GPS.h rename to Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/AP_GPS/GPS.h diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_GPS/examples/GPS_406_test/GPS_406_test.pde b/Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/AP_GPS/examples/GPS_406_test/GPS_406_test.pde similarity index 100% rename from Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_GPS/examples/GPS_406_test/GPS_406_test.pde rename to Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/AP_GPS/examples/GPS_406_test/GPS_406_test.pde diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_GPS/examples/GPS_AUTO_test/GPS_AUTO_test.pde b/Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/AP_GPS/examples/GPS_AUTO_test/GPS_AUTO_test.pde similarity index 100% rename from Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_GPS/examples/GPS_AUTO_test/GPS_AUTO_test.pde rename to Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/AP_GPS/examples/GPS_AUTO_test/GPS_AUTO_test.pde diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_GPS/examples/GPS_MTK_test/GPS_MTK_test.pde b/Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/AP_GPS/examples/GPS_MTK_test/GPS_MTK_test.pde similarity index 100% rename from Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_GPS/examples/GPS_MTK_test/GPS_MTK_test.pde rename to Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/AP_GPS/examples/GPS_MTK_test/GPS_MTK_test.pde diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_GPS/examples/GPS_NMEA_test/GPS_NMEA_test.pde b/Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/AP_GPS/examples/GPS_NMEA_test/GPS_NMEA_test.pde similarity index 100% rename from Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_GPS/examples/GPS_NMEA_test/GPS_NMEA_test.pde rename to Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/AP_GPS/examples/GPS_NMEA_test/GPS_NMEA_test.pde diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_GPS/examples/GPS_UBLOX_test/GPS_UBLOX_test.pde b/Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/AP_GPS/examples/GPS_UBLOX_test/GPS_UBLOX_test.pde similarity index 100% rename from Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_GPS/examples/GPS_UBLOX_test/GPS_UBLOX_test.pde rename to Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/AP_GPS/examples/GPS_UBLOX_test/GPS_UBLOX_test.pde diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_Math/AP_Math.h b/Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/AP_Math/AP_Math.h similarity index 100% rename from Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_Math/AP_Math.h rename to Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/AP_Math/AP_Math.h diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_Math/keywords.txt b/Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/AP_Math/keywords.txt similarity index 100% rename from Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_Math/keywords.txt rename to Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/AP_Math/keywords.txt diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_Math/matrix3.h b/Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/AP_Math/matrix3.h similarity index 100% rename from Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_Math/matrix3.h rename to Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/AP_Math/matrix3.h diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_Math/vector2.h b/Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/AP_Math/vector2.h similarity index 100% rename from Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_Math/vector2.h rename to Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/AP_Math/vector2.h diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_Math/vector3.h b/Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/AP_Math/vector3.h similarity index 100% rename from Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_Math/vector3.h rename to Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/AP_Math/vector3.h diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_Navigation/Navigation.cpp b/Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/AP_Navigation/Navigation.cpp similarity index 100% rename from Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_Navigation/Navigation.cpp rename to Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/AP_Navigation/Navigation.cpp diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_Navigation/Navigation.h b/Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/AP_Navigation/Navigation.h similarity index 100% rename from Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_Navigation/Navigation.h rename to Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/AP_Navigation/Navigation.h diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_Navigation/examples/Navigation/Navigation.pde b/Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/AP_Navigation/examples/Navigation/Navigation.pde similarity index 100% rename from Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_Navigation/examples/Navigation/Navigation.pde rename to Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/AP_Navigation/examples/Navigation/Navigation.pde diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_Navigation/examples/Navigation_simple/Navigation_simple.pde b/Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/AP_Navigation/examples/Navigation_simple/Navigation_simple.pde similarity index 100% rename from Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/AP_Navigation/examples/Navigation_simple/Navigation_simple.pde rename to Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/AP_Navigation/examples/Navigation_simple/Navigation_simple.pde diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/DCM/DCM.cpp b/Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/DCM/DCM.cpp similarity index 100% rename from Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/DCM/DCM.cpp rename to Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/DCM/DCM.cpp diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/DCM/DCM.h b/Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/DCM/DCM.h similarity index 100% rename from Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/DCM/DCM.h rename to Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/DCM/DCM.h diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/DCM/examples/DCM_test/DCM_test.pde b/Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/DCM/examples/DCM_test/DCM_test.pde similarity index 100% rename from Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/DCM/examples/DCM_test/DCM_test.pde rename to Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/DCM/examples/DCM_test/DCM_test.pde diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/DataFlash/DataFlash.cpp b/Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/DataFlash/DataFlash.cpp similarity index 100% rename from Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/DataFlash/DataFlash.cpp rename to Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/DataFlash/DataFlash.cpp diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/DataFlash/DataFlash.h b/Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/DataFlash/DataFlash.h similarity index 100% rename from Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/DataFlash/DataFlash.h rename to Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/DataFlash/DataFlash.h diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/DataFlash/examples/DataFlash_test/DataFlash_test.pde b/Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/DataFlash/examples/DataFlash_test/DataFlash_test.pde similarity index 100% rename from Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/DataFlash/examples/DataFlash_test/DataFlash_test.pde rename to Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/DataFlash/examples/DataFlash_test/DataFlash_test.pde diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/DataFlash/keywords.txt b/Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/DataFlash/keywords.txt similarity index 100% rename from Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/DataFlash/keywords.txt rename to Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/DataFlash/keywords.txt diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/FastSerial/FastSerial.cpp b/Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/FastSerial/FastSerial.cpp similarity index 100% rename from Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/FastSerial/FastSerial.cpp rename to Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/FastSerial/FastSerial.cpp diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/FastSerial/FastSerial.h b/Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/FastSerial/FastSerial.h similarity index 100% rename from Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/FastSerial/FastSerial.h rename to Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/FastSerial/FastSerial.h diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/FastSerial/examples/FastSerial/FastSerial.pde b/Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/FastSerial/examples/FastSerial/FastSerial.pde similarity index 100% rename from Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/FastSerial/examples/FastSerial/FastSerial.pde rename to Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/FastSerial/examples/FastSerial/FastSerial.pde diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/FastSerial/keywords.txt b/Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/FastSerial/keywords.txt similarity index 100% rename from Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/FastSerial/keywords.txt rename to Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/FastSerial/keywords.txt diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/GPS_IMU/.DS_Store b/Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/GPS_IMU/.DS_Store similarity index 100% rename from Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/GPS_IMU/.DS_Store rename to Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/GPS_IMU/.DS_Store diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/GPS_IMU/GPS_IMU.cpp b/Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/GPS_IMU/GPS_IMU.cpp similarity index 100% rename from Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/GPS_IMU/GPS_IMU.cpp rename to Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/GPS_IMU/GPS_IMU.cpp diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/GPS_IMU/GPS_IMU.h b/Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/GPS_IMU/GPS_IMU.h similarity index 100% rename from Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/GPS_IMU/GPS_IMU.h rename to Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/GPS_IMU/GPS_IMU.h diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/GPS_IMU/examples/.DS_Store b/Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/GPS_IMU/examples/.DS_Store similarity index 100% rename from Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/GPS_IMU/examples/.DS_Store rename to Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/GPS_IMU/examples/.DS_Store diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/GPS_IMU/examples/GPS_IMU_test/GPS_IMU_test.pde b/Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/GPS_IMU/examples/GPS_IMU_test/GPS_IMU_test.pde similarity index 100% rename from Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/GPS_IMU/examples/GPS_IMU_test/GPS_IMU_test.pde rename to Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/GPS_IMU/examples/GPS_IMU_test/GPS_IMU_test.pde diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/GPS_IMU/keywords.txt b/Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/GPS_IMU/keywords.txt similarity index 100% rename from Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/GPS_IMU/keywords.txt rename to Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/GPS_IMU/keywords.txt diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/GPS_MTK/GPS_MTK.cpp b/Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/GPS_MTK/GPS_MTK.cpp similarity index 100% rename from Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/GPS_MTK/GPS_MTK.cpp rename to Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/GPS_MTK/GPS_MTK.cpp diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/GPS_MTK/GPS_MTK.h b/Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/GPS_MTK/GPS_MTK.h similarity index 100% rename from Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/GPS_MTK/GPS_MTK.h rename to Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/GPS_MTK/GPS_MTK.h diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/GPS_MTK/examples/GPS_MTK_test/GPS_MTK_test.pde b/Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/GPS_MTK/examples/GPS_MTK_test/GPS_MTK_test.pde similarity index 100% rename from Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/GPS_MTK/examples/GPS_MTK_test/GPS_MTK_test.pde rename to Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/GPS_MTK/examples/GPS_MTK_test/GPS_MTK_test.pde diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/GPS_MTK/keywords.txt b/Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/GPS_MTK/keywords.txt similarity index 100% rename from Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/GPS_MTK/keywords.txt rename to Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/GPS_MTK/keywords.txt diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/GPS_NMEA/GPS_NMEA.cpp b/Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/GPS_NMEA/GPS_NMEA.cpp similarity index 100% rename from Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/GPS_NMEA/GPS_NMEA.cpp rename to Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/GPS_NMEA/GPS_NMEA.cpp diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/GPS_NMEA/GPS_NMEA.h b/Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/GPS_NMEA/GPS_NMEA.h similarity index 100% rename from Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/GPS_NMEA/GPS_NMEA.h rename to Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/GPS_NMEA/GPS_NMEA.h diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/GPS_NMEA/examples/GPS_NMEA_test/GPS_NMEA_test.pde b/Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/GPS_NMEA/examples/GPS_NMEA_test/GPS_NMEA_test.pde similarity index 100% rename from Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/GPS_NMEA/examples/GPS_NMEA_test/GPS_NMEA_test.pde rename to Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/GPS_NMEA/examples/GPS_NMEA_test/GPS_NMEA_test.pde diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/GPS_NMEA/keywords.txt b/Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/GPS_NMEA/keywords.txt similarity index 100% rename from Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/GPS_NMEA/keywords.txt rename to Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/GPS_NMEA/keywords.txt diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/GPS_UBLOX/GPS_UBLOX.cpp b/Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/GPS_UBLOX/GPS_UBLOX.cpp similarity index 100% rename from Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/GPS_UBLOX/GPS_UBLOX.cpp rename to Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/GPS_UBLOX/GPS_UBLOX.cpp diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/GPS_UBLOX/GPS_UBLOX.h b/Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/GPS_UBLOX/GPS_UBLOX.h similarity index 100% rename from Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/GPS_UBLOX/GPS_UBLOX.h rename to Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/GPS_UBLOX/GPS_UBLOX.h diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/GPS_UBLOX/examples/GPS_UBLOX_test/GPS_UBLOX_test.pde b/Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/GPS_UBLOX/examples/GPS_UBLOX_test/GPS_UBLOX_test.pde similarity index 100% rename from Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/GPS_UBLOX/examples/GPS_UBLOX_test/GPS_UBLOX_test.pde rename to Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/GPS_UBLOX/examples/GPS_UBLOX_test/GPS_UBLOX_test.pde diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/GPS_UBLOX/keywords.txt b/Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/GPS_UBLOX/keywords.txt similarity index 100% rename from Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/GPS_UBLOX/keywords.txt rename to Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/GPS_UBLOX/keywords.txt diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/JETI_Box/JETI_Box.cpp b/Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/JETI_Box/JETI_Box.cpp similarity index 100% rename from Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/JETI_Box/JETI_Box.cpp rename to Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/JETI_Box/JETI_Box.cpp diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/JETI_Box/JETI_Box.cpp.bak b/Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/JETI_Box/JETI_Box.cpp.bak similarity index 100% rename from Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/JETI_Box/JETI_Box.cpp.bak rename to Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/JETI_Box/JETI_Box.cpp.bak diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/JETI_Box/JETI_Box.h b/Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/JETI_Box/JETI_Box.h similarity index 100% rename from Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/JETI_Box/JETI_Box.h rename to Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/JETI_Box/JETI_Box.h diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/JETI_Box/keywords.txt b/Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/JETI_Box/keywords.txt similarity index 100% rename from Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/JETI_Box/keywords.txt rename to Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/JETI_Box/keywords.txt diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/RC/APM2_RC.cpp b/Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/RC/APM2_RC.cpp similarity index 100% rename from Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/RC/APM2_RC.cpp rename to Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/RC/APM2_RC.cpp diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/RC/APM2_RC.h b/Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/RC/APM2_RC.h similarity index 100% rename from Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/RC/APM2_RC.h rename to Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/RC/APM2_RC.h diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/RC/AP_RC.cpp b/Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/RC/AP_RC.cpp similarity index 100% rename from Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/RC/AP_RC.cpp rename to Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/RC/AP_RC.cpp diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/RC/AP_RC.h b/Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/RC/AP_RC.h similarity index 100% rename from Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/RC/AP_RC.h rename to Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/RC/AP_RC.h diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/RC/RC.cpp b/Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/RC/RC.cpp similarity index 100% rename from Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/RC/RC.cpp rename to Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/RC/RC.cpp diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/RC/RC.h b/Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/RC/RC.h similarity index 100% rename from Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/RC/RC.h rename to Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/RC/RC.h diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/RC/examples/APM_RC_elevons/APM_RC_elevons.pde b/Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/RC/examples/APM_RC_elevons/APM_RC_elevons.pde similarity index 100% rename from Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/RC/examples/APM_RC_elevons/APM_RC_elevons.pde rename to Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/RC/examples/APM_RC_elevons/APM_RC_elevons.pde diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/RC/examples/APM_RC_test/APM_RC_test.pde b/Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/RC/examples/APM_RC_test/APM_RC_test.pde similarity index 100% rename from Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/RC/examples/APM_RC_test/APM_RC_test.pde rename to Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/RC/examples/APM_RC_test/APM_RC_test.pde diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/RC/examples/AP_RC_elevons/AP_RC_elevons.pde b/Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/RC/examples/AP_RC_elevons/AP_RC_elevons.pde similarity index 100% rename from Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/RC/examples/AP_RC_elevons/AP_RC_elevons.pde rename to Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/RC/examples/AP_RC_elevons/AP_RC_elevons.pde diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/RC/examples/AP_RC_test/AP_RC_test.pde b/Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/RC/examples/AP_RC_test/AP_RC_test.pde similarity index 100% rename from Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/RC/examples/AP_RC_test/AP_RC_test.pde rename to Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/RC/examples/AP_RC_test/AP_RC_test.pde diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/RC/keywords.txt b/Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/RC/keywords.txt similarity index 100% rename from Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/RC/keywords.txt rename to Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/RC/keywords.txt diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/Waypoints/Waypoints.cpp b/Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/Waypoints/Waypoints.cpp similarity index 100% rename from Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/Waypoints/Waypoints.cpp rename to Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/Waypoints/Waypoints.cpp diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/Waypoints/Waypoints.h b/Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/Waypoints/Waypoints.h similarity index 100% rename from Tools/ArduPPM/WorkBasket/Jeti Duplex/X-DIY_Jeti_V2/libraries/Waypoints/Waypoints.h rename to Tools/ArduPPM/WorkBasket/Jeti_Duplex/X-DIY_Jeti_V2/libraries/Waypoints/Waypoints.h diff --git a/Tools/ArduPPM/WorkBasket/Jeti Duplex/readme.txt b/Tools/ArduPPM/WorkBasket/Jeti_Duplex/readme.txt similarity index 100% rename from Tools/ArduPPM/WorkBasket/Jeti Duplex/readme.txt rename to Tools/ArduPPM/WorkBasket/Jeti_Duplex/readme.txt diff --git a/Tools/ArdupilotMegaPlanner/CurrentState.cs b/Tools/ArdupilotMegaPlanner/CurrentState.cs index ed0bab8257..81eb9306ba 100644 --- a/Tools/ArdupilotMegaPlanner/CurrentState.cs +++ b/Tools/ArdupilotMegaPlanner/CurrentState.cs @@ -138,7 +138,7 @@ namespace ArdupilotMega //battery public float battery_voltage { get { return _battery_voltage; } set { _battery_voltage = value / 1000; } } private float _battery_voltage; - public float battery_remaining { get { return _battery_remaining; } set { _battery_remaining = value / 1000; if (_battery_remaining < 0) _battery_remaining = 0; } } + public float battery_remaining { get { return _battery_remaining; } set { _battery_remaining = value / 1000; if (_battery_remaining < 0 || _battery_remaining > 100) _battery_remaining = 0; } } private float _battery_remaining; // HIL diff --git a/Tools/ArdupilotMegaPlanner/Firmware/firmware2.xml b/Tools/ArdupilotMegaPlanner/Firmware/firmware2.xml index 937a0ffc96..f772467318 100644 --- a/Tools/ArdupilotMegaPlanner/Firmware/firmware2.xml +++ b/Tools/ArdupilotMegaPlanner/Firmware/firmware2.xml @@ -4,7 +4,7 @@ http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AP-1280.hex http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AP-2560.hex http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AP-2560-2.hex - ArduPlane V2.27 + ArduPlane V2.28 12 @@ -12,7 +12,7 @@ http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/APHIL-1280.hex http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/APHIL-2560.hex http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/APHIL-2560-2.hex - ArduPlane V2.27 HIL + ArduPlane V2.28 HIL #define FLIGHT_MODE_CHANNEL 8 #define FLIGHT_MODE_1 AUTO @@ -47,7 +47,7 @@ http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AP-trunk-1280.hex http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AP-trunk-2560.hex http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AP-trunk-2560-2.hex - ArduPlane V2.27 APM trunk + ArduPlane V2.28 APM trunk 12 @@ -55,7 +55,7 @@ http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Quad-1280.hex http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Quad-2560.hex http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Quad-2560-2.hex - ArduCopter V2.2 Quad + ArduCopter V2.2 b2 Quad #define FRAME_CONFIG QUAD_FRAME #define FRAME_ORIENTATION X_FRAME @@ -67,7 +67,7 @@ http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Tri-1280.hex http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Tri-2560.hex http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Tri-2560-2.hex - ArduCopter V2.2 Tri + ArduCopter V2.2 b2 Tri #define FRAME_CONFIG TRI_FRAME #define FRAME_ORIENTATION X_FRAME @@ -79,7 +79,7 @@ http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Hexa-1280.hex http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Hexa-2560.hex http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Hexa-2560-2.hex - ArduCopter V2.2 Hexa + ArduCopter V2.2 b2 Hexa #define FRAME_CONFIG HEXA_FRAME #define FRAME_ORIENTATION X_FRAME @@ -91,7 +91,7 @@ http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Y6-1280.hex http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Y6-2560.hex http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Y6-2560-2.hex - ArduCopter V2.2 Y6 + ArduCopter V2.2 b2 Y6 #define FRAME_CONFIG Y6_FRAME #define FRAME_ORIENTATION X_FRAME @@ -103,7 +103,7 @@ http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Octav-1280.hex http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Octav-2560.hex http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Octav-2560-2.hex - ArduCopter V2.2 Octav + ArduCopter V2.2 b2 Octav #define FRAME_CONFIG OCTA_FRAME #define FRAME_ORIENTATION V_FRAME @@ -115,7 +115,7 @@ http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Octa-1280.hex http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Octa-2560.hex http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-Octa-2560-2.hex - ArduCopter V2.2 Octa + ArduCopter V2.2 b2 Octa #define FRAME_CONFIG OCTA_FRAME #define FRAME_ORIENTATION X_FRAME @@ -175,7 +175,7 @@ http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-QUADHIL-1280.hex http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-QUADHIL-2560.hex http://meee146-planner.googlecode.com/git/Tools/ArdupilotMegaPlanner/Firmware/AC2-QUADHIL-2560-2.hex - ArduCopter V2.2 Quad Hil + ArduCopter V2.2 b2 Quad Hil #define FRAME_CONFIG QUAD_FRAME #define FRAME_ORIENTATION PLUS_FRAME diff --git a/Tools/ArdupilotMegaPlanner/Joystick.cs b/Tools/ArdupilotMegaPlanner/Joystick.cs index 060e50f5d5..b655f1a6c1 100644 --- a/Tools/ArdupilotMegaPlanner/Joystick.cs +++ b/Tools/ArdupilotMegaPlanner/Joystick.cs @@ -322,11 +322,12 @@ namespace ArdupilotMega { if (but.buttonno != -1 && getButtonState(but.buttonno)) { + string mode = but.mode; MainV2.instance.BeginInvoke((System.Windows.Forms.MethodInvoker)delegate() { try { - MainV2.comPort.setMode(but.mode); + MainV2.comPort.setMode(mode); } catch { System.Windows.Forms.MessageBox.Show("Failed to change Modes"); } diff --git a/Tools/ArdupilotMegaPlanner/Properties/AssemblyInfo.cs b/Tools/ArdupilotMegaPlanner/Properties/AssemblyInfo.cs index 9f0f2c03ff..f321f3d578 100644 --- a/Tools/ArdupilotMegaPlanner/Properties/AssemblyInfo.cs +++ b/Tools/ArdupilotMegaPlanner/Properties/AssemblyInfo.cs @@ -34,5 +34,5 @@ using System.Resources; // by using the '*' as shown below: // [assembly: AssemblyVersion("1.0.*")] [assembly: AssemblyVersion("1.0.0.0")] -[assembly: AssemblyFileVersion("1.1.21")] +[assembly: AssemblyFileVersion("1.1.22")] [assembly: NeutralResourcesLanguageAttribute("")] diff --git a/Tools/ArdupilotMegaPlanner/Setup/Setup.cs b/Tools/ArdupilotMegaPlanner/Setup/Setup.cs index 445180de8c..91139af672 100644 --- a/Tools/ArdupilotMegaPlanner/Setup/Setup.cs +++ b/Tools/ArdupilotMegaPlanner/Setup/Setup.cs @@ -240,7 +240,7 @@ namespace ArdupilotMega.Setup MainV2.comPort.setParam("RC" + (a + 1).ToString("0") + "_MIN", rcmin[a]); MainV2.comPort.setParam("RC" + (a + 1).ToString("0") + "_MAX", rcmax[a]); } - if (rctrim[a] < 1195 && rctrim[a] > 1205) + if (rctrim[a] < 1195 || rctrim[a] > 1205) MainV2.comPort.setParam("RC" + (a + 1).ToString("0") + "_TRIM", rctrim[a]); } catch { MessageBox.Show("Failed to set Channel " + (a + 1).ToString()); } diff --git a/Tools/ArdupilotMegaPlanner/Setup/Setup.resx b/Tools/ArdupilotMegaPlanner/Setup/Setup.resx index 5f938f54f0..eb8fbec012 100644 --- a/Tools/ArdupilotMegaPlanner/Setup/Setup.resx +++ b/Tools/ArdupilotMegaPlanner/Setup/Setup.resx @@ -117,15 +117,1899 @@ System.Resources.ResXResourceWriter, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + groupBoxElevons + + + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabRadioIn + + + 0 + + + CHK_revch3 + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabRadioIn + + + 1 + + + CHK_revch4 + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabRadioIn + + + 2 + + + CHK_revch2 + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabRadioIn + + + 3 + + + CHK_revch1 + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabRadioIn + + + 4 + + + BUT_Calibrateradio + + + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc + + + tabRadioIn + + + 5 + + + BAR8 + + + ArdupilotMega.HorizontalProgressBar2, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc + + + tabRadioIn + + + 6 + + + BAR7 + + + ArdupilotMega.HorizontalProgressBar2, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc + + + tabRadioIn + + + 7 + + + BAR6 + + + ArdupilotMega.HorizontalProgressBar2, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc + + + tabRadioIn + + + 8 + + + BAR5 + + + ArdupilotMega.HorizontalProgressBar2, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc + + + tabRadioIn + + + 9 + + + BARpitch + + + ArdupilotMega.VerticalProgressBar2, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc + + + tabRadioIn + + + 10 + + + BARthrottle + + + ArdupilotMega.VerticalProgressBar2, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc + + + tabRadioIn + + + 11 + + + BARyaw + + + ArdupilotMega.HorizontalProgressBar2, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc + + + tabRadioIn + + + 12 + + + BARroll + + + ArdupilotMega.HorizontalProgressBar2, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc + + + tabRadioIn + + + 13 + + + + 4, 22 + + + + 3, 3, 3, 3 + + + 666, 393 + + + 0 + + + Radio Input + + + tabRadioIn + + + System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabControl1 + + + 0 + + + CB_simple6 + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabModes + + + 0 + + + CB_simple5 + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabModes + + + 1 + + + CB_simple4 + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabModes + + + 2 + + + CB_simple3 + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabModes + + + 3 + + + CB_simple2 + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabModes + + + 4 + + + CB_simple1 + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabModes + + + 5 + + + label14 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabModes + + + 6 + + + LBL_flightmodepwm + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabModes + + + 7 + + + label13 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabModes + + + 8 + + + lbl_currentmode + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabModes + + + 9 + + + label12 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabModes + + + 10 + + + label11 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabModes + + + 11 + + + label10 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabModes + + + 12 + + + label9 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabModes + + + 13 + + + label8 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabModes + + + 14 + + + label7 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabModes + + + 15 + + + label6 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabModes + + + 16 + + + CMB_fmode6 + + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabModes + + + 17 + + + label5 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabModes + + + 18 + + + CMB_fmode5 + + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabModes + + + 19 + + + label4 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabModes + + + 20 + + + CMB_fmode4 + + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabModes + + + 21 + + + label3 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabModes + + + 22 + + + CMB_fmode3 + + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabModes + + + 23 + + + label2 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabModes + + + 24 + + + CMB_fmode2 + + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabModes + + + 25 + + + label1 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabModes + + + 26 + + + CMB_fmode1 + + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabModes + + + 27 + + + BUT_SaveModes + + + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc + + + tabModes + + + 28 + + + 4, 22 + + + 666, 393 + + + 3 + + + Modes + + + tabModes + + + System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabControl1 + + + 1 + + + label27 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHardware + + + 0 + + + CMB_sonartype + + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHardware + + + 1 + + + CHK_enableoptflow + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHardware + + + 2 + + + pictureBox2 + + + System.Windows.Forms.PictureBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHardware + + + 3 + + + linkLabelmagdec + + + System.Windows.Forms.LinkLabel, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHardware + + + 4 + + + label100 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHardware + + + 5 + + + TXT_declination + + + System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHardware + + + 6 + + + CHK_enableairspeed + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHardware + + + 7 + + + CHK_enablesonar + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHardware + + + 8 + + + CHK_enablecompass + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHardware + + + 9 + + + pictureBox4 + + + System.Windows.Forms.PictureBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHardware + + + 10 + + + pictureBox3 + + + System.Windows.Forms.PictureBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHardware + + + 11 + + + pictureBox1 + + + System.Windows.Forms.PictureBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHardware + + + 12 + + + 4, 22 + + + 3, 3, 3, 3 + + + 666, 393 + + + 1 + + + Hardware + + + tabHardware + + + System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabControl1 + + + 2 + + + 172, 267 + + + 2, 2, 2, 2 + + + 76, 20 + + + 38 + + + TXT_ampspervolt + + + System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabBattery + + + 0 + + + 172, 245 + + + 2, 2, 2, 2 + + + 76, 20 + + + 37 + + + TXT_divider + + + System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabBattery + + + 1 + + + 172, 224 + + + 2, 2, 2, 2 + + + 76, 20 + + + 36 + + + TXT_voltage + + + System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabBattery + + + 2 + + + 172, 202 + + + 2, 2, 2, 2 + + + 76, 20 + + + 35 + + + TXT_measuredvoltage + + + System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabBattery + + + 3 + + + 172, 180 + + + 2, 2, 2, 2 + + + 76, 20 + + + 34 + + + TXT_inputvoltage + + + System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabBattery + + + 4 + + + True + + + NoControl + + + 29, 270 + + + 2, 0, 2, 0 + + + 101, 13 + + + 33 + + + 3. Amperes per volt: + + + label35 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabBattery + + + 5 + + + True + + + NoControl + + + 28, 248 + + + 2, 0, 2, 0 + + + 122, 13 + + + 32 + + + Voltage divider (Calced): + + + label34 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabBattery + + + 6 + + + True + + + NoControl + + + 28, 227 + + + 2, 0, 2, 0 + + + 123, 13 + + + 31 + + + Battery voltage (Calced): + + + label33 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabBattery + + + 7 + + + True + + + NoControl + + + 28, 205 + + + 2, 0, 2, 0 + + + 142, 13 + + + 30 + + + 2. Measured battery voltage: + + + label32 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabBattery + + + 8 + + + True + + + NoControl + + + 28, 183 + + + 2, 0, 2, 0 + + + 84, 13 + + + 29 + + + 1. Input voltage: + + + label31 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabBattery + + + 9 + + + 31, 110 + + + 2, 2, 2, 2 + + + True + + + 428, 62 + + + 28 + + + Voltage sensor calibration: +1. Measure APM input voltage and enter it to the box below (~4.68) +2. Measure battery voltage and enter it to the box below (main battery) +3. From current sensor datasheet, enter amperes per volt value to the box below + + + textBox3 + + + System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabBattery + + + 10 + + + True + + + NoControl + + + 305, 50 + + + 48, 13 + + + 23 + + + Capacity + + + label29 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabBattery + + + 11 + + + NoControl + + + 123, 50 + + + 42, 13 + + + 24 + + + Monitor + + + label30 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabBattery + + + 12 + + + 366, 47 + + + 83, 20 + + + 25 + + + TXT_battcapacity + + + System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabBattery + + + 13 + + + 0: Disabled + + + + + + + + + 3: Battery Volts + + + 4: Volts & Current + + + 177, 46 + + + 121, 21 + + + 26 + + + CMB_batmontype + + + System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabBattery + + + 14 + + + Zoom + + + NoControl + + + 31, 21 + + + 75, 75 + + + 2 + + + pictureBox5 + + + System.Windows.Forms.PictureBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabBattery + + + 15 + + + 4, 22 + + + 2, 2, 2, 2 + + + 666, 393 + + + 6 + + + Battery + + + tabBattery + + + System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabControl1 + + + 3 + + + label28 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabArducopter + + + 0 + + + label16 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabArducopter + + + 1 + + + label15 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabArducopter + + + 2 + + + BUT_levelac2 + + + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc + + + tabArducopter + + + 3 + + + pictureBoxQuadX + + + System.Windows.Forms.PictureBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabArducopter + + + 4 + + + pictureBoxQuad + + + System.Windows.Forms.PictureBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabArducopter + + + 5 + + + 4, 22 + + + 666, 393 + + + 2 + + + ArduCopter2 + + + tabArducopter + + + System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabControl1 + + + 4 + + + BUT_HS4save + + + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc + + + tabHeli + + + 0 + + + BUT_swash_manual + + + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc + + + tabHeli + + + 1 + + + groupBox3 + + + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHeli + + + 2 + + + label44 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHeli + + + 3 + + + label43 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHeli + + + 4 + + + label42 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHeli + + + 5 + + + groupBox2 + + + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHeli + + + 6 + + + groupBox1 + + + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHeli + + + 7 + + + HS4_TRIM + + + System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHeli + + + 8 + + + HS3_TRIM + + + System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHeli + + + 9 + + + HS2_TRIM + + + System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHeli + + + 10 + + + HS1_TRIM + + + System.Windows.Forms.NumericUpDown, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHeli + + + 11 + + + label39 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHeli + + + 12 + + + label38 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHeli + + + 13 + + + label37 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHeli + + + 14 + + + label36 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHeli + + + 15 + + + label26 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHeli + + + 16 + + + PIT_MAX_ + + + System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHeli + + + 17 + + + label25 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHeli + + + 18 + + + ROL_MAX_ + + + System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHeli + + + 19 + + + label23 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHeli + + + 20 + + + label22 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHeli + + + 21 + + + HS4_REV + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHeli + + + 22 + + + label20 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHeli + + + 23 + + + label19 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHeli + + + 24 + + + label18 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHeli + + + 25 + + + SV3_POS_ + + + System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHeli + + + 26 + + + SV2_POS_ + + + System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHeli + + + 27 + + + SV1_POS_ + + + System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHeli + + + 28 + + + HS3_REV + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHeli + + + 29 + + + HS2_REV + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHeli + + + 30 + + + HS1_REV + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHeli + + + 31 + + + label17 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHeli + + + 32 + + + HS4 + + + ArdupilotMega.HorizontalProgressBar2, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc + + + tabHeli + + + 33 + + + HS3 + + + ArdupilotMega.VerticalProgressBar2, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc + + + tabHeli + + + 34 + + + Gservoloc + + + AGaugeApp.AGauge, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc + + + tabHeli + + + 35 + + + 4, 22 + + + 666, 393 + + + 5 + + + AC2 Heli + + + tabHeli + + + System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabControl1 + + + 5 + + + Fill + + + 0, 0 + + + 674, 419 + + + 93 + + + tabControl1 + + + System.Windows.Forms.TabControl, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + $this + + + 0 + + + CHK_mixmode + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBoxElevons + + + 0 + + + CHK_elevonch2rev + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBoxElevons + + + 1 + + + CHK_elevonrev + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBoxElevons + + + 2 + + + CHK_elevonch1rev + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBoxElevons + + + 3 + + + 21, 340 + + + 409, 42 + + + 111 + + + Elevon Config + + + groupBoxElevons + + + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabRadioIn + + + 0 + True - NoControl - 13, 19 @@ -255,30 +2139,6 @@ 3 - - 21, 340 - - - 409, 42 - - - 111 - - - Elevon Config - - - groupBoxElevons - - - System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabRadioIn - - - 0 - True @@ -450,6 +2310,9 @@ 6 + + 17, 17 + 446, 185 @@ -597,33 +2460,6 @@ 13 - - 4, 22 - - - 3, 3, 3, 3 - - - 666, 393 - - - 0 - - - Radio Input - - - tabRadioIn - - - System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabControl1 - - - 0 - True @@ -960,9 +2796,6 @@ PWM 0 - 1230 - - False - label12 @@ -993,9 +2826,6 @@ PWM 1750 + - - False - label11 @@ -1026,9 +2856,6 @@ PWM 1621 - 1749 - - False - label10 @@ -1059,9 +2886,6 @@ PWM 1491 - 1620 - - False - label9 @@ -1092,9 +2916,6 @@ PWM 1361 - 1490 - - False - label8 @@ -1125,9 +2946,6 @@ PWM 1231 - 1360 - - False - label7 @@ -1473,30 +3291,6 @@ 28 - - 4, 22 - - - 666, 393 - - - 3 - - - Modes - - - tabModes - - - System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabControl1 - - - 1 - NoControl @@ -1857,519 +3651,6 @@ 12 - - 4, 22 - - - 3, 3, 3, 3 - - - 666, 393 - - - 1 - - - Hardware - - - tabHardware - - - System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabControl1 - - - 2 - - - 162, 267 - - - 2, 2, 2, 2 - - - 76, 20 - - - 38 - - - TXT_ampspervolt - - - System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabBattery - - - 0 - - - 162, 245 - - - 2, 2, 2, 2 - - - 76, 20 - - - 37 - - - TXT_divider - - - System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabBattery - - - 1 - - - 162, 224 - - - 2, 2, 2, 2 - - - 76, 20 - - - 36 - - - TXT_voltage - - - System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabBattery - - - 2 - - - 162, 202 - - - 2, 2, 2, 2 - - - 76, 20 - - - 35 - - - TXT_measuredvoltage - - - System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabBattery - - - 3 - - - 162, 180 - - - 2, 2, 2, 2 - - - 76, 20 - - - 34 - - - TXT_inputvoltage - - - System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabBattery - - - 4 - - - True - - - NoControl - - - 29, 270 - - - 2, 0, 2, 0 - - - 89, 13 - - - 33 - - - Amperes per volt: - - - label35 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabBattery - - - 5 - - - True - - - NoControl - - - 28, 248 - - - 2, 0, 2, 0 - - - 80, 13 - - - 32 - - - Voltage divider: - - - label34 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabBattery - - - 6 - - - True - - - NoControl - - - 28, 227 - - - 2, 0, 2, 0 - - - 81, 13 - - - 31 - - - Battery voltage: - - - label33 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabBattery - - - 7 - - - True - - - NoControl - - - 28, 205 - - - 2, 0, 2, 0 - - - 130, 13 - - - 30 - - - Measured battery voltage: - - - label32 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabBattery - - - 8 - - - True - - - NoControl - - - 28, 183 - - - 2, 0, 2, 0 - - - 72, 13 - - - 29 - - - Input voltage: - - - label31 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabBattery - - - 9 - - - 31, 110 - - - 2, 2, 2, 2 - - - True - - - 428, 62 - - - 28 - - - Voltage sensor calibration: -1. Measure APM input voltage and enter it to the box below -2. Measure battery voltage and enter it to the box below -3. From current sensor datasheet, enter amperes per volt value to the box below - - - textBox3 - - - System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabBattery - - - 10 - - - True - - - NoControl - - - 305, 50 - - - 48, 13 - - - 23 - - - Capacity - - - label29 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabBattery - - - 11 - - - NoControl - - - 123, 50 - - - 42, 13 - - - 24 - - - Monitor - - - label30 - - - System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabBattery - - - 12 - - - 366, 47 - - - 83, 20 - - - 25 - - - TXT_battcapacity - - - System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabBattery - - - 13 - - - 0: Disabled - - - 1: 3 Cell - - - 2: 4 Cell - - - 3: Battery Volts - - - 4: Volts & Current - - - 177, 46 - - - 121, 21 - - - 26 - - - CMB_batmontype - - - System.Windows.Forms.ComboBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabBattery - - - 14 - - - Zoom - - - NoControl - - - 31, 21 - - - 75, 75 - - - 2 - - - pictureBox5 - - - System.Windows.Forms.PictureBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabBattery - - - 15 - - - 4, 22 - - - 2, 2, 2, 2 - - - 666, 393 - - - 6 - - - Battery - - - tabBattery - - - System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabControl1 - - - 3 - True @@ -2542,30 +3823,6 @@ will work with hexa's etc 5 - - 4, 22 - - - 666, 393 - - - 2 - - - ArduCopter2 - - - tabArducopter - - - System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabControl1 - - - 4 - NoControl @@ -2620,6 +3877,78 @@ will work with hexa's etc 1 + + label46 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox3 + + + 0 + + + label45 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox3 + + + 1 + + + GYR_ENABLE_ + + + System.Windows.Forms.CheckBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox3 + + + 2 + + + GYR_GAIN_ + + + System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox3 + + + 3 + + + 433, 271 + + + 101, 63 + + + 135 + + + Gyro + + + groupBox3 + + + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHeli + + + 2 + True @@ -2731,30 +4060,6 @@ will work with hexa's etc 3 - - 433, 271 - - - 101, 63 - - - 135 - - - Gyro - - - groupBox3 - - - System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabHeli - - - 2 - True @@ -2845,6 +4150,75 @@ will work with hexa's etc 5 + + label24 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox2 + + + 0 + + + HS4_MIN + + + System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox2 + + + 1 + + + HS4_MAX + + + System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox2 + + + 2 + + + label40 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox2 + + + 3 + + + 433, 143 + + + 169, 78 + + + 130 + + + groupBox2 + + + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + tabHeli + + + 6 + True @@ -2953,26 +4327,98 @@ will work with hexa's etc 3 - - 433, 143 + + label41 - - 169, 78 + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - 130 + + groupBox1 - - groupBox2 + + 0 - + + label21 + + + System.Windows.Forms.Label, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox1 + + + 1 + + + COL_MIN_ + + + System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox1 + + + 2 + + + COL_MID_ + + + System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox1 + + + 3 + + + COL_MAX_ + + + System.Windows.Forms.TextBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + + groupBox1 + + + 4 + + + BUT_0collective + + + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc + + + groupBox1 + + + 5 + + + 293, 52 + + + 80, 209 + + + 129 + + + groupBox1 + + System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - + tabHeli - - 6 + + 7 True @@ -3133,27 +4579,6 @@ will work with hexa's etc 5 - - 293, 52 - - - 80, 209 - - - 129 - - - groupBox1 - - - System.Windows.Forms.GroupBox, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabHeli - - - 7 - 535, 241 @@ -3898,69 +5323,6 @@ will work with hexa's etc 35 - - 4, 22 - - - 666, 393 - - - 5 - - - AC2 Heli - - - tabHeli - - - System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - tabControl1 - - - 5 - - - Fill - - - 0, 0 - - - 674, 419 - - - 93 - - - tabControl1 - - - System.Windows.Forms.TabControl, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 - - - $this - - - 0 - - - NoControl - - - 214, 161 - - - 195, 23 - - - 0 - - - Reset APM Hardware to Default - BUT_reset @@ -3991,6 +5353,33 @@ will work with hexa's etc System.Windows.Forms.TabPage, System.Windows.Forms, Version=2.0.0.0, Culture=neutral, PublicKeyToken=b77a5c561934e089 + + NoControl + + + 214, 161 + + + 195, 23 + + + 0 + + + Reset APM Hardware to Default + + + BUT_reset + + + ArdupilotMega.MyButton, ArdupilotMegaPlanner, Version=1.0.0.0, Culture=neutral, PublicKeyToken=38326cb7e06851fc + + + tabReset + + + 0 + True diff --git a/libraries/APM_RC/APM_RC_APM1.cpp b/libraries/APM_RC/APM_RC_APM1.cpp index 1a480832f4..9f13274a40 100644 --- a/libraries/APM_RC/APM_RC_APM1.cpp +++ b/libraries/APM_RC/APM_RC_APM1.cpp @@ -139,17 +139,17 @@ void APM_RC_APM1::OutputCh(uint8_t ch, uint16_t pwm) switch(ch) { - case 0: OCR5B=pwm; break; //ch0 - case 1: OCR5C=pwm; break; //ch1 - case 2: OCR1B=pwm; break; //ch2 - case 3: OCR1C=pwm; break; //ch3 - case 4: OCR4C=pwm; break; //ch4 - case 5: OCR4B=pwm; break; //ch5 - case 6: OCR3C=pwm; break; //ch6 - case 7: OCR3B=pwm; break; //ch7 - case 8: OCR5A=pwm; break; //ch8, PL3 - case 9: OCR1A=pwm; break; //ch9, PB5 - case 10: OCR3A=pwm; break; //ch10, PE3 + case 0: OCR5B=pwm; break; //ch1 + case 1: OCR5C=pwm; break; //ch2 + case 2: OCR1B=pwm; break; //ch3 + case 3: OCR1C=pwm; break; //ch4 + case 4: OCR4C=pwm; break; //ch5 + case 5: OCR4B=pwm; break; //ch6 + case 6: OCR3C=pwm; break; //ch7 + case 7: OCR3B=pwm; break; //ch8 + case 8: OCR5A=pwm; break; //ch9, PL3 + case 9: OCR1A=pwm; break; //ch10, PB5 + case 10: OCR3A=pwm; break; //ch11, PE3 } } diff --git a/libraries/AP_Common/Arduino.mk b/libraries/AP_Common/Arduino.mk index e61a56835a..a87d99767c 100644 --- a/libraries/AP_Common/Arduino.mk +++ b/libraries/AP_Common/Arduino.mk @@ -265,12 +265,12 @@ endif # # Sketch source files -SKETCHPDESRCS := $(wildcard $(SRCROOT)/*.pde) +SKETCHPDESRCS := $(wildcard $(SRCROOT)/*.pde $(SRCROOT)/*.ino) SKETCHSRCS := $(wildcard $(addprefix $(SRCROOT)/,$(SRCSUFFIXES))) -SKETCHPDE := $(wildcard $(SRCROOT)/$(SKETCH).pde) +SKETCHPDE := $(wildcard $(SRCROOT)/$(SKETCH).pde $(SRCROOT)/$(SKETCH).ino) SKETCHCPP := $(BUILDROOT)/$(SKETCH).cpp -ifeq ($(SKETCHPDE),) -$(error ERROR: sketch $(SKETCH) is missing $(SKETCH).pde) +ifneq ($(words $(SKETCHPDE)),1) +$(error ERROR: sketch $(SKETCH) must contain exactly one of $(SKETCH).pde or $(SKETCH).ino) endif # Sketch object files @@ -566,7 +566,7 @@ $(CORELIB): $(CORELIBOBJS) # This process strives to be as faithful to the Arduino implementation as # possible. Conceptually, the process is as follows: # -# * All of the .pde files are concatenated, starting with the file named +# * All of the .pde/.ino files are concatenated, starting with the file named # for the sketch and followed by the others in alphabetical order. # * An insertion point is created in the concatenated file at # the first statement that isn't a preprocessor directive or comment. @@ -590,7 +590,7 @@ $(SKETCHCPP): $(SKETCHCPP_SRC) # # The sketch splitter is an awk script used to split off the -# header and body of the concatenated .pde files. It also +# header and body of the concatenated .pde/.ino files. It also # inserts #line directives to help in backtracking from compiler # and debugger messages to the original source file. # @@ -626,7 +626,7 @@ endef # # The prototype scanner is an awk script used to generate function -# prototypes from the concantenated .pde files. +# prototypes from the concantenated .pde/.ino files. # # Function definitions are expected to follow the form # diff --git a/libraries/AP_Compass/Compass.h b/libraries/AP_Compass/Compass.h index 33f5ccafbb..67a533fb02 100644 --- a/libraries/AP_Compass/Compass.h +++ b/libraries/AP_Compass/Compass.h @@ -102,8 +102,6 @@ public: /// Program new offset values. /// - /// XXX DEPRECATED - /// /// @param x Offset to the raw mag_x value. /// @param y Offset to the raw mag_y value. /// @param z Offset to the raw mag_z value.