From bdc615e4cc6b2b80d32f92a570af223738494769 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 21 Mar 2020 09:38:10 +1100 Subject: [PATCH] Tools: added rcda_decode script --- Tools/scripts/rcda_decode.py | 51 ++++++++++++++++++++++++++++++++++++ 1 file changed, 51 insertions(+) create mode 100755 Tools/scripts/rcda_decode.py diff --git a/Tools/scripts/rcda_decode.py b/Tools/scripts/rcda_decode.py new file mode 100755 index 0000000000..bd2910cd4d --- /dev/null +++ b/Tools/scripts/rcda_decode.py @@ -0,0 +1,51 @@ +#!/usr/bin/env python + +''' +decode RCDA messages from a log and optionally play back to a serial port. The RCDA message is +captures RC input bytes when RC_OPTIONS=16 is set +''' + +import struct + +from argparse import ArgumentParser +parser = ArgumentParser(description=__doc__) +parser.add_argument("--condition", default=None, help="select packets by condition") +parser.add_argument("--baudrate", type=int, default=115200, help="baudrate") +parser.add_argument("--port", type=str, default=None, help="port") +parser.add_argument("--delay-mul", type=float, default=1.0, help="delay multiplier") +parser.add_argument("log", metavar="LOG") +import time +import serial + +args = parser.parse_args() + +from pymavlink import mavutil + +print("Processing log %s" % args.log) +mlog = mavutil.mavlink_connection(args.log) + +if args.port: + port = serial.Serial(args.port, args.baudrate, timeout=1.0) + +tlast = -1 +counter = 0 + +while True: + msg = mlog.recv_match(type=['RCDA'], condition=args.condition) + if msg is None: + mlog.rewind() + tlast = -1 + continue + tnow = msg.TimeUS + if tlast == -1: + tlast = tnow + buf = struct.pack("