WPNav: rounding error fix in loiter
Contributed by Leonard Hall
This commit is contained in:
parent
8cb7bd628e
commit
c4f17b3235
@ -535,8 +535,8 @@ void AC_WPNav::get_loiter_position_to_velocity(float dt, float max_speed_cms)
|
||||
desired_vel.x = vel_sqrt * dist_error.x/dist_error_total;
|
||||
desired_vel.y = vel_sqrt * dist_error.y/dist_error_total;
|
||||
}else{
|
||||
desired_vel.x = _pid_pos_lat->get_p(dist_error.x);
|
||||
desired_vel.y = _pid_pos_lon->get_p(dist_error.y);
|
||||
desired_vel.x = _pid_pos_lat->kP() * dist_error.x;
|
||||
desired_vel.y = _pid_pos_lon->kP() * dist_error.y;
|
||||
}
|
||||
|
||||
// ensure velocity stays within limits
|
||||
|
Loading…
Reference in New Issue
Block a user