mirror of https://github.com/ArduPilot/ardupilot
AR_WPNav: remove get_accel_max, get_jerk_max
This commit is contained in:
parent
ee317299fc
commit
d03e801b65
|
@ -341,24 +341,6 @@ bool AR_WPNav::set_desired_location_expect_fast_update(const Location &destinati
|
|||
return true;
|
||||
}
|
||||
|
||||
// get max acceleration in m/s/s
|
||||
float AR_WPNav::get_accel_max() const
|
||||
{
|
||||
if (is_positive(_accel_max)) {
|
||||
return _accel_max;
|
||||
}
|
||||
return _atc.get_accel_max();
|
||||
}
|
||||
|
||||
// get max jerk in m/s/s/s
|
||||
float AR_WPNav::get_jerk_max() const
|
||||
{
|
||||
if (is_positive(_jerk_max)) {
|
||||
return _jerk_max;
|
||||
}
|
||||
return get_accel_max();
|
||||
}
|
||||
|
||||
// calculate vehicle stopping point using current location, velocity and maximum acceleration
|
||||
bool AR_WPNav::get_stopping_location(Location& stopping_loc)
|
||||
{
|
||||
|
|
|
@ -98,12 +98,6 @@ public:
|
|||
float get_radius() const { return _radius; }
|
||||
float get_pivot_rate() const { return _pivot.get_rate_max(); }
|
||||
|
||||
// get max acceleration in m/s/s
|
||||
float get_accel_max() const;
|
||||
|
||||
// get max jerk in m/s/s/s
|
||||
float get_jerk_max() const;
|
||||
|
||||
// calculate stopping location using current position and attitude controller provided maximum deceleration
|
||||
// returns true on success, false on failure
|
||||
bool get_stopping_location(Location& stopping_loc) WARN_IF_UNUSED;
|
||||
|
|
Loading…
Reference in New Issue