Skip to content

Commit 7f61ace

Browse files
committed
autotest: add test for Copter compassmot
1 parent 5b69ff6 commit 7f61ace

File tree

1 file changed

+63
-0
lines changed

1 file changed

+63
-0
lines changed

Tools/autotest/arducopter.py

+63
Original file line numberDiff line numberDiff line change
@@ -2055,6 +2055,67 @@ def ModeCircle(self, holdtime=36):
20552055

20562056
self.do_RTL()
20572057

2058+
def CompassMot(self):
2059+
'''test code that adjust mag field for motor interference'''
2060+
self.run_cmd(
2061+
mavutil.mavlink.MAV_CMD_PREFLIGHT_CALIBRATION,
2062+
0, # p1
2063+
0, # p2
2064+
0, # p3
2065+
0, # p4
2066+
0, # p5
2067+
1, # p6
2068+
0 # p7
2069+
)
2070+
self.context_collect("STATUSTEXT")
2071+
self.wait_statustext("Starting calibration", check_context=True)
2072+
self.wait_statustext("Current", check_context=True)
2073+
rc3_min = self.get_parameter('RC3_MIN')
2074+
rc3_max = self.get_parameter('RC3_MAX')
2075+
rc3_dz = self.get_parameter('RC3_DZ')
2076+
2077+
def set_rc3_for_throttle_pct(thr_pct):
2078+
value = int((rc3_min+rc3_dz) + (thr_pct/100.0) * (rc3_max-(rc3_min+rc3_dz)))
2079+
self.progress("Setting rc3 to %u" % value)
2080+
self.set_rc(3, value)
2081+
2082+
throttle_in_pct = 0
2083+
set_rc3_for_throttle_pct(throttle_in_pct)
2084+
self.assert_received_message_field_values("COMPASSMOT_STATUS", {
2085+
"interference": 0,
2086+
"throttle": throttle_in_pct
2087+
}, verbose=True, very_verbose=True)
2088+
tstart = self.get_sim_time()
2089+
delta = 5
2090+
while True:
2091+
if self.get_sim_time_cached() - tstart > 60:
2092+
raise NotAchievedException("did not run through entire range")
2093+
throttle_in_pct += delta
2094+
self.progress("Using throttle %f%%" % throttle_in_pct)
2095+
set_rc3_for_throttle_pct(throttle_in_pct)
2096+
self.wait_message_field_values("COMPASSMOT_STATUS", {
2097+
"throttle": throttle_in_pct * 10.0,
2098+
}, verbose=True, very_verbose=True, epsilon=1)
2099+
if throttle_in_pct == 0:
2100+
# finished counting down
2101+
break
2102+
if throttle_in_pct == 100:
2103+
# start counting down
2104+
delta = -delta
2105+
2106+
m = self.wait_message_field_values("COMPASSMOT_STATUS", {
2107+
"throttle": 0,
2108+
}, verbose=True)
2109+
for axis in "X", "Y", "Z":
2110+
fieldname = "Compensation" + axis
2111+
if getattr(m, fieldname) <= 0:
2112+
raise NotAchievedException("Expected non-zero %s" % fieldname)
2113+
2114+
# it's kind of crap - but any command-ack will stop the
2115+
# calibration
2116+
self.mav.mav.command_ack_send(0, 1)
2117+
self.wait_statustext("Calibration successful")
2118+
20582119
def MagFail(self):
20592120
'''test failover of compass in EKF'''
20602121
# we want both EK2 and EK3
@@ -10944,6 +11005,7 @@ def tests2b(self): # this block currently around 9.5mins here
1094411005
self.CameraLogMessages,
1094511006
self.LoiterToGuidedHomeVSOrigin,
1094611007
self.GuidedModeThrust,
11008+
self.CompassMot,
1094711009
])
1094811010
return ret
1094911011

@@ -10975,6 +11037,7 @@ def disabled_tests(self):
1097511037
"FlyMissionTwice": "See https://github.com/ArduPilot/ardupilot/pull/18561",
1097611038
"GPSForYawCompassLearn": "Vehicle currently crashed in spectacular fashion",
1097711039
"GuidedModeThrust": "land detector raises internal error as we're not saying we're about to take off but just did",
11040+
"CompassMot": "Cuases an arithmetic exception in the EKF",
1097811041
}
1097911042

1098011043

0 commit comments

Comments
 (0)