forked from ArduPilot/pymavlink
-
Notifications
You must be signed in to change notification settings - Fork 0
/
CSVReader.py
203 lines (160 loc) · 5.97 KB
/
CSVReader.py
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
#!/usr/bin/env python
'''
CSV log file reader
Copyright Peter Barker 2020
Released under GNU GPL version 3 or later
Timestamp must be in first column, microseconds
First row must be column headings.
e.g.
pbarker@bluebottle:~/rc/pymavlink(pr/csvreader)$ head -2 $LOG
WEEK_NB;TOW;ACCL_X;ACCL_Y;ACCL_Z;GYRO_X;GYRO_Y;GYRO_Z;TEMP;STATUS;COUNTER;VALID_CHCKSM
2100.0;371149.08302956074;-0.25742456316947937;-0.017161637544631958;9.684066772460938;0.003054326167330146;-0.00578140327706933;0.0006544984644278884;34.599998474121094;0.0;54637.0;0.0
pbarker@bluebottle:~/rc/pymavlink(pr/csvreader)$ MAVExplorer.py "csv:$LOG:separator=;:timestamp_expression=gps_time_to_epoch(CSV.WEEK_NB,CSV.TOW*1000.0)"
MAV> graph CSV.GYRO_X
in this case the GPS time was in seconds-since-week-start, so a conversion to ms is required
'''
from __future__ import print_function
from builtins import range
from builtins import object
import csv
import struct
from . import mavutil
from . import mavextra
from . import mavexpression
class CSVMessage(object):
def __init__(self, message_type, fmt, line):
self.fmt = fmt
self.message_type = message_type
self.line = []
for entry in line:
try:
self.line.append(float(entry))
except ValueError:
self.line.append(entry)
def get_type(self):
return self.message_type
def __str__(self):
ret = "%s {" % self.message_type
for (c, val) in zip(self.fmt.headings, self.line):
ret += "%s : %s, " % (c, str(val))
return ret + '}'
# methods for MAVExplorer:
def get_fieldnames(self):
return self.fmt.headings
# end methods for MAVExplorer
def __getattr__(self, field):
'''override field getter'''
if field == '_timestamp':
if self.fmt.timestamp_expression is not None:
return mavexpression.evaluate_expression(self.fmt.timestamp_expression, self.fmt.messages)
return int(self.line[0])
return self.line[self.fmt.field_offset[field]]
class CSVFormat(object):
def __init__(self, headings, messages, timestamp_expression=None):
self.headings = headings
self.messages = messages
self.timestamp_expression = timestamp_expression
# map from a field name to an offset in the line:
self.field_offset = {}
count = 0
for heading in self.headings:
self.field_offset[heading] = count
count += 1
class CSVReader(object):
'''parse a CSV file'''
def __init__(self,
filename,
zero_time_base=False,
progress_callback=None,
separator=';',
message_type='CSV',
timestamp_expression=None,
):
self.messages = { 'MAV' : self }
self.filename = filename
self.separator = separator
self.message_type = message_type
self.progress_callback = progress_callback
self.timestamp_expression = timestamp_expression
self.timestamp = 0
self.verbose = False
self.f = None
self.linecount = None
self._rewind() # opens files etc etc
self.recv_msg() # populate self.messages
self._rewind() # opens files etc etc
# start attributes for MAVExplorer
self._flightmodes = []
# end attributes for MAVExplorer
# start methods for MAVExplorer:
def flightmode_list(self):
return self._flightmodes
@property
def _count(self):
# implicitly rewinds
if self.linecount is None:
self.linecount = self.count_lines()
return self.linecount
def count_lines(self):
self._rewind()
count = 0
while True:
try:
if count == 0:
if self._parse_next() == None:
raise StopIteration
else:
next(self.reader)
count += 1
except StopIteration:
self._rewind()
return count
def rewind(self):
self._rewind()
def name_to_id(self, name):
return 1 # FIXME
# end methods for MAVExplorer
def _rewind(self):
'''reset state on rewind'''
self.percent = 0
if self.f is not None:
self.f.close()
self.f = open(self.filename, mode='r')
self.reader = csv.reader(self.f, delimiter=self.separator)
self.fmt = CSVFormat(next(self.reader),
self.messages,
timestamp_expression=self.timestamp_expression)
def recv_msg(self):
return self._parse_next()
def recv_match(self, condition=None, type=None, blocking=False):
# print("recv_match called (condition=%s type=%s blocking=%s" % (str(condition), str(type), str(blocking)))
'''recv the next message that matches the given condition
type can be a string or a list of strings'''
if type is not None and not isinstance(type, list) and not isinstance(type, set):
type = [type]
while True:
m = self.recv_msg()
if m is None:
return None
if type is not None and not m.get_type() in type:
continue
if not mavutil.evaluate_condition(condition, self.messages):
continue
return m
def check_condition(self, condition):
'''check if a condition is true'''
return mavutil.evaluate_condition(condition, self.messages)
def _parse_next(self):
'''read one message, returning it as an object'''
try:
line = next(self.reader)
except StopIteration:
return None
m = CSVMessage(self.message_type, self.fmt, line)
self._add_msg(m)
return m
def _add_msg(self, m):
'''add a new message'''
self.messages[self.message_type] = m
if __name__ == "__main__":
print("FIXME")