mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-03 04:03:59 -04:00
Tools: fixed call to apj_tool in skyviper build
This commit is contained in:
parent
c39a802655
commit
98ab1c13db
@ -70,10 +70,16 @@ class set_default_parameters(Task.Task):
|
|||||||
return "apj_tool"
|
return "apj_tool"
|
||||||
def run(self):
|
def run(self):
|
||||||
rel_default_parameters = self.env.get_flat('DEFAULT_PARAMETERS')
|
rel_default_parameters = self.env.get_flat('DEFAULT_PARAMETERS')
|
||||||
abs_default_parameters = os.path.join(self.env.STANDARD_BUILDDIR,
|
abs_default_parameters = os.path.join(self.env.SRCROOT, rel_default_parameters)
|
||||||
rel_default_parameters)
|
apj_tool = self.env.APJ_TOOL
|
||||||
run_str = ("python ${APJ_TOOL} --set-file %s ${SRC}" %
|
sys.path.append(os.path.dirname(apj_tool))
|
||||||
(abs_default_parameters,))
|
from apj_tool import embedded_defaults
|
||||||
|
defaults = embedded_defaults(self.inputs[0].abspath())
|
||||||
|
if not defaults.find():
|
||||||
|
print("Error: Param defaults support not found in firmware")
|
||||||
|
sys.exit(1)
|
||||||
|
defaults.set_file(abs_default_parameters)
|
||||||
|
defaults.save()
|
||||||
|
|
||||||
|
|
||||||
class generate_fw(Task.Task):
|
class generate_fw(Task.Task):
|
||||||
@ -188,13 +194,13 @@ def configure(cfg):
|
|||||||
env.AP_HAL_ROOT = srcpath('libraries/AP_HAL_ChibiOS')
|
env.AP_HAL_ROOT = srcpath('libraries/AP_HAL_ChibiOS')
|
||||||
env.BUILDDIR = bldpath('modules/ChibiOS')
|
env.BUILDDIR = bldpath('modules/ChibiOS')
|
||||||
env.BUILDROOT = bldpath('')
|
env.BUILDROOT = bldpath('')
|
||||||
|
env.SRCROOT = srcpath('')
|
||||||
env.PT_DIR = srcpath('Tools/ardupilotwaf/chibios/image')
|
env.PT_DIR = srcpath('Tools/ardupilotwaf/chibios/image')
|
||||||
env.UPLOAD_TOOLS = srcpath('Tools/ardupilotwaf')
|
env.UPLOAD_TOOLS = srcpath('Tools/ardupilotwaf')
|
||||||
env.CHIBIOS_SCRIPTS = srcpath('libraries/AP_HAL_ChibiOS/hwdef/scripts')
|
env.CHIBIOS_SCRIPTS = srcpath('libraries/AP_HAL_ChibiOS/hwdef/scripts')
|
||||||
env.TOOLS_SCRIPTS = srcpath('Tools/scripts')
|
env.TOOLS_SCRIPTS = srcpath('Tools/scripts')
|
||||||
env.APJ_TOOL = srcpath('Tools/scripts/apj_tool.py')
|
env.APJ_TOOL = srcpath('Tools/scripts/apj_tool.py')
|
||||||
env.SERIAL_PORT = srcpath('/dev/serial/by-id/*_STLink*')
|
env.SERIAL_PORT = srcpath('/dev/serial/by-id/*_STLink*')
|
||||||
env.STANDARD_BUILDDIR = srcpath("build/some-board")
|
|
||||||
|
|
||||||
# relative paths to pass to make, relative to directory that make is run from
|
# relative paths to pass to make, relative to directory that make is run from
|
||||||
env.CH_ROOT_REL = os.path.relpath(env.CH_ROOT, env.BUILDROOT)
|
env.CH_ROOT_REL = os.path.relpath(env.CH_ROOT, env.BUILDROOT)
|
||||||
|
@ -12,6 +12,7 @@ class embedded_defaults(object):
|
|||||||
def __init__(self, filename):
|
def __init__(self, filename):
|
||||||
self.filename = filename
|
self.filename = filename
|
||||||
self.offset = 0
|
self.offset = 0
|
||||||
|
self.max_len = 0
|
||||||
self.extension = os.path.splitext(filename)[1]
|
self.extension = os.path.splitext(filename)[1]
|
||||||
if self.extension.lower() in ['.apj', '.px4']:
|
if self.extension.lower() in ['.apj', '.px4']:
|
||||||
self.load_apj()
|
self.load_apj()
|
||||||
@ -22,7 +23,7 @@ class embedded_defaults(object):
|
|||||||
|
|
||||||
def load_binary(self):
|
def load_binary(self):
|
||||||
'''load firmware from binary file'''
|
'''load firmware from binary file'''
|
||||||
f = open(self.filename,'r')
|
f = open(self.filename,'rb')
|
||||||
self.firmware = f.read()
|
self.firmware = f.read()
|
||||||
f.close()
|
f.close()
|
||||||
print("Loaded binary file of length %u" % len(self.firmware))
|
print("Loaded binary file of length %u" % len(self.firmware))
|
||||||
@ -91,6 +92,7 @@ class embedded_defaults(object):
|
|||||||
while True:
|
while True:
|
||||||
i = self.firmware[self.offset:].find(magic_str)
|
i = self.firmware[self.offset:].find(magic_str)
|
||||||
if i == -1:
|
if i == -1:
|
||||||
|
print("No param area found")
|
||||||
return None
|
return None
|
||||||
matched = True
|
matched = True
|
||||||
for j in range(len(param_magic)):
|
for j in range(len(param_magic)):
|
||||||
@ -195,37 +197,38 @@ def defaults_contents(firmware, ofs, length):
|
|||||||
'''return current defaults contents'''
|
'''return current defaults contents'''
|
||||||
return firmware
|
return firmware
|
||||||
|
|
||||||
parser = argparse.ArgumentParser(description='manipulate parameter defaults in an ArduPilot firmware')
|
if __name__ == '__main__':
|
||||||
|
parser = argparse.ArgumentParser(description='manipulate parameter defaults in an ArduPilot firmware')
|
||||||
|
|
||||||
parser.add_argument('firmware_file')
|
parser.add_argument('firmware_file')
|
||||||
parser.add_argument('--set-file', type=str, default=None, help='replace parameter defaults from a file')
|
parser.add_argument('--set-file', type=str, default=None, help='replace parameter defaults from a file')
|
||||||
parser.add_argument('--set', type=str, default=None, help='replace one parameter default, in form NAME=VALUE')
|
parser.add_argument('--set', type=str, default=None, help='replace one parameter default, in form NAME=VALUE')
|
||||||
parser.add_argument('--show', action='store_true', default=False, help='show current parameter defaults')
|
parser.add_argument('--show', action='store_true', default=False, help='show current parameter defaults')
|
||||||
parser.add_argument('--extract', action='store_true', default=False, help='extract firmware image to *.bin')
|
parser.add_argument('--extract', action='store_true', default=False, help='extract firmware image to *.bin')
|
||||||
|
|
||||||
args = parser.parse_args()
|
args = parser.parse_args()
|
||||||
|
|
||||||
defaults = embedded_defaults(args.firmware_file)
|
defaults = embedded_defaults(args.firmware_file)
|
||||||
|
|
||||||
if not defaults.find():
|
if not defaults.find():
|
||||||
print("Error: Param defaults support not found in firmware")
|
print("Error: Param defaults support not found in firmware")
|
||||||
sys.exit(1)
|
sys.exit(1)
|
||||||
|
|
||||||
print("Found param defaults max_length=%u length=%u" % (defaults.max_len, defaults.length))
|
print("Found param defaults max_length=%u length=%u" % (defaults.max_len, defaults.length))
|
||||||
|
|
||||||
if args.set_file:
|
if args.set_file:
|
||||||
# load new defaults from a file
|
# load new defaults from a file
|
||||||
defaults.set_file(args.set_file)
|
defaults.set_file(args.set_file)
|
||||||
defaults.save()
|
defaults.save()
|
||||||
|
|
||||||
if args.set:
|
if args.set:
|
||||||
# set a single parameter
|
# set a single parameter
|
||||||
defaults.set_one(args.set)
|
defaults.set_one(args.set)
|
||||||
defaults.save()
|
defaults.save()
|
||||||
|
|
||||||
if args.show:
|
if args.show:
|
||||||
# show all defaults
|
# show all defaults
|
||||||
print(defaults.contents())
|
print(defaults.contents())
|
||||||
|
|
||||||
if args.extract:
|
if args.extract:
|
||||||
defaults.extract()
|
defaults.extract()
|
||||||
|
Loading…
Reference in New Issue
Block a user