Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Path: blob/master/Tools/scripts/apj_tool.py
Views: 1798
#!/usr/bin/env python31'''2tool to manipulate ArduPilot firmware files, changing default parameters3'''45import os, sys, struct, json, base64, zlib, hashlib67import argparse89def to_ascii(s):10'''get ascii string'''11if sys.version_info.major >= 3:12return str(s, 'ascii')13else:14return str(s)1516def to_bytes(s):17'''get bytes string'''18if sys.version_info.major >= 3:19if isinstance(s,bytes):20return s21if isinstance(s,int):22s = chr(s)23return bytes(s, 'ascii')24else:25return bytes(s)2627class embedded_defaults(object):28'''class to manipulate embedded defaults in a firmware'''29def __init__(self, filename):30self.filename = filename31self.offset = 032self.max_len = 033self.extension = os.path.splitext(filename)[1]34if self.extension.lower() in ['.apj', '.px4']:35self.load_apj()36elif self.extension.lower() in ['.abin']:37self.load_abin()38else:39self.load_binary()4041def load_binary(self):42'''load firmware from binary file'''43f = open(self.filename,'rb')44self.firmware = f.read()45f.close()46print("Loaded binary file of length %u" % len(self.firmware))4748def load_abin(self):49'''load firmware from abin file'''50f = open(self.filename,'r')51self.headers = []52while True:53line = f.readline().rstrip()54if line == '--':55break56self.headers.append(line)57if len(self.headers) > 50:58print("Error: too many abin headers")59sys.exit(1)60self.firmware = f.read()61f.close()62print("Loaded abin file of length %u" % len(self.firmware))6364def load_apj(self):65'''load firmware from a json apj or px4 file'''66f = open(self.filename,'r')67self.fw_json = json.load(f)68f.close()69self.firmware = zlib.decompress(base64.b64decode(self.fw_json['image']))70print("Loaded apj file of length %u" % len(self.firmware))7172def save_binary(self):73'''save binary file'''74f = open(self.filename, 'wb')75f.write(self.firmware)76f.close()77print("Saved binary of length %u" % len(self.firmware))7879def save_apj(self):80'''save apj file'''81self.fw_json['image'] = to_ascii(base64.b64encode(zlib.compress(self.firmware, 9)))82f = open(self.filename,'w')83json.dump(self.fw_json,f,indent=4)84f.truncate()85f.close()86print("Saved apj of length %u" % len(self.firmware))8788def save_abin(self):89'''save abin file'''90f = open(self.filename,'w')91for i in range(len(self.headers)):92line = self.headers[i]93if line.startswith('MD5: '):94h = hashlib.new('md5')95h.update(self.firmware)96f.write('MD5: %s\n' % h.hexdigest())97else:98f.write(line+'\n')99f.write('--\n')100f.write(self.firmware)101f.close()102print("Saved abin of length %u" % len(self.firmware))103104def find(self):105'''find defaults in firmware'''106# these are the magic headers from AP_Param.cpp107magic_str = "PARMDEF".encode('ascii')108param_magic = [ 0x55, 0x37, 0xf4, 0xa0, 0x38, 0x5d, 0x48, 0x5b ]109def u_ord(c):110return ord(c) if sys.version_info.major < 3 else c111112while True:113i = self.firmware[self.offset:].find(magic_str)114if i == -1:115print("No param area found")116return None117matched = True118for j in range(len(param_magic)):119if u_ord(self.firmware[self.offset+i+j+8]) != param_magic[j]:120matched = False121break122if not matched:123self.offset += i+8124continue125self.offset += i126self.max_len, self.length = struct.unpack("<HH", self.firmware[self.offset+16:self.offset+20])127return True128129def contents(self):130'''return current contents'''131contents = self.firmware[self.offset+20:self.offset+20+self.length]132# remove carriage returns133contents = contents.replace(b'\r',b'')134return contents135136def set_contents(self, contents):137'''set new defaults as a string'''138length = len(contents)139if length > self.max_len:140print("Error: Length %u larger than maximum %u" % (length, self.max_len))141sys.exit(1)142new_fw = self.firmware[:self.offset+18]143new_fw += struct.pack("<H", length)144new_fw += to_bytes(contents)145new_fw += self.firmware[self.offset+20+length:]146self.firmware = new_fw147self.length = len(contents)148149def set_file(self, filename):150'''set defaults to contents of a file'''151print("Setting defaults from %s" % filename)152f = open(filename, 'r')153contents = f.read()154f.close()155# remove carriage returns from the file156contents = contents.replace('\r','')157self.set_contents(contents)158159def split_multi(self, s, separators):160'''split a string, handling multiple separators'''161for sep in separators:162s = s.replace(to_bytes(sep), b' ')163return s.split()164165def set_one(self, set):166'''set a single parameter'''167v = set.split('=')168if len(v) != 2:169print("Error: set takes form NAME=VALUE")170sys.exit(1)171param_name = to_bytes(v[0].upper())172param_value = to_bytes(v[1])173174contents = self.contents()175lines = contents.strip().split(b'\n')176changed = False177for i in range(len(lines)):178a = self.split_multi(lines[i], b", =\t")179if len(a) != 2:180continue181if a[0].upper() == param_name:182separator = to_bytes(lines[i][len(param_name)])183lines[i] = b'%s%s%s' % (param_name, separator, param_value)184changed = True185if not changed:186lines.append(to_bytes('%s=%s' % (to_ascii(param_name), to_ascii(param_value))))187contents = b'\n'.join(lines)188contents = contents.lstrip() + b'\n'189self.set_contents(contents)190191def save(self):192'''save new firmware'''193if self.extension.lower() in ['.apj', '.px4']:194self.save_apj()195elif self.extension.lower() in ['.abin']:196self.save_abin()197else:198self.save_binary()199200def extract(self):201'''extract firmware image to *.bin'''202a = os.path.splitext(self.filename)203if len(a) == 1:204a.append('.bin')205else:206a = (a[0], '.bin')207binfile = ''.join(a)208print("Extracting firmware to %s" % binfile)209f = open(binfile,'wb')210f.write(self.firmware)211f.close()212213214def defaults_contents(firmware, ofs, length):215'''return current defaults contents'''216return firmware217218if __name__ == '__main__':219parser = argparse.ArgumentParser(description='manipulate parameter defaults in an ArduPilot firmware')220221parser.add_argument('firmware_file')222parser.add_argument('--set-file', type=str, default=None, help='replace parameter defaults from a file')223parser.add_argument('--set', type=str, default=None, help='replace one parameter default, in form NAME=VALUE')224parser.add_argument('--show', action='store_true', default=False, help='show current parameter defaults')225parser.add_argument('--extract', action='store_true', default=False, help='extract firmware image to *.bin')226227args = parser.parse_args()228229defaults = embedded_defaults(args.firmware_file)230231have_defaults = defaults.find()232233if not have_defaults and not args.extract:234print("Error: Param defaults support not found in firmware; see https://ardupilot.org/copter/docs/common-oem-customizations.html for embedding defaults.parm")235sys.exit(1)236237if have_defaults:238print("Found param defaults max_length=%u length=%u" % (defaults.max_len, defaults.length))239240if args.set_file:241# load new defaults from a file242defaults.set_file(args.set_file)243defaults.save()244245if args.set:246# set a single parameter247defaults.set_one(args.set)248defaults.save()249250if args.show:251# show all defaults252print(to_ascii(defaults.contents()))253254if args.extract:255defaults.extract()256257258