CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutSign UpSign In
Ardupilot

Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.

GitHub Repository: Ardupilot/ardupilot
Path: blob/master/ArduPlane/commands.cpp
Views: 1798
1
/*
2
* logic for dealing with the current command in the mission and home location
3
*/
4
5
#include "Plane.h"
6
7
/*
8
* set_next_WP - sets the target location the vehicle should fly to
9
*/
10
void Plane::set_next_WP(const Location &loc)
11
{
12
if (auto_state.next_wp_crosstrack) {
13
// copy the current WP into the OldWP slot
14
prev_WP_loc = next_WP_loc;
15
auto_state.crosstrack = true;
16
} else {
17
// we should not try to cross-track for this waypoint
18
prev_WP_loc = current_loc;
19
// use cross-track for the next waypoint
20
auto_state.next_wp_crosstrack = true;
21
auto_state.crosstrack = false;
22
}
23
24
// Load the next_WP slot
25
// ---------------------
26
next_WP_loc = loc;
27
28
// if lat and lon is zero, then use current lat/lon
29
// this allows a mission to contain a "loiter on the spot"
30
// command
31
if (next_WP_loc.lat == 0 && next_WP_loc.lng == 0) {
32
next_WP_loc.lat = current_loc.lat;
33
next_WP_loc.lng = current_loc.lng;
34
// additionally treat zero altitude as current altitude
35
if (next_WP_loc.alt == 0) {
36
next_WP_loc.alt = current_loc.alt;
37
next_WP_loc.relative_alt = false;
38
next_WP_loc.terrain_alt = false;
39
}
40
}
41
42
// convert relative alt to absolute alt
43
if (next_WP_loc.relative_alt) {
44
next_WP_loc.relative_alt = false;
45
next_WP_loc.alt += home.alt;
46
}
47
48
// are we already past the waypoint? This happens when we jump
49
// waypoints, and it can cause us to skip a waypoint. If we are
50
// past the waypoint when we start on a leg, then use the current
51
// location as the previous waypoint, to prevent immediately
52
// considering the waypoint complete
53
if (current_loc.past_interval_finish_line(prev_WP_loc, next_WP_loc)) {
54
prev_WP_loc = current_loc;
55
}
56
57
// zero out our loiter vals to watch for missed waypoints
58
loiter_angle_reset();
59
60
setup_glide_slope();
61
setup_turn_angle();
62
63
// update plane.target_altitude straight away, or if we are too
64
// close to out loiter point we may decide we are at the correct
65
// altitude before updating it (this is based on scheduler table
66
// ordering, where we navigate() before we
67
// adjust_altitude_target(), and navigate() uses values updated in
68
// adjust_altitude_target()
69
adjust_altitude_target();
70
}
71
72
void Plane::set_guided_WP(const Location &loc)
73
{
74
if (aparm.loiter_radius < 0 || loc.loiter_ccw) {
75
loiter.direction = -1;
76
} else {
77
loiter.direction = 1;
78
}
79
80
// copy the current location into the OldWP slot
81
// ---------------------------------------
82
prev_WP_loc = current_loc;
83
84
// Load the next_WP slot
85
// ---------------------
86
next_WP_loc = loc;
87
88
// used to control FBW and limit the rate of climb
89
// -----------------------------------------------
90
set_target_altitude_current();
91
92
setup_glide_slope();
93
setup_turn_angle();
94
95
// disable crosstrack, head directly to the point
96
auto_state.crosstrack = false;
97
98
// reset loiter start time.
99
loiter.start_time_ms = 0;
100
101
// start in non-VTOL mode
102
auto_state.vtol_loiter = false;
103
104
loiter_angle_reset();
105
106
#if HAL_QUADPLANE_ENABLED
107
// cancel pending takeoff
108
quadplane.guided_takeoff = false;
109
#endif
110
}
111
112
/*
113
update home location from GPS
114
this is called as long as we have 3D lock and the arming switch is
115
not pushed
116
117
returns true if home is changed
118
*/
119
bool Plane::update_home()
120
{
121
if (hal.util->was_watchdog_armed()) {
122
return false;
123
}
124
if ((g2.home_reset_threshold == -1) ||
125
((g2.home_reset_threshold > 0) &&
126
(fabsf(barometer.get_altitude()) > g2.home_reset_threshold))) {
127
// don't auto-update if we have changed barometer altitude
128
// significantly. This allows us to cope with slow baro drift
129
// but not re-do home and the baro if we have changed height
130
// significantly
131
return false;
132
}
133
bool ret = false;
134
if (ahrs.home_is_set() && !ahrs.home_is_locked() && gps.status() >= AP_GPS::GPS_OK_FIX_3D) {
135
Location loc;
136
if (ahrs.get_location(loc)) {
137
// we take the altitude directly from the GPS as we are
138
// about to reset the baro calibration. We can't use AHRS
139
// altitude or we can end up perpetuating a bias in
140
// altitude, as AHRS alt depends on home alt, which means
141
// we would have a circular dependency
142
loc.alt = gps.location().alt;
143
ret = AP::ahrs().set_home(loc);
144
}
145
}
146
147
// even if home is not updated we do a baro reset to stop baro
148
// drift errors while disarmed
149
barometer.update_calibration();
150
ahrs.resetHeightDatum();
151
152
update_current_loc();
153
154
return ret;
155
}
156
157
bool Plane::set_home_persistently(const Location &loc)
158
{
159
if (hal.util->was_watchdog_armed()) {
160
return false;
161
}
162
if (!AP::ahrs().set_home(loc)) {
163
return false;
164
}
165
166
// Save Home to EEPROM
167
mission.write_home_to_storage();
168
169
return true;
170
}
171
172