Copter: add Precision Landing to GPS land

This commit is contained in:
Randy Mackay 2015-08-28 17:14:40 +09:00
parent 0da38ba2bf
commit f4b152f0e3
2 changed files with 16 additions and 0 deletions

View File

@ -240,6 +240,7 @@ private:
enum HomeState home_state : 2; // 18,19 // home status (unset, set, locked)
uint8_t using_interlock : 1; // 20 // aux switch motor interlock function is in use
uint8_t motor_emergency_stop: 1; // 21 // motor estop switch, shuts off motors when enabled
uint8_t land_repo_active : 1; // 22 // true if the pilot is overriding the landing position
};
uint32_t value;
} ap;

View File

@ -30,6 +30,9 @@ bool Copter::land_init(bool ignore_checks)
land_pause = false;
// reset flag indicating if pilot has applied roll or pitch inputs during landing
ap.land_repo_active = false;
return true;
}
@ -91,6 +94,11 @@ void Copter::land_gps_run()
// process pilot's roll and pitch input
roll_control = channel_roll->control_in;
pitch_control = channel_pitch->control_in;
// record if pilot has overriden roll or pitch
if (roll_control != 0 || pitch_control != 0) {
ap.land_repo_active = true;
}
}
// get pilot's desired yaw rate
@ -100,6 +108,13 @@ void Copter::land_gps_run()
// process roll, pitch inputs
wp_nav.set_pilot_desired_acceleration(roll_control, pitch_control);
#if PRECISION_LANDING == ENABLED
// run precision landing
if (!ap.land_repo_active) {
wp_nav.shift_loiter_target(precland.get_target_shift(wp_nav.get_loiter_target()));
}
#endif
// run loiter controller
wp_nav.update_loiter(ekfGndSpdLimit, ekfNavVelGainScaler);