#!/usr/bin/env python3 ''' unpack a param.pck file from @PARAM/param.pck via mavlink FTP ''' import struct, sys from argparse import ArgumentParser parser = ArgumentParser(description=__doc__) parser.add_argument("file", metavar="LOG") args = parser.parse_args() data = open(args.file,'rb').read() last_name = "" magic = 0x671b # header of 6 bytes magic2,num_params,total_params = struct.unpack(" 0 and data[0] == pad_byte: data = data[1:] if len(data) == 0: break ptype, plen = struct.unpack(">4) & 0x0F ptype &= 0x0F if not ptype in data_types: raise Exception("bad type 0x%x" % ptype) (type_len, type_format) = data_types[ptype] name_len = ((plen>>4) & 0x0F) + 1 common_len = (plen & 0x0F) name = last_name[0:common_len] + data[2:2+name_len].decode('utf-8') vdata = data[2+name_len:2+name_len+type_len] last_name = name data = data[2+name_len+type_len:] v, = struct.unpack("<" + type_format, vdata) count += 1 print("%-16s %f" % (name, float(v))) if count != num_params or count > total_params: print("Error: Got %u params expected %u/%u" % (count, num_params, total_params)) sys.exit(1) sys.exit(0)