Browse Source

tools: LogAnalyser, ensure error msgs go to stderr not stdout

master
Kevin Hester 11 years ago committed by Andrew Tridgell
parent
commit
1a4fce60e8
  1. 7
      Tools/LogAnalyzer/DataflashLog.py

7
Tools/LogAnalyzer/DataflashLog.py

@ -4,13 +4,13 @@
# Initial code by Andrew Chapman (amchapman@gmail.com), 16th Jan 2014 # Initial code by Andrew Chapman (amchapman@gmail.com), 16th Jan 2014
# #
from __future__ import print_function
import collections import collections
import os import os
import numpy import numpy
import bisect import bisect
import sys import sys
class Format: class Format:
'''Data channel format as specified by the FMT lines in the log file''' '''Data channel format as specified by the FMT lines in the log file'''
msgType = 0 msgType = 0
@ -332,7 +332,7 @@ class DataflashLog:
else: else:
errorMsg = "Error parsing line %d of log file: %s" % (lineNumber, self.filename) errorMsg = "Error parsing line %d of log file: %s" % (lineNumber, self.filename)
if ignoreBadlines: if ignoreBadlines:
print errorMsg + " (skipping line)" print(errorMsg + " (skipping line)", file=sys.stderr)
self.skippedLines += 1 self.skippedLines += 1
else: else:
raise Exception("") raise Exception("")
@ -372,7 +372,7 @@ class DataflashLog:
if (len(tokens2)-1) != len(self.formats[groupName].labels): if (len(tokens2)-1) != len(self.formats[groupName].labels):
errorMsg = "%s line's value count (%d) not matching FMT specification (%d) on line %d" % (groupName, len(tokens2)-1, len(self.formats[groupName].labels), lineNumber) errorMsg = "%s line's value count (%d) not matching FMT specification (%d) on line %d" % (groupName, len(tokens2)-1, len(self.formats[groupName].labels), lineNumber)
if ignoreBadlines: if ignoreBadlines:
print errorMsg + " (skipping line)" print(errorMsg + " (skipping line)", file=sys.stderr)
self.skippedLines += 1 self.skippedLines += 1
continue continue
else: else:
@ -386,6 +386,7 @@ class DataflashLog:
channel.dictData[lineNumber] = value channel.dictData[lineNumber] = value
channel.listData.append((lineNumber,value)) channel.listData.append((lineNumber,value))
except Exception as e: except Exception as e:
print("BAD LINE: " + line, file=sys.stderr)
raise Exception("Error parsing line %d of log file %s - %s" % (lineNumber,self.filename,e.args[0])) raise Exception("Error parsing line %d of log file %s - %s" % (lineNumber,self.filename,e.args[0]))

Loading…
Cancel
Save