mirror of https://github.com/ArduPilot/ardupilot
Tracker: auto move servos only with valid vehicle position
This commit is contained in:
parent
0d1fefc23d
commit
bf4ba9ffc4
|
@ -10,6 +10,11 @@
|
||||||
*/
|
*/
|
||||||
static void update_auto(void)
|
static void update_auto(void)
|
||||||
{
|
{
|
||||||
|
// exit immediately if we do not have a valid vehicle position
|
||||||
|
if (!vehicle.location_valid) {
|
||||||
|
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);
|
||||||
|
|
Loading…
Reference in New Issue