Skip to content

Commit

Permalink
AC_PosControl: add clear_desired_velocity_ff_z method
Browse files Browse the repository at this point in the history
  • Loading branch information
lthall authored and rmackay9 committed Apr 28, 2017
1 parent aab27d8 commit 6e92f74
Showing 1 changed file with 3 additions and 0 deletions.
3 changes: 3 additions & 0 deletions libraries/AC_AttitudeControl/AC_PosControl.h
Original file line number Diff line number Diff line change
Expand Up @@ -220,6 +220,9 @@ class AC_PosControl
/// set_desired_velocity_z - sets desired velocity in cm/s in z axis
void set_desired_velocity_z(float vel_z_cms) {_vel_desired.z = vel_z_cms;}

// clear desired velocity feed-forward in z axis
void clear_desired_velocity_ff_z() { _flags.use_desvel_ff_z = false; }

/// set_desired_velocity_xy - sets desired velocity in cm/s in lat and lon directions
/// when update_xy_controller is next called the position target is moved based on the desired velocity and
/// the desired velocities are fed forward into the rate_to_accel step
Expand Down

0 comments on commit 6e92f74

Please sign in to comment.