diff --git a/ArduCopterMega/APM_Config.h b/ArduCopterMega/APM_Config.h index 7c5525ffdf..3b8a354fdb 100644 --- a/ArduCopterMega/APM_Config.h +++ b/ArduCopterMega/APM_Config.h @@ -15,7 +15,7 @@ // These are all experimental and underwork, jp 23-12-10 //#define ENABLE_EXTRAS ENABLED //#define ENABLE_EXTRAINIT ENABLED -#define ENABLE_CAM ENABLED +//#define ENABLE_CAM ENABLED //#define ENABLE_AM ENABLED //#define ENABLE_xx ENABLED diff --git a/ArduCopterMega/Camera.pde b/ArduCopterMega/Camera.pde index 5af5669e16..cb0528b6b0 100644 --- a/ArduCopterMega/Camera.pde +++ b/ArduCopterMega/Camera.pde @@ -19,18 +19,6 @@ camera_stabilization() //rc_camera_pitch.servo_out; rc_camera_pitch.calc_pwm(); - Serial.print(rc_camera_pitch.radio_min,DEC); - Serial.print(" "); - Serial.print(rc_camera_pitch.radio_trim,DEC); - Serial.print(" "); - Serial.print(rc_camera_pitch.radio_max,DEC); - Serial.print(" "); - Serial.print(rc_camera_pitch.servo_out,DEC); - Serial.print(" "); - Serial.print(rc_camera_pitch.angle_to_pwm(),DEC); - Serial.print(" "); - Serial.println(rc_camera_pitch.radio_out,DEC); - APM_RC.OutputCh(CH_5,rc_camera_pitch.radio_out); //If you want to do control mixing use this function. diff --git a/ArduCopterMega/radio.pde b/ArduCopterMega/radio.pde index 1fd8ff8de7..a219bcc72c 100644 --- a/ArduCopterMega/radio.pde +++ b/ArduCopterMega/radio.pde @@ -60,6 +60,13 @@ void trim_radio() rc_4.trim(); // yaw } +void trim_yaw() +{ + for (byte i = 0; i < 50; i++){ + read_radio(); + } + rc_4.trim(); // yaw +} #define ARM_DELAY 10 #define DISARM_DELAY 10 diff --git a/ArduCopterMega/system.pde b/ArduCopterMega/system.pde index 19319217ee..037c111680 100644 --- a/ArduCopterMega/system.pde +++ b/ArduCopterMega/system.pde @@ -235,8 +235,7 @@ void startup_ground(void) // read the radio to set trims // --------------------------- - // I am disabling this. It's not appropriate for Copters, only planes - //trim_radio(); + trim_yaw(); // Warm up and read Gyro offsets // -----------------------------