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_auto.cpp
Views: 1798
1
#include "mode.h"
2
#include "Plane.h"
3
4
bool ModeAuto::_enter()
5
{
6
#if HAL_QUADPLANE_ENABLED
7
// check if we should refuse auto mode due to a missing takeoff in
8
// guided_wait_takeoff state
9
if (plane.previous_mode == &plane.mode_guided &&
10
quadplane.guided_wait_takeoff_on_mode_enter) {
11
if (!plane.mission.starts_with_takeoff_cmd()) {
12
gcs().send_text(MAV_SEVERITY_ERROR,"Takeoff waypoint required");
13
quadplane.guided_wait_takeoff = true;
14
return false;
15
}
16
}
17
18
if (plane.quadplane.available() && plane.quadplane.enable == 2) {
19
plane.auto_state.vtol_mode = true;
20
} else {
21
plane.auto_state.vtol_mode = false;
22
}
23
#else
24
plane.auto_state.vtol_mode = false;
25
#endif
26
plane.next_WP_loc = plane.prev_WP_loc = plane.current_loc;
27
// start or resume the mission, based on MIS_AUTORESET
28
plane.mission.start_or_resume();
29
30
if (hal.util->was_watchdog_armed()) {
31
if (hal.util->persistent_data.waypoint_num != 0) {
32
gcs().send_text(MAV_SEVERITY_INFO, "Watchdog: resume WP %u", hal.util->persistent_data.waypoint_num);
33
plane.mission.set_current_cmd(hal.util->persistent_data.waypoint_num);
34
hal.util->persistent_data.waypoint_num = 0;
35
}
36
}
37
38
#if HAL_SOARING_ENABLED
39
plane.g2.soaring_controller.init_cruising();
40
#endif
41
42
return true;
43
}
44
45
void ModeAuto::_exit()
46
{
47
if (plane.mission.state() == AP_Mission::MISSION_RUNNING) {
48
plane.mission.stop();
49
50
bool restart = plane.mission.get_current_nav_cmd().id == MAV_CMD_NAV_LAND;
51
#if HAL_QUADPLANE_ENABLED
52
if (plane.quadplane.is_vtol_land(plane.mission.get_current_nav_cmd().id)) {
53
restart = false;
54
}
55
#endif
56
if (restart) {
57
plane.landing.restart_landing_sequence();
58
}
59
}
60
plane.auto_state.started_flying_in_auto_ms = 0;
61
}
62
63
void ModeAuto::update()
64
{
65
if (plane.mission.state() != AP_Mission::MISSION_RUNNING) {
66
// this could happen if AP_Landing::restart_landing_sequence() returns false which would only happen if:
67
// restart_landing_sequence() is called when not executing a NAV_LAND or there is no previous nav point
68
plane.set_mode(plane.mode_rtl, ModeReason::MISSION_END);
69
gcs().send_text(MAV_SEVERITY_INFO, "Aircraft in auto without a running mission");
70
return;
71
}
72
73
uint16_t nav_cmd_id = plane.mission.get_current_nav_cmd().id;
74
75
#if HAL_QUADPLANE_ENABLED
76
if (plane.quadplane.in_vtol_auto()) {
77
plane.quadplane.control_auto();
78
return;
79
}
80
#endif
81
82
#if AP_PLANE_GLIDER_PULLUP_ENABLED
83
if (pullup.in_pullup()) {
84
return;
85
}
86
#endif
87
88
if (nav_cmd_id == MAV_CMD_NAV_TAKEOFF ||
89
(nav_cmd_id == MAV_CMD_NAV_LAND && plane.flight_stage == AP_FixedWing::FlightStage::ABORT_LANDING)) {
90
plane.takeoff_calc_roll();
91
plane.takeoff_calc_pitch();
92
plane.takeoff_calc_throttle();
93
} else if (nav_cmd_id == MAV_CMD_NAV_LAND) {
94
plane.calc_nav_roll();
95
plane.calc_nav_pitch();
96
97
// allow landing to restrict the roll limits
98
plane.nav_roll_cd = plane.landing.constrain_roll(plane.nav_roll_cd, plane.g.level_roll_limit*100UL);
99
100
if (plane.landing.is_throttle_suppressed()) {
101
// if landing is considered complete throttle is never allowed, regardless of landing type
102
SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, 0.0);
103
} else {
104
plane.calc_throttle();
105
}
106
#if AP_SCRIPTING_ENABLED
107
} else if (nav_cmd_id == MAV_CMD_NAV_SCRIPT_TIME) {
108
// NAV_SCRIPTING has a desired roll and pitch rate and desired throttle
109
plane.nav_roll_cd = ahrs.roll_sensor;
110
plane.nav_pitch_cd = ahrs.pitch_sensor;
111
#endif
112
} else {
113
// we are doing normal AUTO flight, the special cases
114
// are for takeoff and landing
115
if (nav_cmd_id != MAV_CMD_NAV_CONTINUE_AND_CHANGE_ALT) {
116
plane.steer_state.hold_course_cd = -1;
117
}
118
plane.calc_nav_roll();
119
plane.calc_nav_pitch();
120
plane.calc_throttle();
121
}
122
}
123
124
void ModeAuto::navigate()
125
{
126
if (AP::ahrs().home_is_set()) {
127
plane.mission.update();
128
}
129
}
130
131
132
bool ModeAuto::does_auto_navigation() const
133
{
134
#if AP_SCRIPTING_ENABLED
135
return (!plane.nav_scripting_active());
136
#endif
137
return true;
138
}
139
140
bool ModeAuto::does_auto_throttle() const
141
{
142
#if AP_SCRIPTING_ENABLED
143
return (!plane.nav_scripting_active());
144
#endif
145
return true;
146
}
147
148
// returns true if the vehicle can be armed in this mode
149
bool ModeAuto::_pre_arm_checks(size_t buflen, char *buffer) const
150
{
151
#if HAL_QUADPLANE_ENABLED
152
if (plane.quadplane.enabled()) {
153
if (plane.quadplane.option_is_set(QuadPlane::OPTION::ONLY_ARM_IN_QMODE_OR_AUTO) &&
154
!plane.quadplane.is_vtol_takeoff(plane.mission.get_current_nav_cmd().id)) {
155
hal.util->snprintf(buffer, buflen, "not in VTOL takeoff");
156
return false;
157
}
158
if (!plane.mission.starts_with_takeoff_cmd()) {
159
hal.util->snprintf(buffer, buflen, "missing takeoff waypoint");
160
return false;
161
}
162
}
163
#endif
164
// Note that this bypasses the base class checks
165
return true;
166
}
167
168
bool ModeAuto::is_landing() const
169
{
170
return (plane.flight_stage == AP_FixedWing::FlightStage::LAND);
171
}
172
173
void ModeAuto::run()
174
{
175
#if AP_PLANE_GLIDER_PULLUP_ENABLED
176
if (pullup.in_pullup()) {
177
pullup.stabilize_pullup();
178
return;
179
}
180
#endif
181
182
if (plane.mission.get_current_nav_cmd().id == MAV_CMD_NAV_ALTITUDE_WAIT) {
183
184
wiggle_servos();
185
186
SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, 0.0);
187
SRV_Channels::set_output_scaled(SRV_Channel::k_throttleLeft, 0.0);
188
SRV_Channels::set_output_scaled(SRV_Channel::k_throttleRight, 0.0);
189
190
SRV_Channels::set_output_to_trim(SRV_Channel::k_throttle);
191
SRV_Channels::set_output_to_trim(SRV_Channel::k_throttleLeft);
192
SRV_Channels::set_output_to_trim(SRV_Channel::k_throttleRight);
193
194
// Relax attitude control
195
reset_controllers();
196
197
} else {
198
// Normal flight, run base class
199
Mode::run();
200
201
}
202
}
203
204