AP_Vehicle: add get_steering_and_throttle

This commit is contained in:
Randy Mackay 2023-05-30 19:58:30 +09:00 committed by Andrew Tridgell
parent 57b54a4263
commit 1fd1a7f881
1 changed files with 2 additions and 1 deletions

View File

@ -175,8 +175,9 @@ public:
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)
// get or 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; }
virtual bool get_steering_and_throttle(float& steering, float& throttle) { return false; }
// set turn rate in deg/sec and speed in meters/sec (for use by scripting with Rover)
virtual bool set_desired_turn_rate_and_speed(float turn_rate, float speed) { return false; }