AP_Vehicle: added set_rudder_offset()

This commit is contained in:
Andrew Tridgell 2022-12-23 08:21:28 +11:00
parent 8d12ca567b
commit 63e5261406
1 changed files with 1 additions and 0 deletions

View File

@ -159,6 +159,7 @@ public:
// command throttle percentage and roll, pitch, yaw target
// rates. For use with scripting controllers
virtual void set_target_throttle_rate_rpy(float throttle_pct, float roll_rate_dps, float pitch_rate_dps, float yaw_rate_dps) {}
virtual void set_rudder_offset(float rudder_pct, bool run_yaw_rate_controller) {}
virtual bool nav_scripting_enable(uint8_t mode) {return false;}
// get target location (for use by scripting)