mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-07 08:23:56 -04:00
AP_Vehicle: Added method to takeoff for use by external control
This commit is contained in:
parent
e49c65d38e
commit
cff3f81e0c
@ -172,6 +172,8 @@ public:
|
||||
virtual bool is_crashed() const;
|
||||
|
||||
#if AP_SCRIPTING_ENABLED || AP_EXTERNAL_CONTROL_ENABLED
|
||||
// Method to takeoff for use by external control
|
||||
virtual bool start_takeoff(const float alt) { return false; }
|
||||
// Method to control vehicle position for use by external control
|
||||
virtual bool set_target_location(const Location& target_loc) { return false; }
|
||||
#endif // AP_SCRIPTING_ENABLED || AP_EXTERNAL_CONTROL_ENABLED
|
||||
@ -179,7 +181,6 @@ public:
|
||||
/*
|
||||
methods to control vehicle for use by scripting
|
||||
*/
|
||||
virtual bool start_takeoff(float alt) { return false; }
|
||||
virtual bool set_target_pos_NED(const Vector3f& target_pos, bool use_yaw, float yaw_deg, bool use_yaw_rate, float yaw_rate_degs, bool yaw_relative, bool terrain_alt) { return false; }
|
||||
virtual bool set_target_posvel_NED(const Vector3f& target_pos, const Vector3f& target_vel) { return false; }
|
||||
virtual bool set_target_posvelaccel_NED(const Vector3f& target_pos, const Vector3f& target_vel, const Vector3f& target_accel, bool use_yaw, float yaw_deg, bool use_yaw_rate, float yaw_rate_degs, bool yaw_relative) { return false; }
|
||||
|
Loading…
Reference in New Issue
Block a user