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/ArduSub/AP_Arming_Sub.cpp
Views: 1798
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
return false;
42
}
43
44
bool AP_Arming_Sub::pre_arm_checks(bool display_failure)
45
{
46
if (armed) {
47
return true;
48
}
49
// don't allow arming unless there is a disarm button configured
50
if (!has_disarm_function()) {
51
check_failed(display_failure, "Must assign a disarm or arm_toggle button");
52
return false;
53
}
54
55
return AP_Arming::pre_arm_checks(display_failure);
56
}
57
58
bool AP_Arming_Sub::ins_checks(bool display_failure)
59
{
60
// call parent class checks
61
if (!AP_Arming::ins_checks(display_failure)) {
62
return false;
63
}
64
65
// additional sub-specific checks
66
if (check_enabled(ARMING_CHECK_INS)) {
67
char failure_msg[50] = {};
68
if (!AP::ahrs().pre_arm_check(false, failure_msg, sizeof(failure_msg))) {
69
check_failed(ARMING_CHECK_INS, display_failure, "AHRS: %s", failure_msg);
70
return false;
71
}
72
}
73
74
return true;
75
}
76
77
bool AP_Arming_Sub::arm(AP_Arming::Method method, bool do_arming_checks)
78
{
79
static bool in_arm_motors = false;
80
81
// exit immediately if already in this function
82
if (in_arm_motors) {
83
return false;
84
}
85
86
in_arm_motors = true;
87
88
if (!AP_Arming::arm(method, do_arming_checks)) {
89
AP_Notify::events.arming_failed = true;
90
in_arm_motors = false;
91
return false;
92
}
93
94
#if HAL_LOGGING_ENABLED
95
// let logger know that we're armed (it may open logs e.g.)
96
AP::logger().set_vehicle_armed(true);
97
#endif
98
99
// disable cpu failsafe because initialising everything takes a while
100
sub.mainloop_failsafe_disable();
101
102
// notify that arming will occur (we do this early to give plenty of warning)
103
AP_Notify::flags.armed = true;
104
// call notify update a few times to ensure the message gets out
105
for (uint8_t i=0; i<=10; i++) {
106
AP::notify().update();
107
}
108
109
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
110
send_arm_disarm_statustext("Arming motors");
111
#endif
112
113
AP_AHRS &ahrs = AP::ahrs();
114
115
sub.initial_armed_bearing = ahrs.yaw_sensor;
116
117
if (!ahrs.home_is_set()) {
118
// Reset EKF altitude if home hasn't been set yet (we use EKF altitude as substitute for alt above home)
119
120
// Always use absolute altitude for ROV
121
// ahrs.resetHeightDatum();
122
// AP::logger().Write_Event(LogEvent::EKF_ALT_RESET);
123
} else if (!ahrs.home_is_locked()) {
124
// Reset home position if it has already been set before (but not locked)
125
if (!sub.set_home_to_current_location(false)) {
126
// ignore this failure
127
}
128
}
129
130
hal.util->set_soft_armed(true);
131
132
// enable output to motors
133
sub.enable_motor_output();
134
135
// finally actually arm the motors
136
sub.motors.armed(true);
137
138
#if HAL_LOGGING_ENABLED
139
// log flight mode in case it was changed while vehicle was disarmed
140
AP::logger().Write_Mode((uint8_t)sub.control_mode, sub.control_mode_reason);
141
#endif
142
143
// reenable failsafe
144
sub.mainloop_failsafe_enable();
145
146
// perf monitor ignores delay due to arming
147
AP::scheduler().perf_info.ignore_this_loop();
148
149
// flag exiting this function
150
in_arm_motors = false;
151
152
// if we do not have an ekf origin then we can't use the WMM tables
153
if (!sub.ensure_ekf_origin()) {
154
gcs().send_text(MAV_SEVERITY_WARNING, "Compass performance degraded");
155
if (check_enabled(ARMING_CHECK_PARAMETERS)) {
156
check_failed(ARMING_CHECK_PARAMETERS, true, "No world position, check ORIGIN_* parameters");
157
return false;
158
}
159
}
160
// return success
161
return true;
162
}
163
164
bool AP_Arming_Sub::disarm(const AP_Arming::Method method, bool do_disarm_checks)
165
{
166
// return immediately if we are already disarmed
167
if (!sub.motors.armed()) {
168
return false;
169
}
170
171
if (!AP_Arming::disarm(method, do_disarm_checks)) {
172
return false;
173
}
174
175
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
176
send_arm_disarm_statustext("Disarming motors");
177
#endif
178
179
auto &ahrs = AP::ahrs();
180
181
// save compass offsets learned by the EKF if enabled
182
if (ahrs.use_compass() && AP::compass().get_learn_type() == Compass::LEARN_EKF) {
183
for (uint8_t i=0; i<COMPASS_MAX_INSTANCES; i++) {
184
Vector3f magOffsets;
185
if (ahrs.getMagOffsets(i, magOffsets)) {
186
AP::compass().set_and_save_offsets(i, magOffsets);
187
}
188
}
189
}
190
191
// send disarm command to motors
192
sub.motors.armed(false);
193
194
// reset the mission
195
sub.mission.reset();
196
197
#if HAL_LOGGING_ENABLED
198
AP::logger().set_vehicle_armed(false);
199
#endif
200
201
hal.util->set_soft_armed(false);
202
203
// clear input holds
204
sub.clear_input_hold();
205
206
return true;
207
}
208
209