diff --git a/ArduCopterMega/control_modes.pde b/ArduCopterMega/control_modes.pde index 451a8d074c..f5d3ff6417 100644 --- a/ArduCopterMega/control_modes.pde +++ b/ArduCopterMega/control_modes.pde @@ -87,8 +87,8 @@ void read_trim_switch() // this is a test for Max's tri-copter if(g.frame_type == TRI_FRAME){ - g.rc_4.trim(); // yaw - g.rc_4.save_eeprom(); + //g.rc_4.trim(); // yaw + //g.rc_4.save_eeprom(); } } trim_flag = false; diff --git a/ArduCopterMega/defines.h b/ArduCopterMega/defines.h index 7292ba7f8e..93a16b40bd 100644 --- a/ArduCopterMega/defines.h +++ b/ArduCopterMega/defines.h @@ -302,7 +302,6 @@ #define ONBOARD_PARAM_NAME_LENGTH 15 #define MAX_WAYPOINTS ((EEPROM_MAX_ADDR - WP_START_BYTE) / WP_SIZE) - 1 // - 1 to be safe -/* #ifndef MAV_CMD_DO_ROI # define MAV_CMD_DO_ROI 201 #endif @@ -322,4 +321,4 @@ # define MAV_ROI_TARGET 4 #endif -*/ \ No newline at end of file +//*/ \ No newline at end of file diff --git a/ArduCopterMega/motors.pde b/ArduCopterMega/motors.pde index af171c335e..38b8e1bbdc 100644 --- a/ArduCopterMega/motors.pde +++ b/ArduCopterMega/motors.pde @@ -127,7 +127,7 @@ set_servos_4() motor_out[CH_4] = g.rc_3.radio_out - g.rc_2.pwm_out; // this is a compensation for the angle of the yaw motor. Its linear, but should work ok. - motor_out[CH_4] += (float)(abs(g.rc_4.control_in)) * .013; + //motor_out[CH_4] += (float)(abs(g.rc_4.control_in)) * .013; // servo Yaw APM_RC.OutputCh(CH_7, g.rc_4.radio_out); diff --git a/ArduCopterMega/setup.pde b/ArduCopterMega/setup.pde index 83fc5d1f5b..bea8450398 100644 --- a/ArduCopterMega/setup.pde +++ b/ArduCopterMega/setup.pde @@ -511,7 +511,7 @@ setup_frame(uint8_t argc, const Menu::arg *argv) g.frame_type = HEXAP_FRAME; }else{ - Serial.printf_P(PSTR("\nOptions:[+, x, tri, hexa, y6]\n")); + Serial.printf_P(PSTR("\nOptions:[+, x, tri, hexa+, hexax, y6]\n")); report_frame(); return 0; }