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/mode.cpp
Views: 1798
1
#include "Plane.h"
2
3
Mode::Mode() :
4
unused_integer{17},
5
#if HAL_QUADPLANE_ENABLED
6
pos_control(plane.quadplane.pos_control),
7
attitude_control(plane.quadplane.attitude_control),
8
loiter_nav(plane.quadplane.loiter_nav),
9
quadplane(plane.quadplane),
10
poscontrol(plane.quadplane.poscontrol),
11
#endif
12
ahrs(plane.ahrs)
13
{
14
}
15
16
void Mode::exit()
17
{
18
// call sub-classes exit
19
_exit();
20
// stop autotuning if not AUTOTUNE mode
21
if (plane.control_mode != &plane.mode_autotune){
22
plane.autotune_restore();
23
}
24
25
}
26
27
bool Mode::enter()
28
{
29
#if AP_SCRIPTING_ENABLED
30
// reset nav_scripting.enabled
31
plane.nav_scripting.enabled = false;
32
#endif
33
34
// cancel inverted flight
35
plane.auto_state.inverted_flight = false;
36
37
// cancel waiting for rudder neutral
38
plane.takeoff_state.waiting_for_rudder_neutral = false;
39
40
// don't cross-track when starting a mission
41
plane.auto_state.next_wp_crosstrack = false;
42
43
// reset landing check
44
plane.auto_state.checked_for_autoland = false;
45
46
// zero locked course
47
plane.steer_state.locked_course_err = 0;
48
plane.steer_state.locked_course = false;
49
50
// reset crash detection
51
plane.crash_state.is_crashed = false;
52
plane.crash_state.impact_detected = false;
53
54
// reset external attitude guidance
55
plane.guided_state.last_forced_rpy_ms.zero();
56
plane.guided_state.last_forced_throttle_ms = 0;
57
58
#if AP_PLANE_OFFBOARD_GUIDED_SLEW_ENABLED
59
plane.guided_state.target_heading = -4; // radians here are in range -3.14 to 3.14, so a default value needs to be outside that range
60
plane.guided_state.target_heading_type = GUIDED_HEADING_NONE;
61
plane.guided_state.target_airspeed_cm = -1; // same as above, although an airspeed of -1 is rare on plane.
62
plane.guided_state.target_alt_time_ms = 0;
63
plane.guided_state.target_location.set_alt_cm(-1, Location::AltFrame::ABSOLUTE);
64
#endif
65
66
#if AP_CAMERA_ENABLED
67
plane.camera.set_is_auto_mode(this == &plane.mode_auto);
68
#endif
69
70
// zero initial pitch and highest airspeed on mode change
71
plane.auto_state.highest_airspeed = 0;
72
plane.auto_state.initial_pitch_cd = ahrs.pitch_sensor;
73
74
// disable taildrag takeoff on mode change
75
plane.auto_state.fbwa_tdrag_takeoff_mode = false;
76
77
// start with previous WP at current location
78
plane.prev_WP_loc = plane.current_loc;
79
80
// new mode means new loiter
81
plane.loiter.start_time_ms = 0;
82
83
// record time of mode change
84
plane.last_mode_change_ms = AP_HAL::millis();
85
86
// set VTOL auto state
87
plane.auto_state.vtol_mode = is_vtol_mode();
88
plane.auto_state.vtol_loiter = false;
89
90
// initialize speed variable used in AUTO and GUIDED for DO_CHANGE_SPEED commands
91
plane.new_airspeed_cm = -1;
92
93
// clear postponed long failsafe if mode change (from GCS) occurs before recall of long failsafe
94
plane.long_failsafe_pending = false;
95
96
#if HAL_QUADPLANE_ENABLED
97
quadplane.mode_enter();
98
#endif
99
100
#if AP_TERRAIN_AVAILABLE
101
plane.target_altitude.terrain_following_pending = false;
102
#endif
103
104
// disable auto mode servo idle during altitude wait command
105
plane.auto_state.idle_mode = false;
106
107
bool enter_result = _enter();
108
109
if (enter_result) {
110
// -------------------
111
// these must be done AFTER _enter() because they use the results to set more flags
112
113
// start with throttle suppressed in auto_throttle modes
114
plane.throttle_suppressed = does_auto_throttle();
115
#if HAL_ADSB_ENABLED
116
plane.adsb.set_is_auto_mode(does_auto_navigation());
117
#endif
118
119
// set the nav controller stale AFTER _enter() so that we can check if we're currently in a loiter during the mode change
120
plane.nav_controller->set_data_is_stale();
121
122
// reset steering integrator on mode change
123
plane.steerController.reset_I();
124
125
// update RC failsafe, as mode change may have necessitated changing the failsafe throttle
126
plane.control_failsafe();
127
128
#if AP_FENCE_ENABLED
129
// pilot requested flight mode change during a fence breach indicates pilot is attempting to manually recover
130
// this flight mode change could be automatic (i.e. fence, battery, GPS or GCS failsafe)
131
// but it should be harmless to disable the fence temporarily in these situations as well
132
plane.fence.manual_recovery_start();
133
#endif
134
//reset mission if in landing sequence, disarmed, not flying, and have changed to a non-autothrottle mode to clear prearm
135
if (plane.mission.get_in_landing_sequence_flag() &&
136
!plane.is_flying() && !plane.arming.is_armed_and_safety_off() &&
137
!plane.control_mode->does_auto_navigation()) {
138
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "In landing sequence: mission reset");
139
plane.mission.reset();
140
}
141
142
// Make sure the flight stage is correct for the new mode
143
plane.update_flight_stage();
144
145
// reset landing state
146
plane.landing.reset();
147
148
149
#if HAL_QUADPLANE_ENABLED
150
if (quadplane.enabled()) {
151
float aspeed;
152
bool have_airspeed = quadplane.ahrs.airspeed_estimate(aspeed);
153
quadplane.assisted_flight = quadplane.assist.should_assist(aspeed, have_airspeed);
154
}
155
#endif
156
}
157
158
return enter_result;
159
}
160
161
bool Mode::is_vtol_man_throttle() const
162
{
163
#if HAL_QUADPLANE_ENABLED
164
if (plane.quadplane.tailsitter.is_in_fw_flight() &&
165
plane.quadplane.assisted_flight) {
166
// We are a tailsitter that has fully transitioned to Q-assisted forward flight.
167
// In this case the forward throttle directly drives the vertical throttle so
168
// set vertical throttle state to match the forward throttle state. Confusingly the booleans are inverted,
169
// forward throttle uses 'does_auto_throttle' whereas vertical uses 'is_vtol_man_throttle'.
170
return !does_auto_throttle();
171
}
172
#endif
173
return false;
174
}
175
176
void Mode::update_target_altitude()
177
{
178
Location target_location;
179
180
if (plane.landing.is_flaring()) {
181
// during a landing flare, use TECS_LAND_SINK as a target sink
182
// rate, and ignores the target altitude
183
plane.set_target_altitude_location(plane.next_WP_loc);
184
} else if (plane.landing.is_on_approach()) {
185
plane.landing.setup_landing_glide_slope(plane.prev_WP_loc, plane.next_WP_loc, plane.current_loc, plane.target_altitude.offset_cm);
186
#if AP_RANGEFINDER_ENABLED
187
plane.landing.adjust_landing_slope_for_rangefinder_bump(plane.rangefinder_state, plane.prev_WP_loc, plane.next_WP_loc, plane.current_loc, plane.auto_state.wp_distance, plane.target_altitude.offset_cm);
188
#endif
189
} else if (plane.landing.get_target_altitude_location(target_location)) {
190
plane.set_target_altitude_location(target_location);
191
#if HAL_SOARING_ENABLED
192
} else if (plane.g2.soaring_controller.is_active() && plane.g2.soaring_controller.get_throttle_suppressed()) {
193
// Reset target alt to current alt, to prevent large altitude errors when gliding.
194
plane.set_target_altitude_location(plane.current_loc);
195
plane.reset_offset_altitude();
196
#endif
197
} else if (plane.reached_loiter_target()) {
198
// once we reach a loiter target then lock to the final
199
// altitude target
200
plane.set_target_altitude_location(plane.next_WP_loc);
201
} else if (plane.target_altitude.offset_cm != 0 &&
202
!plane.current_loc.past_interval_finish_line(plane.prev_WP_loc, plane.next_WP_loc)) {
203
// control climb/descent rate
204
plane.set_target_altitude_proportion(plane.next_WP_loc, 1.0f-plane.auto_state.wp_proportion);
205
206
// stay within the range of the start and end locations in altitude
207
plane.constrain_target_altitude_location(plane.next_WP_loc, plane.prev_WP_loc);
208
} else {
209
plane.set_target_altitude_location(plane.next_WP_loc);
210
}
211
}
212
213
// returns true if the vehicle can be armed in this mode
214
bool Mode::pre_arm_checks(size_t buflen, char *buffer) const
215
{
216
if (!_pre_arm_checks(buflen, buffer)) {
217
if (strlen(buffer) == 0) {
218
// If no message is provided add a generic one
219
hal.util->snprintf(buffer, buflen, "mode not armable");
220
}
221
return false;
222
}
223
224
return true;
225
}
226
227
// Auto and Guided do not call this to bypass the q-mode check.
228
bool Mode::_pre_arm_checks(size_t buflen, char *buffer) const
229
{
230
#if HAL_QUADPLANE_ENABLED
231
if (plane.quadplane.enabled() && !is_vtol_mode() &&
232
plane.quadplane.option_is_set(QuadPlane::OPTION::ONLY_ARM_IN_QMODE_OR_AUTO)) {
233
hal.util->snprintf(buffer, buflen, "not Q mode");
234
return false;
235
}
236
#endif
237
return true;
238
}
239
240
void Mode::run()
241
{
242
// Direct stick mixing functionality has been removed, so as not to remove all stick mixing from the user completely
243
// the old direct option is now used to enable fbw mixing, this is easier than doing a param conversion.
244
if ((plane.g.stick_mixing == StickMixing::FBW) || (plane.g.stick_mixing == StickMixing::DIRECT_REMOVED)) {
245
plane.stabilize_stick_mixing_fbw();
246
}
247
plane.stabilize_roll();
248
plane.stabilize_pitch();
249
plane.stabilize_yaw();
250
}
251
252
// Reset rate and steering controllers
253
void Mode::reset_controllers()
254
{
255
// reset integrators
256
plane.rollController.reset_I();
257
plane.pitchController.reset_I();
258
plane.yawController.reset_I();
259
260
// reset steering controls
261
plane.steer_state.locked_course = false;
262
plane.steer_state.locked_course_err = 0;
263
264
// reset TECS
265
plane.TECS_controller.reset();
266
}
267
268
bool Mode::is_taking_off() const
269
{
270
return (plane.flight_stage == AP_FixedWing::FlightStage::TAKEOFF);
271
}
272
273
// Helper to output to both k_rudder and k_steering servo functions
274
void Mode::output_rudder_and_steering(float val)
275
{
276
SRV_Channels::set_output_scaled(SRV_Channel::k_rudder, val);
277
SRV_Channels::set_output_scaled(SRV_Channel::k_steering, val);
278
}
279
280
// Output pilot throttle, this is used in stabilized modes without auto throttle control
281
// Direct mapping if THR_PASS_STAB is set
282
// Otherwise apply curve for trim correction if configured
283
void Mode::output_pilot_throttle()
284
{
285
if (plane.g.throttle_passthru_stabilize) {
286
// THR_PASS_STAB set, direct mapping
287
SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, plane.get_throttle_input(true));
288
return;
289
}
290
291
// get throttle, but adjust center to output TRIM_THROTTLE if flight option set
292
SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, plane.get_adjusted_throttle_input(true));
293
}
294
295
// true if throttle min/max limits should be applied
296
bool Mode::use_throttle_limits() const
297
{
298
#if AP_SCRIPTING_ENABLED
299
if (plane.nav_scripting_active()) {
300
return false;
301
}
302
#endif
303
304
if (this == &plane.mode_stabilize ||
305
this == &plane.mode_training ||
306
this == &plane.mode_acro ||
307
this == &plane.mode_fbwa ||
308
this == &plane.mode_autotune) {
309
// a manual throttle mode
310
return !plane.g.throttle_passthru_stabilize;
311
}
312
313
if (is_guided_mode() && plane.guided_throttle_passthru) {
314
// manual pass through of throttle while in GUIDED
315
return false;
316
}
317
318
#if HAL_QUADPLANE_ENABLED
319
if (quadplane.in_vtol_mode()) {
320
return quadplane.allow_forward_throttle_in_vtol_mode();
321
}
322
#endif
323
324
return true;
325
}
326
327
// true if voltage correction should be applied to throttle
328
bool Mode::use_battery_compensation() const
329
{
330
#if AP_SCRIPTING_ENABLED
331
if (plane.nav_scripting_active()) {
332
return false;
333
}
334
#endif
335
336
if (this == &plane.mode_stabilize ||
337
this == &plane.mode_training ||
338
this == &plane.mode_acro ||
339
this == &plane.mode_fbwa ||
340
this == &plane.mode_autotune) {
341
// a manual throttle mode
342
return false;
343
}
344
345
if (is_guided_mode() && plane.guided_throttle_passthru) {
346
// manual pass through of throttle while in GUIDED
347
return false;
348
}
349
350
#if HAL_QUADPLANE_ENABLED
351
if (quadplane.in_vtol_mode()) {
352
return false;
353
}
354
#endif
355
356
return true;
357
}
358
359