diff --git a/ArduPlane/ArduPlane.cpp b/ArduPlane/ArduPlane.cpp index 36bc4f5b53e091..02dcd401eb2dda 100644 --- a/ArduPlane/ArduPlane.cpp +++ b/ArduPlane/ArduPlane.cpp @@ -798,8 +798,8 @@ bool Plane::get_wp_crosstrack_error_m(float &xtrack_error) const return true; } -#if AP_SCRIPTING_ENABLED -// set target location (for use by scripting) +#if AP_SCRIPTING_ENABLED || AP_EXTERNAL_CONTROL_ENABLED +// set target location (for use by external control and scripting) bool Plane::set_target_location(const Location &target_loc) { Location loc{target_loc}; @@ -816,7 +816,9 @@ bool Plane::set_target_location(const Location &target_loc) plane.set_guided_WP(loc); return true; } +#endif //AP_SCRIPTING_ENABLED || AP_EXTERNAL_CONTROL_ENABLED +#if AP_SCRIPTING_ENABLED // set target location (for use by scripting) bool Plane::get_target_location(Location& target_loc) { diff --git a/ArduPlane/Plane.h b/ArduPlane/Plane.h index 66852d99d4d755..71936b61a4e8f8 100644 --- a/ArduPlane/Plane.h +++ b/ArduPlane/Plane.h @@ -1245,8 +1245,10 @@ class Plane : public AP_Vehicle { void failsafe_check(void); bool is_landing() const override; bool is_taking_off() const override; -#if AP_SCRIPTING_ENABLED +#if AP_SCRIPTING_ENABLED || AP_EXTERNAL_CONTROL_ENABLED bool set_target_location(const Location& target_loc) override; +#endif //AP_SCRIPTING_ENABLED || AP_EXTERNAL_CONTROL_ENABLED +#if AP_SCRIPTING_ENABLED bool get_target_location(Location& target_loc) override; bool update_target_location(const Location &old_loc, const Location &new_loc) override; bool set_velocity_match(const Vector2f &velocity) override;