Book a Demo!
CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutPoliciesSign UpSign In
Ardupilot
GitHub Repository: Ardupilot/ardupilot
Path: blob/master/ArduSub/AP_Arming_Sub.cpp
9386 views
1
#include "AP_Arming_Sub.h"
2
#include "Sub.h"
3
4
bool AP_Arming_Sub::rc_calibration_checks(bool display_failure)
5
{
6
const RC_Channel *channels[] = {
7
sub.channel_roll,
8
sub.channel_pitch,
9
sub.channel_throttle,
10
sub.channel_yaw
11
};
12
return rc_checks_copter_sub(display_failure, channels);
13
}
14
15
bool AP_Arming_Sub::has_disarm_function() const {
16
bool has_shift_function = false;
17
// make sure the craft has a disarm button assigned before it is armed
18
// check all the standard btn functions
19
for (uint8_t i = 0; i < 16; i++) {
20
switch (sub.get_button(i)->function(false)) {
21
case JSButton::k_shift :
22
has_shift_function = true;
23
break;
24
case JSButton::k_arm_toggle :
25
return true;
26
case JSButton::k_disarm :
27
return true;
28
}
29
}
30
31
// check all the shift functions if there's shift assigned
32
if (has_shift_function) {
33
for (uint8_t i = 0; i < 16; i++) {
34
switch (sub.get_button(i)->function(true)) {
35
case JSButton::k_arm_toggle :
36
case JSButton::k_disarm :
37
return true;
38
}
39
}
40
}
41
// check if an AUX function that disarms or estops is setup
42
if (rc().find_channel_for_option(RC_Channel::AUX_FUNC::MOTOR_ESTOP) ||
43
rc().find_channel_for_option(RC_Channel::AUX_FUNC::DISARM) ||
44
rc().find_channel_for_option(RC_Channel::AUX_FUNC::ARMDISARM) ||
45
rc().find_channel_for_option(RC_Channel::AUX_FUNC::ARM_EMERGENCY_STOP)) {
46
return true;
47
}
48
return false;
49
}
50
51
bool AP_Arming_Sub::pre_arm_checks(bool display_failure)
52
{
53
if (armed) {
54
return true;
55
}
56
// don't allow arming unless there is a disarm button configured
57
if (!has_disarm_function()) {
58
check_failed(display_failure, "Must assign a disarm or arm_toggle button or disarm aux function");
59
return false;
60
}
61
62
return AP_Arming::pre_arm_checks(display_failure);
63
}
64
65
bool AP_Arming_Sub::ins_checks(bool display_failure)
66
{
67
// call parent class checks
68
if (!AP_Arming::ins_checks(display_failure)) {
69
return false;
70
}
71
72
// additional sub-specific checks
73
if (check_enabled(Check::INS)) {
74
char failure_msg[50] = {};
75
if (!AP::ahrs().pre_arm_check(false, failure_msg, sizeof(failure_msg))) {
76
check_failed(Check::INS, display_failure, "AHRS: %s", failure_msg);
77
return false;
78
}
79
}
80
81
return true;
82
}
83
84
bool AP_Arming_Sub::arm(AP_Arming::Method method, bool do_arming_checks)
85
{
86
static bool in_arm_motors = false;
87
88
// exit immediately if already in this function
89
if (in_arm_motors) {
90
return false;
91
}
92
93
in_arm_motors = true;
94
95
//if RC checks enabled, and RC_OPTIONS enabled for "0" throttle, and enabled check for throttle within trim position
96
if (check_enabled(Check::RC) &&
97
rc().option_is_enabled(RC_Channels::Option::ARMING_CHECK_THROTTLE) &&
98
(sub.g.thr_arming_position == WITHIN_THR_TRIM)) {
99
const char *rc_item = "Throttle";
100
// check throttle is within trim+/- dz, ie centered throttle
101
if (!sub.channel_throttle->in_trim_dz()) {
102
check_failed(Check::RC, true, "%s not centered/close to trim", rc_item);
103
AP_Notify::events.arming_failed = true;
104
in_arm_motors = false;
105
return false;
106
}
107
}
108
109
if (!AP_Arming::arm(method, do_arming_checks)) {
110
AP_Notify::events.arming_failed = true;
111
in_arm_motors = false;
112
return false;
113
}
114
115
#if HAL_LOGGING_ENABLED
116
// let logger know that we're armed (it may open logs e.g.)
117
AP::logger().set_vehicle_armed(true);
118
#endif
119
120
// disable cpu failsafe because initialising everything takes a while
121
sub.mainloop_failsafe_disable();
122
123
// notify that arming will occur (we do this early to give plenty of warning)
124
AP_Notify::flags.armed = true;
125
// call notify update a few times to ensure the message gets out
126
for (uint8_t i=0; i<=10; i++) {
127
AP::notify().update();
128
}
129
130
send_arm_disarm_statustext("Arming motors");
131
132
AP_AHRS &ahrs = AP::ahrs();
133
134
sub.initial_armed_bearing = ahrs.yaw_sensor;
135
136
if (!ahrs.home_is_set()) {
137
// Reset EKF altitude if home hasn't been set yet (we use EKF altitude as substitute for alt above home)
138
139
// Always use absolute altitude for ROV
140
// ahrs.resetHeightDatum();
141
// AP::logger().Write_Event(LogEvent::EKF_ALT_RESET);
142
} else if (!ahrs.home_is_locked()) {
143
// Reset home position if it has already been set before (but not locked)
144
if (!sub.set_home_to_current_location(false)) {
145
// ignore this failure
146
}
147
}
148
149
hal.util->set_soft_armed(true);
150
151
// enable output to motors
152
sub.enable_motor_output();
153
154
// finally actually arm the motors
155
sub.motors.armed(true);
156
157
#if HAL_LOGGING_ENABLED
158
// log flight mode in case it was changed while vehicle was disarmed
159
AP::logger().Write_Mode((uint8_t)sub.control_mode, sub.control_mode_reason);
160
#endif
161
162
// reenable failsafe
163
sub.mainloop_failsafe_enable();
164
165
// perf monitor ignores delay due to arming
166
AP::scheduler().perf_info.ignore_this_loop();
167
168
// flag exiting this function
169
in_arm_motors = false;
170
171
// if we do not have an ekf origin then we can't use the WMM tables
172
Location origin_loc;
173
if (!ahrs.get_origin(origin_loc)) {
174
gcs().send_text(MAV_SEVERITY_WARNING, "Compass performance degraded");
175
if (check_enabled(Check::PARAMETERS)) {
176
check_failed(Check::PARAMETERS, true, "No world position, check AHRS_ORIGIN_* parameters");
177
return false;
178
}
179
}
180
// return success
181
return true;
182
}
183
184
bool AP_Arming_Sub::disarm(const AP_Arming::Method method, bool do_disarm_checks)
185
{
186
// return immediately if we are already disarmed
187
if (!sub.motors.armed()) {
188
return false;
189
}
190
191
if (!AP_Arming::disarm(method, do_disarm_checks)) {
192
return false;
193
}
194
195
send_arm_disarm_statustext("Disarming motors");
196
197
auto &ahrs = AP::ahrs();
198
199
// save compass offsets learned by the EKF if enabled
200
if (ahrs.use_compass() && AP::compass().get_learn_type() == Compass::LearnType::COPY_FROM_EKF) {
201
for (uint8_t i=0; i<COMPASS_MAX_INSTANCES; i++) {
202
Vector3f magOffsets;
203
if (ahrs.getMagOffsets(i, magOffsets)) {
204
AP::compass().set_and_save_offsets(i, magOffsets);
205
}
206
}
207
}
208
209
// send disarm command to motors
210
sub.motors.armed(false);
211
212
// reset the mission
213
sub.mission.reset();
214
215
#if HAL_LOGGING_ENABLED
216
AP::logger().set_vehicle_armed(false);
217
#endif
218
219
hal.util->set_soft_armed(false);
220
221
// clear input holds
222
sub.clear_input_hold();
223
224
return true;
225
}
226
227