Skip to content

Commit 1184c5e

Browse files
Sub: simplify setting-home-from-ekf-origin logic
1 parent 11149f9 commit 1184c5e

File tree

2 files changed

+2
-24
lines changed

2 files changed

+2
-24
lines changed

ArduSub/Sub.h

Lines changed: 0 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -445,7 +445,6 @@ class Sub : public AP_Vehicle {
445445
void userhook_SlowLoop();
446446
void userhook_SuperSlowLoop();
447447
void update_home_from_EKF();
448-
void set_home_to_current_location_inflight();
449448
bool set_home_to_current_location(bool lock) override WARN_IF_UNUSED;
450449
bool set_home(const Location& loc, bool lock) override WARN_IF_UNUSED;
451450
float get_alt_rel() const WARN_IF_UNUSED;

ArduSub/commands.cpp

Lines changed: 2 additions & 23 deletions
Original file line numberDiff line numberDiff line change
@@ -7,29 +7,8 @@ void Sub::update_home_from_EKF()
77
if (ahrs.home_is_set()) {
88
return;
99
}
10-
11-
// special logic if home is set in-flight
12-
if (motors.armed()) {
13-
set_home_to_current_location_inflight();
14-
} else {
15-
// move home to current ekf location (this will set home_state to HOME_SET)
16-
if (!set_home_to_current_location(false)) {
17-
// ignore this failure
18-
}
19-
}
20-
}
21-
22-
// set_home_to_current_location_inflight - set home to current GPS location (horizontally) and EKF origin vertically
23-
void Sub::set_home_to_current_location_inflight()
24-
{
25-
// get current location from EKF
26-
Location temp_loc;
27-
Location ekf_origin;
28-
if (ahrs.get_location(temp_loc) && ahrs.get_origin(ekf_origin)) {
29-
temp_loc.copy_alt_from(ekf_origin);
30-
if (!set_home(temp_loc, false)) {
31-
// ignore this failure
32-
}
10+
if (!set_home_to_current_location(false)) {
11+
// ignore this failure
3312
}
3413
}
3514

0 commit comments

Comments
 (0)