HIL: we only need 50Hz attitude for HIL

putting it in the fastest loop clogged up mavlink too much

git-svn-id: https://arducopter.googlecode.com/svn/trunk@2923 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
tridge60@gmail.com 2011-07-19 09:49:57 +00:00
parent 3d641a3b45
commit efae9dddd5

View File

@ -598,11 +598,6 @@ static void fast_loop()
// record throttle output
// ------------------------------
throttle_integrator += g.rc_3.servo_out;
#if HIL_PROTOCOL == HIL_PROTOCOL_MAVLINK && HIL_MODE != HIL_MODE_DISABLED
// HIL for a copter needs very fast update of the servo values
hil.send_message(MSG_RADIO_OUT);
#endif
}
static void medium_loop()
@ -771,6 +766,11 @@ static void medium_loop()
// ---------------------------
static void fifty_hz_loop()
{
#if HIL_PROTOCOL == HIL_PROTOCOL_MAVLINK && HIL_MODE != HIL_MODE_DISABLED
// HIL for a copter needs very fast update of the servo values
hil.send_message(MSG_RADIO_OUT);
#endif
// use Yaw to find our bearing error
calc_bearing_error();