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/Rover/AP_Arming.cpp
Views: 1798
1
#include "AP_Arming.h"
2
#include "Rover.h"
3
4
// perform pre_arm_rc_checks checks
5
bool AP_Arming_Rover::rc_calibration_checks(const bool display_failure)
6
{
7
// set rc-checks to success if RC checks are disabled
8
if (!check_enabled(ARMING_CHECK_RC)) {
9
return true;
10
}
11
12
const RC_Channel *channels[] = {
13
rover.channel_steer,
14
rover.channel_throttle
15
};
16
const char *channel_names[] = {"Steer", "Throttle"};
17
18
for (uint8_t i= 0 ; i < ARRAY_SIZE(channels); i++) {
19
const RC_Channel *channel = channels[i];
20
const char *channel_name = channel_names[i];
21
// check if radio has been calibrated
22
if (channel->get_radio_min() > RC_Channel::RC_CALIB_MIN_LIMIT_PWM) {
23
check_failed(ARMING_CHECK_RC, display_failure, "%s radio min too high", channel_name);
24
return false;
25
}
26
if (channel->get_radio_max() < RC_Channel::RC_CALIB_MAX_LIMIT_PWM) {
27
check_failed(ARMING_CHECK_RC, display_failure, "%s radio max too low", channel_name);
28
return false;
29
}
30
}
31
return AP_Arming::rc_calibration_checks(display_failure);
32
}
33
34
// performs pre_arm gps related checks and returns true if passed
35
bool AP_Arming_Rover::gps_checks(bool display_failure)
36
{
37
if (!rover.control_mode->requires_position() && !rover.control_mode->requires_velocity()) {
38
// we don't care!
39
return true;
40
}
41
42
// call parent gps checks
43
if (!AP_Arming::gps_checks(display_failure)) {
44
return false;
45
}
46
47
const AP_AHRS &ahrs = AP::ahrs();
48
49
// always check if inertial nav has started and is ready
50
char failure_msg[50] = {};
51
if (!ahrs.pre_arm_check(true, failure_msg, sizeof(failure_msg))) {
52
check_failed(display_failure, "AHRS: %s", failure_msg);
53
return false;
54
}
55
56
// check for ekf failsafe
57
if (rover.failsafe.ekf) {
58
check_failed(display_failure, "EKF failsafe");
59
return false;
60
}
61
62
// ensure position estimate is ok
63
if (!rover.ekf_position_ok()) {
64
// vehicle level position estimate checks
65
check_failed(display_failure, "Need Position Estimate");
66
return false;
67
}
68
69
return true;
70
}
71
72
bool AP_Arming_Rover::pre_arm_checks(bool report)
73
{
74
if (armed) {
75
// if we are already armed then skip the checks
76
return true;
77
}
78
79
//are arming checks disabled?
80
if (checks_to_perform == 0) {
81
return mandatory_checks(report);
82
}
83
84
if (rover.g2.sailboat.sail_enabled() && !rover.g2.windvane.enabled()) {
85
check_failed(report, "Sailing enabled with no WindVane");
86
return false;
87
}
88
89
return (AP_Arming::pre_arm_checks(report)
90
& motor_checks(report)
91
#if AP_OAPATHPLANNER_ENABLED
92
& oa_check(report)
93
#endif
94
& parameter_checks(report)
95
& mode_checks(report));
96
}
97
98
bool AP_Arming_Rover::arm_checks(AP_Arming::Method method)
99
{
100
//are arming checks disabled?
101
if (checks_to_perform == 0) {
102
return true;
103
}
104
return AP_Arming::arm_checks(method);
105
}
106
107
void AP_Arming_Rover::update_soft_armed()
108
{
109
hal.util->set_soft_armed(is_armed() &&
110
hal.util->safety_switch_state() != AP_HAL::Util::SAFETY_DISARMED);
111
#if HAL_LOGGING_ENABLED
112
AP::logger().set_vehicle_armed(hal.util->get_soft_armed());
113
#endif
114
}
115
116
/*
117
arm motors
118
*/
119
bool AP_Arming_Rover::arm(AP_Arming::Method method, const bool do_arming_checks)
120
{
121
if (!AP_Arming::arm(method, do_arming_checks)) {
122
AP_Notify::events.arming_failed = true;
123
return false;
124
}
125
126
// Set the SmartRTL home location. If activated, SmartRTL will ultimately try to land at this point
127
rover.g2.smart_rtl.set_home(true);
128
129
// initialize simple mode heading
130
rover.mode_simple.init_heading();
131
132
// save home heading for use in sail vehicles
133
rover.g2.windvane.record_home_heading();
134
135
update_soft_armed();
136
137
send_arm_disarm_statustext("Throttle armed");
138
139
return true;
140
}
141
142
/*
143
disarm motors
144
*/
145
bool AP_Arming_Rover::disarm(const AP_Arming::Method method, bool do_disarm_checks)
146
{
147
if (!AP_Arming::disarm(method, do_disarm_checks)) {
148
return false;
149
}
150
if (rover.control_mode != &rover.mode_auto) {
151
// reset the mission on disarm if we are not in auto
152
rover.mode_auto.mission.reset();
153
}
154
155
update_soft_armed();
156
157
send_arm_disarm_statustext("Throttle disarmed");
158
159
return true;
160
}
161
162
#if AP_OAPATHPLANNER_ENABLED
163
// check object avoidance has initialised correctly
164
bool AP_Arming_Rover::oa_check(bool report)
165
{
166
char failure_msg[50] = {};
167
if (rover.g2.oa.pre_arm_check(failure_msg, ARRAY_SIZE(failure_msg))) {
168
return true;
169
}
170
171
check_failed(report, "%s", failure_msg);
172
return false;
173
}
174
#endif // AP_OAPATHPLANNER_ENABLED
175
176
// perform parameter checks
177
bool AP_Arming_Rover::parameter_checks(bool report)
178
{
179
// success if parameter checks are disabled
180
if (!check_enabled(ARMING_CHECK_PARAMETERS)) {
181
return true;
182
}
183
184
// check waypoint speed is positive
185
if (!is_positive(rover.g2.wp_nav.get_default_speed())) {
186
check_failed(ARMING_CHECK_PARAMETERS, report, "WP_SPEED too low");
187
return false;
188
}
189
190
return true;
191
}
192
193
// check if arming allowed from this mode
194
bool AP_Arming_Rover::mode_checks(bool report)
195
{
196
//display failure if arming in this mode is not allowed
197
if (!rover.control_mode->allows_arming()) {
198
check_failed(report, "Mode not armable");
199
return false;
200
}
201
return true;
202
}
203
204
// check motors are ready
205
bool AP_Arming_Rover::motor_checks(bool report)
206
{
207
bool ret = rover.g2.motors.pre_arm_check(report);
208
209
#if HAL_TORQEEDO_ENABLED
210
char failure_msg[50] = {};
211
AP_Torqeedo *torqeedo = AP_Torqeedo::get_singleton();
212
if (torqeedo != nullptr) {
213
if (!torqeedo->pre_arm_checks(failure_msg, ARRAY_SIZE(failure_msg))) {
214
check_failed(report, "Torqeedo: %s", failure_msg);
215
ret = false;
216
}
217
}
218
#endif
219
220
return ret;
221
}
222
223