|
|
|
@ -7,6 +7,24 @@ import os, sys, struct, json, base64, zlib, hashlib
@@ -7,6 +7,24 @@ import os, sys, struct, json, base64, zlib, hashlib
|
|
|
|
|
|
|
|
|
|
import argparse |
|
|
|
|
|
|
|
|
|
def to_ascii(s): |
|
|
|
|
'''get ascii string''' |
|
|
|
|
if sys.version_info.major >= 3: |
|
|
|
|
return str(s, 'ascii') |
|
|
|
|
else: |
|
|
|
|
return str(s) |
|
|
|
|
|
|
|
|
|
def to_bytes(s): |
|
|
|
|
'''get bytes string''' |
|
|
|
|
if sys.version_info.major >= 3: |
|
|
|
|
if isinstance(s,bytes): |
|
|
|
|
return s |
|
|
|
|
if isinstance(s,int): |
|
|
|
|
s = chr(s) |
|
|
|
|
return bytes(s, 'ascii') |
|
|
|
|
else: |
|
|
|
|
return bytes(s) |
|
|
|
|
|
|
|
|
|
class embedded_defaults(object): |
|
|
|
|
'''class to manipulate embedded defaults in a firmware''' |
|
|
|
|
def __init__(self, filename): |
|
|
|
@ -61,7 +79,7 @@ class embedded_defaults(object):
@@ -61,7 +79,7 @@ class embedded_defaults(object):
|
|
|
|
|
|
|
|
|
|
def save_apj(self): |
|
|
|
|
'''save apj file''' |
|
|
|
|
self.fw_json['image'] = base64.b64encode(zlib.compress(self.firmware, 9)) |
|
|
|
|
self.fw_json['image'] = to_ascii(base64.b64encode(zlib.compress(self.firmware, 9))) |
|
|
|
|
f = open(self.filename,'w') |
|
|
|
|
json.dump(self.fw_json,f,indent=4) |
|
|
|
|
f.truncate() |
|
|
|
@ -113,7 +131,7 @@ class embedded_defaults(object):
@@ -113,7 +131,7 @@ class embedded_defaults(object):
|
|
|
|
|
'''return current contents''' |
|
|
|
|
contents = self.firmware[self.offset+20:self.offset+20+self.length] |
|
|
|
|
# remove carriage returns |
|
|
|
|
contents = contents.replace('\r','') |
|
|
|
|
contents = contents.replace(b'\r',b'') |
|
|
|
|
return contents |
|
|
|
|
|
|
|
|
|
def set_contents(self, contents): |
|
|
|
@ -124,7 +142,7 @@ class embedded_defaults(object):
@@ -124,7 +142,7 @@ class embedded_defaults(object):
|
|
|
|
|
sys.exit(1) |
|
|
|
|
new_fw = self.firmware[:self.offset+18] |
|
|
|
|
new_fw += struct.pack("<H", length) |
|
|
|
|
new_fw += contents.encode('ascii') |
|
|
|
|
new_fw += to_bytes(contents) |
|
|
|
|
new_fw += self.firmware[self.offset+20+length:] |
|
|
|
|
self.firmware = new_fw |
|
|
|
|
self.length = len(contents) |
|
|
|
@ -139,11 +157,11 @@ class embedded_defaults(object):
@@ -139,11 +157,11 @@ class embedded_defaults(object):
|
|
|
|
|
contents = contents.replace('\r','') |
|
|
|
|
self.set_contents(contents) |
|
|
|
|
|
|
|
|
|
def split_multi(self, str, separators): |
|
|
|
|
def split_multi(self, s, separators): |
|
|
|
|
'''split a string, handling multiple separators''' |
|
|
|
|
for sep in separators: |
|
|
|
|
str = str.replace(sep, ' ') |
|
|
|
|
return str.split() |
|
|
|
|
s = s.replace(to_bytes(sep), b' ') |
|
|
|
|
return s.split() |
|
|
|
|
|
|
|
|
|
def set_one(self, set): |
|
|
|
|
'''set a single parameter''' |
|
|
|
@ -151,26 +169,24 @@ class embedded_defaults(object):
@@ -151,26 +169,24 @@ class embedded_defaults(object):
|
|
|
|
|
if len(v) != 2: |
|
|
|
|
print("Error: set takes form NAME=VALUE") |
|
|
|
|
sys.exit(1) |
|
|
|
|
param_name = v[0].upper() |
|
|
|
|
param_value = v[1] |
|
|
|
|
param_name = to_bytes(v[0].upper()) |
|
|
|
|
param_value = to_bytes(v[1]) |
|
|
|
|
|
|
|
|
|
contents = self.contents() |
|
|
|
|
lines = contents.strip().split('\n') |
|
|
|
|
lines = contents.strip().split(b'\n') |
|
|
|
|
changed = False |
|
|
|
|
for i in range(len(lines)): |
|
|
|
|
a = self.split_multi(lines[i], ", =\t") |
|
|
|
|
a = self.split_multi(lines[i], b", =\t") |
|
|
|
|
if len(a) != 2: |
|
|
|
|
continue |
|
|
|
|
if a[0].upper() == param_name: |
|
|
|
|
separator=lines[i][len(param_name)] |
|
|
|
|
print("Changing %s from %s to %s" % (param_name, a[1], param_value)) |
|
|
|
|
lines[i] = '%s%s%s' % (param_name, separator, param_value) |
|
|
|
|
separator = to_bytes(lines[i][len(param_name)]) |
|
|
|
|
lines[i] = b'%s%s%s' % (param_name, separator, param_value) |
|
|
|
|
changed = True |
|
|
|
|
if not changed: |
|
|
|
|
print("Adding %s=%s" % (param_name, param_value)) |
|
|
|
|
lines.append('%s=%s' % (param_name, param_value)) |
|
|
|
|
contents = '\n'.join(lines) |
|
|
|
|
contents = contents.lstrip() + '\n' |
|
|
|
|
lines.append(to_bytes('%s=%s' % (to_ascii(param_name), to_ascii(param_value)))) |
|
|
|
|
contents = b'\n'.join(lines) |
|
|
|
|
contents = contents.lstrip() + b'\n' |
|
|
|
|
self.set_contents(contents) |
|
|
|
|
|
|
|
|
|
def save(self): |
|
|
|
@ -231,7 +247,7 @@ if __name__ == '__main__':
@@ -231,7 +247,7 @@ if __name__ == '__main__':
|
|
|
|
|
|
|
|
|
|
if args.show: |
|
|
|
|
# show all defaults |
|
|
|
|
print(defaults.contents()) |
|
|
|
|
print(to_ascii(defaults.contents())) |
|
|
|
|
|
|
|
|
|
if args.extract: |
|
|
|
|
defaults.extract() |
|
|
|
|