Copter: remove unused set_desired_velocity_with_accel_and_fence_limits

This commit is contained in:
Randy Mackay 2021-09-07 21:29:34 +09:00 committed by Andrew Tridgell
parent b6312d21a7
commit 53e767ee77
2 changed files with 0 additions and 6 deletions

View File

@ -924,7 +924,6 @@ private:
void accel_control_run(); void accel_control_run();
void velaccel_control_run(); void velaccel_control_run();
void posvelaccel_control_run(); void posvelaccel_control_run();
void set_desired_velocity_with_accel_and_fence_limits(const Vector3f& vel_des);
void set_yaw_state(bool use_yaw, float yaw_cd, bool use_yaw_rate, float yaw_rate_cds, bool relative_angle); void set_yaw_state(bool use_yaw, float yaw_cd, bool use_yaw_rate, float yaw_rate_cds, bool relative_angle);
bool use_pilot_yaw(void) const; bool use_pilot_yaw(void) const;

View File

@ -884,11 +884,6 @@ void ModeGuided::angle_control_run()
} }
} }
// helper function to update position controller's desired velocity while respecting acceleration limits
void ModeGuided::set_desired_velocity_with_accel_and_fence_limits(const Vector3f& vel_des)
{
}
// helper function to set yaw state and targets // helper function to set yaw state and targets
void ModeGuided::set_yaw_state(bool use_yaw, float yaw_cd, bool use_yaw_rate, float yaw_rate_cds, bool relative_angle) void ModeGuided::set_yaw_state(bool use_yaw, float yaw_cd, bool use_yaw_rate, float yaw_rate_cds, bool relative_angle)
{ {