AntennaTracker: 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 420f80db75
commit 98daf23d88
6 changed files with 11 additions and 15 deletions

View File

@ -451,13 +451,6 @@ MAV_RESULT GCS_MAVLINK_Tracker::handle_command_int_packet(const mavlink_command_
}
}
bool GCS_MAVLINK_Tracker::set_home_to_current_location(bool _lock) {
return tracker.set_home(AP::gps().location());
}
bool GCS_MAVLINK_Tracker::set_home(const Location& loc, bool _lock) {
return tracker.set_home(loc);
}
void GCS_MAVLINK_Tracker::handle_message(const mavlink_message_t &msg)
{
switch (msg.msgid) {
@ -584,7 +577,7 @@ void GCS_MAVLINK_Tracker::handle_message_mission_item(const mavlink_message_t &m
// check if this is the HOME wp
if (packet.seq == 0) {
if (!tracker.set_home(tell_command)) {
if (!tracker.set_home(tell_command, false)) {
result = MAV_MISSION_ERROR;
goto mission_failed;
}

View File

@ -27,9 +27,6 @@ protected:
return 0; // what if we have been picked up and carried somewhere?
}
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;
void send_pid_tuning() override;

View File

@ -92,7 +92,7 @@ void Tracker::one_second_loop()
// set home to current location
Location temp_loc;
if (ahrs.get_location(temp_loc)) {
if (!set_home(temp_loc)){
if (!set_home(temp_loc, false)) {
// fail silently
}
}

View File

@ -197,7 +197,8 @@ private:
void init_ardupilot() override;
bool get_home_eeprom(Location &loc) const;
bool set_home_eeprom(const Location &temp) WARN_IF_UNUSED;
bool set_home(const Location &temp) WARN_IF_UNUSED;
bool set_home_to_current_location(bool lock) override WARN_IF_UNUSED;
bool set_home(const Location &temp, bool lock) override WARN_IF_UNUSED;
void prepare_servos();
void set_mode(Mode &newmode, ModeReason reason);
bool set_mode(uint8_t new_mode, ModeReason reason) override;

View File

@ -51,7 +51,7 @@ void Tracker::update_GPS(void)
// Now have an initial GPS position
// use it as the HOME position in future startups
current_loc = gps.location();
IGNORE_RETURN(set_home(current_loc));
IGNORE_RETURN(set_home(current_loc, false));
ground_start_count = 0;
}
}

View File

@ -116,7 +116,12 @@ bool Tracker::set_home_eeprom(const Location &temp)
return true;
}
bool Tracker::set_home(const Location &temp)
bool Tracker::set_home_to_current_location(bool lock)
{
return set_home(AP::gps().location(), lock);
}
bool Tracker::set_home(const Location &temp, bool lock)
{
// check EKF origin has been set
Location ekf_origin;