mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 00:04:02 -04:00
AC_PosControl: add clear_desired_velocity_ff_z method
This commit is contained in:
parent
aab27d8d0e
commit
6e92f74ca0
@ -220,6 +220,9 @@ public:
|
|||||||
/// set_desired_velocity_z - sets desired velocity in cm/s in z axis
|
/// 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;}
|
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
|
/// 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
|
/// 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
|
/// the desired velocities are fed forward into the rate_to_accel step
|
||||||
|
Loading…
Reference in New Issue
Block a user