mirror of https://github.com/ArduPilot/ardupilot
Added additional nav params to reset
This commit is contained in:
parent
be3edc19f8
commit
9e67c7efca
|
@ -146,6 +146,15 @@ static void reset_nav(void)
|
|||
g.pi_nav_lat.reset_I();
|
||||
g.pi_nav_lon.reset_I();
|
||||
|
||||
circle_angle = 0;
|
||||
crosstrack_error = 0;
|
||||
nav_lat = 0;
|
||||
nav_lon = 0;
|
||||
nav_roll = 0;
|
||||
nav_pitch = 0;
|
||||
target_bearing = 0;
|
||||
wp_distance = 0;
|
||||
wp_totalDistance = 0;
|
||||
long_error = 0;
|
||||
lat_error = 0;
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue