mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-24 17:48:35 -04:00
AR_WPNav: make get_stopping_location public
This commit is contained in:
parent
e28d56f63a
commit
b6efcbcf3b
@ -81,6 +81,10 @@ public:
|
||||
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
|
||||
// returns true on success, false on failure
|
||||
bool get_stopping_location(Location& stopping_loc) WARN_IF_UNUSED;
|
||||
|
||||
// parameter var table
|
||||
static const struct AP_Param::GroupInfo var_info[];
|
||||
|
||||
@ -101,10 +105,6 @@ private:
|
||||
// have been updated: _wp_bearing_cd, _cross_track_error, _distance_to_destination
|
||||
void update_desired_speed(float dt);
|
||||
|
||||
// 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;
|
||||
|
||||
// returns true if vehicle should pivot turn at next waypoint
|
||||
bool use_pivot_steering_at_next_WP(float yaw_error_cd) const;
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user