mirror of https://github.com/ArduPilot/ardupilot
ArduCopter: Enabled external control for takeoff
Co-authored-by: Ryan Friedman <25047695+Ryanf55@users.noreply.github.com>
This commit is contained in:
parent
5398f1a499
commit
20aeae1a09
|
@ -285,13 +285,9 @@ bool Copter::set_target_location(const Location& target_loc)
|
|||
|
||||
return mode_guided.set_destination(target_loc);
|
||||
}
|
||||
#endif //MODE_GUIDED_ENABLED
|
||||
#endif //AP_SCRIPTING_ENABLED || AP_EXTERNAL_CONTROL_ENABLED
|
||||
|
||||
#if AP_SCRIPTING_ENABLED
|
||||
#if MODE_GUIDED_ENABLED
|
||||
// start takeoff to given altitude (for use by scripting)
|
||||
bool Copter::start_takeoff(float alt)
|
||||
bool Copter::start_takeoff(const float alt)
|
||||
{
|
||||
// exit if vehicle is not in Guided mode or Auto-Guided mode
|
||||
if (!flightmode->in_guided_mode()) {
|
||||
|
@ -304,7 +300,11 @@ bool Copter::start_takeoff(float alt)
|
|||
}
|
||||
return false;
|
||||
}
|
||||
#endif //MODE_GUIDED_ENABLED
|
||||
#endif //AP_SCRIPTING_ENABLED || AP_EXTERNAL_CONTROL_ENABLED
|
||||
|
||||
#if AP_SCRIPTING_ENABLED
|
||||
#if MODE_GUIDED_ENABLED
|
||||
// set target position (for use by scripting)
|
||||
bool Copter::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)
|
||||
{
|
||||
|
|
|
@ -668,12 +668,12 @@ private:
|
|||
#if AP_SCRIPTING_ENABLED || AP_EXTERNAL_CONTROL_ENABLED
|
||||
#if MODE_GUIDED_ENABLED
|
||||
bool set_target_location(const Location& target_loc) override;
|
||||
bool start_takeoff(const float alt) override;
|
||||
#endif // MODE_GUIDED_ENABLED
|
||||
#endif // AP_SCRIPTING_ENABLED || AP_EXTERNAL_CONTROL_ENABLED
|
||||
|
||||
#if AP_SCRIPTING_ENABLED
|
||||
#if MODE_GUIDED_ENABLED
|
||||
bool start_takeoff(float alt) override;
|
||||
bool get_target_location(Location& target_loc) override;
|
||||
bool update_target_location(const Location &old_loc, const Location &new_loc) override;
|
||||
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) override;
|
||||
|
|
Loading…
Reference in New Issue