mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-21 16:18:29 -04:00
Copter: use simplified precland interface
This commit is contained in:
parent
f74e162451
commit
91a5b26725
@ -269,6 +269,8 @@ private:
|
||||
uint32_t start_ms;
|
||||
} takeoff_state;
|
||||
|
||||
uint32_t precland_last_update_ms;
|
||||
|
||||
RCMapper rcmap;
|
||||
|
||||
// board specific config
|
||||
|
@ -420,10 +420,15 @@ void Copter::auto_land_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()));
|
||||
if (!ap.land_repo_active && precland.target_acquired() && precland_last_update_ms != precland.last_update_ms()) {
|
||||
Vector3f target_pos;
|
||||
precland.get_target_position(target_pos);
|
||||
pos_control.set_xy_target(target_pos.x, target_pos.y);
|
||||
pos_control.freeze_ff_xy();
|
||||
precland_last_update_ms = precland.last_update_ms();
|
||||
}
|
||||
#endif
|
||||
|
||||
|
@ -123,8 +123,12 @@ void Copter::land_gps_run()
|
||||
|
||||
#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()));
|
||||
if (!ap.land_repo_active && precland.target_acquired() && precland_last_update_ms != precland.last_update_ms()) {
|
||||
Vector3f target_pos;
|
||||
precland.get_target_position(target_pos);
|
||||
pos_control.set_xy_target(target_pos.x, target_pos.y);
|
||||
pos_control.freeze_ff_xy();
|
||||
precland_last_update_ms = precland.last_update_ms();
|
||||
}
|
||||
#endif
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user