AP_Vehicle: add get_circle_radius, set_circle_rate

This commit is contained in:
Randy Mackay 2021-08-24 20:11:13 +09:00 committed by Andrew Tridgell
parent 36f23fd498
commit b8a1662ce1

View File

@ -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