Book a Demo!
CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutPoliciesSign UpSign In
Ardupilot
GitHub Repository: Ardupilot/ardupilot
Path: blob/master/Tools/scripts/apj_tool.py
9365 views
1
#!/usr/bin/env python3
2
3
# flake8: noqa
4
5
'''
6
tool to manipulate ArduPilot firmware files, changing default parameters
7
'''
8
9
import os, sys, struct, json, base64, zlib, hashlib
10
11
import argparse
12
13
def to_ascii(s):
14
'''get ascii string'''
15
if sys.version_info.major >= 3:
16
return str(s, 'ascii')
17
else:
18
return str(s)
19
20
def to_bytes(s):
21
'''get bytes string'''
22
if sys.version_info.major >= 3:
23
if isinstance(s,bytes):
24
return s
25
if isinstance(s,int):
26
s = chr(s)
27
return bytes(s, 'ascii')
28
else:
29
return bytes(s)
30
31
class embedded_defaults(object):
32
'''class to manipulate embedded defaults in a firmware'''
33
def __init__(self, filename):
34
self.filename = filename
35
self.offset = 0
36
self.max_len = 0
37
self.extension = os.path.splitext(filename)[1]
38
if self.extension.lower() in ['.apj', '.px4']:
39
self.load_apj()
40
elif self.extension.lower() in ['.abin']:
41
self.load_abin()
42
else:
43
self.load_binary()
44
45
def load_binary(self):
46
'''load firmware from binary file'''
47
f = open(self.filename,'rb')
48
self.firmware = f.read()
49
f.close()
50
print("Loaded binary file of length %u" % len(self.firmware))
51
52
def load_abin(self):
53
'''load firmware from abin file'''
54
f = open(self.filename,'r')
55
self.headers = []
56
while True:
57
line = f.readline().rstrip()
58
if line == '--':
59
break
60
self.headers.append(line)
61
if len(self.headers) > 50:
62
print("Error: too many abin headers")
63
sys.exit(1)
64
self.firmware = f.read()
65
f.close()
66
print("Loaded abin file of length %u" % len(self.firmware))
67
68
def load_apj(self):
69
'''load firmware from a json apj or px4 file'''
70
f = open(self.filename,'r')
71
self.fw_json = json.load(f)
72
f.close()
73
self.firmware = zlib.decompress(base64.b64decode(self.fw_json['image']))
74
print("Loaded apj file of length %u" % len(self.firmware))
75
76
def save_binary(self):
77
'''save binary file'''
78
f = open(self.filename, 'wb')
79
f.write(self.firmware)
80
f.close()
81
print("Saved binary of length %u" % len(self.firmware))
82
83
def save_apj(self):
84
'''save apj file'''
85
self.fw_json['image'] = to_ascii(base64.b64encode(zlib.compress(self.firmware, 9)))
86
f = open(self.filename,'w')
87
json.dump(self.fw_json,f,indent=4)
88
f.truncate()
89
f.close()
90
print("Saved apj of length %u" % len(self.firmware))
91
92
def save_abin(self):
93
'''save abin file'''
94
f = open(self.filename,'w')
95
for i in range(len(self.headers)):
96
line = self.headers[i]
97
if line.startswith('MD5: '):
98
h = hashlib.new('md5')
99
h.update(self.firmware)
100
f.write('MD5: %s\n' % h.hexdigest())
101
else:
102
f.write(line+'\n')
103
f.write('--\n')
104
f.write(self.firmware)
105
f.close()
106
print("Saved abin of length %u" % len(self.firmware))
107
108
def find(self):
109
'''find defaults in firmware'''
110
# these are the magic headers from AP_Param.cpp
111
magic_str = "PARMDEF".encode('ascii')
112
param_magic = [ 0x55, 0x37, 0xf4, 0xa0, 0x38, 0x5d, 0x48, 0x5b ]
113
def u_ord(c):
114
return ord(c) if sys.version_info.major < 3 else c
115
116
while True:
117
i = self.firmware[self.offset:].find(magic_str)
118
if i == -1:
119
print("No param area found")
120
return None
121
matched = True
122
for j in range(len(param_magic)):
123
if u_ord(self.firmware[self.offset+i+j+8]) != param_magic[j]:
124
matched = False
125
break
126
if not matched:
127
self.offset += i+8
128
continue
129
self.offset += i
130
self.max_len, self.length = struct.unpack("<HH", self.firmware[self.offset+16:self.offset+20])
131
return True
132
133
def contents(self):
134
'''return current contents'''
135
contents = self.firmware[self.offset+20:self.offset+20+self.length]
136
# remove carriage returns
137
contents = contents.replace(b'\r',b'')
138
return contents
139
140
def set_contents(self, contents):
141
'''set new defaults as a string'''
142
length = len(contents)
143
if length > self.max_len:
144
print("Error: Length %u larger than maximum %u" % (length, self.max_len))
145
sys.exit(1)
146
new_fw = self.firmware[:self.offset+18]
147
new_fw += struct.pack("<H", length)
148
new_fw += to_bytes(contents)
149
new_fw += self.firmware[self.offset+20+length:]
150
self.firmware = new_fw
151
self.length = len(contents)
152
153
def set_file(self, filename):
154
'''set defaults to contents of a file'''
155
print("Setting defaults from %s" % filename)
156
f = open(filename, 'r')
157
contents = f.read()
158
f.close()
159
# remove carriage returns from the file
160
contents = contents.replace('\r','')
161
self.set_contents(contents)
162
163
def split_multi(self, s, separators):
164
'''split a string, handling multiple separators'''
165
for sep in separators:
166
s = s.replace(to_bytes(sep), b' ')
167
return s.split()
168
169
def set_one(self, set):
170
'''set a single parameter'''
171
v = set.split('=')
172
if len(v) != 2:
173
print("Error: set takes form NAME=VALUE")
174
sys.exit(1)
175
param_name = to_bytes(v[0].upper())
176
param_value = to_bytes(v[1])
177
178
contents = self.contents()
179
lines = contents.strip().split(b'\n')
180
changed = False
181
for i in range(len(lines)):
182
a = self.split_multi(lines[i], b", =\t")
183
if len(a) != 2:
184
continue
185
if a[0].upper() == param_name:
186
separator = to_bytes(lines[i][len(param_name)])
187
lines[i] = b'%s%s%s' % (param_name, separator, param_value)
188
changed = True
189
if not changed:
190
lines.append(to_bytes('%s=%s' % (to_ascii(param_name), to_ascii(param_value))))
191
contents = b'\n'.join(lines)
192
contents = contents.lstrip() + b'\n'
193
self.set_contents(contents)
194
195
def save(self):
196
'''save new firmware'''
197
if self.extension.lower() in ['.apj', '.px4']:
198
self.save_apj()
199
elif self.extension.lower() in ['.abin']:
200
self.save_abin()
201
else:
202
self.save_binary()
203
204
def extract(self):
205
'''extract firmware image to *.bin'''
206
a = os.path.splitext(self.filename)
207
if len(a) == 1:
208
a.append('.bin')
209
else:
210
a = (a[0], '.bin')
211
binfile = ''.join(a)
212
print("Extracting firmware to %s" % binfile)
213
f = open(binfile,'wb')
214
f.write(self.firmware)
215
f.close()
216
217
218
def defaults_contents(firmware, ofs, length):
219
'''return current defaults contents'''
220
return firmware
221
222
if __name__ == '__main__':
223
parser = argparse.ArgumentParser(description='manipulate parameter defaults in an ArduPilot firmware')
224
225
parser.add_argument('firmware_file')
226
parser.add_argument('--set-file', type=str, default=None, help='replace parameter defaults from a file')
227
parser.add_argument('--set', type=str, default=None, help='replace one parameter default, in form NAME=VALUE')
228
parser.add_argument('--show', action='store_true', default=False, help='show current parameter defaults')
229
parser.add_argument('--extract', action='store_true', default=False, help='extract firmware image to *.bin')
230
231
args = parser.parse_args()
232
233
defaults = embedded_defaults(args.firmware_file)
234
235
have_defaults = defaults.find()
236
237
if not have_defaults and not args.extract:
238
print("Error: Param defaults support not found in firmware; see https://ardupilot.org/copter/docs/common-oem-customizations.html for embedding defaults.parm")
239
sys.exit(1)
240
241
if have_defaults:
242
print("Found param defaults max_length=%u length=%u" % (defaults.max_len, defaults.length))
243
244
if args.set_file:
245
# load new defaults from a file
246
defaults.set_file(args.set_file)
247
defaults.save()
248
249
if args.set:
250
# set a single parameter
251
defaults.set_one(args.set)
252
defaults.save()
253
254
if args.show:
255
# show all defaults
256
print(to_ascii(defaults.contents()))
257
258
if args.extract:
259
defaults.extract()
260
261