mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-26 17:53:59 -04:00
AR_WPNav: add accessors for accel and jerk limits
This commit is contained in:
parent
e1c006c25d
commit
d982c28ef2
@ -91,6 +91,8 @@ public:
|
|||||||
|
|
||||||
// accessors for parameter values
|
// accessors for parameter values
|
||||||
float get_default_speed() const { return _speed_max; }
|
float get_default_speed() const { return _speed_max; }
|
||||||
|
float get_default_accel() const { return _accel_max; }
|
||||||
|
float get_default_jerk() const { return _jerk_max; }
|
||||||
float get_radius() const { return _radius; }
|
float get_radius() const { return _radius; }
|
||||||
float get_pivot_rate() const { return _pivot.get_rate_max(); }
|
float get_pivot_rate() const { return _pivot.get_rate_max(); }
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user