Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Plane: disallow mavlink disarm while flying #20234

Merged
merged 4 commits into from
Mar 9, 2022
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
9 changes: 6 additions & 3 deletions ArduPlane/AP_Arming.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -275,12 +275,15 @@ bool AP_Arming_Plane::arm(const AP_Arming::Method method, const bool do_arming_c
bool AP_Arming_Plane::disarm(const AP_Arming::Method method, bool do_disarm_checks)
{
if (do_disarm_checks &&
method == AP_Arming::Method::RUDDER) {
// don't allow rudder-disarming in flight:
(method == AP_Arming::Method::MAVLINK ||
method == AP_Arming::Method::RUDDER)) {
if (plane.is_flying()) {
// obviously this could happen in-flight so we can't warn about it
// don't allow mavlink or rudder disarm while flying
return false;
}
}

if (do_disarm_checks && method == AP_Arming::Method::RUDDER) {
// option must be enabled:
if (get_rudder_arming_type() != AP_Arming::RudderArming::ARMDISARM) {
gcs().send_text(MAV_SEVERITY_INFO, "Rudder disarm: disabled");
Expand Down
4 changes: 2 additions & 2 deletions Tools/autotest/arducopter.py
Original file line number Diff line number Diff line change
Expand Up @@ -3961,7 +3961,7 @@ def test_guided_local_position_target(self, x, y, z_up):

if not (m.type_mask == (target_typemask | MAV_POS_TARGET_TYPE_MASK.LAST_BYTE) or m.type_mask == target_typemask):
raise NotAchievedException("Did not receive proper mask: expected=%u or %u, got=%u" %
((target_typemask | MAV_POS_TARGET_TYPE_MASK.LAST_BYTE), target_typemask, m.type_mask))
((target_typemask | MAV_POS_TARGET_TYPE_MASK.LAST_BYTE), target_typemask, m.type_mask))

if x - m.x > 0.1:
raise NotAchievedException("Did not receive proper target position x: wanted=%f got=%f" % (x, m.x))
Expand Down Expand Up @@ -4012,7 +4012,7 @@ def test_guided_local_velocity_target(self, vx, vy, vz_up, timeout=3):
# Check the last received message
if not (m.type_mask == (target_typemask | MAV_POS_TARGET_TYPE_MASK.LAST_BYTE) or m.type_mask == target_typemask):
raise NotAchievedException("Did not receive proper mask: expected=%u or %u, got=%u" %
((target_typemask | MAV_POS_TARGET_TYPE_MASK.LAST_BYTE), target_typemask, m.type_mask))
((target_typemask | MAV_POS_TARGET_TYPE_MASK.LAST_BYTE), target_typemask, m.type_mask))

if vx - m.vx > 0.1:
raise NotAchievedException("Did not receive proper target velocity vx: wanted=%f got=%f" % (vx, m.vx))
Expand Down
8 changes: 4 additions & 4 deletions Tools/autotest/arduplane.py
Original file line number Diff line number Diff line change
Expand Up @@ -1038,7 +1038,7 @@ def ThrottleFailsafe(self):
"SIM_RC_FAIL": 0, # fix receiver
})
self.zero_throttle()
self.disarm_vehicle()
self.disarm_vehicle(force=True)
self.context_pop()
self.reboot_sitl()

Expand Down Expand Up @@ -2268,7 +2268,7 @@ def fly_soaring(self):
self.wait_waypoint(4, 4, timeout=1200, max_dist=120)

# Disarm
self.disarm_vehicle()
self.disarm_vehicle_expect_fail()

self.progress("Mission OK")

Expand Down Expand Up @@ -2365,7 +2365,7 @@ def fly_soaring_speed_to_fly(self):
raise NotAchievedException("Airspeed did not reduce with lower SOAR_VSPEED")

# Disarm
self.disarm_vehicle()
self.disarm_vehicle_expect_fail()

self.progress("Mission OK")

Expand Down Expand Up @@ -2872,7 +2872,7 @@ def fail_speed():
self.context_clear_collection("STATUSTEXT")
###################################################################

self.disarm_vehicle()
self.disarm_vehicle(force=True)

except Exception as e:
self.print_exception_caught(e)
Expand Down
18 changes: 17 additions & 1 deletion Tools/autotest/common.py
Original file line number Diff line number Diff line change
Expand Up @@ -4361,6 +4361,22 @@ def disarm_vehicle(self, timeout=60, force=False):
timeout=timeout)
return self.wait_disarmed()

def disarm_vehicle_expect_fail(self):
'''disarm, checking first that non-forced disarm fails, then doing a forced disarm'''
self.progress("Disarm - expect to fail")
self.run_cmd(mavutil.mavlink.MAV_CMD_COMPONENT_ARM_DISARM,
0, # DISARM
0,
0,
0,
0,
0,
0,
timeout=10,
want_result=mavutil.mavlink.MAV_RESULT_FAILED)
self.progress("Disarm - forced")
self.disarm_vehicle(force=True)

def wait_disarmed_default_wait_time(self):
return 30

Expand Down Expand Up @@ -11191,7 +11207,7 @@ def test_frsky_sport(self):
# ok done, stop the engine
if self.is_plane():
self.zero_throttle()
if not self.disarm_vehicle():
if not self.disarm_vehicle(force=True):
raise NotAchievedException("Failed to DISARM")

def test_frsky_d(self):
Expand Down
5 changes: 2 additions & 3 deletions Tools/autotest/quadplane.py
Original file line number Diff line number Diff line change
Expand Up @@ -248,13 +248,12 @@ def test_airmode(self):
self.progress("Waiting for Motor1 to speed up")
self.wait_servo_channel_value(5, spin_min_pwm, comparator=operator.ge)

self.progress("Disarm/rearm with GCS")
self.disarm_vehicle()
self.disarm_vehicle_expect_fail()
self.arm_vehicle()

self.progress("Verify that airmode is still on")
self.wait_servo_channel_value(5, spin_min_pwm, comparator=operator.ge)
self.disarm_vehicle()
self.disarm_vehicle(force=True)
self.wait_ready_to_arm()

def test_motor_mask(self):
Expand Down