Created
November 2, 2020 23:39
-
-
Save jaxxzer/23325a7f87c51161801cad709c7e02ac to your computer and use it in GitHub Desktop.
Verify Pixhawk SD card
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
#!/usr/bin/python | |
# - verify that logging to sd card is working OK | |
import os | |
import time | |
from pymavlink import mavutil | |
from argparse import ArgumentParser | |
parser = ArgumentParser(description=__doc__) | |
parser.add_argument("--port", dest="port", required=True, help="Serial port of the device to erase") | |
parser.add_argument("--baudrate", dest="baudrate", type=int, default=115200, help="Baudrate to use for device communications") | |
args = parser.parse_args() | |
def wait_msg(msg_type, timeout): | |
start = time.time() | |
print(start) | |
while time.time() < start + timeout: | |
msg = master.recv_match() | |
while msg is not None: | |
print(msg) | |
if msg.get_type() == msg_type: | |
return msg | |
msg = master.recv_match() | |
time.sleep(0.001) | |
return None | |
while not os.path.exists(args.port): | |
print("waiting for connection to %s" % args.port) | |
time.sleep(0.5) | |
master = mavutil.mavlink_connection(args.port, args.baudrate) | |
master.target_system = 1 | |
master.target_component = 1 | |
print("waiting for autopilot heartbeat...") | |
master.wait_heartbeat() | |
print("waiting for SYS_STATUS...") | |
master.param_set_send("SR0_EXT_STAT",10) | |
msg = wait_msg("SYS_STATUS", 0.1) | |
while msg is None: | |
master.mav.heartbeat_send(6,8,0,0,0) | |
master.param_set_send("SR0_EXT_STAT",10) | |
msg = wait_msg("SYS_STATUS", 0.1) | |
print("arming...") | |
master.mav.heartbeat_send(0,0,0,0,0) | |
master.mav.command_long_send( | |
1, # target_system | |
1, | |
400, # MAV_CMD_COMPONENT_ARM_DISARM - arm | |
0, # confirmation | |
1, # param1 (1 to indicate arm) | |
0, # param2 (all other params meaningless) | |
0, # param3 | |
0, # param4 | |
0, # param5 | |
0, # param6 | |
0) # param7 | |
print("checking that logging to sd card is ok...") | |
# drain the autopilot output, otherwise the next step may not actually wait 2 seconds | |
while wait_msg("SYS_STATUS", 0.01) is not None: | |
continue | |
# check SYS_STATUS for 2 seconds (20 * 10Hz) | |
for x in range(20): | |
msg = None | |
while msg is None: | |
msg = wait_msg("SYS_STATUS", 0.1) | |
if not (msg.onboard_control_sensors_health & 0x1000000): | |
print("logging is NOT ok!!!!") | |
print("check the SD card") | |
master.close() | |
exit(1) | |
print("logging is ok") | |
master.close() | |
Sign up for free
to join this conversation on GitHub.
Already have an account?
Sign in to comment