Rover: 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 6477effa3f
commit 2b76f66ebc
3 changed files with 2 additions and 12 deletions

View File

@ -656,14 +656,6 @@ MAV_RESULT GCS_MAVLINK_Rover::_handle_command_preflight_calibration(const mavlin
return GCS_MAVLINK::_handle_command_preflight_calibration(packet, msg);
}
bool GCS_MAVLINK_Rover::set_home_to_current_location(bool _lock) {
return rover.set_home_to_current_location(_lock);
}
bool GCS_MAVLINK_Rover::set_home(const Location& loc, bool _lock) {
return rover.set_home(loc, _lock);
}
MAV_RESULT GCS_MAVLINK_Rover::handle_command_int_packet(const mavlink_command_int_t &packet, const mavlink_message_t &msg)
{
switch (packet.command) {

View File

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

View File

@ -295,8 +295,8 @@ private:
bool is_balancebot() const;
// commands.cpp
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;
void update_home();
// crash_check.cpp