forked from ArduPilot/ardupilot
-
Notifications
You must be signed in to change notification settings - Fork 0
Commit
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
uses frames from lua CAN bus capture and plays back for driver development
- Loading branch information
Showing
1 changed file
with
52 additions
and
0 deletions.
There are no files selected for viewing
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
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,52 @@ | ||
#!/usr/bin/env python3 | ||
''' | ||
playback a set of CAN frames from libraries/AP_Scripting/examples/CAN_logger.lua onto a CAN bus | ||
''' | ||
|
||
import dronecan | ||
import time | ||
import sys | ||
import threading | ||
from pymavlink import mavutil | ||
from dronecan.driver.common import CANFrame | ||
|
||
|
||
# get command line arguments | ||
from argparse import ArgumentParser | ||
parser = ArgumentParser(description='CAN playback') | ||
parser.add_argument("logfile", default=None, type=str, help="logfile") | ||
parser.add_argument("canport", default=None, type=str, help="CAN port") | ||
|
||
args = parser.parse_args() | ||
|
||
print("Connecting to %s" % args.canport) | ||
driver = dronecan.driver.make_driver(args.canport) | ||
|
||
print("Opening %s" % args.logfile) | ||
mlog = mavutil.mavlink_connection(args.logfile) | ||
|
||
tstart = time.time() | ||
first_tstamp = None | ||
|
||
while True: | ||
m = mlog.recv_match(type='CANF') | ||
|
||
if m is None: | ||
print("Rewinding") | ||
mlog.rewind() | ||
tstart = time.time() | ||
first_tstamp = None | ||
continue | ||
|
||
if first_tstamp is None: | ||
first_tstamp = m.TimeUS | ||
dt = time.time() - tstart | ||
dt2 = (m.TimeUS - first_tstamp)*1.0e-6 | ||
if dt2 > dt: | ||
time.sleep(dt2 - dt) | ||
data = [m.B0, m.B1, m.B2, m.B3, m.B4, m.B5, m.B6, m.B7] | ||
data = data[:m.DLC] | ||
fid = m.Id | ||
is_extended = (fid & (1<<31)) != 0 | ||
driver.send(fid, data, extended=is_extended, canfd=False) | ||
print(m) |