Small fix on the Traditional Helicopter Collective-Yaw compensation calculation.

This commit is contained in:
Robert Lefebvre 2012-03-15 20:14:18 -04:00
parent 68e37774a6
commit be3fe36c52
1 changed files with 1 additions and 1 deletions

View File

@ -204,7 +204,7 @@ static void heli_move_swash(int roll_out, int pitch_out, int coll_out, int yaw_o
// rudder feed forward based on collective
#if HIL_MODE == HIL_MODE_DISABLED // don't do rudder feed forward in simulator
if( !g.heli_ext_gyro_enabled ) {
yaw_offset = g.heli_collective_yaw_effect * abs(coll_out_scaled - g.heli_collective_mid);
yaw_offset = g.heli_collective_yaw_effect * abs(coll_out_scaled - heli_throttle_mid);
}
#endif
}