Skip to content

Commit

Permalink
AP_Vehicle: Added method to takeoff for use by external control
Browse files Browse the repository at this point in the history
  • Loading branch information
snktshrma committed Nov 17, 2024
1 parent 1a58f54 commit fcc932c
Showing 1 changed file with 2 additions and 1 deletion.
3 changes: 2 additions & 1 deletion libraries/AP_Vehicle/AP_Vehicle.h
Original file line number Diff line number Diff line change
Expand Up @@ -172,14 +172,15 @@ class AP_Vehicle : public AP_HAL::HAL::Callbacks {
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
#if AP_SCRIPTING_ENABLED
/*
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; }
Expand Down

0 comments on commit fcc932c

Please sign in to comment.