forked from ArduPilot/ardupilot
-
Notifications
You must be signed in to change notification settings - Fork 25
/
mode.cpp
185 lines (157 loc) · 5.56 KB
/
mode.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
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
#include "Blimp.h"
/*
* High level calls to set and update flight modes logic for individual
* flight modes is in control_acro.cpp, control_stabilize.cpp, etc
*/
#include <AP_Vehicle/AP_MultiCopter.h>
/*
constructor for Mode object
*/
Mode::Mode(void) :
g(blimp.g),
g2(blimp.g2),
inertial_nav(blimp.inertial_nav),
ahrs(blimp.ahrs),
motors(blimp.motors),
channel_right(blimp.channel_right),
channel_front(blimp.channel_front),
channel_down(blimp.channel_down),
channel_yaw(blimp.channel_yaw),
G_Dt(blimp.G_Dt)
{ };
// return the static controller object corresponding to supplied mode
Mode *Blimp::mode_from_mode_num(const Mode::Number mode)
{
Mode *ret = nullptr;
switch (mode) {
case Mode::Number::LAND:
ret = &mode_land;
break;
case Mode::Number::MANUAL:
ret = &mode_manual;
break;
case Mode::Number::VELOCITY:
ret = &mode_velocity;
break;
case Mode::Number::LOITER:
ret = &mode_loiter;
break;
default:
break;
}
return ret;
}
// set_mode - change flight mode and perform any necessary initialisation
// optional force parameter used to force the flight mode change (used only first time mode is set)
// returns true if mode was successfully set
// Some modes can always be set successfully but the return state of other flight modes should be checked and the caller should deal with failures appropriately
bool Blimp::set_mode(Mode::Number mode, ModeReason reason)
{
// return immediately if we are already in the desired mode
if (mode == control_mode) {
control_mode_reason = reason;
return true;
}
Mode *new_flightmode = mode_from_mode_num((Mode::Number)mode);
if (new_flightmode == nullptr) {
notify_no_such_mode((uint8_t)mode);
return false;
}
bool ignore_checks = !motors->armed(); // allow switching to any mode if disarmed. We rely on the arming check to perform
if (!ignore_checks &&
new_flightmode->requires_GPS() &&
!blimp.position_ok()) {
gcs().send_text(MAV_SEVERITY_WARNING, "Mode change failed: %s requires position", new_flightmode->name());
AP::logger().Write_Error(LogErrorSubsystem::FLIGHT_MODE, LogErrorCode(mode));
return false;
}
// check for valid altitude if old mode did not require it but new one does
// we only want to stop changing modes if it could make things worse
if (!ignore_checks &&
!blimp.ekf_alt_ok() &&
flightmode->has_manual_throttle() &&
!new_flightmode->has_manual_throttle()) {
gcs().send_text(MAV_SEVERITY_WARNING, "Mode change failed: %s need alt estimate", new_flightmode->name());
AP::logger().Write_Error(LogErrorSubsystem::FLIGHT_MODE, LogErrorCode(mode));
return false;
}
if (!new_flightmode->init(ignore_checks)) {
gcs().send_text(MAV_SEVERITY_WARNING,"Flight mode change failed %s", new_flightmode->name());
AP::logger().Write_Error(LogErrorSubsystem::FLIGHT_MODE, LogErrorCode(mode));
return false;
}
// perform any cleanup required by previous flight mode
exit_mode(flightmode, new_flightmode);
// store previous flight mode (only used by tradeheli's autorotation)
prev_control_mode = control_mode;
// update flight mode
flightmode = new_flightmode;
control_mode = mode;
control_mode_reason = reason;
logger.Write_Mode((uint8_t)control_mode, reason);
gcs().send_message(MSG_HEARTBEAT);
// update notify object
notify_flight_mode();
// return success
return true;
}
bool Blimp::set_mode(const uint8_t new_mode, const ModeReason reason)
{
static_assert(sizeof(Mode::Number) == sizeof(new_mode), "The new mode can't be mapped to the vehicles mode number");
#ifdef DISALLOW_GCS_MODE_CHANGE_DURING_RC_FAILSAFE
if (reason == ModeReason::GCS_COMMAND && blimp.failsafe.radio) {
// don't allow mode changes while in radio failsafe
return false;
}
#endif
return blimp.set_mode(static_cast<Mode::Number>(new_mode), reason);
}
// update_flight_mode - calls the appropriate attitude controllers based on flight mode
// called at 100hz or more
void Blimp::update_flight_mode()
{
flightmode->run();
}
// exit_mode - high level call to organise cleanup as a flight mode is exited
void Blimp::exit_mode(Mode *&old_flightmode,
Mode *&new_flightmode){}
// notify_flight_mode - sets notify object based on current flight mode. Only used for OreoLED notify device
void Blimp::notify_flight_mode()
{
AP_Notify::flags.autopilot_mode = flightmode->is_autopilot();
AP_Notify::flags.flight_mode = (uint8_t)control_mode;
notify.set_flight_mode_str(flightmode->name4());
}
void Mode::update_navigation()
{
// run autopilot to make high level decisions about control modes
run_autopilot();
}
// returns desired angle in centi-degrees
void Mode::get_pilot_desired_accelerations(float &right_out, float &front_out) const
{
// throttle failsafe check
if (blimp.failsafe.radio || !blimp.ap.rc_receiver_present) {
right_out = 0;
front_out = 0;
return;
}
// fetch roll and pitch inputs
right_out = channel_right->get_control_in();
front_out = channel_front->get_control_in();
}
bool Mode::is_disarmed_or_landed() const
{
if (!motors->armed() || !blimp.ap.auto_armed || blimp.ap.land_complete) {
return true;
}
return false;
}
bool Mode::set_mode(Mode::Number mode, ModeReason reason)
{
return blimp.set_mode(mode, reason);
}
GCS_Blimp &Mode::gcs()
{
return blimp.gcs();
}