ArduPlane: move handling of DO_SET_HOME up to GCS_MAVLink base class

This commit is contained in:
Peter Barker 2024-04-03 21:40:30 +11:00 committed by Andrew Tridgell
parent 5d41125b49
commit 42ce0867ae
3 changed files with 11 additions and 11 deletions

View File

@ -781,25 +781,25 @@ void GCS_MAVLINK_Plane::packetReceived(const mavlink_status_t &status,
} }
bool GCS_MAVLINK_Plane::set_home_to_current_location(bool _lock) bool Plane::set_home_to_current_location(bool _lock)
{ {
if (!plane.set_home_persistently(AP::gps().location())) { if (!set_home_persistently(AP::gps().location())) {
return false; return false;
} }
if (_lock) { if (_lock) {
AP::ahrs().lock_home(); AP::ahrs().lock_home();
} }
if ((plane.control_mode == &plane.mode_rtl) if ((control_mode == &mode_rtl)
#if HAL_QUADPLANE_ENABLED #if HAL_QUADPLANE_ENABLED
|| (plane.control_mode == &plane.mode_qrtl) || (control_mode == &mode_qrtl)
#endif #endif
) { ) {
// if in RTL head to the updated home location // if in RTL head to the updated home location
plane.control_mode->enter(); control_mode->enter();
} }
return true; return true;
} }
bool GCS_MAVLINK_Plane::set_home(const Location& loc, bool _lock) bool Plane::set_home(const Location& loc, bool _lock)
{ {
if (!AP::ahrs().set_home(loc)) { if (!AP::ahrs().set_home(loc)) {
return false; return false;
@ -807,13 +807,13 @@ bool GCS_MAVLINK_Plane::set_home(const Location& loc, bool _lock)
if (_lock) { if (_lock) {
AP::ahrs().lock_home(); AP::ahrs().lock_home();
} }
if ((plane.control_mode == &plane.mode_rtl) if ((control_mode == &mode_rtl)
#if HAL_QUADPLANE_ENABLED #if HAL_QUADPLANE_ENABLED
|| (plane.control_mode == &plane.mode_qrtl) || (control_mode == &mode_qrtl)
#endif #endif
) { ) {
// if in RTL head to the updated home location // if in RTL head to the updated home location
plane.control_mode->enter(); control_mode->enter();
} }
return true; return true;
} }

View File

@ -42,8 +42,6 @@ protected:
bool persist_streamrates() const override { return true; } bool persist_streamrates() const override { return true; }
bool set_home_to_current_location(bool lock) override WARN_IF_UNUSED;
bool set_home(const Location& loc, bool lock) override WARN_IF_UNUSED;
uint64_t capabilities() const override; uint64_t capabilities() const override;
void send_nav_controller_output() const override; void send_nav_controller_output() const override;

View File

@ -986,6 +986,8 @@ private:
// set home location and store it persistently: // set home location and store it persistently:
bool set_home_persistently(const Location &loc) WARN_IF_UNUSED; bool set_home_persistently(const Location &loc) WARN_IF_UNUSED;
bool set_home_to_current_location(bool lock) override WARN_IF_UNUSED;
bool set_home(const Location& loc, bool lock) override WARN_IF_UNUSED;
// control_modes.cpp // control_modes.cpp
void read_control_switch(); void read_control_switch();