AC_PosControl: add shift_pos_xy_target

This commit is contained in:
Randy Mackay 2015-10-29 16:30:14 +09:00
parent 16a0281c92
commit 550ba478c9
2 changed files with 16 additions and 0 deletions

View File

@ -532,6 +532,19 @@ void AC_PosControl::set_xy_target(float x, float y)
_pos_target.y = y;
}
/// shift position target target in x, y axis
void AC_PosControl::shift_pos_xy_target(float x_cm, float y_cm)
{
// move pos controller target
_pos_target.x += x_cm;
_pos_target.y += y_cm;
// disable feed forward
if (!is_zero(x_cm) || !is_zero(y_cm)) {
freeze_ff_xy();
}
}
/// set_target_to_stopping_point_xy - sets horizontal target to reasonable stopping position in cm from home
void AC_PosControl::set_target_to_stopping_point_xy()
{

View File

@ -209,6 +209,9 @@ public:
/// set_xy_target in cm from home
void set_xy_target(float x, float y);
/// shift position target target in x, y axis
void shift_pos_xy_target(float x_cm, float y_cm);
/// get_desired_velocity - returns xy desired velocity (i.e. feed forward) in cm/s in lat and lon direction
const Vector3f& get_desired_velocity() { return _vel_desired; }