mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-05 15:33:57 -04:00
LogAnalyzer: adjust for change in vehicle definition MSG string
We changed from ArduCopter to APM:Copter, breaking parts of the LogAnalyzer This change has LogAnalyzer canonicalise its output to Ardu{Plane,Rover,Copter} Also account for change in MODE message - ThrCrs has gone away
This commit is contained in:
parent
0c61e09b70
commit
e357be3d85
@ -12,6 +12,8 @@ import bisect
|
||||
import sys
|
||||
import ctypes
|
||||
|
||||
from VehicleType import VehicleType, VehicleTypeString
|
||||
|
||||
class Format(object):
|
||||
'''Data channel format as specified by the FMT lines in the log file'''
|
||||
def __init__(self,msgType,msgLen,name,types,labels):
|
||||
@ -383,7 +385,7 @@ class DataflashLogHelper:
|
||||
'''returns an human readable error string if the log is essentially empty, otherwise returns None'''
|
||||
# naive check for now, see if the throttle output was ever above 20%
|
||||
throttleThreshold = 20
|
||||
if logdata.vehicleType == "ArduCopter":
|
||||
if logdata.vehicleType == VehicleType.Copter:
|
||||
throttleThreshold = 200 # copter uses 0-1000, plane+rover use 0-100
|
||||
if "CTUN" in logdata.channels:
|
||||
maxThrottle = logdata.channels["CTUN"]["ThrOut"].max()
|
||||
@ -403,7 +405,8 @@ class DataflashLog(object):
|
||||
def __init__(self, logfile=None, format="auto", ignoreBadlines=False):
|
||||
self.filename = None
|
||||
|
||||
self.vehicleType = "" # ArduCopter, ArduPlane, ArduRover, etc, verbatim as given by header
|
||||
self.vehicleType = None # from VehicleType enumeration; value derived from header
|
||||
self.vehicleTypeString = None # set at same time has the enum value
|
||||
self.firmwareVersion = ""
|
||||
self.firmwareHash = ""
|
||||
self.freeRAM = 0
|
||||
@ -425,7 +428,7 @@ class DataflashLog(object):
|
||||
|
||||
def getCopterType(self):
|
||||
'''returns quad/hex/octo/tradheli if this is a copter log'''
|
||||
if self.vehicleType != "ArduCopter":
|
||||
if self.vehicleType != VehicleType.Copter:
|
||||
return None
|
||||
motLabels = []
|
||||
if "MOT" in self.formats: # not listed in PX4 log header for some reason?
|
||||
@ -492,6 +495,22 @@ class DataflashLog(object):
|
||||
# TODO: calculate logging rate based on timestamps
|
||||
# ...
|
||||
|
||||
msg_vehicle_to_vehicle_map = {
|
||||
"ArduCopter": VehicleType.Copter,
|
||||
"APM:Copter": VehicleType.Copter,
|
||||
"ArduPlane": VehicleType.Plane,
|
||||
"ArduRover": VehicleType.Rover
|
||||
}
|
||||
|
||||
# takes the vehicle type supplied via "MSG" and sets vehicleType from
|
||||
# the VehicleType enumeration
|
||||
def set_vehicleType_from_MSG_vehicle(self, MSG_vehicle):
|
||||
ret = self.msg_vehicle_to_vehicle_map.get(MSG_vehicle, None)
|
||||
if ret is None:
|
||||
raise ValueError("Unknown vehicle type (%s)" % (MSG_vehicle))
|
||||
self.vehicleType = ret
|
||||
self.vehicleTypeString = VehicleTypeString[ret]
|
||||
|
||||
def process(self, lineNumber, e):
|
||||
if e.NAME == 'FMT':
|
||||
cls = e.to_class()
|
||||
@ -505,15 +524,14 @@ class DataflashLog(object):
|
||||
elif e.NAME == "MSG":
|
||||
if not self.vehicleType:
|
||||
tokens = e.Message.split(' ')
|
||||
vehicleTypes = ["ArduPlane", "ArduCopter", "ArduRover"]
|
||||
self.vehicleType = tokens[0]
|
||||
self.set_vehicleType_from_MSG_vehicle(tokens[0]);
|
||||
self.firmwareVersion = tokens[1]
|
||||
if len(tokens) == 3:
|
||||
self.firmwareHash = tokens[2][1:-1]
|
||||
else:
|
||||
self.messages[lineNumber] = e.Message
|
||||
elif e.NAME == "MODE":
|
||||
if self.vehicleType in ["ArduCopter"]:
|
||||
if self.vehicleType == VehicleType.Copter:
|
||||
try:
|
||||
modes = {0:'STABILIZE',
|
||||
1:'ACRO',
|
||||
@ -530,13 +548,21 @@ class DataflashLog(object):
|
||||
14:'FLIP',
|
||||
15:'AUTOTUNE',
|
||||
16:'HYBRID',}
|
||||
self.modeChanges[lineNumber] = (modes[int(e.Mode)], e.ThrCrs)
|
||||
if hasattr(e, 'ThrCrs'):
|
||||
self.modeChanges[lineNumber] = (modes[int(e.Mode)], e.ThrCrs)
|
||||
else:
|
||||
# assume it has ModeNum:
|
||||
self.modeChanges[lineNumber] = (modes[int(e.Mode)], e.ModeNum)
|
||||
except:
|
||||
self.modeChanges[lineNumber] = (e.Mode, e.ThrCrs)
|
||||
elif self.vehicleType in ["ArduPlane", "APM:Plane", "ArduRover", "APM:Rover", "APM:Copter"]:
|
||||
if hasattr(e, 'ThrCrs'):
|
||||
self.modeChanges[lineNumber] = (e.Mode, e.ThrCrs)
|
||||
else:
|
||||
# assume it has ModeNum:
|
||||
self.modeChanges[lineNumber] = (e.Mode, e.ModeNum)
|
||||
elif self.vehicleType in [VehicleType.Plane, VehicleType.Copter, VehicleType.Rover]:
|
||||
self.modeChanges[lineNumber] = (e.Mode, e.ModeNum)
|
||||
else:
|
||||
raise Exception("Unknown log type for MODE line vehicletype=({}) linw=({})".format(self.vehicleType, repr(e)))
|
||||
raise Exception("Unknown log type for MODE line vehicletype=({}) linw=({})".format(self.vehicleTypeString, repr(e)))
|
||||
# anything else must be the log data
|
||||
else:
|
||||
groupName = e.NAME
|
||||
@ -583,7 +609,7 @@ class DataflashLog(object):
|
||||
elif tokens2[0] in knownHardwareTypes:
|
||||
self.hardwareType = line # not sure if we can parse this more usefully, for now only need to report it back verbatim
|
||||
elif (len(tokens2) == 2 or len(tokens2) == 3) and tokens2[1][0].lower() == "v": # e.g. ArduCopter V3.1 (5c6503e2)
|
||||
self.vehicleType = tokens2[0]
|
||||
self.set_vehicleType_from_MSG_vehicle(tokens2[0])
|
||||
self.firmwareVersion = tokens2[1]
|
||||
if len(tokens2) == 3:
|
||||
self.firmwareHash = tokens2[2][1:-1]
|
||||
|
@ -30,6 +30,7 @@ import datetime
|
||||
import time
|
||||
from xml.sax.saxutils import escape
|
||||
|
||||
from VehicleType import VehicleType
|
||||
|
||||
class TestResult(object):
|
||||
'''all tests return a standardized result type'''
|
||||
@ -96,10 +97,10 @@ class TestSuite(object):
|
||||
print 'Log size: %.2fmb (%d lines)' % (self.logdata.filesizeKB / 1024.0, self.logdata.lineCount)
|
||||
print 'Log duration: %s' % str(datetime.timedelta(seconds=self.logdata.durationSecs)) + '\n'
|
||||
|
||||
if self.logdata.vehicleType == "ArduCopter" and self.logdata.getCopterType():
|
||||
print 'Vehicle Type: %s (%s)' % (self.logdata.vehicleType, self.logdata.getCopterType())
|
||||
if self.logdata.vehicleType == VehicleType.Copter and self.logdata.getCopterType():
|
||||
print 'Vehicle Type: %s (%s)' % (self.logdata.vehicleTypeString, self.logdata.getCopterType())
|
||||
else:
|
||||
print 'Vehicle Type: %s' % self.logdata.vehicleType
|
||||
print 'Vehicle Type: %s' % self.logdata.vehicleTypeString
|
||||
print 'Firmware Version: %s (%s)' % (self.logdata.firmwareVersion, self.logdata.firmwareHash)
|
||||
print 'Hardware: %s' % self.logdata.hardwareType
|
||||
print 'Free RAM: %s' % self.logdata.freeRAM
|
||||
@ -158,8 +159,8 @@ class TestSuite(object):
|
||||
print >>xml, " <sizekb>" + escape(`self.logdata.filesizeKB`) + "</sizekb>"
|
||||
print >>xml, " <sizelines>" + escape(`self.logdata.lineCount`) + "</sizelines>"
|
||||
print >>xml, " <duration>" + escape(str(datetime.timedelta(seconds=self.logdata.durationSecs))) + "</duration>"
|
||||
print >>xml, " <vehicletype>" + escape(self.logdata.vehicleType) + "</vehicletype>"
|
||||
if self.logdata.vehicleType == "ArduCopter" and self.logdata.getCopterType():
|
||||
print >>xml, " <vehicletype>" + escape(self.logdata.vehicleTypeString) + "</vehicletype>"
|
||||
if self.logdata.vehicleType == VehicleType.Copter and self.logdata.getCopterType():
|
||||
print >>xml, " <coptertype>" + escape(self.logdata.getCopterType()) + "</coptertype>"
|
||||
print >>xml, " <firmwareversion>" + escape(self.logdata.firmwareVersion) + "</firmwareversion>"
|
||||
print >>xml, " <firmwarehash>" + escape(self.logdata.firmwareHash) + "</firmwarehash>"
|
||||
|
@ -9,6 +9,7 @@
|
||||
|
||||
import DataflashLog
|
||||
import traceback
|
||||
from VehicleType import VehicleType
|
||||
|
||||
try:
|
||||
|
||||
@ -16,7 +17,8 @@ try:
|
||||
logdata = DataflashLog.DataflashLog()
|
||||
logdata.read("examples/robert_lefebvre_octo_PM.log", ignoreBadlines=False)
|
||||
assert(logdata.filename == "examples/robert_lefebvre_octo_PM.log")
|
||||
assert(logdata.vehicleType == "ArduCopter")
|
||||
assert(logdata.vehicleType == VehicleType.Copter)
|
||||
assert(logdata.vehicleTypeString == "ArduCopter")
|
||||
assert(logdata.firmwareVersion == "V3.0.1")
|
||||
assert(logdata.firmwareHash == "5c6503e2")
|
||||
assert(logdata.freeRAM == 1331)
|
||||
@ -38,7 +40,7 @@ try:
|
||||
assert(logdata.channels['CTUN']['CRate'].listData[3] == (317, 35))
|
||||
assert(logdata.channels['CTUN']['CRate'].listData[51] == (421, 31))
|
||||
assert(logdata.channels['CTUN']['CRate'].listData[115] == (563, -8))
|
||||
assert(int(logdata.filesizeKB) == 302)
|
||||
assert(int(logdata.filesizeKB) == 307)
|
||||
assert(logdata.durationSecs == 155)
|
||||
assert(logdata.lineCount == 4750)
|
||||
|
||||
|
12
Tools/LogAnalyzer/VehicleType.py
Normal file
12
Tools/LogAnalyzer/VehicleType.py
Normal file
@ -0,0 +1,12 @@
|
||||
class VehicleType():
|
||||
Plane = 17
|
||||
Copter = 23
|
||||
Rover = 37
|
||||
|
||||
# these should really be "Plane", "Copter" and "Rover", but many
|
||||
# things use these values as triggers in their code:
|
||||
VehicleTypeString = {
|
||||
17: "ArduPlane",
|
||||
23: "ArduCopter",
|
||||
37: "ArduRover"
|
||||
}
|
Loading…
Reference in New Issue
Block a user