Browse Source

Slowed Auto Descent

Don't return true in Landing code to prevent flyways in Stabilize
master
Jason Short 13 years ago
parent
commit
78255b722e
  1. 5
      ArduCopter/commands_logic.pde
  2. 2
      ArduCopter/commands_process.pde

5
ArduCopter/commands_logic.pde

@ -348,7 +348,7 @@ static bool verify_land()
static int16_t velocity_land = -1; static int16_t velocity_land = -1;
// land at .62 meter per second // land at .62 meter per second
next_WP.alt = original_alt - ((millis() - land_start) / 16); // condition_value = our initial next_WP.alt = original_alt - ((millis() - land_start) / 32); // condition_value = our initial
if (old_alt == 0) if (old_alt == 0)
old_alt = current_loc.alt; old_alt = current_loc.alt;
@ -384,8 +384,7 @@ static bool verify_land()
// reset old_alt // reset old_alt
old_alt = 0; old_alt = 0;
//init_disarm_motors(); return false;
return true;
} }
//Serial.printf("N, %d\n", velocity_land); //Serial.printf("N, %d\n", velocity_land);
//Serial.printf("N_alt, %ld\n", next_WP.alt); //Serial.printf("N_alt, %ld\n", next_WP.alt);

2
ArduCopter/commands_process.pde

@ -63,6 +63,8 @@ static void update_commands()
// if we are on the ground, enter stabilize, else Land // if we are on the ground, enter stabilize, else Land
if (land_complete == true){ if (land_complete == true){
set_mode(STABILIZE); set_mode(STABILIZE);
// disarm motors
//init_disarm_motors();
} else { } else {
set_mode(LAND); set_mode(LAND);
} }

Loading…
Cancel
Save