cmake cleanup nuttx dependency handling (#7007)

- closes #6501
 - closes #6820
 - closes #6881
This commit is contained in:
Daniel Agar 2017-04-17 20:57:35 -04:00 committed by GitHub
parent f460f5b34c
commit 3721fb9d52
6 changed files with 214 additions and 98 deletions

View File

@ -81,7 +81,12 @@ endif
ifdef NINJA_BUILD
PX4_CMAKE_GENERATOR := Ninja
PX4_MAKE := $(NINJA_BIN)
PX4_MAKE_ARGS :=
ifdef VERBOSE
PX4_MAKE_ARGS := -v
else
PX4_MAKE_ARGS :=
endif
else
ifdef SYSTEMROOT
# Windows
@ -102,6 +107,17 @@ else
BUILD_DIR_SUFFIX :=
endif
# NuttX verbose output
ifdef VN
export PX4_NUTTX_BUILD_VERBOSE=1
export V=1
endif
# NuttX verbose patches output
ifdef VNP
export PX4_NUTTX_PATCHES_VERBOSE=1
endif
# additional config parameters passed to cmake
CMAKE_ARGS :=
ifdef EXTERNAL_MODULES_LOCATION
@ -327,10 +343,16 @@ clean:
-@$(MAKE) --no-print-directory -C NuttX/nuttx clean
submodulesclean:
@git submodule foreach --quiet --recursive git clean -ff -x -d
@git submodule update --quiet --init --recursive --force || true
@git submodule sync --recursive
@git submodule deinit -f .
@git submodule update --init --recursive --force
submodulesupdate:
@git submodule update --quiet --init --recursive || true
@git submodule sync --recursive
@git submodule update --init --recursive
gazeboclean:
@rm -rf ~/.gazebo/*

View File

@ -440,13 +440,6 @@ function(px4_generate_messages)
)
set_source_files_properties(${msg_source_files_out} PROPERTIES GENERATED TRUE)
# We remove uORBTopics.cpp to make sure the generator is re-run, which is
# necessary when a .msg file is removed and because uORBTopics.cpp depends
# on all topics.
execute_process(COMMAND rm uORBTopics.cpp
WORKING_DIRECTORY ${msg_source_out_path}
ERROR_QUIET)
# multi messages for target OS
set(msg_multi_out_path
${PX4_BINARY_DIR}/src/platforms/${OS}/px4_messages)

View File

@ -35,7 +35,7 @@
#
# Defined functions in this file
#
# OS Specific Functions
# OS Specific Functions
#
# * px4_nuttx_add_firmware
# * px4_nuttx_make_uavcan_bootloadable
@ -43,9 +43,9 @@
# * px4_nuttx_add_export
# * px4_nuttx_add_romfs
#
# Required OS Inteface Functions
# Required OS Inteface Functions
#
# * px4_os_add_flags
# * px4_os_add_flags
# * px4_os_prebuild_targets
#
@ -123,8 +123,8 @@ endfunction()
# SW_MINOR <number>)
#
# Input:
# BOARD : the board
# BIN : the bin file to generate the bootloadable image from
# BOARD : the board
# BIN : the bin file to generate the bootloadable image from
# HWNAME : the uavcan name
# HW_MAJOR : the major hardware revision
# HW_MINOR : the minor hardware revision
@ -248,43 +248,58 @@ function(px4_nuttx_add_export)
REQUIRED OUT CONFIG THREADS
ARGN ${ARGN})
set(nuttx_src ${PX4_BINARY_DIR}/${CONFIG}/NuttX)
set(nuttx_build_options "--quiet")
set(nuttx_build_output ">nuttx_build.log")
if ($ENV{PX4_NUTTX_BUILD_VERBOSE} MATCHES "1")
set(nuttx_build_options)
set(nuttx_build_output)
set(nuttx_build_uses_terminal "USES_TERMINAL")
endif()
# all patches
file(GLOB nuttx_patches ${PX4_SOURCE_DIR}/nuttx-patches/*.patch)
list(SORT nuttx_patches)
if ($ENV{PX4_NUTTX_PATCHES_VERBOSE} MATCHES "1")
set(nuttx_patches_uses_terminal "USES_TERMINAL")
endif()
# nuttx-patches
add_subdirectory(${PX4_SOURCE_DIR}/nuttx-patches ${PX4_BINARY_DIR}/${CONFIG})
set(nuttx_build_src ${PX4_BINARY_DIR}/${CONFIG}/NuttX)
set(nuttx_export_dir ${nuttx_build_src}/nuttx/nuttx-export)
# nuttx cmake dependency files
set(nuttx_copy_stamp ${PX4_BINARY_DIR}/${CONFIG}_nuttx_copy.stamp)
set(nuttx_configure_stamp ${PX4_BINARY_DIR}/${CONFIG}_nuttx_configure.stamp)
set(nuttx_export_stamp ${PX4_BINARY_DIR}/${CONFIG}_nuttx_export.stamp)
# copy
file(GLOB_RECURSE nuttx_all_files ${PX4_SOURCE_DIR}/NuttX/*)
file(RELATIVE_PATH nuttx_cp_src ${PX4_BINARY_DIR} ${PX4_SOURCE_DIR}/NuttX)
add_custom_command(OUTPUT ${PX4_BINARY_DIR}/nuttx_copy_${CONFIG}.stamp
COMMAND ${MKDIR} -p ${nuttx_src}
COMMAND rsync -a --delete --exclude=.git ${nuttx_cp_src}/ ${CONFIG}/NuttX/
COMMAND ${TOUCH} ${PX4_BINARY_DIR}/nuttx_copy_${CONFIG}.stamp
DEPENDS ${DEPENDS} ${nuttx_patches} ${nuttx_all_files}
add_custom_command(OUTPUT ${nuttx_copy_stamp}
COMMAND ${MKDIR} -p ${nuttx_build_src}
COMMAND rsync -rp --inplace --delete --exclude=.git --exclude=nuttx-export ${nuttx_cp_src}/ ${CONFIG}/NuttX/
COMMAND cmake -E touch ${nuttx_copy_stamp}
DEPENDS ${px4_nuttx_patches} ${nuttx_all_files}
COMMENT "Copying NuttX for ${CONFIG} with ${config_nuttx_config}"
WORKING_DIRECTORY ${PX4_BINARY_DIR}
)
add_custom_target(nuttx_copy_${CONFIG} DEPENDS ${PX4_BINARY_DIR}/nuttx_copy_${CONFIG}.stamp)
WORKING_DIRECTORY ${PX4_BINARY_DIR})
add_custom_target(nuttx_copy_${CONFIG} DEPENDS ${DEPENDS} ${nuttx_copy_stamp})
# patch
unset (last_patch )
unset(last_patch_stamp)
add_custom_target(nuttx_patch_${CONFIG})
foreach(patch ${nuttx_patches})
foreach(patch ${px4_nuttx_patches})
get_filename_component(patch_file_name ${patch} NAME)
string(REPLACE "/" "_" patch_name "nuttx_patch_${patch_file_name}-${CONFIG}")
set(patch_stamp ${nuttx_src}/${patch_name}.stamp)
string(REPLACE "/" "_" patch_name "${CONFIG}-nuttx_patch_${patch_file_name}")
set(patch_stamp ${PX4_BINARY_DIR}/${patch_name}.stamp)
add_custom_command(OUTPUT ${patch_stamp}
COMMAND ${PATCH} -d ${nuttx_src} -s -p1 -N < ${patch}
COMMAND ${TOUCH} ${patch_stamp}
DEPENDS ${last_patch} ${DEPENDS} nuttx_copy_${CONFIG} ${patch}
USES_TERMINAL
COMMENT "${CONFIG} Applying NuttX patch: nuttx-patches/${patch_file_name}")
COMMAND ${PATCH} --verbose -d ${nuttx_build_src} -s -p1 -N < ${patch}
COMMAND cmake -E touch ${patch_stamp}
DEPENDS ${nuttx_copy_stamp} ${patch} ${last_patch_stamp}
COMMENT "${CONFIG}: nuttx-patches/${patch_file_name} applied"
${nuttx_patches_uses_terminal})
add_custom_target(${patch_name} DEPENDS ${patch_stamp})
add_dependencies(nuttx_patch_${CONFIG} ${patch_name})
set (last_patch ${patch_name})
set(last_patch_stamp ${patch_stamp})
endforeach()
# Read defconfig to see if CONFIG_ARMV7M_STACKCHECK is yes
@ -297,44 +312,56 @@ function(px4_nuttx_add_export)
set(config_nuttx_hw_stack_check_${CONFIG} y CACHE INTERNAL "" FORCE)
endif()
# configure
file(GLOB_RECURSE config_files ${PX4_SOURCE_DIR}/nuttx-configs/${CONFIG}/*)
add_custom_command(OUTPUT ${nuttx_src}/nuttx/.config
COMMAND ${CP} -rp ${PX4_SOURCE_DIR}/nuttx-configs/*.mk ${nuttx_src}/nuttx/
COMMAND ${CP} -rp ${PX4_SOURCE_DIR}/nuttx-configs/${CONFIG} ${nuttx_src}/nuttx/configs
COMMAND cd ${nuttx_src}/nuttx/tools && sh configure.sh ${CONFIG}/${config_nuttx_config}
DEPENDS ${DEPENDS} nuttx_patch_${CONFIG} ${config_files}
# nuttx configure
file(GLOB_RECURSE nuttx-configs ${PX4_SOURCE_DIR}/nuttx-configs/${CONFIG}/*)
add_custom_command(OUTPUT ${nuttx_configure_stamp} ${nuttx_build_src}/nuttx/.config
COMMAND ${CP} -rp ${PX4_SOURCE_DIR}/nuttx-configs/*.mk ${nuttx_build_src}/nuttx/
COMMAND ${CP} -rp ${PX4_SOURCE_DIR}/nuttx-configs/${CONFIG} ${nuttx_build_src}/nuttx/configs
COMMAND cd ${nuttx_build_src}/nuttx/tools && sh configure.sh ${CONFIG}/${config_nuttx_config}
COMMAND cmake -E touch ${nuttx_configure_stamp}
DEPENDS nuttx_patch_${CONFIG} ${nuttx-configs} ${nuttx_copy_stamp}
WORKING_DIRECTORY ${PX4_BINARY_DIR}
COMMENT "Configuring NuttX for ${CONFIG} with ${config_nuttx_config}")
add_custom_target(nuttx_configure_${CONFIG} DEPENDS ${nuttx_configure_stamp} nuttx_patch_${CONFIG})
# manual reconfigure helpers
# manual nuttx oldconfig helper
add_custom_target(oldconfig_${CONFIG}
COMMAND cd ${nuttx_src}/nuttx
COMMAND ${MAKE} -C ${nuttx_src}/nuttx CONFIG_ARCH_BOARD=${CONFIG} oldconfig
COMMAND ${CP} ${nuttx_src}/nuttx/.config ${PX4_SOURCE_DIR}/nuttx-configs/${CONFIG}/${config_nuttx_config}/defconfig
COMMAND ${MAKE} --no-print-directory -C ${nuttx_build_src}/nuttx CONFIG_ARCH_BOARD=${CONFIG} oldconfig
COMMAND ${CP} ${nuttx_build_src}/nuttx/.config ${PX4_SOURCE_DIR}/nuttx-configs/${CONFIG}/${config_nuttx_config}/defconfig
COMMAND ${PX4_SOURCE_DIR}/Tools/nuttx_defconf_tool.sh ${PX4_SOURCE_DIR}/nuttx-configs/${CONFIG}/${config_nuttx_config}/defconfig
DEPENDS ${nuttx_src}/nuttx/.config
DEPENDS nuttx_configure_${CONFIG}
WORKING_DIRECTORY ${nuttx_build_src}/nuttx
COMMENT "Running NuttX make oldconfig for ${CONFIG} with ${config_nuttx_config}"
USES_TERMINAL)
# manual nuttx menuconfig helper
add_custom_target(menuconfig_${CONFIG}
COMMAND cd ${nuttx_src}/nuttx
COMMAND ${MAKE} -C ${nuttx_src}/nuttx CONFIG_ARCH_BOARD=${CONFIG} menuconfig
COMMAND ${CP} ${nuttx_src}/nuttx/.config ${PX4_SOURCE_DIR}/nuttx-configs/${CONFIG}/${config_nuttx_config}/defconfig
COMMAND ${MAKE} --no-print-directory -C ${nuttx_build_src}/nuttx CONFIG_ARCH_BOARD=${CONFIG} menuconfig
COMMAND ${CP} ${nuttx_build_src}/nuttx/.config ${PX4_SOURCE_DIR}/nuttx-configs/${CONFIG}/${config_nuttx_config}/defconfig
COMMAND ${PX4_SOURCE_DIR}/Tools/nuttx_defconf_tool.sh ${PX4_SOURCE_DIR}/nuttx-configs/${CONFIG}/${config_nuttx_config}/defconfig
DEPENDS ${nuttx_src}/nuttx/.config
DEPENDS nuttx_configure_${CONFIG}
WORKING_DIRECTORY ${nuttx_build_src}/nuttx
COMMENT "Running NuttX make menuconfig for ${CONFIG} with ${config_nuttx_config}"
USES_TERMINAL)
# build and export
add_custom_command(OUTPUT ${nuttx_src}/nuttx/nuttx-export/include/nuttx/config.h
COMMAND ${RM} -rf ${nuttx_src}/nuttx/nuttx-export
COMMAND ${MAKE} --no-print-directory --quiet -C ${nuttx_src}/nuttx -r CONFIG_ARCH_BOARD=${CONFIG} export > nuttx_build.log
DEPENDS ${DEPENDS} ${nuttx_src}/nuttx/.config
# nuttx build and export
add_custom_command(
OUTPUT ${nuttx_export_stamp}
${nuttx_export_dir}/include/nuttx/config.h
COMMAND ${RM} -rf ${nuttx_export_dir}
COMMAND ${MAKE} ${nuttx_build_options} --no-print-directory -C ${nuttx_build_src}/nuttx -r CONFIG_ARCH_BOARD=${CONFIG} export ${nuttx_build_output}
COMMAND cmake -E touch ${nuttx_export_stamp}
DEPENDS ${nuttx_copy_stamp} ${nuttx_configure_stamp} nuttx_patch_${CONFIG}
WORKING_DIRECTORY ${PX4_BINARY_DIR}
COMMENT "Building NuttX for ${CONFIG} with ${config_nuttx_config}")
COMMENT "Building NuttX for ${CONFIG} with ${config_nuttx_config}"
${nuttx_build_uses_terminal})
add_custom_target(${OUT} DEPENDS ${nuttx_src}/nuttx/nuttx-export/include/nuttx/config.h)
file(GLOB_RECURSE nuttx_export_src ${nuttx_export_dir})
foreach(nuttx_export_file ${nuttx_export_dir})
set_source_files_properties(${nuttx_export_src} PROPERTIES GENERATED TRUE)
endforeach()
add_custom_target(${OUT} DEPENDS nuttx_copy_${CONFIG} nuttx_patch_${CONFIG} nuttx_configure_${CONFIG} ${nuttx_export_stamp})
endfunction()
@ -377,7 +404,7 @@ endfunction()
#
# px4_nuttx_add_romfs
#
# The functions creates a ROMFS filesystem for nuttx.
# The functions creates a ROMFS filesystem for nuttx.
#
# Usage:
# px4_nuttx_add_romfs(
@ -387,7 +414,7 @@ endfunction()
#
# Input:
# ROOT : the root of the ROMFS
# EXTRAS : list of extra files
# EXTRAS : list of extra files
#
# Output:
# OUT : the ROMFS library target
@ -610,8 +637,8 @@ endfunction()
# )
#
# Input:
# BOARD : board
# THREADS : number of threads for building
# BOARD : board
# THREADS : number of threads for building
#
# Output:
# OUT : the target list
@ -647,10 +674,10 @@ endfunction()
# )
#
# Input:
# HWCLASS : the class of hardware
# CONFIG : the nuttx condufiguration to use
# ROMFS : whether or not to use incllude theROMFS
# ROMFSROOT : If ROMFS used set the root the default is px4fmu_common
# HWCLASS : the class of hardware
# CONFIG : the nuttx condufiguration to use
# ROMFS : whether or not to use incllude theROMFS
# ROMFSROOT : If ROMFS used set the root the default is px4fmu_common
#
# Output:
# OUT : None

View File

@ -64,8 +64,6 @@ struct_size, padding_end_size = add_padding_bytes(sorted_fields, search_path)
topic_fields = ["uint64_t timestamp"]+["%s %s" % (convert_type(field.type), field.name) for field in sorted_fields]
}@
#include <px4_config.h>
#include <drivers/drv_orb_dev.h>
#include <uORB/topics/@(topic_name).h>

View File

@ -0,0 +1,77 @@
############################################################################
#
# Copyright (c) 2017 PX4 Development Team. All rights reserved.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
#
# 1. Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
# 2. Redistributions in binary form must reproduce the above copyright
# notice, this list of conditions and the following disclaimer in
# the documentation and/or other materials provided with the
# distribution.
# 3. Neither the name PX4 nor the names of its contributors may be
# used to endorse or promote products derived from this software
# without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.
#
############################################################################
set(nuttx_patches
00001-REJECTED-add-math.h.patch
00002-REJECTED-fix-shadow-wanings.patch
00003-REJECTED-add-var-expansion-in-nsh-parse.patch
00004-REJECTED-avoid-export-copy-with-export-insitu.patch
00005-REJECTED-support-c++11.patch
00006-REJECTED-cstdint-fix.patch
00007-REJECTED-silence-jobserver-warnings.patch
00008-REJECTED-static-assert-fix.patch
00009-REJECTED-ctype-fix-shadow-wanings.patch
00010-BACKPORT-stm32-flash-F4-dcache-corruption-fix-no-HSI-on.patch
00011-BACKPORT-priority-restoration-fix.patch
00012-BACKPORT-stack-coloration-overreach-fix.patch
00013-BACKPORT-stm32-serial-dma-hotfix.patch
00014-BACKPORT-i2c-hotfix.patch
00015-BACKPORT-stm32f7-DTCM.patch
00016-BACKPORT-fix-CRTSCTS-defines.patch
00017-BACKPORT-cdcacm.patch
00018-BACKPORT-stm32-serial-break.patch
00019-BACKPORT-stm32-rcc-keep-HSI-on.patch
00020-BACKPORT-ramtron-CONFIG-prefix.patch
00021-BACKPORT-stm32f3x-add-BKP.patch
00022-BACKPORT-stm32-bkp-reference-fix.patch
00023-BACKPORT-stm32f7-bkp-reference-fix.patch
00024-BACKPORT-stm32f7-serial-dma-hotfix.patch
00025-BACKPORT-add-set-ex-to-nsh.patch
90000-PENDING-wip-inflight-to-upstream.patch
)
# add absolute path and sort
set(px4_nuttx_patches)
foreach(patch_file ${nuttx_patches})
list(APPEND px4_nuttx_patches ${CMAKE_CURRENT_SOURCE_DIR}/${patch_file})
endforeach()
list(SORT px4_nuttx_patches)
set(px4_nuttx_patches ${px4_nuttx_patches} PARENT_SCOPE)
file(GLOB patches_found *.patch)
foreach(patch_file ${patches_found})
list (FIND px4_nuttx_patches ${patch_file} _index)
if (${_index} EQUAL -1)
message(WARNING "${patch_file} missing from nuttx-patches/CMakeLists.txt")
endif()
endforeach()

View File

@ -68,35 +68,34 @@ px4_join(OUT CMAKE_CXX_FLAGS LIST "${cxx_flags};${optimization_flags}" GLUE " ")
include_directories(
${include_dirs}
${PX4_BINARY_DIR}/src/modules/systemlib/mixer
.
)
link_directories(${link_dirs})
add_definitions(${definitions})
set(srcs
${PX4_SOURCE_DIR}/src/drivers/boards/${config_io_board}/px4io_init.c
${PX4_SOURCE_DIR}/src/drivers/boards/${config_io_board}/px4io_timer_config.c
${PX4_SOURCE_DIR}/src/drivers/stm32/drv_hrt.c
${PX4_SOURCE_DIR}/src/drivers/stm32/drv_io_timer.c
${PX4_SOURCE_DIR}/src/drivers/stm32/drv_pwm_servo.c
${PX4_SOURCE_DIR}/src/lib/rc/dsm.c
${PX4_SOURCE_DIR}/src/lib/rc/sbus.c
${PX4_SOURCE_DIR}/src/lib/rc/st24.c
${PX4_SOURCE_DIR}/src/lib/rc/sumd.c
${PX4_SOURCE_DIR}/src/modules/systemlib/mixer/mixer.cpp
${PX4_SOURCE_DIR}/src/modules/systemlib/mixer/mixer_group.cpp
${PX4_SOURCE_DIR}/src/modules/systemlib/mixer/mixer_helicopter.cpp
${PX4_SOURCE_DIR}/src/modules/systemlib/mixer/mixer_multirotor.cpp
${PX4_SOURCE_DIR}/src/modules/systemlib/mixer/mixer_simple.cpp
${PX4_SOURCE_DIR}/src/modules/systemlib/perf_counter.c
${PX4_SOURCE_DIR}/src/modules/systemlib/pwm_limit/pwm_limit.c
${PX4_SOURCE_DIR}/src/modules/systemlib/up_cxxinitialize.c
adc.c
controls.c
mixer.cpp
px4io.c
registers.c
safety.c
../systemlib/up_cxxinitialize.c
../systemlib/perf_counter.c
mixer.cpp
../systemlib/mixer/mixer.cpp
../systemlib/mixer/mixer_group.cpp
../systemlib/mixer/mixer_multirotor.cpp
../systemlib/mixer/mixer_helicopter.cpp
../systemlib/mixer/mixer_simple.cpp
../systemlib/pwm_limit/pwm_limit.c
../../lib/rc/st24.c
../../lib/rc/sumd.c
../../lib/rc/sbus.c
../../lib/rc/dsm.c
../../drivers/stm32/drv_hrt.c
../../drivers/stm32/drv_io_timer.c
../../drivers/stm32/drv_pwm_servo.c
../../drivers/boards/${config_io_board}/px4io_init.c
../../drivers/boards/${config_io_board}/px4io_timer_config.c
)
if(${config_io_board} STREQUAL "px4io-v1")
@ -106,20 +105,19 @@ if(${config_io_board} STREQUAL "px4io-v1")
elseif(${config_io_board} STREQUAL "px4io-v2")
list(APPEND srcs
serial.c
../systemlib/hx_stream.c
${PX4_SOURCE_DIR}/src/modules/systemlib/hx_stream.c
)
endif()
set(fw_io_name ${config_io_board})
add_executable(${fw_io_name}
${srcs})
add_executable(${fw_io_name} ${srcs})
add_dependencies(${fw_io_name}
nuttx_export_${config_io_board}
msg_gen
io_prebuild_targets
mixer_gen
msg_gen
nuttx_export_${config_io_board}
)
set(nuttx_export_dir ${PX4_BINARY_DIR}/${config_io_board}/NuttX/nuttx/nuttx-export)
@ -134,14 +132,15 @@ target_link_libraries(${fw_io_name}
-Wl,--start-group
apps nuttx nosys m gcc
${config_io_extra_libs}
-Wl,--end-group)
-Wl,--end-group
)
px4_nuttx_create_bin(OUT ${CMAKE_CURRENT_BINARY_DIR}/${fw_io_name}.bin
px4_nuttx_create_bin(
OUT ${CMAKE_CURRENT_BINARY_DIR}/${fw_io_name}.bin
EXE ${fw_io_name}
)
add_custom_target(fw_io
DEPENDS ${CMAKE_CURRENT_BINARY_DIR}/${fw_io_name}.bin)
add_custom_target(fw_io DEPENDS ${CMAKE_CURRENT_BINARY_DIR}/${fw_io_name}.bin)
# vim: set noet ft=cmake fenc=utf-8 ff=unix :