AC_WPNav: remove unused set_loiter_velocity

This commit is contained in:
Jonathan Challinger 2015-04-29 17:23:32 -07:00 committed by Randy Mackay
parent 187dd0dccd
commit 2b29060a4e
2 changed files with 0 additions and 19 deletions

View File

@ -196,22 +196,6 @@ void AC_WPNav::loiter_soften_for_landing()
_pos_control.freeze_ff_xy();
}
/// set_loiter_velocity - allows main code to pass the maximum velocity for loiter
void AC_WPNav::set_loiter_velocity(float velocity_cms)
{
// range check velocity and update position controller
//float maxSpd_cms = _ahrs.getSpeedlimit();
if (velocity_cms >= WPNAV_LOITER_SPEED_MIN) {
_loiter_speed_cms = velocity_cms;
// initialise pos controller speed
_pos_control.set_speed_xy(_loiter_speed_cms);
// initialise pos controller acceleration
_pos_control.set_accel_xy(_loiter_accel_cmss);
}
}
/// set_pilot_desired_acceleration - sets pilot desired acceleration from roll and pitch stick input
void AC_WPNav::set_pilot_desired_acceleration(float control_roll, float control_pitch)
{

View File

@ -73,9 +73,6 @@ public:
/// loiter_soften_for_landing - reduce response for landing
void loiter_soften_for_landing();
/// set_loiter_velocity - allows main code to pass the maximum velocity for loiter
void set_loiter_velocity(float velocity_cms);
/// calculate_loiter_leash_length - calculates the maximum distance in cm that the target position may be from the current location
void calculate_loiter_leash_length();