mirror of https://github.com/ArduPilot/ardupilot
waf: fixed unnecessary nul termination of ROMFS
This commit is contained in:
parent
7fb44d1164
commit
4e33aff5d6
|
@ -34,12 +34,14 @@ def embed_file(out, f, idx, embedded_name, uncompressed):
|
|||
|
||||
compressed = tempfile.NamedTemporaryFile()
|
||||
if uncompressed:
|
||||
compressed.write(open(f,'rb').read())
|
||||
# ensure nul termination
|
||||
if sys.version_info[0] >= 3:
|
||||
compressed.write(bytearray(0))
|
||||
nul = bytearray(0)
|
||||
else:
|
||||
compressed.write(chr(0))
|
||||
nul = chr(0)
|
||||
if contents[-1] != nul:
|
||||
contents += nul
|
||||
compressed.write(contents)
|
||||
else:
|
||||
# compress it
|
||||
f = open(compressed.name, "wb")
|
||||
|
|
Loading…
Reference in New Issue