mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 00:28:30 -04:00
Copter: move init of global nav variables to set_nav_mode
This commit is contained in:
parent
4842335a24
commit
b7579bb028
@ -89,6 +89,8 @@ static bool set_nav_mode(uint8_t new_nav_mode)
|
||||
|
||||
case NAV_NONE:
|
||||
nav_initialised = true;
|
||||
// initialise global navigation variables including wp_distance, nav_roll
|
||||
reset_nav_params();
|
||||
break;
|
||||
|
||||
case NAV_CIRCLE:
|
||||
|
@ -523,10 +523,6 @@ static bool set_mode(uint8_t mode)
|
||||
|
||||
// update flight mode
|
||||
if (success) {
|
||||
if(ap.manual_attitude) {
|
||||
// We are under manual attitude control so initialise nav parameter for when we next enter an autopilot mode
|
||||
reset_nav_params();
|
||||
}
|
||||
control_mode = mode;
|
||||
Log_Write_Mode(control_mode);
|
||||
}else{
|
||||
|
Loading…
Reference in New Issue
Block a user