forked from ArduPilot/ardupilot
-
Notifications
You must be signed in to change notification settings - Fork 0
/
commands.cpp
68 lines (57 loc) · 1.7 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
#include "Rover.h"
// set ahrs home to current location from inertial-nav location
bool Rover::set_home_to_current_location(bool lock)
{
Location temp_loc;
if (ahrs.have_inertial_nav() && ahrs.get_location(temp_loc)) {
if (!set_home(temp_loc, lock)) {
return false;
}
// we have successfully set AHRS home, set it for SmartRTL
g2.smart_rtl.set_home(true);
return true;
}
return false;
}
// sets ahrs home to specified location
// returns true if home location set successfully
bool Rover::set_home(const Location& loc, bool lock)
{
// set ahrs home
if (!ahrs.set_home(loc)) {
return false;
}
// lock home position
if (lock) {
ahrs.lock_home();
}
// Save Home to EEPROM
mode_auto.mission.write_home_to_storage();
// send text of home position to ground stations
gcs().send_text(MAV_SEVERITY_INFO, "Set HOME to %.6f %.6f at %.2fm",
static_cast<double>(loc.lat * 1.0e-7f),
static_cast<double>(loc.lng * 1.0e-7f),
static_cast<double>(loc.alt * 0.01f));
// return success
return true;
}
// called periodically while disarmed to update our home position to
// our current location
void Rover::update_home()
{
if (ahrs.home_is_locked()) {
// we've been explicitly told our home location
return;
}
Location loc{};
if (!ahrs.get_location(loc)) {
return;
}
barometer.update_calibration();
if (ahrs.home_is_set() &&
loc.get_distance(ahrs.get_home()) < DISTANCE_HOME_MINCHANGE) {
// insufficiently moved from current home - don't change it
return;
}
IGNORE_RETURN(ahrs.set_home(loc));
}