From 1f63a1a63c4af45272edc7ca8483c591022ee77a Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Tue, 24 Aug 2021 20:11:13 +0900 Subject: [PATCH] AP_Vehicle: add get_circle_radius, set_circle_rate --- libraries/AP_Vehicle/AP_Vehicle.h | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/libraries/AP_Vehicle/AP_Vehicle.h b/libraries/AP_Vehicle/AP_Vehicle.h index 23b2a55f28..7ac298be56 100644 --- a/libraries/AP_Vehicle/AP_Vehicle.h +++ b/libraries/AP_Vehicle/AP_Vehicle.h @@ -191,6 +191,10 @@ public: // get target location (for use by scripting) virtual bool get_target_location(Location& target_loc) { return false; } + // circle mode controls (only used by scripting with Copter) + virtual bool get_circle_radius(float &radius_m) { return false; } + virtual bool set_circle_rate(float rate_dps) { return false; } + // set steering and throttle (-1 to +1) (for use by scripting with Rover) virtual bool set_steering_and_throttle(float steering, float throttle) { return false; } #endif // ENABLE_SCRIPTING