diff --git a/ArduCopterMega/defines.h b/ArduCopterMega/defines.h index ff20eed224..7972a12bc1 100644 --- a/ArduCopterMega/defines.h +++ b/ArduCopterMega/defines.h @@ -115,7 +115,7 @@ #define RELAY_TOGGLE 5 #define STOP_REPEAT 10 -//#define MAV_CMD_CONDITION_YAW 23 +#define MAV_CMD_CONDITION_YAW 23 // GCS Message ID's #define MSG_ACKNOWLEDGE 0x00 diff --git a/ArduCopterMega/setup.pde b/ArduCopterMega/setup.pde index e3a4c45fad..1fab699f5e 100644 --- a/ArduCopterMega/setup.pde +++ b/ArduCopterMega/setup.pde @@ -98,9 +98,12 @@ setup_factory(uint8_t argc, const Menu::arg *argv) return(-1); AP_Var::erase_all(); Serial.printf_P(PSTR("\nFACTORY RESET complete - please reset APM to continue")); + + default_log_bitmask(); + default_gains(); + for (;;) { } - // note, cannot actually return here return(0); } @@ -643,7 +646,7 @@ default_throttle() save_EEPROM_throttle(); } -void default_logs() +void default_log_bitmask() { // convenience macro for testing LOG_* and setting LOGBIT_* diff --git a/ArduCopterMega/system.pde b/ArduCopterMega/system.pde index 9230c5c9f4..4ea60a4086 100644 --- a/ArduCopterMega/system.pde +++ b/ArduCopterMega/system.pde @@ -304,6 +304,7 @@ void set_mode(byte mode) if (g.log_bitmask & MASK_LOG_MODE) Log_Write_Mode(control_mode); + } void set_failsafe(boolean mode) diff --git a/ArduCopterMega/test.pde b/ArduCopterMega/test.pde index 69c7f3c9fa..0d7dc39f51 100644 --- a/ArduCopterMega/test.pde +++ b/ArduCopterMega/test.pde @@ -774,10 +774,12 @@ test_rawgps(uint8_t argc, const Menu::arg *argv) while(1){ if (Serial3.available()) Serial1.write(Serial3.read()); + if (Serial1.available()) Serial3.write(Serial1.read()); + if(Serial.available() > 0){ - return (0); + return (0); } } }