Browse Source

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
master
Randy Mackay 11 years ago
parent
commit
2155951e63
  1. 4
      AntennaTracker/control_auto.pde
  2. 6
      AntennaTracker/tracking.pde

4
AntennaTracker/control_auto.pde

@ -10,10 +10,6 @@ @@ -10,10 +10,6 @@
*/
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 pitch = constrain_float(nav_status.pitch+g.pitch_trim, -90, 90);
update_pitch_servo(pitch);

6
AntennaTracker/tracking.pde

@ -89,6 +89,12 @@ static void update_tracking(void) @@ -89,6 +89,12 @@ static void update_tracking(void)
// update bearing and distance to vehicle
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) {
case AUTO:
update_auto();

Loading…
Cancel
Save