mirror of https://github.com/ArduPilot/ardupilot
AC_WPNav: add getter for wp_radius_cm
This commit is contained in:
parent
0a41cdaa24
commit
7ec7b478f0
|
@ -140,6 +140,8 @@ public:
|
|||
return get_wp_distance_to_destination() < _wp_radius_cm;
|
||||
}
|
||||
|
||||
float get_wp_radius_cm() const { return _wp_radius_cm; }
|
||||
|
||||
/// update_wpnav - run the wp controller - should be called at 100hz or higher
|
||||
virtual bool update_wpnav();
|
||||
|
||||
|
|
Loading…
Reference in New Issue