mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Tracker: move startup delay to update_tracking call
This ensure the tracker does not move in any mode until after the startup delay has passed
This commit is contained in:
parent
1135ef3610
commit
2155951e63
@ -10,10 +10,6 @@
|
|||||||
*/
|
*/
|
||||||
static void update_auto(void)
|
static void update_auto(void)
|
||||||
{
|
{
|
||||||
if (g.startup_delay > 0 &&
|
|
||||||
hal.scheduler->millis() - start_time_ms < g.startup_delay*1000) {
|
|
||||||
return;
|
|
||||||
}
|
|
||||||
float yaw = wrap_180_cd((nav_status.bearing+g.yaw_trim)*100) * 0.01f;
|
float yaw = wrap_180_cd((nav_status.bearing+g.yaw_trim)*100) * 0.01f;
|
||||||
float pitch = constrain_float(nav_status.pitch+g.pitch_trim, -90, 90);
|
float pitch = constrain_float(nav_status.pitch+g.pitch_trim, -90, 90);
|
||||||
update_pitch_servo(pitch);
|
update_pitch_servo(pitch);
|
||||||
|
@ -89,6 +89,12 @@ static void update_tracking(void)
|
|||||||
// update bearing and distance to vehicle
|
// update bearing and distance to vehicle
|
||||||
update_bearing_and_distance();
|
update_bearing_and_distance();
|
||||||
|
|
||||||
|
// do not perform any servo updates until startup delay has passed
|
||||||
|
if (g.startup_delay > 0 &&
|
||||||
|
hal.scheduler->millis() - start_time_ms < g.startup_delay*1000) {
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
switch (control_mode) {
|
switch (control_mode) {
|
||||||
case AUTO:
|
case AUTO:
|
||||||
update_auto();
|
update_auto();
|
||||||
|
Loading…
Reference in New Issue
Block a user