Browse Source

Landing update for better baro landing

mission-4.1.18
Jason Short 13 years ago
parent
commit
67cd412105
  1. 4
      ArduCopter/commands_logic.pde

4
ArduCopter/commands_logic.pde

@ -401,15 +401,15 @@ static bool verify_land_baro()
landing_boost++; landing_boost++;
landing_boost = min(landing_boost, 40); landing_boost = min(landing_boost, 40);
} }
if(current_loc.alt < 200 ){ if(current_loc.alt < 200 ){
wp_control = NO_NAV_MODE; wp_control = NO_NAV_MODE;
} }
if(current_loc.alt < 150 ){ if(current_loc.alt < 150 ){
if(abs(climb_rate) < 20) { if(abs(climb_rate) < 20) {
landing_boost++;
if(ground_detector++ > 30) { if(ground_detector++ > 30) {
//landing_boost = 100;
//Serial.print("land_complete\n");
land_complete = true; land_complete = true;
ground_detector = 0; ground_detector = 0;
// init disarm motors // init disarm motors

Loading…
Cancel
Save