Skip to content

Commit

Permalink
AC_WPNav: update usage of update_xy_controller
Browse files Browse the repository at this point in the history
  • Loading branch information
jschall committed Jan 28, 2015
1 parent 60beb81 commit 0125d40
Show file tree
Hide file tree
Showing 2 changed files with 4 additions and 4 deletions.
2 changes: 1 addition & 1 deletion libraries/AC_WPNav/AC_Circle.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -151,7 +151,7 @@ void AC_Circle::update()
}

// update position controller
_pos_control.update_xy_controller(false, 1.0f);
_pos_control.update_xy_controller(AC_PosControl::XY_MODE_POS_ONLY, 1.0f);
}
}

Expand Down
6 changes: 3 additions & 3 deletions libraries/AC_WPNav/AC_WPNav.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -343,7 +343,7 @@ void AC_WPNav::update_loiter(float ekfGndSpdLimit, float ekfNavVelGainScaler)
dt = 0.0f;
}
calc_loiter_desired_velocity(dt,ekfGndSpdLimit);
_pos_control.update_xy_controller(true, ekfNavVelGainScaler);
_pos_control.update_xy_controller(AC_PosControl::XY_MODE_SLOW_POS_AND_VEL, ekfNavVelGainScaler);
}
}

Expand Down Expand Up @@ -651,7 +651,7 @@ void AC_WPNav::update_wpnav()
}
_pos_control.freeze_ff_z();

_pos_control.update_xy_controller(false, 1.0f);
_pos_control.update_xy_controller(AC_PosControl::XY_MODE_POS_ONLY, 1.0f);
check_wp_leash_length();

_wp_last_update = hal.scheduler->millis();
Expand Down Expand Up @@ -914,7 +914,7 @@ void AC_WPNav::update_spline()
_pos_control.freeze_ff_z();

// run horizontal position controller
_pos_control.update_xy_controller(false, 1.0f);
_pos_control.update_xy_controller(AC_PosControl::XY_MODE_POS_ONLY, 1.0f);

_wp_last_update = hal.scheduler->millis();
}
Expand Down

0 comments on commit 0125d40

Please sign in to comment.