mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-08 17:03:57 -04:00
ACM : Attitude : added nav param reset
This commit is contained in:
parent
3c78c4a7a3
commit
5ad38a32bf
@ -527,8 +527,14 @@ static void reset_nav_params(void)
|
|||||||
wp_distance = 0;
|
wp_distance = 0;
|
||||||
|
|
||||||
// Will be set by new command, used by loiter
|
// Will be set by new command, used by loiter
|
||||||
long_error = 0;
|
long_error = 0;
|
||||||
lat_error = 0;
|
lat_error = 0;
|
||||||
|
nav_lon = 0;
|
||||||
|
nav_lat = 0;
|
||||||
|
nav_roll = 0;
|
||||||
|
nav_pitch = 0;
|
||||||
|
auto_roll = 0;
|
||||||
|
auto_pitch = 0;
|
||||||
|
|
||||||
// make sure we stick to Nav yaw on takeoff
|
// make sure we stick to Nav yaw on takeoff
|
||||||
auto_yaw = nav_yaw;
|
auto_yaw = nav_yaw;
|
||||||
|
Loading…
Reference in New Issue
Block a user