mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AP_Vehicle: extend nav_scripting to all modes
This commit is contained in:
parent
b262e9ffbf
commit
c3950aed2f
@ -204,6 +204,7 @@ public:
|
|||||||
// command throttle percentage and roll, pitch, yaw target
|
// command throttle percentage and roll, pitch, yaw target
|
||||||
// rates. For use with scripting controllers
|
// rates. For use with scripting controllers
|
||||||
virtual bool set_target_throttle_rate_rpy(float throttle_pct, float roll_rate_dps, float pitch_rate_dps, float yaw_rate_dps) { return false; }
|
virtual bool set_target_throttle_rate_rpy(float throttle_pct, float roll_rate_dps, float pitch_rate_dps, float yaw_rate_dps) { return false; }
|
||||||
|
virtual bool nav_scripting_enable(uint8_t mode) {return false;}
|
||||||
|
|
||||||
// get target location (for use by scripting)
|
// get target location (for use by scripting)
|
||||||
virtual bool get_target_location(Location& target_loc) { return false; }
|
virtual bool get_target_location(Location& target_loc) { return false; }
|
||||||
|
Loading…
Reference in New Issue
Block a user