|
|
|
@ -4822,6 +4822,7 @@ class AutoTestCopter(AutoTest):
@@ -4822,6 +4822,7 @@ class AutoTestCopter(AutoTest):
|
|
|
|
|
self.set_parameter("SIM_RICH_CTRL", 8) |
|
|
|
|
self.set_parameter("RC9_OPTION", 85) |
|
|
|
|
self.set_parameter("LOG_DISARMED", 1) |
|
|
|
|
self.set_parameter("BATT2_MONITOR", 17) |
|
|
|
|
self.set_rc(9, 1000) # remember this is a switch position - stop |
|
|
|
|
self.customise_SITL_commandline(["--uartF=sim:richenpower"]) |
|
|
|
|
self.mavproxy.expect("requested state is not RUN") |
|
|
|
@ -4854,6 +4855,19 @@ class AutoTestCopter(AutoTest):
@@ -4854,6 +4855,19 @@ class AutoTestCopter(AutoTest):
|
|
|
|
|
|
|
|
|
|
self.wait_generator_speed_and_state(8000, 30000, mavutil.mavlink.MAV_GENERATOR_STATUS_FLAG_GENERATING) |
|
|
|
|
|
|
|
|
|
bs = self.mav.recv_match( |
|
|
|
|
type="BATTERY_STATUS", |
|
|
|
|
condition="BATTERY_STATUS.id==1", # id is zero-indexed |
|
|
|
|
timeout=1, |
|
|
|
|
blocking=True |
|
|
|
|
) |
|
|
|
|
if bs is None: |
|
|
|
|
raise NotAchievedException("Did not receive BATTERY_STATUS") |
|
|
|
|
self.progress("Received battery status: %s" % str(bs)) |
|
|
|
|
want_bs_volt = 50000 |
|
|
|
|
if bs.voltages[0] != want_bs_volt: |
|
|
|
|
raise NotAchievedException("Battery voltage not as expected (want=%f) got=(%f)" % (want_bs_volt, bs.voltages[0],)) |
|
|
|
|
|
|
|
|
|
self.progress("Moving *back* to idle") |
|
|
|
|
self.set_rc(9, 1500) # remember this is a switch position - idle |
|
|
|
|
self.wait_generator_speed_and_state(3000, 10000, mavutil.mavlink.MAV_GENERATOR_STATUS_FLAG_IDLE) |
|
|
|
|