mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 02:18:29 -04:00
AP_Vehicle: added update_target_location()
This commit is contained in:
parent
8df4b1adda
commit
32e071eb08
@ -208,6 +208,7 @@ public:
|
||||
|
||||
// get target location (for use by scripting)
|
||||
virtual bool get_target_location(Location& target_loc) { return false; }
|
||||
virtual bool update_target_location(const Location &old_loc, const Location &new_loc) { return false; }
|
||||
|
||||
// circle mode controls (only used by scripting with Copter)
|
||||
virtual bool get_circle_radius(float &radius_m) { return false; }
|
||||
@ -223,6 +224,9 @@ public:
|
||||
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) {}
|
||||
|
||||
// allow for VTOL velocity matching of a target
|
||||
virtual bool set_velocity_match(const Vector2f &velocity) { return false; }
|
||||
|
||||
|
||||
// control outputs enumeration
|
||||
enum class ControlOutput {
|
||||
|
Loading…
Reference in New Issue
Block a user