mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AP_Navigation: added a turn_distance() method with turn_angle
This commit is contained in:
parent
a72b362c1f
commit
7a6186f7e6
@ -51,9 +51,14 @@ public:
|
|||||||
|
|
||||||
// return the distance in meters at which a turn should commence
|
// return the distance in meters at which a turn should commence
|
||||||
// to allow the vehicle to neatly move to the next track in the
|
// to allow the vehicle to neatly move to the next track in the
|
||||||
// mission when approaching a waypoint
|
// mission when approaching a waypoint. Assumes 90 degree turn
|
||||||
virtual float turn_distance(float wp_radius) const = 0;
|
virtual float turn_distance(float wp_radius) const = 0;
|
||||||
|
|
||||||
|
// return the distance in meters at which a turn should commence
|
||||||
|
// to allow the vehicle to neatly move to the next track in the
|
||||||
|
// mission when approaching a waypoint
|
||||||
|
virtual float turn_distance(float wp_radius, float turn_angle) 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
Block a user