AC_AttitudeControlMulti: run control_monitor_update in rate_controller_run

This commit is contained in:
Randy Mackay 2016-05-31 15:04:49 +09:00
parent 1639e22b74
commit 570920c7d7

View File

@ -228,4 +228,6 @@ void AC_AttitudeControl_Multi::rate_controller_run()
_motors.set_roll(rate_bf_to_motor_roll(_ang_vel_target_rads.x));
_motors.set_pitch(rate_bf_to_motor_pitch(_ang_vel_target_rads.y));
_motors.set_yaw(rate_bf_to_motor_yaw(_ang_vel_target_rads.z));
control_monitor_update();
}