-
Notifications
You must be signed in to change notification settings - Fork 10
/
Copy pathdecode_rockblock_csv.py
executable file
·179 lines (156 loc) · 6.91 KB
/
decode_rockblock_csv.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
#!/usr/bin/env python
import argparse
from datetime import datetime
import matplotlib.pyplot as plt
import numpy as np
from pymavlink import mavlink
import pandas as pd
MAV = mavlink.MAVLink(0)
def printmsg(data):
m = None
try:
m = MAV.parse_buffer(data)
except:
pass
if m is not None:
for msg in m:
print 'MAV MSG %3d %s' % (msg.get_msgId(), msg.get_type())
print msg
# TODO also parse the Iridium lat/long and compare it to the received messages
def main():
parser = argparse.ArgumentParser(description='Parses a csv file consisting of SatCom messages generated by RockBlock.')
parser.add_argument('-f', dest='filename', required=True, help='Filename of the input csv file')
args = parser.parse_args()
data = pd.read_csv(args.filename, header=0)
hl2 = {
'id': 235,
'timestamp': [],
'type': [],
'autopilot': [],
'custom_mode': [],
'latitude': [],
'longitude': [],
'altitude': [],
'target_altitude': [],
'heading': [],
'target_heading': [],
'target_distance': [],
'throttle': [],
'airspeed': [],
'airspeed_sp': [],
'groundspeed': [],
'windspeed': [],
'wind_heading': [],
'eph': [],
'epv': [],
'temperature_air': [],
'climb_rate': [],
'battery': [],
'wp_num': [],
'failure_flags': [],
'custom0': [],
'custom1': [],
'custom2': [],
}
ack = {
'id': 77,
'timestamp': [],
'command': [],
'result': [],
'progress': [],
'result_param2': [],
'target_system': [],
'target_component': [],
}
first_timestamp = datetime.strptime(data['Date Time (UTC)'][len(data) - 1], '%d/%b/%Y %H:%M:%S')
# loop over data in reverse order
for i in range(len(data) - 1, -1, -1):
timestamp = (datetime.strptime(data['Date Time (UTC)'][i], '%d/%b/%Y %H:%M:%S') - first_timestamp).total_seconds()
payload = data['Payload'][i]
m = None
try:
m = MAV.parse_buffer(payload.decode('hex'))
except:
pass
if m is not None:
for msg in m:
if msg.id == hl2['id']:
if msg.target_altitude > 0: # filter out the initial message
hl2['timestamp'].append(msg.timestamp*1e-3)
hl2['type'].append(msg.type)
hl2['autopilot'].append(msg.autopilot)
hl2['custom_mode'].append(msg.custom_mode)
hl2['latitude'].append(msg.latitude*1e-7)
hl2['longitude'].append(msg.longitude*1e-7)
hl2['altitude'].append(msg.altitude)
hl2['target_altitude'].append(msg.target_altitude)
hl2['heading'].append(msg.heading*2)
hl2['target_heading'].append(msg.target_heading*2)
hl2['target_distance'].append(msg.target_distance*1e-1)
hl2['throttle'].append(msg.throttle)
hl2['airspeed'].append(msg.airspeed*0.2)
hl2['airspeed_sp'].append(msg.airspeed_sp*0.2)
hl2['groundspeed'].append(msg.groundspeed*0.2)
hl2['windspeed'].append(msg.windspeed*0.2)
hl2['wind_heading'].append(msg.wind_heading*2)
hl2['eph'].append(msg.eph*1e-1)
hl2['epv'].append(msg.epv*1e-1)
hl2['temperature_air'].append(msg.temperature_air)
hl2['climb_rate'].append(msg.climb_rate*1e-1)
hl2['battery'].append(msg.battery)
hl2['wp_num'].append(msg.wp_num)
hl2['failure_flags'].append(msg.failure_flags)
hl2['custom0'].append(msg.custom0)
hl2['custom1'].append(msg.custom1)
hl2['custom2'].append(msg.custom2)
elif msg.id == ack['id']:
ack['timestamp'].append(timestamp)
ack['command'].append(msg.command)
ack['result'].append(msg.result)
ack['progress'].append(msg.progress)
ack['result_param2'].append(msg.result_param2)
ack['target_system'].append(msg.target_system)
ack['target_component'].append(msg.target_component)
else:
print('Unknown message id:')
print(msg.id)
# plot the position plots
fig, axs = plt.subplots(nrows=2, ncols=2)
axs[0][0].plot(hl2['timestamp'], hl2['latitude'])
axs[0][1].plot(hl2['timestamp'], hl2['longitude'])
axs[1][0].plot(hl2['timestamp'], hl2['altitude'])
axs[1][1].plot(hl2['timestamp'], hl2['target_altitude'])
axs[0][0].set(xlabel='timestamp [s]', ylabel='latitude [deg]')
axs[0][1].set(xlabel='timestamp [s]', ylabel='longitude [deg]')
axs[1][0].set(xlabel='timestamp [s]', ylabel='altitude [m]')
axs[1][1].set(xlabel='timestamp [s]', ylabel='target_altitude [m]')
fig, axs = plt.subplots(nrows=2, ncols=2)
axs[0][0].plot(hl2['timestamp'], hl2['heading'])
axs[0][1].plot(hl2['timestamp'], hl2['target_heading'])
axs[1][0].plot(hl2['timestamp'], hl2['target_distance'])
axs[1][1].plot(hl2['timestamp'], hl2['throttle'])
axs[0][0].set(xlabel='timestamp [s]', ylabel='heading [deg]')
axs[0][1].set(xlabel='timestamp [s]', ylabel='target_heading [deg]')
axs[1][0].set(xlabel='timestamp [s]', ylabel='target_distance [m]')
axs[1][1].set(xlabel='timestamp [s]', ylabel='throttle [%]')
fig, axs = plt.subplots(nrows=2, ncols=2)
axs[0][0].plot(hl2['timestamp'], hl2['airspeed'])
axs[0][1].plot(hl2['timestamp'], hl2['airspeed_sp'])
axs[1][0].plot(hl2['timestamp'], hl2['groundspeed'])
axs[1][1].plot(hl2['timestamp'], hl2['temperature_air'])
axs[0][0].set(xlabel='timestamp [s]', ylabel='airspeed [m/s]')
axs[0][1].set(xlabel='timestamp [s]', ylabel='airspeed_sp [m/s]')
axs[1][0].set(xlabel='timestamp [s]', ylabel='groundspeed [m/s]')
axs[1][1].set(xlabel='timestamp [s]', ylabel='temperature_air [degC]')
fig, axs = plt.subplots(nrows=2, ncols=2)
axs[0][0].plot(hl2['timestamp'], hl2['windspeed'])
axs[0][1].plot(hl2['timestamp'], hl2['wind_heading'])
axs[1][0].plot(hl2['timestamp'], hl2['climb_rate'])
axs[1][1].plot(hl2['timestamp'], hl2['battery'])
axs[0][0].set(xlabel='timestamp [s]', ylabel='windspeed [m/s]')
axs[0][1].set(xlabel='timestamp [s]', ylabel='wind_heading [deg]')
axs[1][0].set(xlabel='timestamp [s]', ylabel='climb_rate [m/s]')
axs[1][1].set(xlabel='timestamp [s]', ylabel='battery [%]')
plt.show()
if __name__ == '__main__':
main()