mirror of https://github.com/ArduPilot/ardupilot
Tools: LogAnalyzer: handle changed RCOU and parameters in motorbalance
This commit is contained in:
parent
f42df1bc54
commit
45bc95edeb
|
@ -1,6 +1,7 @@
|
|||
from LogAnalyzer import Test,TestResult
|
||||
import DataflashLog
|
||||
|
||||
from VehicleType import VehicleType
|
||||
|
||||
class TestBalanceTwist(Test):
|
||||
'''test for badly unbalanced copter, including yaw twist'''
|
||||
|
@ -12,7 +13,7 @@ class TestBalanceTwist(Test):
|
|||
self.result = TestResult()
|
||||
self.result.status = TestResult.StatusType.GOOD
|
||||
|
||||
if logdata.vehicleType != "ArduCopter":
|
||||
if logdata.vehicleType != VehicleType.Copter:
|
||||
self.result.status = TestResult.StatusType.NA
|
||||
return
|
||||
|
||||
|
@ -23,10 +24,9 @@ class TestBalanceTwist(Test):
|
|||
ch = []
|
||||
|
||||
for i in range(8):
|
||||
if "Chan"+`(i+1)` in logdata.channels["RCOU"]:
|
||||
ch.append(map(lambda x: x[1], logdata.channels["RCOU"]["Chan"+`(i+1)`].listData))
|
||||
elif "Ch"+`(i+1)` in logdata.channels["RCOU"]:
|
||||
ch.append(map(lambda x: x[1], logdata.channels["RCOU"]["Ch"+`(i+1)`].listData))
|
||||
for prefix in "Chan", "Ch", "C":
|
||||
if prefix+`(i+1)` in logdata.channels["RCOU"]:
|
||||
ch.append(map(lambda x: x[1], logdata.channels["RCOU"][prefix+`(i+1)`].listData))
|
||||
|
||||
ch = zip(*ch)
|
||||
num_channels = 0
|
||||
|
@ -38,7 +38,11 @@ class TestBalanceTwist(Test):
|
|||
if num_channels < 2:
|
||||
return
|
||||
|
||||
min_throttle = logdata.parameters["RC3_MIN"] + logdata.parameters["THR_MIN"] / (logdata.parameters["RC3_MAX"]-logdata.parameters["RC3_MIN"])/1000.0
|
||||
try:
|
||||
min_throttle = logdata.parameters["RC3_MIN"] + logdata.parameters["THR_MIN"] / (logdata.parameters["RC3_MAX"]-logdata.parameters["RC3_MIN"])/1000.0
|
||||
except KeyError as e:
|
||||
min_throttle = logdata.parameters["MOT_PWM_MIN"] / (logdata.parameters["MOT_PWM_MAX"]-logdata.parameters["RC3_MIN"])/1000.0
|
||||
|
||||
ch = filter(lambda x:sum(x)/num_channels > min_throttle, ch)
|
||||
|
||||
if len(ch) == 0:
|
||||
|
|
Loading…
Reference in New Issue