mirror of https://github.com/ArduPilot/ardupilot
waf: added --board-start-time configure option
This commit is contained in:
parent
3e83d40bd8
commit
673bf619e5
|
@ -496,6 +496,8 @@ def load_env_vars(env):
|
|||
env.CHIBIOS_BUILD_FLAGS += ' ENABLE_STATS=yes'
|
||||
if env.ENABLE_DFU_BOOT and env.BOOTLOADER:
|
||||
env.CHIBIOS_BUILD_FLAGS += ' USE_ASXOPT=-DCRT0_ENTRY_HOOK=TRUE'
|
||||
if env.AP_BOARD_START_TIME:
|
||||
env.CHIBIOS_BUILD_FLAGS += ' AP_BOARD_START_TIME=0x%x' % env.AP_BOARD_START_TIME
|
||||
|
||||
|
||||
def setup_optimization(env):
|
||||
|
|
10
wscript
10
wscript
|
@ -382,6 +382,11 @@ configuration in order to save typing.
|
|||
default=0,
|
||||
help='number of auxiliary IMUs')
|
||||
|
||||
g.add_option('--board-start-time',
|
||||
type='int',
|
||||
default=0,
|
||||
help='zero time on boot in microseconds')
|
||||
|
||||
def _collect_autoconfig_files(cfg):
|
||||
for m in sys.modules.values():
|
||||
paths = []
|
||||
|
@ -452,6 +457,11 @@ def configure(cfg):
|
|||
if cfg.options.num_aux_imus > 0:
|
||||
cfg.define('INS_AUX_INSTANCES', cfg.options.num_aux_imus)
|
||||
|
||||
if cfg.options.board_start_time != 0:
|
||||
cfg.define('AP_BOARD_START_TIME', cfg.options.board_start_time)
|
||||
# also in env for hrt.c
|
||||
cfg.env.AP_BOARD_START_TIME = cfg.options.board_start_time
|
||||
|
||||
cfg.load('ap_library')
|
||||
|
||||
cfg.msg('Setting board to', cfg.options.board)
|
||||
|
|
Loading…
Reference in New Issue