mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-03 12:14:10 -04:00
LogAnalyzer: added PM slow loop check, first version of xml output
This commit is contained in:
parent
36e480483f
commit
8d691c2a60
@ -130,7 +130,7 @@ class DataflashLog:
|
|||||||
|
|
||||||
vehicleType = None # ArduCopter, ArduPlane, ArduRover, etc, verbatim as given by header
|
vehicleType = None # ArduCopter, ArduPlane, ArduRover, etc, verbatim as given by header
|
||||||
firmwareVersion = None
|
firmwareVersion = None
|
||||||
firmwareHash = None
|
firmwareHash = ""
|
||||||
freeRAM = None
|
freeRAM = None
|
||||||
hardwareType = None # APM 1, APM 2, PX4, MPNG, etc What is VRBrain? BeagleBone, etc? Needs more testing
|
hardwareType = None # APM 1, APM 2, PX4, MPNG, etc What is VRBrain? BeagleBone, etc? Needs more testing
|
||||||
|
|
||||||
@ -141,7 +141,7 @@ class DataflashLog:
|
|||||||
channels = {} # lineLabel -> {dataLabel:Channel}
|
channels = {} # lineLabel -> {dataLabel:Channel}
|
||||||
|
|
||||||
filesizeKB = None
|
filesizeKB = None
|
||||||
durationSecs = None
|
durationSecs = 0
|
||||||
lineCount = None
|
lineCount = None
|
||||||
|
|
||||||
def getCopterType(self):
|
def getCopterType(self):
|
||||||
|
@ -80,7 +80,7 @@ class TestSuite:
|
|||||||
startTime = time.time()
|
startTime = time.time()
|
||||||
test.run(self.logdata) # RUN THE TEST
|
test.run(self.logdata) # RUN THE TEST
|
||||||
endTime = time.time()
|
endTime = time.time()
|
||||||
test.execTime = endTime-startTime
|
test.execTime = 1000 * (endTime-startTime)
|
||||||
|
|
||||||
def outputPlainText(self, outputStats):
|
def outputPlainText(self, outputStats):
|
||||||
print 'Dataflash log analysis report for file: ' + self.logfile
|
print 'Dataflash log analysis report for file: ' + self.logfile
|
||||||
@ -119,19 +119,80 @@ class TestSuite:
|
|||||||
print " %20s %s" % ("",line)
|
print " %20s %s" % ("",line)
|
||||||
print '\n'
|
print '\n'
|
||||||
|
|
||||||
|
|
||||||
# temp - test some spot values
|
|
||||||
#print "GPS abs alt on line 24126 is " + `self.logdata.channels["GPS"]["Alt"].dictData[24126]` # 52.03
|
|
||||||
#print "ATT pitch on line 22153 is " + `self.logdata.channels["ATT"]["Pitch"].dictData[22153]` # -7.03
|
|
||||||
#gpsAlt = self.logdata.channels["GPS"]["Alt"]
|
|
||||||
#print "All GPS Alt data: %s\n\n" % gpsAlt.dictData
|
|
||||||
#gpsAltSeg = gpsAlt.getSegment(426,711)
|
|
||||||
#print "Segment of GPS Alt data from %d to %d: %s\n\n" % (426,711,gpsAltSeg.dictData)
|
|
||||||
|
|
||||||
def outputXML(self, xmlFile):
|
def outputXML(self, xmlFile):
|
||||||
# TODO: implement XML output
|
# TODO: implement XML output
|
||||||
# ...
|
|
||||||
raise Exception("outputXML() not implemented yet")
|
xml = None
|
||||||
|
try:
|
||||||
|
xml = open(xmlFile, 'w')
|
||||||
|
except:
|
||||||
|
sys.stderr.write("Error opening output xml file: %s" % xmlFile)
|
||||||
|
sys.exit(1)
|
||||||
|
|
||||||
|
print >>xml, "<?xml version=\"1.0\" encoding=\"UTF-8\"?>"
|
||||||
|
print >>xml, "<loganalysis>"
|
||||||
|
|
||||||
|
# output header info
|
||||||
|
print >>xml, "<header>"
|
||||||
|
print >>xml, " <logfile>" + self.logfile + "</logfile>"
|
||||||
|
print >>xml, " <sizekb>" + `self.logdata.filesizeKB` + "</sizekb>"
|
||||||
|
print >>xml, " <sizelines>" + `self.logdata.lineCount` + "</sizelines>"
|
||||||
|
print >>xml, " <duration>" + str(datetime.timedelta(seconds=self.logdata.durationSecs)) + "</duration>"
|
||||||
|
print >>xml, " <vehicletype>" + self.logdata.vehicleType + "</vehicletype>"
|
||||||
|
if self.logdata.vehicleType == "ArduCopter" and self.logdata.getCopterType():
|
||||||
|
print >>xml, " <coptertype>" + self.logdata.getCopterType() + "</coptertype>"
|
||||||
|
print >>xml, " <firmwareversion>" + self.logdata.firmwareVersion + "</firmwareversion>"
|
||||||
|
print >>xml, " <firmwarehash>" + self.logdata.firmwareHash + "</firmwarehash>"
|
||||||
|
print >>xml, " <hardwaretype>" + self.logdata.hardwareType + "</hardwaretype>"
|
||||||
|
print >>xml, " <freemem>" + `self.logdata.freeRAM` + "</freemem>"
|
||||||
|
print >>xml, "</header>"
|
||||||
|
|
||||||
|
# output parameters
|
||||||
|
print >>xml, "<params>"
|
||||||
|
for param, value in self.logdata.parameters.items():
|
||||||
|
print >>xml, " <param name=\"%s\" value=\"%s\" />" % (param,`value`)
|
||||||
|
#print >>xml, " <paramname>" + param + "</paramname>"
|
||||||
|
#print >>xml, " <paramvalue>" + `value` + "</paramvalue>"
|
||||||
|
#print >>xml, " </param>"
|
||||||
|
print >>xml, "</params>"
|
||||||
|
|
||||||
|
# output test results
|
||||||
|
print >>xml, "<results>"
|
||||||
|
for test in self.tests:
|
||||||
|
if not test.enable:
|
||||||
|
continue
|
||||||
|
print >>xml, " <result>"
|
||||||
|
if test.result.status == TestResult.StatusType.PASS:
|
||||||
|
print >>xml, " <name>" + test.name + "</name>"
|
||||||
|
print >>xml, " <status>PASS</status>"
|
||||||
|
print >>xml, " <message>" + test.result.statusMessage + "</message>"
|
||||||
|
print >>xml, " <extrafeedback>" + test.result.extraFeedback + "</extrafeedback>"
|
||||||
|
elif test.result.status == TestResult.StatusType.FAIL:
|
||||||
|
print >>xml, " <name>" + test.name + "</name>"
|
||||||
|
print >>xml, " <status>FAIL</status>"
|
||||||
|
print >>xml, " <message>" + test.result.statusMessage + "</message>"
|
||||||
|
print >>xml, " <extrafeedback>" + test.result.extraFeedback + "</extrafeedback>"
|
||||||
|
print >>xml, " <data>(test data will be embeded here at some point)</data>"
|
||||||
|
elif test.result.status == TestResult.StatusType.WARN:
|
||||||
|
print >>xml, " <name>" + test.name + "</name>"
|
||||||
|
print >>xml, " <status>WARN</status>"
|
||||||
|
print >>xml, " <message>" + test.result.statusMessage + "</message>"
|
||||||
|
print >>xml, " <extrafeedback>" + test.result.extraFeedback + "</extrafeedback>"
|
||||||
|
print >>xml, " <data>(test data will be embeded here at some point)</data>"
|
||||||
|
elif test.result.status == TestResult.StatusType.NA:
|
||||||
|
# skip any that aren't relevant for this vehicle/hardware/etc
|
||||||
|
continue
|
||||||
|
else:
|
||||||
|
print >>xml, " <name>" + test.name + "</name>"
|
||||||
|
print >>xml, " <status>UNKNOWN</status>"
|
||||||
|
print >>xml, " <message>" + test.result.statusMessage + "</message>"
|
||||||
|
print >>xml, " <extrafeedback>" + test.result.extraFeedback + "</extrafeedback>"
|
||||||
|
print >>xml, " </result>"
|
||||||
|
print >>xml, "</results>"
|
||||||
|
|
||||||
|
print >>xml, "</loganalysis>"
|
||||||
|
|
||||||
|
xml.close()
|
||||||
|
|
||||||
|
|
||||||
def main():
|
def main():
|
||||||
@ -177,6 +238,13 @@ def main():
|
|||||||
if not args.quiet:
|
if not args.quiet:
|
||||||
print "XML output written to file: %s\n" % args.xml
|
print "XML output written to file: %s\n" % args.xml
|
||||||
|
|
||||||
|
# temp - test some spot values - include a bunch of this in a unit test at some point
|
||||||
|
#print "GPS abs alt on line 24126 is " + `self.logdata.channels["GPS"]["Alt"].dictData[24126]` # 52.03
|
||||||
|
#print "ATT pitch on line 22153 is " + `self.logdata.channels["ATT"]["Pitch"].dictData[22153]` # -7.03
|
||||||
|
#gpsAlt = self.logdata.channels["GPS"]["Alt"]
|
||||||
|
#print "All GPS Alt data: %s\n\n" % gpsAlt.dictData
|
||||||
|
#gpsAltSeg = gpsAlt.getSegment(426,711)
|
||||||
|
#print "Segment of GPS Alt data from %d to %d: %s\n\n" % (426,711,gpsAltSeg.dictData)
|
||||||
|
|
||||||
if __name__ == "__main__":
|
if __name__ == "__main__":
|
||||||
main()
|
main()
|
||||||
|
368
Tools/LogAnalyzer/example_output.xml
Normal file
368
Tools/LogAnalyzer/example_output.xml
Normal file
@ -0,0 +1,368 @@
|
|||||||
|
<?xml version="1.0" encoding="UTF-8"?>
|
||||||
|
<loganalysis>
|
||||||
|
<header>
|
||||||
|
<logfile>logs/robert_lefebvre_octo_PM.log</logfile>
|
||||||
|
<sizekb>302.744140625</sizekb>
|
||||||
|
<sizelines>4750</sizelines>
|
||||||
|
<duration>0:02:35</duration>
|
||||||
|
<vehicletype>ArduCopter</vehicletype>
|
||||||
|
<coptertype>octo</coptertype>
|
||||||
|
<firmwareversion>V3.0.1</firmwareversion>
|
||||||
|
<firmwarehash></firmwarehash>
|
||||||
|
<hardwaretype>APM 2</hardwaretype>
|
||||||
|
<freemem>1331</freemem>
|
||||||
|
</header>
|
||||||
|
<params>
|
||||||
|
<param name="RC7_REV" value="1.0" />
|
||||||
|
<param name="MNT_MODE" value="3.0" />
|
||||||
|
<param name="LOITER_LON_P" value="1.0" />
|
||||||
|
<param name="FLTMODE1" value="1.0" />
|
||||||
|
<param name="FLTMODE3" value="0.0" />
|
||||||
|
<param name="FLTMODE2" value="6.0" />
|
||||||
|
<param name="TUNE_HIGH" value="10000.0" />
|
||||||
|
<param name="FLTMODE4" value="5.0" />
|
||||||
|
<param name="FLTMODE6" value="2.0" />
|
||||||
|
<param name="SYSID_SW_TYPE" value="10.0" />
|
||||||
|
<param name="LOITER_LON_D" value="0.0" />
|
||||||
|
<param name="RC5_REV" value="1.0" />
|
||||||
|
<param name="THR_RATE_IMAX" value="300.0" />
|
||||||
|
<param name="MNT_RC_IN_PAN" value="0.0" />
|
||||||
|
<param name="RC2_MIN" value="1110.0" />
|
||||||
|
<param name="LOITER_LON_I" value="0.5" />
|
||||||
|
<param name="HLD_LON_P" value="1.0" />
|
||||||
|
<param name="STB_RLL_I" value="0.0" />
|
||||||
|
<param name="LOW_VOLT" value="10.5" />
|
||||||
|
<param name="MNT_CONTROL_Y" value="0.0" />
|
||||||
|
<param name="MNT_CONTROL_X" value="0.0" />
|
||||||
|
<param name="FRAME" value="1.0" />
|
||||||
|
<param name="MNT_CONTROL_Z" value="0.0" />
|
||||||
|
<param name="OF_PIT_IMAX" value="100.0" />
|
||||||
|
<param name="AHRS_ORIENTATION" value="0.0" />
|
||||||
|
<param name="SIMPLE" value="0.0" />
|
||||||
|
<param name="RC2_MAX" value="1929.0" />
|
||||||
|
<param name="MNT_JSTICK_SPD" value="0.0" />
|
||||||
|
<param name="RC8_FUNCTION" value="0.0" />
|
||||||
|
<param name="INS_ACCSCAL_X" value="0.992788" />
|
||||||
|
<param name="ACRO_P" value="4.5" />
|
||||||
|
<param name="MNT_ANGMIN_ROL" value="-4500.0" />
|
||||||
|
<param name="OF_RLL_P" value="2.5" />
|
||||||
|
<param name="STB_RLL_P" value="3.5" />
|
||||||
|
<param name="STB_YAW_P" value="3.0" />
|
||||||
|
<param name="SR0_RAW_SENS" value="2.0" />
|
||||||
|
<param name="FLTMODE5" value="0.0" />
|
||||||
|
<param name="RATE_YAW_I" value="0.02" />
|
||||||
|
<param name="MAG_ENABLE" value="1.0" />
|
||||||
|
<param name="MNT_RETRACT_Y" value="0.0" />
|
||||||
|
<param name="MNT_RETRACT_X" value="0.0" />
|
||||||
|
<param name="RATE_YAW_IMAX" value="800.0" />
|
||||||
|
<param name="WPNAV_SPEED_DN" value="150.0" />
|
||||||
|
<param name="WP_YAW_BEHAVIOR" value="2.0" />
|
||||||
|
<param name="RC11_REV" value="1.0" />
|
||||||
|
<param name="SYSID_THISMAV" value="1.0" />
|
||||||
|
<param name="SR0_EXTRA1" value="10.0" />
|
||||||
|
<param name="SR0_EXTRA2" value="10.0" />
|
||||||
|
<param name="ACRO_BAL_PITCH" value="200.0" />
|
||||||
|
<param name="STB_YAW_I" value="0.0" />
|
||||||
|
<param name="INS_ACCSCAL_Z" value="0.97621" />
|
||||||
|
<param name="INS_ACCSCAL_Y" value="1.00147" />
|
||||||
|
<param name="LED_MODE" value="9.0" />
|
||||||
|
<param name="FS_GCS_ENABLE" value="0.0" />
|
||||||
|
<param name="MNT_RC_IN_ROLL" value="0.0" />
|
||||||
|
<param name="INAV_TC_Z" value="8.0" />
|
||||||
|
<param name="RATE_PIT_IMAX" value="4500.0" />
|
||||||
|
<param name="HLD_LON_IMAX" value="3000.0" />
|
||||||
|
<param name="THR_RATE_I" value="0.0" />
|
||||||
|
<param name="SR3_EXTRA1" value="0.0" />
|
||||||
|
<param name="STB_PIT_IMAX" value="800.0" />
|
||||||
|
<param name="AHRS_TRIM_Z" value="0.0" />
|
||||||
|
<param name="RC2_REV" value="1.0" />
|
||||||
|
<param name="INS_MPU6K_FILTER" value="20.0" />
|
||||||
|
<param name="THR_MIN" value="130.0" />
|
||||||
|
<param name="AHRS_TRIM_Y" value="0.021683" />
|
||||||
|
<param name="RC11_DZ" value="0.0" />
|
||||||
|
<param name="THR_MAX" value="1000.0" />
|
||||||
|
<param name="SR3_EXTRA2" value="0.0" />
|
||||||
|
<param name="MNT_NEUTRAL_Z" value="0.0" />
|
||||||
|
<param name="THR_MID" value="300.0" />
|
||||||
|
<param name="MNT_NEUTRAL_X" value="0.0" />
|
||||||
|
<param name="AMP_PER_VOLT" value="18.002001" />
|
||||||
|
<param name="SR0_POSITION" value="3.0" />
|
||||||
|
<param name="MNT_STAB_PAN" value="0.0" />
|
||||||
|
<param name="FS_BATT_ENABLE" value="0.0" />
|
||||||
|
<param name="LAND_SPEED" value="50.0" />
|
||||||
|
<param name="OF_PIT_D" value="0.12" />
|
||||||
|
<param name="SR0_PARAMS" value="50.0" />
|
||||||
|
<param name="COMPASS_ORIENT" value="0.0" />
|
||||||
|
<param name="WPNAV_ACCEL" value="200.0" />
|
||||||
|
<param name="THR_ACCEL_IMAX" value="5000.0" />
|
||||||
|
<param name="SR3_POSITION" value="0.0" />
|
||||||
|
<param name="WPNAV_RADIUS" value="100.0" />
|
||||||
|
<param name="WP_TOTAL" value="14.0" />
|
||||||
|
<param name="RC8_MAX" value="1856.0" />
|
||||||
|
<param name="OF_PIT_P" value="2.5" />
|
||||||
|
<param name="SR3_RAW_SENS" value="0.0" />
|
||||||
|
<param name="RTL_ALT_FINAL" value="0.0" />
|
||||||
|
<param name="SR3_PARAMS" value="0.0" />
|
||||||
|
<param name="SR0_EXTRA3" value="2.0" />
|
||||||
|
<param name="LOITER_LAT_I" value="0.5" />
|
||||||
|
<param name="RC6_DZ" value="0.0" />
|
||||||
|
<param name="RC4_TRIM" value="1524.0" />
|
||||||
|
<param name="RATE_RLL_P" value="0.07" />
|
||||||
|
<param name="LOITER_LAT_D" value="0.0" />
|
||||||
|
<param name="STB_PIT_P" value="3.5" />
|
||||||
|
<param name="OF_PIT_I" value="0.5" />
|
||||||
|
<param name="RATE_RLL_I" value="1.0" />
|
||||||
|
<param name="AHRS_TRIM_X" value="0.003997" />
|
||||||
|
<param name="RC3_REV" value="1.0" />
|
||||||
|
<param name="STB_PIT_I" value="0.0" />
|
||||||
|
<param name="FS_THR_ENABLE" value="0.0" />
|
||||||
|
<param name="LOITER_LAT_P" value="1.0" />
|
||||||
|
<param name="AHRS_RP_P" value="0.1" />
|
||||||
|
<param name="FENCE_ACTION" value="1.0" />
|
||||||
|
<param name="TOY_RATE" value="1.0" />
|
||||||
|
<param name="RATE_RLL_D" value="0.006" />
|
||||||
|
<param name="RC5_MIN" value="1151.0" />
|
||||||
|
<param name="RC5_TRIM" value="1676.0" />
|
||||||
|
<param name="STB_RLL_IMAX" value="800.0" />
|
||||||
|
<param name="RC4_DZ" value="40.0" />
|
||||||
|
<param name="AHRS_YAW_P" value="0.1" />
|
||||||
|
<param name="RC11_TRIM" value="1500.0" />
|
||||||
|
<param name="MOT_TCRV_ENABLE" value="1.0" />
|
||||||
|
<param name="CAM_TRIGG_TYPE" value="1.0" />
|
||||||
|
<param name="STB_YAW_IMAX" value="800.0" />
|
||||||
|
<param name="RC4_MAX" value="1942.0" />
|
||||||
|
<param name="LOITER_LAT_IMAX" value="400.0" />
|
||||||
|
<param name="CH7_OPT" value="9.0" />
|
||||||
|
<param name="RC11_FUNCTION" value="7.0" />
|
||||||
|
<param name="SR0_EXT_STAT" value="2.0" />
|
||||||
|
<param name="SONAR_TYPE" value="0.0" />
|
||||||
|
<param name="RC3_MAX" value="1930.0" />
|
||||||
|
<param name="RATE_YAW_D" value="0.0" />
|
||||||
|
<param name="FENCE_ALT_MAX" value="30.0" />
|
||||||
|
<param name="COMPASS_MOT_Y" value="0.0" />
|
||||||
|
<param name="AXIS_ENABLE" value="1.0" />
|
||||||
|
<param name="FENCE_ENABLE" value="0.0" />
|
||||||
|
<param name="RC10_DZ" value="0.0" />
|
||||||
|
<param name="PILOT_VELZ_MAX" value="250.0" />
|
||||||
|
<param name="BATT_CAPACITY" value="1760.0" />
|
||||||
|
<param name="FS_THR_VALUE" value="975.0" />
|
||||||
|
<param name="RC4_MIN" value="1115.0" />
|
||||||
|
<param name="MNT_ANGMAX_TIL" value="4500.0" />
|
||||||
|
<param name="RTL_LOIT_TIME" value="5000.0" />
|
||||||
|
<param name="ARMING_CHECK" value="1.0" />
|
||||||
|
<param name="THR_RATE_P" value="6.0" />
|
||||||
|
<param name="OF_RLL_IMAX" value="100.0" />
|
||||||
|
<param name="RC6_MIN" value="971.0" />
|
||||||
|
<param name="SR0_RAW_CTRL" value="0.0" />
|
||||||
|
<param name="RC6_MAX" value="2078.0" />
|
||||||
|
<param name="RC5_MAX" value="1829.0" />
|
||||||
|
<param name="LOITER_LON_IMAX" value="400.0" />
|
||||||
|
<param name="MNT_STAB_TILT" value="0.0" />
|
||||||
|
<param name="MOT_TCRV_MIDPCT" value="52.0" />
|
||||||
|
<param name="COMPASS_OFS_Z" value="-5.120774" />
|
||||||
|
<param name="COMPASS_OFS_Y" value="46.709824" />
|
||||||
|
<param name="COMPASS_OFS_X" value="-20.490345" />
|
||||||
|
<param name="THR_ALT_I" value="0.0" />
|
||||||
|
<param name="RC10_TRIM" value="1500.0" />
|
||||||
|
<param name="INS_PRODUCT_ID" value="88.0" />
|
||||||
|
<param name="RC11_MIN" value="1100.0" />
|
||||||
|
<param name="FS_GPS_ENABLE" value="1.0" />
|
||||||
|
<param name="HLD_LAT_IMAX" value="3000.0" />
|
||||||
|
<param name="RC3_TRIM" value="1476.0" />
|
||||||
|
<param name="RC6_FUNCTION" value="0.0" />
|
||||||
|
<param name="TRIM_THROTTLE" value="260.0" />
|
||||||
|
<param name="MNT_STAB_ROLL" value="0.0" />
|
||||||
|
<param name="INAV_TC_XY" value="2.5" />
|
||||||
|
<param name="RC1_DZ" value="30.0" />
|
||||||
|
<param name="MNT_RETRACT_Z" value="0.0" />
|
||||||
|
<param name="THR_ACC_ENABLE" value="1.0" />
|
||||||
|
<param name="LOG_BITMASK" value="830.0" />
|
||||||
|
<param name="TUNE_LOW" value="0.0" />
|
||||||
|
<param name="CIRCLE_RATE" value="5.0" />
|
||||||
|
<param name="CAM_DURATION" value="10.0" />
|
||||||
|
<param name="MNT_NEUTRAL_Y" value="0.0" />
|
||||||
|
<param name="RC10_MIN" value="1100.0" />
|
||||||
|
<param name="INS_ACCOFFS_X" value="-0.019376" />
|
||||||
|
<param name="THR_RATE_D" value="0.0" />
|
||||||
|
<param name="INS_ACCOFFS_Z" value="1.370947" />
|
||||||
|
<param name="RC4_REV" value="1.0" />
|
||||||
|
<param name="CIRCLE_RADIUS" value="10.0" />
|
||||||
|
<param name="RATE_RLL_IMAX" value="4500.0" />
|
||||||
|
<param name="HLD_LAT_P" value="1.0" />
|
||||||
|
<param name="AHRS_GPS_MINSATS" value="6.0" />
|
||||||
|
<param name="FLOW_ENABLE" value="0.0" />
|
||||||
|
<param name="RC8_REV" value="1.0" />
|
||||||
|
<param name="SONAR_GAIN" value="0.2" />
|
||||||
|
<param name="RC2_TRIM" value="1521.0" />
|
||||||
|
<param name="WP_INDEX" value="0.0" />
|
||||||
|
<param name="RC1_REV" value="1.0" />
|
||||||
|
<param name="RC7_DZ" value="0.0" />
|
||||||
|
<param name="AHRS_GPS_USE" value="1.0" />
|
||||||
|
<param name="MNT_ANGMIN_PAN" value="-4500.0" />
|
||||||
|
<param name="SR3_RC_CHAN" value="0.0" />
|
||||||
|
<param name="COMPASS_LEARN" value="0.0" />
|
||||||
|
<param name="ACRO_TRAINER" value="1.0" />
|
||||||
|
<param name="CAM_SERVO_OFF" value="1100.0" />
|
||||||
|
<param name="RC5_DZ" value="0.0" />
|
||||||
|
<param name="SCHED_DEBUG" value="0.0" />
|
||||||
|
<param name="RC11_MAX" value="1900.0" />
|
||||||
|
<param name="AHRS_WIND_MAX" value="0.0" />
|
||||||
|
<param name="SR3_EXT_STAT" value="0.0" />
|
||||||
|
<param name="MNT_ANGMAX_PAN" value="4500.0" />
|
||||||
|
<param name="MNT_ANGMAX_ROL" value="4500.0" />
|
||||||
|
<param name="RC_SPEED" value="490.0" />
|
||||||
|
<param name="SUPER_SIMPLE" value="0.0" />
|
||||||
|
<param name="VOLT_DIVIDER" value="10.0" />
|
||||||
|
<param name="COMPASS_MOTCT" value="0.0" />
|
||||||
|
<param name="SR3_RAW_CTRL" value="0.0" />
|
||||||
|
<param name="SONAR_ENABLE" value="0.0" />
|
||||||
|
<param name="INS_ACCOFFS_Y" value="0.362242" />
|
||||||
|
<param name="SYSID_SW_MREV" value="120.0" />
|
||||||
|
<param name="WPNAV_LOIT_SPEED" value="1000.0" />
|
||||||
|
<param name="BATT_MONITOR" value="4.0" />
|
||||||
|
<param name="MNT_RC_IN_TILT" value="8.0" />
|
||||||
|
<param name="CH8_OPT" value="0.0" />
|
||||||
|
<param name="RTL_ALT" value="1000.0" />
|
||||||
|
<param name="SR0_RC_CHAN" value="2.0" />
|
||||||
|
<param name="RC1_MIN" value="1111.0" />
|
||||||
|
<param name="RSSI_PIN" value="-1.0" />
|
||||||
|
<param name="MOT_TCRV_MAXPCT" value="93.0" />
|
||||||
|
<param name="GND_ABS_PRESS" value="101566.97" />
|
||||||
|
<param name="RC1_MAX" value="1936.0" />
|
||||||
|
<param name="FENCE_TYPE" value="3.0" />
|
||||||
|
<param name="RC5_FUNCTION" value="0.0" />
|
||||||
|
<param name="OF_RLL_D" value="0.12" />
|
||||||
|
<param name="BATT_VOLT_PIN" value="13.0" />
|
||||||
|
<param name="WPNAV_SPEED" value="1000.0" />
|
||||||
|
<param name="RC7_MAX" value="1884.0" />
|
||||||
|
<param name="CAM_SERVO_ON" value="1300.0" />
|
||||||
|
<param name="RATE_PIT_I" value="1.0" />
|
||||||
|
<param name="RC7_MIN" value="969.0" />
|
||||||
|
<param name="AHRS_COMP_BETA" value="0.1" />
|
||||||
|
<param name="OF_RLL_I" value="0.5" />
|
||||||
|
<param name="COMPASS_DEC" value="0.0" />
|
||||||
|
<param name="RC3_MIN" value="1113.0" />
|
||||||
|
<param name="RC2_DZ" value="30.0" />
|
||||||
|
<param name="FENCE_RADIUS" value="30.0" />
|
||||||
|
<param name="HLD_LON_I" value="0.0" />
|
||||||
|
<param name="ACRO_BAL_ROLL" value="200.0" />
|
||||||
|
<param name="COMPASS_AUTODEC" value="1.0" />
|
||||||
|
<param name="SR3_EXTRA3" value="0.0" />
|
||||||
|
<param name="COMPASS_USE" value="1.0" />
|
||||||
|
<param name="RC10_MAX" value="1900.0" />
|
||||||
|
<param name="RATE_PIT_P" value="0.07" />
|
||||||
|
<param name="GND_TEMP" value="21.610104" />
|
||||||
|
<param name="RC7_TRIM" value="970.0" />
|
||||||
|
<param name="RC10_REV" value="1.0" />
|
||||||
|
<param name="RATE_YAW_P" value="0.2" />
|
||||||
|
<param name="THR_ALT_P" value="1.0" />
|
||||||
|
<param name="RATE_PIT_D" value="0.006" />
|
||||||
|
<param name="ESC" value="0.0" />
|
||||||
|
<param name="MNT_ANGMIN_TIL" value="-4500.0" />
|
||||||
|
<param name="SERIAL3_BAUD" value="57.0" />
|
||||||
|
<param name="RC8_MIN" value="968.0" />
|
||||||
|
<param name="THR_ALT_IMAX" value="300.0" />
|
||||||
|
<param name="SYSID_MYGCS" value="255.0" />
|
||||||
|
<param name="INS_GYROFFS_Y" value="0.581989" />
|
||||||
|
<param name="TUNE" value="0.0" />
|
||||||
|
<param name="RC8_TRIM" value="970.0" />
|
||||||
|
<param name="RC3_DZ" value="30.0" />
|
||||||
|
<param name="AHRS_GPS_GAIN" value="1.0" />
|
||||||
|
<param name="THR_ACCEL_D" value="0.0" />
|
||||||
|
<param name="TELEM_DELAY" value="0.0" />
|
||||||
|
<param name="THR_ACCEL_I" value="0.5" />
|
||||||
|
<param name="COMPASS_MOT_X" value="0.0" />
|
||||||
|
<param name="COMPASS_MOT_Z" value="0.0" />
|
||||||
|
<param name="RC10_FUNCTION" value="0.0" />
|
||||||
|
<param name="INS_GYROFFS_X" value="-0.001698" />
|
||||||
|
<param name="INS_GYROFFS_Z" value="0.01517" />
|
||||||
|
<param name="RC6_TRIM" value="1473.0" />
|
||||||
|
<param name="THR_ACCEL_P" value="1.2" />
|
||||||
|
<param name="RC8_DZ" value="0.0" />
|
||||||
|
<param name="HLD_LAT_I" value="0.0" />
|
||||||
|
<param name="RC7_FUNCTION" value="0.0" />
|
||||||
|
<param name="RC6_REV" value="1.0" />
|
||||||
|
<param name="BATT_CURR_PIN" value="12.0" />
|
||||||
|
<param name="WPNAV_SPEED_UP" value="250.0" />
|
||||||
|
<param name="RC1_TRIM" value="1524.0" />
|
||||||
|
</params>
|
||||||
|
<results>
|
||||||
|
<result>
|
||||||
|
<name>Balance/Twist</name>
|
||||||
|
<status>PASS</status>
|
||||||
|
<message></message>
|
||||||
|
<extrafeedback></extrafeedback>
|
||||||
|
</result>
|
||||||
|
<result>
|
||||||
|
<name>Brownout</name>
|
||||||
|
<status>PASS</status>
|
||||||
|
<message></message>
|
||||||
|
<extrafeedback></extrafeedback>
|
||||||
|
</result>
|
||||||
|
<result>
|
||||||
|
<name>Compass</name>
|
||||||
|
<status>PASS</status>
|
||||||
|
<message></message>
|
||||||
|
<extrafeedback></extrafeedback>
|
||||||
|
</result>
|
||||||
|
<result>
|
||||||
|
<name>Empty</name>
|
||||||
|
<status>PASS</status>
|
||||||
|
<message></message>
|
||||||
|
<extrafeedback></extrafeedback>
|
||||||
|
</result>
|
||||||
|
<result>
|
||||||
|
<name>Event/Failsafe</name>
|
||||||
|
<status>FAIL</status>
|
||||||
|
<message>ERR found: GPS </message>
|
||||||
|
<extrafeedback></extrafeedback>
|
||||||
|
<data>(test data will be embeded here at some point)</data>
|
||||||
|
</result>
|
||||||
|
<result>
|
||||||
|
<name>GPS</name>
|
||||||
|
<status>WARN</status>
|
||||||
|
<message>Min satellites: 6, Max HDop: 4.68</message>
|
||||||
|
<extrafeedback></extrafeedback>
|
||||||
|
<data>(test data will be embeded here at some point)</data>
|
||||||
|
</result>
|
||||||
|
<result>
|
||||||
|
<name>Parameters</name>
|
||||||
|
<status>FAIL</status>
|
||||||
|
<message>Bad parameters found:</message>
|
||||||
|
<extrafeedback>THR_MID set to 300.0, expecting less than 300
|
||||||
|
</extrafeedback>
|
||||||
|
<data>(test data will be embeded here at some point)</data>
|
||||||
|
</result>
|
||||||
|
<result>
|
||||||
|
<name>Performance</name>
|
||||||
|
<status>FAIL</status>
|
||||||
|
<message>14 slow loop lines found, up to 18% (line 2983)</message>
|
||||||
|
<extrafeedback></extrafeedback>
|
||||||
|
<data>(test data will be embeded here at some point)</data>
|
||||||
|
</result>
|
||||||
|
<result>
|
||||||
|
<name>Pitch/Roll</name>
|
||||||
|
<status>PASS</status>
|
||||||
|
<message></message>
|
||||||
|
<extrafeedback></extrafeedback>
|
||||||
|
</result>
|
||||||
|
<result>
|
||||||
|
<name>Underpowered</name>
|
||||||
|
<status>PASS</status>
|
||||||
|
<message></message>
|
||||||
|
<extrafeedback></extrafeedback>
|
||||||
|
</result>
|
||||||
|
<result>
|
||||||
|
<name>VCC</name>
|
||||||
|
<status>PASS</status>
|
||||||
|
<message></message>
|
||||||
|
<extrafeedback></extrafeedback>
|
||||||
|
</result>
|
||||||
|
<result>
|
||||||
|
<name>Vibration</name>
|
||||||
|
<status>UNKNOWN</status>
|
||||||
|
<message>No IMU log data</message>
|
||||||
|
<extrafeedback></extrafeedback>
|
||||||
|
</result>
|
||||||
|
</results>
|
||||||
|
</loganalysis>
|
@ -10,6 +10,13 @@ class TestGPSGlitch(Test):
|
|||||||
|
|
||||||
def run(self, logdata):
|
def run(self, logdata):
|
||||||
self.result = TestResult()
|
self.result = TestResult()
|
||||||
|
self.result.status = TestResult.StatusType.PASS
|
||||||
|
|
||||||
|
if "GPS" not in logdata.channels:
|
||||||
|
self.result.status = TestResult.StatusType.FAIL
|
||||||
|
self.result.statusMessage = "No GPS log data"
|
||||||
|
return
|
||||||
|
|
||||||
# define and check different thresholds for WARN level and FAIL level
|
# define and check different thresholds for WARN level and FAIL level
|
||||||
minSatsWARN = 6
|
minSatsWARN = 6
|
||||||
minSatsFAIL = 5
|
minSatsFAIL = 5
|
||||||
@ -24,9 +31,7 @@ class TestGPSGlitch(Test):
|
|||||||
self.result.statusMessage = "Min satellites: %s, Max HDop: %s" % (logdata.channels["GPS"]["NSats"].min(), logdata.channels["GPS"]["HDop"].max())
|
self.result.statusMessage = "Min satellites: %s, Max HDop: %s" % (logdata.channels["GPS"]["NSats"].min(), logdata.channels["GPS"]["HDop"].max())
|
||||||
elif foundBadSatsWarn or foundBadHDopWarn:
|
elif foundBadSatsWarn or foundBadHDopWarn:
|
||||||
self.result.status = TestResult.StatusType.WARN
|
self.result.status = TestResult.StatusType.WARN
|
||||||
self.result.statusMessage = "Min satellites: %s, Max HDop: %s" % (logdata.channels["GPS"]["NSats"].min(), logdata.channels["GPS"]["HDop"].max())
|
self.result.statusMessage = "Min satellites: %s, Max HDop: %s" % (logdata.channels["GPS"]["NSats"].min(), logdata.channels["GPS"]["HDop"].max())
|
||||||
else:
|
|
||||||
self.result.status = TestResult.StatusType.PASS
|
|
||||||
|
|
||||||
# TODO: also test for sudden repositioning beyond what the drone could reasonably achieve
|
# TODO: also test for sudden repositioning beyond what the drone could reasonably achieve, like is done with glitch protection - or is that logged when it happens?
|
||||||
# ...
|
# ...
|
||||||
|
@ -50,3 +50,5 @@ class TestParams(Test):
|
|||||||
# TODO: add parameter checks for plane...
|
# TODO: add parameter checks for plane...
|
||||||
pass
|
pass
|
||||||
|
|
||||||
|
if self.result.status == TestResult.StatusType.FAIL:
|
||||||
|
self.result.statusMessage = "Bad parameters found:"
|
||||||
|
@ -12,5 +12,46 @@ class TestPerformance(Test):
|
|||||||
self.result = TestResult()
|
self.result = TestResult()
|
||||||
self.result.status = TestResult.StatusType.PASS
|
self.result.status = TestResult.StatusType.PASS
|
||||||
|
|
||||||
|
# NOTE: we'll ignore MaxT altogether for now, it seems there are quite regularly one or two high values in there, even ignoring the ones expected after arm/disarm events
|
||||||
|
|
||||||
# TODO: test for performance warning messages, slow loops, etc
|
# gather info on arm/disarm lines, we will ignore the MaxT data from the first line found after each of these
|
||||||
|
# armingLines = []
|
||||||
|
# evData = logdata.channels["EV"]["Id"]
|
||||||
|
# orderedEVData = collections.OrderedDict(sorted(evData.dictData.items(), key=lambda t: t[0]))
|
||||||
|
# for line,ev in orderedEVData.iteritems():
|
||||||
|
# if (ev == 10) or (ev == 11):
|
||||||
|
# armingLines.append(line)
|
||||||
|
# ignoreMaxTLines = []
|
||||||
|
# for maxT in logdata.channels["PM"]["MaxT"].listData:
|
||||||
|
# if not armingLines:
|
||||||
|
# break
|
||||||
|
# if maxT[0] > armingLines[0]:
|
||||||
|
# #print "Ignoring maxT from line %d, as it is the first PM line after arming on line %d" % (maxT[0],armingLines[0])
|
||||||
|
# ignoreMaxTLines.append(maxT[0])
|
||||||
|
# armingLines.pop(0)
|
||||||
|
|
||||||
|
|
||||||
|
# check for slow loops, i.e. NLon greater than 5% of NLoop
|
||||||
|
maxPercentSlow = 0
|
||||||
|
maxPercentSlowLine = 0
|
||||||
|
slowLoopLineCount = 0
|
||||||
|
for i in range(len(logdata.channels["PM"]["NLon"].listData)):
|
||||||
|
(line, nLon) = logdata.channels["PM"]["NLon"].listData[i]
|
||||||
|
(line, nLoop) = logdata.channels["PM"]["NLoop"].listData[i]
|
||||||
|
(line, maxT) = logdata.channels["PM"]["MaxT"].listData[i]
|
||||||
|
percentSlow = (nLon / float(nLoop)) * 100
|
||||||
|
if percentSlow > 5.0:
|
||||||
|
slowLoopLineCount = slowLoopLineCount + 1
|
||||||
|
if percentSlow > maxPercentSlow:
|
||||||
|
maxPercentSlow = percentSlow
|
||||||
|
maxPercentSlowLine = line
|
||||||
|
#if (maxT > 13000) and line not in ignoreMaxTLines:
|
||||||
|
# print "MaxT of %d detected on line %d" % (maxT,line)
|
||||||
|
if (maxPercentSlow > 10) or (slowLoopLineCount > 5):
|
||||||
|
self.result.status = TestResult.StatusType.FAIL
|
||||||
|
self.result.statusMessage = "%d slow loop lines found, max %d%% on line %d" % (slowLoopLineCount,maxPercentSlow,maxPercentSlowLine)
|
||||||
|
elif (maxPercentSlow > 5):
|
||||||
|
self.result.status = TestResult.StatusType.WARN
|
||||||
|
self.result.statusMessage = "%d slow loop lines found, max %d%% on line %d" % (slowLoopLineCount,maxPercentSlow,maxPercentSlowLine)
|
||||||
|
else:
|
||||||
|
self.result.extraFeedback = ""
|
||||||
|
@ -16,7 +16,7 @@ class TestVCC(Test):
|
|||||||
|
|
||||||
if not "CURR" in logdata.channels:
|
if not "CURR" in logdata.channels:
|
||||||
self.result.status = TestResult.StatusType.UNKNOWN
|
self.result.status = TestResult.StatusType.UNKNOWN
|
||||||
self.result.statusMessage = "No CURR log data found"
|
self.result.statusMessage = "No CURR log data"
|
||||||
return
|
return
|
||||||
|
|
||||||
# just a naive min/max test for now
|
# just a naive min/max test for now
|
||||||
|
@ -24,7 +24,7 @@ class TestVibration(Test):
|
|||||||
# TODO: in Pixhawk should we use IMU or IMU2?
|
# TODO: in Pixhawk should we use IMU or IMU2?
|
||||||
if not "IMU" in logdata.channels:
|
if not "IMU" in logdata.channels:
|
||||||
self.result.status = TestResult.StatusType.UNKNOWN
|
self.result.status = TestResult.StatusType.UNKNOWN
|
||||||
self.result.statusMessage = "No IMU log data found"
|
self.result.statusMessage = "No IMU log data"
|
||||||
return
|
return
|
||||||
|
|
||||||
# find some stable LOITER data to analyze, at least 10 seconds
|
# find some stable LOITER data to analyze, at least 10 seconds
|
||||||
|
Loading…
Reference in New Issue
Block a user