mirror of https://github.com/ArduPilot/ardupilot
AP_Navigation: Add a loiter radius interface
This commit is contained in:
parent
336b4a64d7
commit
2ac32ad204
|
@ -56,6 +56,10 @@ public:
|
||||||
// mission when approaching a waypoint
|
// mission when approaching a waypoint
|
||||||
virtual float turn_distance(float wp_radius, float turn_angle) const = 0;
|
virtual float turn_distance(float wp_radius, float turn_angle) const = 0;
|
||||||
|
|
||||||
|
// return the target loiter radius for the current location that
|
||||||
|
// will not cause excessive airframe loading
|
||||||
|
virtual float loiter_radius(const float radius) const = 0;
|
||||||
|
|
||||||
// update the internal state of the navigation controller, given
|
// update the internal state of the navigation controller, given
|
||||||
// the previous and next waypoints. This is the step function for
|
// the previous and next waypoints. This is the step function for
|
||||||
// navigation control for path following between two points. This
|
// navigation control for path following between two points. This
|
||||||
|
|
Loading…
Reference in New Issue