Browse Source

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
mission-4.1.18
Randy Mackay 12 years ago
parent
commit
870b9b0fbb
  1. 5
      ArduCopter/navigation.pde

5
ArduCopter/navigation.pde

@ -6,6 +6,11 @@ static void update_navigation() @@ -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
// exit immediately if not auto_armed
if (!ap.auto_armed) {
return;
}
// check for inertial nav updates
if( inertial_nav.position_ok() ) {

Loading…
Cancel
Save