ArduPlane: Make set position tgt depend on ext ctrl

* Set position target used to just be used in scripting, now it's used
  by DDS in external control

Signed-off-by: Ryan Friedman <ryanfriedman5410+github@gmail.com>
This commit is contained in:
Ryan Friedman 2023-12-12 21:32:43 -07:00 committed by Peter Hall
parent faa8ac0085
commit 2e393bbbc6
2 changed files with 7 additions and 3 deletions

View File

@ -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)
{

View File

@ -1245,8 +1245,10 @@ public:
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;