moved rudder servo control out of 200hz loop to test if it will reduce servo noise.

git-svn-id: https://arducopter.googlecode.com/svn/trunk@2260 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
jasonshort 2011-05-14 04:45:28 +00:00
parent 12357746a9
commit 4a7b4ac3b4
2 changed files with 6 additions and 5 deletions

View File

@ -744,6 +744,12 @@ void fifty_hz_loop()
#endif
// XXX this should be absorbed into the above,
// or be a "GCS fast loop" interface
// Hack - had to move to 50hz loop to test a theory
if(g.frame_type == TRI_FRAME){
// servo Yaw
APM_RC.OutputCh(CH_7, g.rc_4.radio_out);
}
}
@ -1251,8 +1257,6 @@ void update_alt()
}
}
// calculate our altitude
if(altitude_sensor == BARO){
current_loc.alt = baro_alt + baro_alt_offset + home.alt;

View File

@ -131,9 +131,6 @@ set_servos_4()
// 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;
// servo Yaw
APM_RC.OutputCh(CH_7, g.rc_4.radio_out);
}else if (g.frame_type == HEXAX_FRAME) {
//Serial.println("6_FRAME");