mirror of https://github.com/ArduPilot/ardupilot
AR_WPNav: allow target position on track to stop advancing
This commit is contained in:
parent
158f7944fd
commit
381fb42023
|
@ -426,7 +426,7 @@ void AR_WPNav::advance_wp_target_along_track(const Location ¤t_loc, float
|
|||
float track_velocity = curr_vel_NED.xy().dot(track_direction);
|
||||
// set time scaler to be consistent with the achievable vehicle speed with a 5% buffer for short term variation.
|
||||
const float time_scaler_dt_max = _overspeed_enabled ? AR_WPNAV_OVERSPEED_RATIO_MAX : 1.0f;
|
||||
track_scaler_dt = constrain_float(0.05f + (track_velocity - _pos_control.get_pos_p().kP() * track_error) / curr_target_vel.length(), 0.1f, time_scaler_dt_max);
|
||||
track_scaler_dt = constrain_float(0.05f + (track_velocity - _pos_control.get_pos_p().kP() * track_error) / curr_target_vel.length(), 0.0f, time_scaler_dt_max);
|
||||
}
|
||||
// change s-curve time speed with a time constant of maximum acceleration / maximum jerk
|
||||
float track_scaler_tc = 1.0f;
|
||||
|
|
Loading…
Reference in New Issue