mirror of https://github.com/ArduPilot/ardupilot
AP_Vehicle: add start_takeoff and set_target_velocity_NED for use in scripting
This commit is contained in:
parent
db2229f684
commit
849adcd678
|
@ -163,8 +163,12 @@ public:
|
|||
return AP_HAL::millis() - _last_flying_ms;
|
||||
}
|
||||
|
||||
// set target location (for use by scripting)
|
||||
/*
|
||||
methods to control vehicle for use by scripting
|
||||
*/
|
||||
virtual bool start_takeoff(float alt) { return false; }
|
||||
virtual bool set_target_location(const Location& target_loc) { return false; }
|
||||
virtual bool set_target_velocity_NED(const Vector3f& vel_ned) { return false; }
|
||||
|
||||
// get target location (for use by scripting)
|
||||
virtual bool get_target_location(Location& target_loc) { return false; }
|
||||
|
|
Loading…
Reference in New Issue