ardupilot/AntennaTracker/control_auto.pde
Randy Mackay 2155951e63 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
2014-10-06 19:40:44 +09:00

18 lines
481 B
Plaintext

// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
/*
* control_auto.pde - auto control mode
*/
/*
* update_auto - runs the auto controller
* called at 50hz while control_mode is 'AUTO'
*/
static void update_auto(void)
{
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);
update_yaw_servo(yaw);
}