-
Notifications
You must be signed in to change notification settings - Fork 10
Commit
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
Add simple script to decode and plot the satcom messages
- Loading branch information
Showing
2 changed files
with
181 additions
and
0 deletions.
There are no files selected for viewing
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
|
@@ -4,3 +4,5 @@ satcomSDcard/ | |
*~ | ||
.settings* | ||
credentials.cfg | ||
.* | ||
*.csv |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,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() |