Copter: only run nav controllers when auto-armed

This stops run-up in target position and nav controller I terms ahead of
throttle being raised
This commit is contained in:
Randy Mackay 2013-05-10 10:46:17 +09:00
parent 5296e858b6
commit 870b9b0fbb
1 changed files with 5 additions and 0 deletions

View File

@ -6,6 +6,11 @@ static void update_navigation()
{ {
static uint32_t nav_last_update = 0; // the system time of the last time nav was run update static uint32_t nav_last_update = 0; // the system time of the last time nav was run update
// exit immediately if not auto_armed
if (!ap.auto_armed) {
return;
}
// check for inertial nav updates // check for inertial nav updates
if( inertial_nav.position_ok() ) { if( inertial_nav.position_ok() ) {