mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 07:44:03 -04:00
Tools: add script which tells you how Copter.ap changes over time
This is a global state object which we really want to get rid of - but while we have it it does contain some useful state. pbarker@bluebottle:~/rc/ardupilot(pr/du32-change)$ ./Tools/scripts/du32_change.py ~/rc/log32.bin 1648874490: Creating connection Original armed_with_airmode_switch: 0 Original auto_armed: 0 Original compass_mot: 0 Original gps_glitching: 0 Original in_arming_delay: 1 Original initialised: 1 Original initialised_params: 1 Original land_complete: 1 Original land_complete_maybe: 1 Original land_repo_active: 0 Original logging_started: 1 Original motor_interlock_switch: 0 Original motor_test: 0 Original new_radio_frame: 1 Original pre_arm_check: 1 Original pre_arm_rc_check: 1 Original prec_land_active: 0 Original rc_receiver_present: 1 Original system_time_set_unused: 0 Original throttle_zero: 1 Original unused1: 0 Original unused2: 0 Original unused3: 0 Original unused_was_simple_mode bit1: 0 Original unused_was_simple_mode bit2: 0 Original usb_connected_unused: 0 Original using_interlock: 0 2022-04-01 08:19:27.03: -in_arming_delay 2022-04-01 08:19:31.04: +auto_armed -throttle_zero 2022-04-01 08:19:38.04: -land_complete -land_complete_maybe 2022-04-01 08:20:34.29: +throttle_zero 2022-04-01 08:20:35.29: -auto_armed +land_complete +land_complete_maybe pbarker@bluebottle:~/rc/ardupilot(pr/du32-change)$
This commit is contained in:
parent
392e80001f
commit
934a125875
118
Tools/scripts/du32_change.py
Executable file
118
Tools/scripts/du32_change.py
Executable file
@ -0,0 +1,118 @@
|
||||
#!/usr/bin/env python
|
||||
|
||||
"""
|
||||
Parses a log file and shows how Copter's du32 changes over time
|
||||
|
||||
AP_FLAKE8_CLEAN
|
||||
|
||||
"""
|
||||
|
||||
from __future__ import print_function
|
||||
|
||||
import optparse
|
||||
import sys
|
||||
import time
|
||||
|
||||
from pymavlink import mavutil
|
||||
|
||||
|
||||
class DU32Change(object):
|
||||
def __init__(self, master):
|
||||
self.master = master
|
||||
|
||||
def progress(self, text):
|
||||
'''emit text with possible timestamps etc'''
|
||||
print("%u: %s" % (time.time(), text))
|
||||
|
||||
def run(self):
|
||||
|
||||
self.progress("Creating connection")
|
||||
self.conn = mavutil.mavlink_connection(master)
|
||||
|
||||
# this eas was generated from Copter.h's structure for ap_t:
|
||||
bit_descriptions_list = [
|
||||
"unused1",
|
||||
"unused_was_simple_mode bit1",
|
||||
"unused_was_simple_mode bit2",
|
||||
"pre_arm_rc_check",
|
||||
"pre_arm_check",
|
||||
"auto_armed",
|
||||
"logging_started",
|
||||
"land_complete",
|
||||
"new_radio_frame",
|
||||
"usb_connected_unused",
|
||||
"rc_receiver_present",
|
||||
"compass_mot",
|
||||
"motor_test",
|
||||
"initialised",
|
||||
"land_complete_maybe",
|
||||
"throttle_zero",
|
||||
"system_time_set_unused",
|
||||
"gps_glitching",
|
||||
"using_interlock",
|
||||
"land_repo_active",
|
||||
"motor_interlock_switch",
|
||||
"in_arming_delay",
|
||||
"initialised_params",
|
||||
"unused3",
|
||||
"unused2",
|
||||
"armed_with_airmode_switch",
|
||||
"prec_land_active",
|
||||
]
|
||||
bit_descriptions = {}
|
||||
count = 0
|
||||
for bit in bit_descriptions_list:
|
||||
bit_descriptions[bit] = count
|
||||
count += 1
|
||||
|
||||
old_m = None
|
||||
|
||||
desired_type = "DU32"
|
||||
while True:
|
||||
m = self.conn.recv_match(type=desired_type)
|
||||
if m is None:
|
||||
break
|
||||
if m.Id != 7:
|
||||
# 7 is LOG_DATA_ID from AP_Logger.h
|
||||
continue
|
||||
if old_m is not None and m.Value == old_m.Value:
|
||||
continue
|
||||
line = ""
|
||||
if old_m is None:
|
||||
for bit in sorted(bit_descriptions.keys()):
|
||||
bit_set = m.Value & (1 << bit_descriptions[bit])
|
||||
if bit_set:
|
||||
print("Original %s: 1" % bit)
|
||||
else:
|
||||
print("Original %s: 0" % bit)
|
||||
else:
|
||||
for bit in bit_descriptions.keys():
|
||||
old_bit_set = old_m.Value & (1 << bit_descriptions[bit])
|
||||
new_bit_set = m.Value & (1 << bit_descriptions[bit])
|
||||
if new_bit_set and not old_bit_set:
|
||||
line += " +%s" % bit
|
||||
elif not new_bit_set and old_bit_set:
|
||||
line += " -%s" % bit
|
||||
|
||||
timestamp = getattr(m, '_timestamp', 0.0)
|
||||
formatted_timestamp = "%s.%02u" % (
|
||||
time.strftime("%Y-%m-%d %H:%M:%S", time.localtime(timestamp)),
|
||||
int(timestamp * 100.0) % 100)
|
||||
|
||||
print("%s: %s" % (formatted_timestamp, line))
|
||||
old_m = m
|
||||
|
||||
|
||||
if __name__ == '__main__':
|
||||
parser = optparse.OptionParser("du32_change.py [options]")
|
||||
|
||||
(opts, args) = parser.parse_args()
|
||||
|
||||
if len(args) < 1:
|
||||
parser.print_help()
|
||||
sys.exit(1)
|
||||
|
||||
master = args[0]
|
||||
|
||||
tester = DU32Change(master)
|
||||
tester.run()
|
Loading…
Reference in New Issue
Block a user