mirror of https://github.com/ArduPilot/ardupilot
AR_WPNav: remove unneeded overshoot methods
This commit is contained in:
parent
75956755bb
commit
43449a4adb
|
@ -424,12 +424,6 @@ void AR_WPNav::set_turn_params(float turn_max_g, float turn_radius, bool pivot_p
|
|||
_pivot_possible = pivot_possible;
|
||||
}
|
||||
|
||||
// set default overshoot (used for sailboats)
|
||||
void AR_WPNav::set_default_overshoot(float overshoot)
|
||||
{
|
||||
_overshoot.set_default(overshoot);
|
||||
}
|
||||
|
||||
// adjust speed to ensure it does not fall below value held in SPEED_MIN
|
||||
void AR_WPNav::apply_speed_min(float &desired_speed)
|
||||
{
|
||||
|
|
|
@ -72,13 +72,9 @@ public:
|
|||
// settor to allow vehicle code to provide turn related param values to this library (should be updated regularly)
|
||||
void set_turn_params(float turn_max_g, float turn_radius, bool pivot_possible);
|
||||
|
||||
// set default overshoot (used for sailboats)
|
||||
void set_default_overshoot(float overshoot);
|
||||
|
||||
// accessors for parameter values
|
||||
float get_default_speed() const { return _speed_max; }
|
||||
float get_radius() const { return _radius; }
|
||||
float get_overshoot() const { return _overshoot; }
|
||||
float get_pivot_rate() const { return _pivot_rate; }
|
||||
|
||||
// calculate stopping location using current position and attitude controller provided maximum deceleration
|
||||
|
|
Loading…
Reference in New Issue