Sub: Workaround for more graceful servo mount initialization

This commit is contained in:
Jacob Walser 2017-04-16 20:14:23 -04:00
parent e92dbad358
commit e24fef70f6

View File

@ -220,7 +220,10 @@ void Sub::fifty_hz_loop()
// Update servo output
RC_Channels::set_pwm_all();
// wait for outputs to initialize: TODO find a better way to do this
if (millis() > 10000) {
SRV_Channels::limit_slew_rate(SRV_Channel::k_mount_tilt, g.cam_slew_limit, 0.02f);
}
SRV_Channels::output_ch_all();
}