mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-08 17:08:28 -04:00
AC_PosControl: update_xy_controller allows not resetting I term
This commit is contained in:
parent
5d0476e522
commit
6c71569775
@ -428,13 +428,15 @@ float AC_PosControl::get_distance_to_target() const
|
||||
}
|
||||
|
||||
/// update_xy_controller - run the horizontal position controller - should be called at 100hz or higher
|
||||
void AC_PosControl::update_xy_controller(bool use_desired_velocity)
|
||||
void AC_PosControl::update_xy_controller(bool use_desired_velocity, bool reset_I)
|
||||
{
|
||||
// catch if we've just been started
|
||||
uint32_t now = hal.scheduler->millis();
|
||||
if ((now - _last_update_ms) >= 1000) {
|
||||
_last_update_ms = now;
|
||||
reset_I_xy();
|
||||
if (reset_I) {
|
||||
reset_I_xy();
|
||||
}
|
||||
_xy_step = 0;
|
||||
}
|
||||
|
||||
|
@ -165,7 +165,7 @@ public:
|
||||
|
||||
/// update_xy_controller - run the horizontal position controller - should be called at 100hz or higher
|
||||
/// when use_desired_velocity is true the desired velocity (i.e. feed forward) is incorporated at the pos_to_rate step
|
||||
void update_xy_controller(bool use_desired_velocity);
|
||||
void update_xy_controller(bool use_desired_velocity, bool reset_I=true);
|
||||
|
||||
/// get_stopping_point_xy - calculates stopping point based on current position, velocity, vehicle acceleration
|
||||
/// distance_max allows limiting distance to stopping point
|
||||
|
Loading…
Reference in New Issue
Block a user