fixed a bug on Yaw.

git-svn-id: https://arducopter.googlecode.com/svn/trunk@1308 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
jasonshort 2010-12-28 01:26:05 +00:00
parent cdb6ad86d3
commit 94ebc7860c
4 changed files with 9 additions and 15 deletions

View File

@ -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

View File

@ -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.

View File

@ -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

View File

@ -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
// -----------------------------