forked from ArduPilot/ardupilot
-
Notifications
You must be signed in to change notification settings - Fork 0
/
commands.cpp
116 lines (102 loc) · 3.24 KB
/
commands.cpp
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
#include "Copter.h"
// checks if we should update ahrs/RTL home position from the EKF
void Copter::update_home_from_EKF()
{
// exit immediately if home already set
if (ahrs.home_is_set()) {
return;
}
// special logic if home is set in-flight
if (motors->armed()) {
set_home_to_current_location_inflight();
} else {
// move home to current ekf location (this will set home_state to HOME_SET)
if (!set_home_to_current_location(false)) {
// ignore failure
}
}
}
// set_home_to_current_location_inflight - set home to current GPS location (horizontally) and EKF origin vertically
void Copter::set_home_to_current_location_inflight() {
// get current location from EKF
Location temp_loc;
if (inertial_nav.get_location(temp_loc)) {
const struct Location &ekf_origin = inertial_nav.get_origin();
temp_loc.alt = ekf_origin.alt;
if (!set_home(temp_loc, false)) {
return;
}
// we have successfully set AHRS home, set it for SmartRTL
#if MODE_SMARTRTL_ENABLED == ENABLED
g2.smart_rtl.set_home(true);
#endif
}
}
// set_home_to_current_location - set home to current GPS location
bool Copter::set_home_to_current_location(bool lock) {
// get current location from EKF
Location temp_loc;
if (inertial_nav.get_location(temp_loc)) {
if (!set_home(temp_loc, lock)) {
return false;
}
// we have successfully set AHRS home, set it for SmartRTL
#if MODE_SMARTRTL_ENABLED == ENABLED
g2.smart_rtl.set_home(true);
#endif
return true;
}
return false;
}
// set_home - sets ahrs home (used for RTL) to specified location
// initialises inertial nav and compass on first call
// returns true if home location set successfully
bool Copter::set_home(const Location& loc, bool lock)
{
// check EKF origin has been set
Location ekf_origin;
if (!ahrs.get_origin(ekf_origin)) {
return false;
}
// check home is close to EKF origin
if (far_from_EKF_origin(loc)) {
return false;
}
const bool home_was_set = ahrs.home_is_set();
// set ahrs home (used for RTL)
if (!ahrs.set_home(loc)) {
return false;
}
// init inav and compass declination
if (!home_was_set) {
// record home is set
Log_Write_Event(DATA_SET_HOME);
#if MODE_AUTO_ENABLED == ENABLED
// log new home position which mission library will pull from ahrs
if (should_log(MASK_LOG_CMD)) {
AP_Mission::Mission_Command temp_cmd;
if (mode_auto.mission.read_cmd_from_storage(0, temp_cmd)) {
logger.Write_Mission_Cmd(mode_auto.mission, temp_cmd);
}
}
#endif
}
// lock home position
if (lock) {
ahrs.lock_home();
}
// return success
return true;
}
// far_from_EKF_origin - checks if a location is too far from the EKF origin
// returns true if too far
bool Copter::far_from_EKF_origin(const Location& loc)
{
// check distance to EKF origin
const struct Location &ekf_origin = inertial_nav.get_origin();
if (ekf_origin.get_distance(loc) > EKF_ORIGIN_MAX_DIST_M) {
return true;
}
// close enough to origin
return false;
}