@@ -136,6 +136,33 @@ bool AP_Arming_Plane::ins_checks(bool display_failure)
136
136
137
137
bool AP_Arming_Plane::arm_checks (AP_Arming::Method method)
138
138
{
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
+
139
166
// are arming checks disabled?
140
167
if (checks_to_perform == 0 ) {
141
168
return true ;
@@ -205,6 +232,19 @@ bool AP_Arming_Plane::arm(const AP_Arming::Method method, const bool do_arming_c
205
232
*/
206
233
bool AP_Arming_Plane::disarm (const AP_Arming::Method method)
207
234
{
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
+
208
248
if (!AP_Arming::disarm (method)) {
209
249
return false ;
210
250
}
0 commit comments