mirror of https://github.com/ArduPilot/ardupilot
HAL_ChibiOS: don't add defaults.parm when building bootloader
This commit is contained in:
parent
7316a478b6
commit
a7d9f4eef7
|
@ -1157,7 +1157,7 @@ def write_env_py(filename):
|
||||||
|
|
||||||
# see if board has a defaults.parm file
|
# see if board has a defaults.parm file
|
||||||
defaults_filename = os.path.join(os.path.dirname(args.hwdef), 'defaults.parm')
|
defaults_filename = os.path.join(os.path.dirname(args.hwdef), 'defaults.parm')
|
||||||
if os.path.exists(defaults_filename):
|
if os.path.exists(defaults_filename) and not args.bootloader:
|
||||||
print("Adding defaults.parm")
|
print("Adding defaults.parm")
|
||||||
env_vars['DEFAULT_PARAMETERS'] = os.path.abspath(defaults_filename)
|
env_vars['DEFAULT_PARAMETERS'] = os.path.abspath(defaults_filename)
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue