mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-30 20:48:33 -04:00
AC_WPNav: integrate update_xy_controller name change
This commit is contained in:
parent
966340a02a
commit
72d2712c4e
@ -233,8 +233,8 @@ void AC_WPNav::update_loiter()
|
||||
// trigger position controller on next update
|
||||
_pos_control.trigger_xy();
|
||||
}else{
|
||||
// run loiter's position to velocity step
|
||||
_pos_control.update_pos_controller(true);
|
||||
// run horizontal position controller
|
||||
_pos_control.update_xy_controller(true);
|
||||
}
|
||||
}
|
||||
|
||||
@ -457,8 +457,8 @@ void AC_WPNav::update_wpnav()
|
||||
advance_wp_target_along_track(dt);
|
||||
_pos_control.trigger_xy();
|
||||
}else{
|
||||
// run position controller
|
||||
_pos_control.update_pos_controller(false);
|
||||
// run horizontal position controller
|
||||
_pos_control.update_xy_controller(false);
|
||||
}
|
||||
}
|
||||
|
||||
@ -661,8 +661,8 @@ void AC_WPNav::update_spline()
|
||||
advance_spline_target_along_track(dt);
|
||||
_pos_control.trigger_xy();
|
||||
}else{
|
||||
// run position controller
|
||||
_pos_control.update_pos_controller(false);
|
||||
// run horizontal position controller
|
||||
_pos_control.update_xy_controller(false);
|
||||
}
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user