AP_Vehicle: add set_desired_speed for use in scripting

This commit is contained in:
Yuri 2022-06-30 13:42:18 -05:00 committed by Randy Mackay
parent 4fc426fb3f
commit 9f076f2c19

View File

@ -221,6 +221,9 @@ public:
// 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; }
// set auto mode speed in meters/sec (for use by scripting with Copter/Rover)
virtual bool set_desired_speed(float speed) { return false; }
// support for NAV_SCRIPT_TIME mission command
virtual bool nav_script_time(uint16_t &id, uint8_t &cmd, float &arg1, float &arg2) { return false; }
virtual void nav_script_time_done(uint16_t id) {}