ArduSub: move handling of DO_SET_HOME up to GCS_MAVLink base class

This commit is contained in:
Peter Barker 2024-04-03 21:40:31 +11:00 committed by Andrew Tridgell
parent 42ce0867ae
commit 89a9a0e6d1
3 changed files with 2 additions and 12 deletions

View File

@ -480,13 +480,6 @@ MAV_RESULT GCS_MAVLINK_Sub::handle_command_do_set_roi(const Location &roi_loc)
return MAV_RESULT_ACCEPTED;
}
bool GCS_MAVLINK_Sub::set_home_to_current_location(bool _lock) {
return sub.set_home_to_current_location(_lock);
}
bool GCS_MAVLINK_Sub::set_home(const Location& loc, bool _lock) {
return sub.set_home(loc, _lock);
}
MAV_RESULT GCS_MAVLINK_Sub::handle_command_int_packet(const mavlink_command_int_t &packet, const mavlink_message_t &msg)
{
switch(packet.command) {

View File

@ -29,9 +29,6 @@ protected:
int32_t global_position_int_alt() const override;
int32_t global_position_int_relative_alt() const 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_banner() override;
void send_nav_controller_output() const override;

View File

@ -423,8 +423,8 @@ private:
void userhook_SuperSlowLoop();
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);
float get_alt_rel() const WARN_IF_UNUSED;
float get_alt_msl() const WARN_IF_UNUSED;