mirror of https://github.com/ArduPilot/ardupilot
better default for speed governer
This commit is contained in:
parent
02d6adb21f
commit
6377cf8549
|
@ -178,7 +178,7 @@ static void set_next_WP(struct Location *wp)
|
||||||
|
|
||||||
// reset speed governer
|
// reset speed governer
|
||||||
// --------------------
|
// --------------------
|
||||||
waypoint_speed_gov = 0;
|
waypoint_speed_gov = WAYPOINT_SPEED_MIN;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue