mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-01 21:48:28 -04:00
Sub: Workaround for more graceful servo mount initialization
This commit is contained in:
parent
e92dbad358
commit
e24fef70f6
@ -220,7 +220,10 @@ void Sub::fifty_hz_loop()
|
|||||||
|
|
||||||
// Update servo output
|
// Update servo output
|
||||||
RC_Channels::set_pwm_all();
|
RC_Channels::set_pwm_all();
|
||||||
SRV_Channels::limit_slew_rate(SRV_Channel::k_mount_tilt, g.cam_slew_limit, 0.02f);
|
// 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();
|
SRV_Channels::output_ch_all();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user