Path: blob/master/Tools/scripts/CAN/CAN_playback.py
9460 views
#!/usr/bin/env python312# flake8: noqa34'''5playback a set of CAN frames6capture frames either using libraries/AP_Scripting/examples/CAN_logger.lua7or the CAN_Pn_OPTIONS bit to enable CAN logging8'''910import dronecan11import time12import sys13import threading14from pymavlink import mavutil15from dronecan.driver.common import CANFrame16import struct171819# get command line arguments20from argparse import ArgumentParser21parser = ArgumentParser(description='CAN playback')22parser.add_argument("logfile", default=None, type=str, help="logfile")23parser.add_argument("canport", default=None, type=str, help="CAN port")24parser.add_argument("--bus", default=0, type=int, help="CAN bus")25parser.add_argument("--nodes", default=None, type=str, help="comma separated list of source node IDs to send")26parser.add_argument("--messageids", default=None, type=str, help="comma separated list of DroneCAN message IDs to send")2728args = parser.parse_args()2930node_filter = None31if args.nodes is not None:32node_filter = set(int(n) for n in args.nodes.split(','))3334msgid_filter = None35if args.messageids is not None:36msgid_filter = set(int(n, 0) for n in args.messageids.split(','))3738print("Connecting to %s" % args.canport)39driver = dronecan.driver.make_driver(args.canport)4041print("Opening %s" % args.logfile)42mlog = mavutil.mavlink_connection(args.logfile)4344tstart = time.time()45first_tstamp = None4647def dlc_to_datalength(dlc):48# Data Length Code 9 10 11 12 13 14 1549# Number of data bytes 12 16 20 24 32 48 6450if (dlc <= 8):51return dlc52elif (dlc == 9):53return 1254elif (dlc == 10):55return 1656elif (dlc == 11):57return 2058elif (dlc == 12):59return 2460elif (dlc == 13):61return 3262elif (dlc == 14):63return 4864return 646566while True:67m = mlog.recv_match(type=['CANF','CAFD'])6869if m is None:70print("Rewinding")71mlog.rewind()72tstart = time.time()73first_tstamp = None74continue7576if getattr(m,'bus',0) != args.bus:77continue7879if node_filter is not None and (m.Id & 0x7F) not in node_filter:80continue8182if msgid_filter is not None:83is_message = (m.Id & 0x7F) != 0 and (m.Id & (1 << 7)) == 084msgId = ((m.Id >> 8) & 0xFFFF)85if not is_message or msgId not in msgid_filter:86print("skip 0x%04x" % msgId, is_message)87continue8889if first_tstamp is None:90first_tstamp = m.TimeUS91dt = time.time() - tstart92dt2 = (m.TimeUS - first_tstamp)*1.0e-693if dt2 > dt:94time.sleep(dt2 - dt)9596canfd = m.get_type() == 'CAFD'97if canfd:98data = struct.pack("<QQQQQQQQ", m.D0, m.D1, m.D2, m.D3, m.D4, m.D5, m.D6, m.D7)99data = data[:dlc_to_datalength(m.DLC)]100else:101data = struct.pack("<BBBBBBBB", m.B0, m.B1, m.B2, m.B3, m.B4, m.B5, m.B6, m.B7)102data = data[:m.DLC]103104fid = m.Id105is_extended = (fid & (1<<31)) != 0106driver.send(fid, data, extended=is_extended, canfd=canfd)107print(m)108109110