diff --git a/ArduCopterMega/APM_Config.h b/ArduCopterMega/APM_Config.h index 5907865c39..bb4f53876a 100644 --- a/ArduCopterMega/APM_Config.h +++ b/ArduCopterMega/APM_Config.h @@ -7,7 +7,7 @@ //#define MAG_ORIENTATION AP_COMPASS_COMPONENTS_DOWN_PINS_FORWARD #define NAV_TEST 1 // 0 = traditional, 1 = rate controlled -#define YAW_OPTION 0 // 0 = hybrid rate approach, 1 = offset Yaw approach +#define YAW_OPTION 1 // 0 = hybrid rate approach, 1 = offset Yaw approach #define AUTO_RESET_LOITER 1 // enables Loiter to reset it's current location based on stick input. #define FRAME_CONFIG QUAD_FRAME diff --git a/ArduCopterMega/radio.pde b/ArduCopterMega/radio.pde index 3878861295..8200bb1473 100644 --- a/ArduCopterMega/radio.pde +++ b/ArduCopterMega/radio.pde @@ -22,7 +22,7 @@ void init_rc_in() g.rc_1.dead_zone = 60; // 60 = .6 degrees g.rc_2.dead_zone = 60; g.rc_3.dead_zone = 60; - g.rc_4.dead_zone = 500; + g.rc_4.dead_zone = 200; //set auxiliary ranges g.rc_5.set_range(0,1000); diff --git a/ArduCopterMega/system.pde b/ArduCopterMega/system.pde index e70dc1b2b7..6b9c3717ba 100644 --- a/ArduCopterMega/system.pde +++ b/ArduCopterMega/system.pde @@ -37,7 +37,7 @@ const struct Menu::command main_menu_commands[] PROGMEM = { }; // Create the top-level menu object. -MENU(main_menu, "AC 2.0.10 Beta", main_menu_commands); +MENU(main_menu, "AC 2.0.11 Beta", main_menu_commands); void init_ardupilot() {