Skip to content

Commit 9b2ef4f

Browse files
committed
Plane: move rudder-arming arm checks into Plane's AP_Arming
1 parent 9728dee commit 9b2ef4f

File tree

2 files changed

+43
-24
lines changed

2 files changed

+43
-24
lines changed

ArduPlane/AP_Arming.cpp

+40
Original file line numberDiff line numberDiff line change
@@ -136,6 +136,33 @@ bool AP_Arming_Plane::ins_checks(bool display_failure)
136136

137137
bool AP_Arming_Plane::arm_checks(AP_Arming::Method method)
138138
{
139+
if (method == AP_Arming::Method::RUDDER) {
140+
const AP_Arming::RudderArming arming_rudder = get_rudder_arming_type();
141+
142+
if (arming_rudder == AP_Arming::RudderArming::IS_DISABLED) {
143+
//parameter disallows rudder arming/disabling
144+
145+
// if we emit a message here then someone doing surface
146+
// checks may be bothered by the message being emitted.
147+
// check_failed(true, "Rudder arming disabled");
148+
return false;
149+
}
150+
151+
// if throttle is not down, then pilot cannot rudder arm/disarm
152+
if (plane.get_throttle_input() != 0){
153+
check_failed(true, "Non-zero throttle");
154+
return false;
155+
}
156+
157+
// if not in a manual throttle mode and not in CRUISE or FBWB
158+
// modes then disallow rudder arming/disarming
159+
if (plane.auto_throttle_mode &&
160+
(plane.control_mode != &plane.mode_cruise && plane.control_mode != &plane.mode_fbwb)) {
161+
check_failed(true, "Mode not rudder-armable");
162+
return false;
163+
}
164+
}
165+
139166
//are arming checks disabled?
140167
if (checks_to_perform == 0) {
141168
return true;
@@ -205,6 +232,19 @@ bool AP_Arming_Plane::arm(const AP_Arming::Method method, const bool do_arming_c
205232
*/
206233
bool AP_Arming_Plane::disarm(const AP_Arming::Method method)
207234
{
235+
if (method == AP_Arming::Method::RUDDER) {
236+
// don't allow rudder-disarming in flight:
237+
if (plane.is_flying()) {
238+
// obviously this could happen in-flight so we can't warn about it
239+
return false;
240+
}
241+
// option must be enabled:
242+
if (get_rudder_arming_type() != AP_Arming::RudderArming::ARMDISARM) {
243+
gcs().send_text(MAV_SEVERITY_INFO, "Rudder disarm: disabled");
244+
return false;
245+
}
246+
}
247+
208248
if (!AP_Arming::disarm(method)) {
209249
return false;
210250
}

ArduPlane/radio.cpp

+3-24
Original file line numberDiff line numberDiff line change
@@ -117,27 +117,6 @@ void Plane::init_rc_out_aux()
117117
*/
118118
void Plane::rudder_arm_disarm_check()
119119
{
120-
AP_Arming::RudderArming arming_rudder = arming.get_rudder_arming_type();
121-
122-
if (arming_rudder == AP_Arming::RudderArming::IS_DISABLED) {
123-
//parameter disallows rudder arming/disabling
124-
return;
125-
}
126-
127-
// if throttle is not down, then pilot cannot rudder arm/disarm
128-
if (get_throttle_input() != 0){
129-
rudder_arm_timer = 0;
130-
return;
131-
}
132-
133-
// if not in a manual throttle mode and not in CRUISE or FBWB
134-
// modes then disallow rudder arming/disarming
135-
if (auto_throttle_mode &&
136-
(control_mode != &mode_cruise && control_mode != &mode_fbwb)) {
137-
rudder_arm_timer = 0;
138-
return;
139-
}
140-
141120
if (!arming.is_armed()) {
142121
// when not armed, full right rudder starts arming counter
143122
if (channel_rudder->get_control_in() > 4000) {
@@ -158,8 +137,8 @@ void Plane::rudder_arm_disarm_check()
158137
// not at full right rudder
159138
rudder_arm_timer = 0;
160139
}
161-
} else if ((arming_rudder == AP_Arming::RudderArming::ARMDISARM) && !is_flying()) {
162-
// when armed and not flying, full left rudder starts disarming counter
140+
} else {
141+
// full left rudder starts disarming counter
163142
if (channel_rudder->get_control_in() < -4000) {
164143
uint32_t now = millis();
165144

@@ -177,7 +156,7 @@ void Plane::rudder_arm_disarm_check()
177156
// not at full left rudder
178157
rudder_arm_timer = 0;
179158
}
180-
}
159+
}
181160
}
182161

183162
void Plane::read_radio()

0 commit comments

Comments
 (0)