ArduCopter: 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 98daf23d88
commit 5d41125b49
3 changed files with 2 additions and 11 deletions

View File

@ -739,8 +739,8 @@ private:
// commands.cpp
void update_home_from_EKF();
void set_home_to_current_location_inflight();
bool set_home_to_current_location(bool lock) WARN_IF_UNUSED;
bool set_home(const Location& loc, bool lock) 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;
bool far_from_EKF_origin(const Location& loc);
// compassmot.cpp

View File

@ -711,13 +711,6 @@ MAV_RESULT GCS_MAVLINK_Copter::handle_preflight_reboot(const mavlink_command_int
return GCS_MAVLINK::handle_preflight_reboot(packet, msg);
}
bool GCS_MAVLINK_Copter::set_home_to_current_location(bool _lock) {
return copter.set_home_to_current_location(_lock);
}
bool GCS_MAVLINK_Copter::set_home(const Location& loc, bool _lock) {
return copter.set_home(loc, _lock);
}
MAV_RESULT GCS_MAVLINK_Copter::handle_command_int_do_reposition(const mavlink_command_int_t &packet)
{
#if MODE_GUIDED_ENABLED == ENABLED

View File

@ -48,8 +48,6 @@ protected:
void handle_landing_target(const mavlink_landing_target_t &packet, uint32_t timestamp_ms) override;
bool set_home_to_current_location(bool lock) override WARN_IF_UNUSED;
bool set_home(const Location& loc, bool lock) override WARN_IF_UNUSED;
void send_nav_controller_output() const override;
uint64_t capabilities() const override;