Browse Source
* NuttX cmake * px4_macros:Pass the stringified predicate as second arg to static assert CC_ASSERT mapes to the c++ static_assert or provides the same funtionality for c via the other macros. The c++ static assert takes 2 argumants the prdicate and a message. This fixes the lacking second argument. * Updated nuttx and apps submodule to upstream nuttx 7.21+==master This is the latest uptake of upstream nuttx and apps. * ROMFS generate with xxd instead of objcopy * delete nuttx-patches * NuttX update submodules to latest px4_nuttx-master * fix nuttx apps and board dependency * docker_run update to latest container 2017-08-29 * cmake ROMFS portable sed usage * NuttX update submodules to latest px4_nuttx-mastersbg
159 changed files with 3199 additions and 4235 deletions
@ -0,0 +1,45 @@
@@ -0,0 +1,45 @@
|
||||
|
||||
message(STATUS "ROMFS: ${config_romfs_root}") |
||||
|
||||
set(romfs_temp_dir ${PX4_BINARY_DIR}/ROMFS/${config_romfs_root}) |
||||
set(romfs_src_dir ${PX4_SOURCE_DIR}/ROMFS/${config_romfs_root}) |
||||
|
||||
# directory setup |
||||
# copy all romfs files, process airframes, prune comments |
||||
file(GLOB_RECURSE init_airframes ${PX4_SOURCE_DIR}/ROMFS/${config_romfs_root}/*/[1-9]*) |
||||
add_custom_command(OUTPUT ${romfs_temp_dir}/init.d/rcS ${romfs_temp_dir}/init.d/rc.autostart |
||||
COMMAND cmake -E copy_directory ${romfs_src_dir} ${romfs_temp_dir} |
||||
COMMAND ${PYTHON_EXECUTABLE} ${PX4_SOURCE_DIR}/Tools/px_process_airframes.py |
||||
-a ${romfs_temp_dir}/init.d |
||||
-s ${romfs_temp_dir}/init.d/rc.autostart |
||||
--board ${BOARD} |
||||
COMMAND ${PYTHON_EXECUTABLE} ${PX4_SOURCE_DIR}/Tools/px_romfs_pruner.py |
||||
--folder ${romfs_temp_dir} --board ${BOARD} |
||||
DEPENDS |
||||
${romfs_src_files} |
||||
${init_airframes} |
||||
${PX4_SOURCE_DIR}/ROMFS/${config_romfs_root}/init.d/rcS |
||||
${PX4_SOURCE_DIR}/Tools/px_process_airframes.py |
||||
) |
||||
|
||||
set(romfs_dependencies) |
||||
list(APPEND romfs_dependencies |
||||
${romfs_temp_dir}/init.d/rcS |
||||
${romfs_temp_dir}/init.d/rc.autostart |
||||
) |
||||
|
||||
# create romfs.bin |
||||
add_custom_command(OUTPUT romfs.img |
||||
COMMAND ${GENROMFS} -f romfs.img -d ${romfs_temp_dir} -V "NSHInitVol" -v > romfs.txt 2>&1 |
||||
DEPENDS ${romfs_dependencies} |
||||
) |
||||
|
||||
# create romfs.o |
||||
add_custom_command(OUTPUT nsh_romfsimg.c |
||||
COMMAND xxd -i romfs.img nsh_romfsimg.c |
||||
COMMAND sed 's/unsigned/const unsigned/g' nsh_romfsimg.c > nsh_romfsimg.c.tmp && mv nsh_romfsimg.c.tmp nsh_romfsimg.c |
||||
DEPENDS romfs.img |
||||
) |
||||
|
||||
add_library(romfs STATIC nsh_romfsimg.c) |
||||
set_target_properties(romfs PROPERTIES LINKER_LANGUAGE C) |
@ -1,5 +1,5 @@
@@ -1,5 +1,5 @@
|
||||
#!/usr/bin/env bash |
||||
|
||||
make px4fmu-v4_default |
||||
cp build_px4fmu-v4_default/parameters.xml ../qgroundcontrol/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml |
||||
cp build_px4fmu-v4_default/airframes.xml ../qgroundcontrol/src/AutoPilotPlugins/PX4/AirframeFactMetaData.xml |
||||
cp build/px4fmu-v4_default/parameters.xml ../qgroundcontrol/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml |
||||
cp build/px4fmu-v4_default/airframes.xml ../qgroundcontrol/src/AutoPilotPlugins/PX4/AirframeFactMetaData.xml |
||||
|
@ -1,30 +1,2 @@
@@ -1,30 +1,2 @@
|
||||
include(nuttx/px4_impl_nuttx) |
||||
|
||||
px4_nuttx_configure(HWCLASS m4 CONFIG bootloader) |
||||
|
||||
set(px4_src_base ${CMAKE_SOURCE_DIR}/src/) |
||||
set(px4_bootloader_base ${px4_src_base}drivers/bootloaders/) |
||||
set(px4_module_base ${px4_src_base}modules/) |
||||
|
||||
# |
||||
# UAVCAN boot loadable Module ID |
||||
|
||||
# |
||||
# Bring in common uavcan hardware identity definitions |
||||
# |
||||
|
||||
include(configs/uavcan_board_ident/esc35-v1) |
||||
|
||||
set(CMAKE_TOOLCHAIN_FILE ${CMAKE_SOURCE_DIR}/cmake/toolchains/Toolchain-arm-none-eabi.cmake) |
||||
|
||||
set(config_module_list |
||||
|
||||
drivers/boards/esc35-v1/bootloader |
||||
|
||||
) |
||||
|
||||
# |
||||
# Bootloaders use a compact vector table not |
||||
# from the lib, but exported in startup |
||||
# |
||||
set(nuttx_startup_files stm32_vectors.o) |
||||
include(nuttx/px4_uavcan_bootloader) |
||||
px4_nuttx_configure(HWCLASS m4 CONFIG bootloader) |
@ -1,30 +1,2 @@
@@ -1,30 +1,2 @@
|
||||
include(nuttx/px4_impl_nuttx) |
||||
|
||||
px4_nuttx_configure(HWCLASS m3 CONFIG bootloader) |
||||
|
||||
set(px4_src_base ${CMAKE_SOURCE_DIR}/src/) |
||||
set(px4_bootloader_base ${px4_src_base}drivers/bootloaders/) |
||||
set(px4_module_base ${px4_src_base}modules/) |
||||
|
||||
# |
||||
# UAVCAN boot loadable Module ID |
||||
|
||||
# |
||||
# Bring in common uavcan hardware identity definitions |
||||
# |
||||
|
||||
include(configs/uavcan_board_ident/px4cannode-v1) |
||||
|
||||
set(CMAKE_TOOLCHAIN_FILE ${CMAKE_SOURCE_DIR}/cmake/toolchains/Toolchain-arm-none-eabi.cmake) |
||||
|
||||
set(config_module_list |
||||
|
||||
drivers/boards/px4cannode-v1/bootloader |
||||
|
||||
) |
||||
|
||||
# |
||||
# Bootloaders use a compact vector table not |
||||
# from the lib, but exported in startup |
||||
# |
||||
set(nuttx_startup_files stm32_vectors.o) |
||||
include(nuttx/px4_uavcan_bootloader) |
||||
px4_nuttx_configure(HWCLASS m3 CONFIG bootloader) |
@ -1,30 +1,2 @@
@@ -1,30 +1,2 @@
|
||||
include(nuttx/px4_impl_nuttx) |
||||
|
||||
px4_nuttx_configure(HWCLASS m4 CONFIG bootloader) |
||||
|
||||
set(px4_src_base ${CMAKE_SOURCE_DIR}/src/) |
||||
set(px4_bootloader_base ${px4_src_base}drivers/bootloaders/) |
||||
set(px4_module_base ${px4_src_base}modules/) |
||||
|
||||
# |
||||
# UAVCAN boot loadable Module ID |
||||
|
||||
# |
||||
# Bring in common uavcan hardware identity definitions |
||||
# |
||||
|
||||
include(configs/uavcan_board_ident/px4esc-v1) |
||||
|
||||
set(CMAKE_TOOLCHAIN_FILE ${CMAKE_SOURCE_DIR}/cmake/toolchains/Toolchain-arm-none-eabi.cmake) |
||||
|
||||
set(config_module_list |
||||
|
||||
drivers/boards/px4esc-v1/bootloader |
||||
|
||||
) |
||||
|
||||
# |
||||
# Bootloaders use a compact vector table not |
||||
# from the lib, but exported in startup |
||||
# |
||||
set(nuttx_startup_files stm32_vectors.o) |
||||
include(nuttx/px4_uavcan_bootloader) |
||||
px4_nuttx_configure(HWCLASS m4 CONFIG bootloader) |
@ -1,96 +1,80 @@
@@ -1,96 +1,80 @@
|
||||
include(nuttx/px4_impl_nuttx) |
||||
|
||||
add_definitions( |
||||
-DFLASH_BASED_PARAMS |
||||
-DPARAM_NO_ORB |
||||
-DPARAM_NO_AUTOSAVE |
||||
-DPARAMETER_BUFFER_SIZE=1024 |
||||
-DFLASH_BASED_PARAMS |
||||
-DPARAM_NO_ORB |
||||
-DPARAM_NO_AUTOSAVE |
||||
-DPARAMETER_BUFFER_SIZE=1024 |
||||
) |
||||
|
||||
px4_nuttx_configure(HWCLASS m4 CONFIG nsh) |
||||
|
||||
# |
||||
# UAVCAN boot loadable Module ID |
||||
|
||||
set(uavcanblid_sw_version_major 0) |
||||
set(uavcanblid_sw_version_minor 1) |
||||
add_definitions( |
||||
-DAPP_VERSION_MAJOR=${uavcanblid_sw_version_major} |
||||
-DAPP_VERSION_MINOR=${uavcanblid_sw_version_minor} |
||||
) |
||||
|
||||
# |
||||
# Bring in common uavcan hardware identity definitions |
||||
# |
||||
|
||||
include(configs/uavcan_board_ident/px4esc-v1) |
||||
add_definitions( |
||||
-DHW_UAVCAN_NAME=${uavcanblid_name} |
||||
-DHW_VERSION_MAJOR=${uavcanblid_hw_version_major} |
||||
-DHW_VERSION_MINOR=${uavcanblid_hw_version_minor} |
||||
) |
||||
|
||||
px4_nuttx_make_uavcan_bootloadable(BOARD ${BOARD} |
||||
BIN ${CMAKE_CURRENT_BINARY_DIR}/src/firmware/nuttx/firmware_nuttx.bin |
||||
HWNAME ${uavcanblid_name} |
||||
HW_MAJOR ${uavcanblid_hw_version_major} |
||||
HW_MINOR ${uavcanblid_hw_version_minor} |
||||
SW_MAJOR ${uavcanblid_sw_version_major} |
||||
SW_MINOR ${uavcanblid_sw_version_minor}) |
||||
BIN ${CMAKE_CURRENT_BINARY_DIR}/src/firmware/nuttx/px4esc-v1.bin |
||||
HWNAME ${uavcanblid_name} |
||||
HW_MAJOR ${uavcanblid_hw_version_major} |
||||
HW_MINOR ${uavcanblid_hw_version_minor} |
||||
SW_MAJOR ${uavcanblid_sw_version_major} |
||||
SW_MINOR ${uavcanblid_sw_version_minor} |
||||
) |
||||
|
||||
set(CMAKE_TOOLCHAIN_FILE ${CMAKE_SOURCE_DIR}/cmake/toolchains/Toolchain-arm-none-eabi.cmake) |
||||
include_directories(${PX4_SOURCE_DIR}/src/drivers/boards/px4esc-v1/bootloader) |
||||
|
||||
set(config_module_list |
||||
|
||||
# |
||||
# Board support modules |
||||
# |
||||
|
||||
drivers/stm32 |
||||
drivers/boards |
||||
drivers/bootloaders |
||||
drivers/device |
||||
drivers/led |
||||
drivers/boards/px4esc-v1 |
||||
drivers/stm32 |
||||
|
||||
# |
||||
# System commands |
||||
# |
||||
systemcmds/config |
||||
systemcmds/reboot |
||||
systemcmds/top |
||||
systemcmds/config |
||||
systemcmds/param |
||||
systemcmds/ver |
||||
systemcmds/param |
||||
|
||||
# |
||||
# General system control |
||||
# |
||||
modules/uavcanesc |
||||
modules/uavcanesc/nshterm |
||||
modules/uavcanesc/commands/cfg |
||||
modules/uavcanesc/commands/selftest |
||||
modules/uavcanesc/commands/dc |
||||
modules/uavcanesc/commands/rpm |
||||
modules/uavcanesc/commands/stat |
||||
modules/uavcanesc |
||||
modules/uavcanesc/nshterm |
||||
modules/uavcanesc/commands/cfg |
||||
modules/uavcanesc/commands/selftest |
||||
modules/uavcanesc/commands/dc |
||||
modules/uavcanesc/commands/rpm |
||||
modules/uavcanesc/commands/stat |
||||
|
||||
# |
||||
# Library modules |
||||
# |
||||
modules/systemlib/param |
||||
modules/systemlib |
||||
lib/micro-CDR |
||||
lib/version |
||||
|
||||
# |
||||
# Libraries |
||||
# |
||||
# had to add for cmake, not sure why wasn't in original config |
||||
platforms/nuttx |
||||
modules/systemlib |
||||
modules/systemlib/param |
||||
modules/uORB |
||||
platforms/common |
||||
platforms/nuttx |
||||
platforms/nuttx/px4_layer |
||||
modules/uORB |
||||
lib/micro-CDR |
||||
|
||||
) |
||||
|
||||
set(config_extra_builtin_cmds |
||||
serdis |
||||
sercon |
||||
) |
||||
|
||||
add_custom_target(sercon) |
||||
set_target_properties(sercon PROPERTIES |
||||
PRIORITY "SCHED_PRIORITY_DEFAULT" |
||||
MAIN "sercon" STACK_MAIN "2048") |
||||
|
||||
add_custom_target(serdis) |
||||
set_target_properties(serdis PROPERTIES |
||||
PRIORITY "SCHED_PRIORITY_DEFAULT" |
||||
MAIN "serdis" STACK_MAIN "2048") |
||||
) |
@ -1,30 +1,2 @@
@@ -1,30 +1,2 @@
|
||||
include(nuttx/px4_impl_nuttx) |
||||
|
||||
px4_nuttx_configure(HWCLASS m4 CONFIG bootloader) |
||||
|
||||
set(px4_src_base ${CMAKE_SOURCE_DIR}/src/) |
||||
set(px4_bootloader_base ${px4_src_base}drivers/bootloaders/) |
||||
set(px4_module_base ${px4_src_base}modules/) |
||||
|
||||
# |
||||
# UAVCAN boot loadable Module ID |
||||
|
||||
# |
||||
# Bring in common uavcan hardware identity definitions |
||||
# |
||||
|
||||
include(configs/uavcan_board_ident/px4flow-v2) |
||||
|
||||
set(CMAKE_TOOLCHAIN_FILE ${CMAKE_SOURCE_DIR}/cmake/toolchains/Toolchain-arm-none-eabi.cmake) |
||||
|
||||
set(config_module_list |
||||
|
||||
drivers/boards/px4flow-v2/bootloader |
||||
|
||||
) |
||||
|
||||
# |
||||
# Bootloaders use a compact vector table not |
||||
# from the lib, but exported in startup |
||||
# |
||||
set(nuttx_startup_files stm32_vectors.o) |
||||
include(nuttx/px4_uavcan_bootloader) |
||||
px4_nuttx_configure(HWCLASS m4 CONFIG bootloader) |
@ -0,0 +1,12 @@
@@ -0,0 +1,12 @@
|
||||
include(nuttx/px4_impl_nuttx) |
||||
|
||||
px4_nuttx_configure(HWCLASS m3 CONFIG nsh) |
||||
|
||||
set(config_module_list |
||||
drivers/boards |
||||
drivers/stm32 |
||||
lib/rc |
||||
modules/px4iofirmware |
||||
modules/systemlib/mixer |
||||
platforms/common |
||||
) |
@ -0,0 +1,14 @@
@@ -0,0 +1,14 @@
|
||||
include(nuttx/px4_impl_nuttx) |
||||
|
||||
px4_nuttx_configure(HWCLASS m3 CONFIG nsh) |
||||
|
||||
set(config_module_list |
||||
drivers/boards/px4io-v2 |
||||
drivers/stm32 |
||||
lib/rc |
||||
modules/px4iofirmware |
||||
modules/systemlib/mixer |
||||
platforms/common |
||||
|
||||
lib/micro-CDR |
||||
) |
@ -1,30 +1,2 @@
@@ -1,30 +1,2 @@
|
||||
include(nuttx/px4_impl_nuttx) |
||||
|
||||
px4_nuttx_configure(HWCLASS m4 CONFIG bootloader) |
||||
|
||||
set(px4_src_base ${CMAKE_SOURCE_DIR}/src/) |
||||
set(px4_bootloader_base ${px4_src_base}drivers/bootloaders/) |
||||
set(px4_module_base ${px4_src_base}modules/) |
||||
|
||||
# |
||||
# UAVCAN boot loadable Module ID |
||||
|
||||
# |
||||
# Bring in common uavcan hardware identity definitions |
||||
# |
||||
|
||||
include(configs/uavcan_board_ident/s2740vc-v1) |
||||
|
||||
set(CMAKE_TOOLCHAIN_FILE ${CMAKE_SOURCE_DIR}/cmake/toolchains/Toolchain-arm-none-eabi.cmake) |
||||
|
||||
set(config_module_list |
||||
|
||||
drivers/boards/s2740vc-v1/bootloader |
||||
|
||||
) |
||||
|
||||
# |
||||
# Bootloaders use a compact vector table not |
||||
# from the lib, but exported in startup |
||||
# |
||||
set(nuttx_startup_files stm32_vectors.o) |
||||
include(nuttx/px4_uavcan_bootloader) |
||||
px4_nuttx_configure(HWCLASS m4 CONFIG bootloader) |
@ -1,30 +1,2 @@
@@ -1,30 +1,2 @@
|
||||
include(nuttx/px4_impl_nuttx) |
||||
|
||||
px4_nuttx_configure(HWCLASS m3 CONFIG bootloader) |
||||
|
||||
set(px4_src_base ${CMAKE_SOURCE_DIR}/src/) |
||||
set(px4_bootloader_base ${px4_src_base}drivers/bootloaders/) |
||||
set(px4_module_base ${px4_src_base}modules/) |
||||
|
||||
# |
||||
# UAVCAN boot loadable Module ID |
||||
|
||||
# |
||||
# Bring in common uavcan hardware identity definitions |
||||
# |
||||
|
||||
include(configs/uavcan_board_ident/zubaxgnss-v1) |
||||
|
||||
set(CMAKE_TOOLCHAIN_FILE ${CMAKE_SOURCE_DIR}/cmake/toolchains/Toolchain-arm-none-eabi.cmake) |
||||
|
||||
set(config_module_list |
||||
|
||||
drivers/boards/zubaxgnss-v1/bootloader |
||||
|
||||
) |
||||
|
||||
# |
||||
# Bootloaders use a compact vector table not |
||||
# from the lib, but exported in startup |
||||
# |
||||
set(nuttx_startup_files stm32_vectors.o) |
||||
include(nuttx/px4_uavcan_bootloader) |
||||
px4_nuttx_configure(HWCLASS m3 CONFIG bootloader) |
@ -1,98 +0,0 @@
@@ -1,98 +0,0 @@
|
||||
#!/usr/bin/env python |
||||
""" |
||||
This converts a binary imagge to an object file |
||||
""" |
||||
from __future__ import print_function |
||||
import subprocess |
||||
import argparse |
||||
import re |
||||
from subprocess import PIPE |
||||
|
||||
#pylint: disable=invalid-name |
||||
parser = argparse.ArgumentParser(description='Convert bin to obj.') |
||||
parser.add_argument('--c_flags', required=True) |
||||
parser.add_argument('--c_compiler', required=True) |
||||
parser.add_argument('--include_path', required=True) |
||||
parser.add_argument('--nm', required=True) |
||||
parser.add_argument('--ld', required=True) |
||||
parser.add_argument('--objcopy', required=True) |
||||
parser.add_argument('--bin', required=True) |
||||
parser.add_argument('--obj', required=True) |
||||
parser.add_argument('--var', required=True) |
||||
args = parser.parse_args() |
||||
|
||||
in_bin = args.bin |
||||
c_flags = args.c_flags |
||||
c_compiler = args.c_compiler |
||||
include_path = args.include_path |
||||
nm = args.nm |
||||
ld = args.ld |
||||
obj = args.obj |
||||
var = args.var |
||||
objcopy = args.objcopy |
||||
|
||||
sym = "_binary_" + in_bin.replace('/', '_').replace('.', '_').replace('-', '_') |
||||
#print("sym: ", sym) |
||||
|
||||
# write empty file |
||||
with open('{obj:s}.c'.format(**locals()), 'w') as f: |
||||
f.write("") |
||||
|
||||
def run_cmd(cmd, d): |
||||
cmd = cmd.format(**d) |
||||
#print(cmd) |
||||
proc = subprocess.Popen(cmd.split(), stdout=PIPE, stderr=PIPE) |
||||
stdout, stderr = proc.communicate() |
||||
if stderr.decode() != "": |
||||
raise RuntimeError(stderr) |
||||
return stdout |
||||
|
||||
# do compile |
||||
run_cmd("{c_compiler:s} -I{include_path:s} {c_flags:s} -c {obj:s}.c -o {obj:s}.c.o", |
||||
locals()) |
||||
|
||||
# link |
||||
run_cmd("{ld:s} -r -o {obj:s}.bin.o {obj:s}.c.o -b binary {in_bin:s}", |
||||
locals()) |
||||
|
||||
# get size of image |
||||
stdout = run_cmd("{nm:s} -p --radix=x {obj:s}.bin.o", locals()) |
||||
re_string = r"^([0-9A-Fa-f]+) .*{sym:s}_size".format(**locals()) |
||||
re_size = re.compile(re_string, re.MULTILINE) |
||||
size_match = re.search(re_size, stdout.decode()) |
||||
|
||||
try: |
||||
size = size_match.group(1) |
||||
except AttributeError as e: |
||||
raise RuntimeError("{:s}\nre:{:s}\n{:s}".format( |
||||
e, re_string, stdout)) |
||||
except IndexError as e: |
||||
group0 = size_match.group(0) |
||||
raise RuntimeError("{:s}\ngroup 0:{:s}\n{:s}".format( |
||||
e, group0, stdout)) |
||||
|
||||
#print("romfs size: ", size) |
||||
|
||||
# write size to file |
||||
with open('{obj:s}.c'.format(**locals()), 'w') as f: |
||||
f.write("const unsigned int {var:s}_len = 0x{size:s};".format( |
||||
**locals())) |
||||
|
||||
# do compile |
||||
run_cmd("{c_compiler:s} -I{include_path:s} {c_flags:s} -c {obj:s}.c -o {obj:s}.c.o", |
||||
locals()) |
||||
|
||||
# link |
||||
run_cmd("{ld:s} -r -o {obj:s} {obj:s}.c.o {obj:s}.bin.o", |
||||
locals()) |
||||
|
||||
# obj copy |
||||
run_cmd(""" |
||||
{objcopy:s} {obj:s} |
||||
--redefine-sym {sym:s}_start={var:s} |
||||
--strip-symbol {sym:s}_size |
||||
--strip-symbol {sym:s}_end |
||||
--rename-section .data=.rodata |
||||
""", locals()) |
||||
|
||||
# vim: set et ft=python fenc= ff=unix sts=4 sw=4 ts=4 : |
@ -1,12 +0,0 @@
@@ -1,12 +0,0 @@
|
||||
/* builtin command list - automatically generated, do not edit */ |
||||
#include <nuttx/config.h> |
||||
#include <nuttx/binfmt/builtin.h> |
||||
#include <nuttx/config.h> |
||||
#if ${command_count} |
||||
${builtin_apps_decl_string} |
||||
const struct builtin_s g_builtins[] = { |
||||
${builtin_apps_string} |
||||
{NULL, 0, 0, NULL} |
||||
}; |
||||
const int g_builtin_count = ${command_count}; |
||||
#endif |
@ -0,0 +1,56 @@
@@ -0,0 +1,56 @@
|
||||
############################################################################ |
||||
# |
||||
# 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. |
||||
# |
||||
############################################################################ |
||||
|
||||
include(nuttx/px4_impl_nuttx) |
||||
|
||||
message(STATUS "PX4 bootloader: ${BOARD}") |
||||
|
||||
# Bring in common uavcan hardware identity definitions |
||||
include(configs/uavcan_board_ident/${BOARD}) |
||||
add_definitions( |
||||
-DHW_UAVCAN_NAME=${uavcanblid_name} |
||||
-DHW_VERSION_MAJOR=${uavcanblid_hw_version_major} |
||||
-DHW_VERSION_MINOR=${uavcanblid_hw_version_minor} |
||||
) |
||||
|
||||
include_directories(src/drivers/boards/${BOARD}/bootloader) |
||||
|
||||
set(config_module_list |
||||
drivers/boards/common |
||||
drivers/boards/${BOARD}/bootloader |
||||
drivers/bootloaders |
||||
) |
||||
|
||||
add_library(nuttx_startup ${PX4_SOURCE_DIR}/platforms/nuttx/NuttX/nuttx/arch/arm/src/stm32/gnu/stm32_vectors.S) |
||||
target_compile_definitions(nuttx_startup PRIVATE -D__ASSEMBLY__) |
||||
add_dependencies(nuttx_startup nuttx_arch_build) |
@ -1,583 +0,0 @@
@@ -1,583 +0,0 @@
|
||||
diff -ruN NuttX/nuttx/arch/arm/include/math.h NuttX/nuttx/arch/arm/include/math.h
|
||||
--- NuttX/nuttx/arch/arm/include/math.h 1969-12-31 14:00:00.000000000 -1000
|
||||
+++ NuttX/nuttx/arch/arm/include/math.h 2014-12-25 17:33:53.404950574 -1000
|
||||
@@ -0,0 +1,579 @@
|
||||
+#ifndef _MATH_H_
|
||||
+
|
||||
+#define _MATH_H_
|
||||
+
|
||||
+#include <machine/ieeefp.h>
|
||||
+#include "_ansi.h"
|
||||
+
|
||||
+_BEGIN_STD_C
|
||||
+
|
||||
+/* Natural log of 2 */
|
||||
+#define _M_LN2 0.693147180559945309417
|
||||
+
|
||||
+#if defined(__GNUC__) && \
|
||||
+ ( (__GNUC__ >= 4) || \
|
||||
+ ( (__GNUC__ >= 3) && defined(__GNUC_MINOR__) && (__GNUC_MINOR__ >= 3) ) )
|
||||
+
|
||||
+ /* gcc >= 3.3 implicitly defines builtins for HUGE_VALx values. */
|
||||
+
|
||||
+# ifndef HUGE_VAL
|
||||
+# define HUGE_VAL (__builtin_huge_val())
|
||||
+# endif
|
||||
+
|
||||
+# ifndef HUGE_VALF
|
||||
+# define HUGE_VALF (__builtin_huge_valf())
|
||||
+# endif
|
||||
+
|
||||
+# ifndef HUGE_VALL
|
||||
+# define HUGE_VALL (__builtin_huge_vall())
|
||||
+# endif
|
||||
+
|
||||
+# ifndef INFINITY
|
||||
+# define INFINITY (__builtin_inff())
|
||||
+# endif
|
||||
+
|
||||
+# ifndef NAN
|
||||
+# define NAN (__builtin_nanf(""))
|
||||
+# endif
|
||||
+
|
||||
+#else /* !gcc >= 3.3 */
|
||||
+
|
||||
+ /* No builtins. Use fixed defines instead. (All 3 HUGE plus the INFINITY
|
||||
+ * * and NAN macros are required to be constant expressions. Using a variable--
|
||||
+ * * even a static const--does not meet this requirement, as it cannot be
|
||||
+ * * evaluated at translation time.)
|
||||
+ * * The infinities are done using numbers that are far in excess of
|
||||
+ * * something that would be expected to be encountered in a floating-point
|
||||
+ * * implementation. (A more certain way uses values from float.h, but that is
|
||||
+ * * avoided because system includes are not supposed to include each other.)
|
||||
+ * * This method might produce warnings from some compilers. (It does in
|
||||
+ * * newer GCCs, but not for ones that would hit this #else.) If this happens,
|
||||
+ * * please report details to the Newlib mailing list. */
|
||||
+
|
||||
+ #ifndef HUGE_VAL
|
||||
+ #define HUGE_VAL (1.0e999999999)
|
||||
+ #endif
|
||||
+
|
||||
+ #ifndef HUGE_VALF
|
||||
+ #define HUGE_VALF (1.0e999999999F)
|
||||
+ #endif
|
||||
+
|
||||
+ #if !defined(HUGE_VALL) && defined(_HAVE_LONG_DOUBLE)
|
||||
+ #define HUGE_VALL (1.0e999999999L)
|
||||
+ #endif
|
||||
+
|
||||
+ #if !defined(INFINITY)
|
||||
+ #define INFINITY (HUGE_VALF)
|
||||
+ #endif
|
||||
+
|
||||
+ #if !defined(NAN)
|
||||
+ #if defined(__GNUC__) && defined(__cplusplus)
|
||||
+ /* Exception: older g++ versions warn about the divide by 0 used in the
|
||||
+ * * normal case (even though older gccs do not). This trick suppresses the
|
||||
+ * * warning, but causes errors for plain gcc, so is only used in the one
|
||||
+ * * special case. */
|
||||
+ static const union { __ULong __i[1]; float __d; } __Nanf = {0x7FC00000};
|
||||
+ #define NAN (__Nanf.__d)
|
||||
+ #else
|
||||
+ #define NAN (0.0F/0.0F)
|
||||
+ #endif
|
||||
+ #endif
|
||||
+
|
||||
+#endif /* !gcc >= 3.3 */
|
||||
+
|
||||
+/* Reentrant ANSI C functions. */
|
||||
+
|
||||
+#ifndef __math_68881
|
||||
+extern double atan _PARAMS((double));
|
||||
+extern double cos _PARAMS((double));
|
||||
+extern double sin _PARAMS((double));
|
||||
+extern double tan _PARAMS((double));
|
||||
+extern double tanh _PARAMS((double));
|
||||
+extern double frexp _PARAMS((double, int *));
|
||||
+extern double modf _PARAMS((double, double *));
|
||||
+extern double ceil _PARAMS((double));
|
||||
+extern double fabs _PARAMS((double));
|
||||
+extern double floor _PARAMS((double));
|
||||
+#endif /* ! defined (__math_68881) */
|
||||
+
|
||||
+/* Non reentrant ANSI C functions. */
|
||||
+
|
||||
+#ifndef _REENT_ONLY
|
||||
+#ifndef __math_68881
|
||||
+extern double acos _PARAMS((double));
|
||||
+extern double asin _PARAMS((double));
|
||||
+extern double atan2 _PARAMS((double, double));
|
||||
+extern double cosh _PARAMS((double));
|
||||
+extern double sinh _PARAMS((double));
|
||||
+extern double exp _PARAMS((double));
|
||||
+extern double ldexp _PARAMS((double, int));
|
||||
+extern double log _PARAMS((double));
|
||||
+extern double log10 _PARAMS((double));
|
||||
+extern double pow _PARAMS((double, double));
|
||||
+extern double sqrt _PARAMS((double));
|
||||
+extern double fmod _PARAMS((double, double));
|
||||
+#endif /* ! defined (__math_68881) */
|
||||
+#endif /* ! defined (_REENT_ONLY) */
|
||||
+
|
||||
+#if !defined(__STRICT_ANSI__) || defined(__cplusplus) || __STDC_VERSION__ >= 199901L
|
||||
+
|
||||
+/* ISO C99 types and macros. */
|
||||
+
|
||||
+#ifndef FLT_EVAL_METHOD
|
||||
+#define FLT_EVAL_METHOD 0
|
||||
+typedef float float_t;
|
||||
+typedef double double_t;
|
||||
+#endif /* FLT_EVAL_METHOD */
|
||||
+
|
||||
+#define FP_NAN 0
|
||||
+#define FP_INFINITE 1
|
||||
+#define FP_ZERO 2
|
||||
+#define FP_SUBNORMAL 3
|
||||
+#define FP_NORMAL 4
|
||||
+
|
||||
+#ifndef FP_ILOGB0
|
||||
+# define FP_ILOGB0 (-INT_MAX)
|
||||
+#endif
|
||||
+#ifndef FP_ILOGBNAN
|
||||
+# define FP_ILOGBNAN INT_MAX
|
||||
+#endif
|
||||
+
|
||||
+#ifndef MATH_ERRNO
|
||||
+# define MATH_ERRNO 1
|
||||
+#endif
|
||||
+#ifndef MATH_ERREXCEPT
|
||||
+# define MATH_ERREXCEPT 2
|
||||
+#endif
|
||||
+#ifndef math_errhandling
|
||||
+# define math_errhandling MATH_ERRNO
|
||||
+#endif
|
||||
+
|
||||
+extern int __isinff (float x);
|
||||
+extern int __isinfd (double x);
|
||||
+extern int __isnanf (float x);
|
||||
+extern int __isnand (double x);
|
||||
+extern int __fpclassifyf (float x);
|
||||
+extern int __fpclassifyd (double x);
|
||||
+extern int __signbitf (float x);
|
||||
+extern int __signbitd (double x);
|
||||
+
|
||||
+#define fpclassify(__x) \
|
||||
+ ((sizeof(__x) == sizeof(float)) ? __fpclassifyf(__x) : \
|
||||
+ __fpclassifyd(__x))
|
||||
+
|
||||
+#ifndef isfinite
|
||||
+ #define isfinite(__y) \
|
||||
+ (__extension__ ({int __cy = fpclassify(__y); \
|
||||
+ __cy != FP_INFINITE && __cy != FP_NAN;}))
|
||||
+#endif
|
||||
+
|
||||
+/* Note: isinf and isnan were once functions in newlib that took double
|
||||
+ * * arguments. C99 specifies that these names are reserved for macros
|
||||
+ * * supporting multiple floating point types. Thus, they are
|
||||
+ * * now defined as macros. Implementations of the old functions
|
||||
+ * * taking double arguments still exist for compatibility purposes
|
||||
+ * * (prototypes for them are in <ieeefp.h>). */
|
||||
+#ifndef isinf
|
||||
+ #define isinf(y) (fpclassify(y) == FP_INFINITE)
|
||||
+#endif
|
||||
+
|
||||
+#ifndef isnan
|
||||
+ #define isnan(y) (fpclassify(y) == FP_NAN)
|
||||
+#endif
|
||||
+
|
||||
+#define isnormal(y) (fpclassify(y) == FP_NORMAL)
|
||||
+#define signbit(__x) \
|
||||
+ ((sizeof(__x) == sizeof(float)) ? __signbitf(__x) : \
|
||||
+ __signbitd(__x))
|
||||
+
|
||||
+#define isgreater(x,y) \
|
||||
+ (__extension__ ({__typeof__(x) __x = (x); __typeof__(y) __y = (y); \
|
||||
+ !isunordered(__x,__y) && (__x > __y);}))
|
||||
+#define isgreaterequal(x,y) \
|
||||
+ (__extension__ ({__typeof__(x) __x = (x); __typeof__(y) __y = (y); \
|
||||
+ !isunordered(__x,__y) && (__x >= __y);}))
|
||||
+#define isless(x,y) \
|
||||
+ (__extension__ ({__typeof__(x) __x = (x); __typeof__(y) __y = (y); \
|
||||
+ !isunordered(__x,__y) && (__x < __y);}))
|
||||
+#define islessequal(x,y) \
|
||||
+ (__extension__ ({__typeof__(x) __x = (x); __typeof__(y) __y = (y); \
|
||||
+ !isunordered(__x,__y) && (__x <= __y);}))
|
||||
+#define islessgreater(x,y) \
|
||||
+ (__extension__ ({__typeof__(x) __x = (x); __typeof__(y) __y = (y); \
|
||||
+ !isunordered(__x,__y) && (__x < __y || __x > __y);}))
|
||||
+
|
||||
+#define isunordered(a,b) \
|
||||
+ (__extension__ ({__typeof__(a) __a = (a); __typeof__(b) __b = (b); \
|
||||
+ fpclassify(__a) == FP_NAN || fpclassify(__b) == FP_NAN;}))
|
||||
+
|
||||
+/* Non ANSI double precision functions. */
|
||||
+
|
||||
+extern double infinity _PARAMS((void));
|
||||
+extern double nan _PARAMS((const char *));
|
||||
+extern int finite _PARAMS((double));
|
||||
+extern double copysign _PARAMS((double, double));
|
||||
+extern double logb _PARAMS((double));
|
||||
+extern int ilogb _PARAMS((double));
|
||||
+
|
||||
+extern double asinh _PARAMS((double));
|
||||
+extern double cbrt _PARAMS((double));
|
||||
+extern double nextafter _PARAMS((double, double));
|
||||
+extern double rint _PARAMS((double));
|
||||
+extern double scalbn _PARAMS((double, int));
|
||||
+
|
||||
+extern double exp2 _PARAMS((double));
|
||||
+extern double scalbln _PARAMS((double, long int));
|
||||
+extern double tgamma _PARAMS((double));
|
||||
+extern double nearbyint _PARAMS((double));
|
||||
+extern long int lrint _PARAMS((double));
|
||||
+extern long long int llrint _PARAMS((double));
|
||||
+extern double round _PARAMS((double));
|
||||
+extern long int lround _PARAMS((double));
|
||||
+extern long long int llround _PARAMS((double));
|
||||
+extern double trunc _PARAMS((double));
|
||||
+extern double remquo _PARAMS((double, double, int *));
|
||||
+extern double fdim _PARAMS((double, double));
|
||||
+extern double fmax _PARAMS((double, double));
|
||||
+extern double fmin _PARAMS((double, double));
|
||||
+extern double fma _PARAMS((double, double, double));
|
||||
+
|
||||
+#ifndef __math_68881
|
||||
+extern double log1p _PARAMS((double));
|
||||
+extern double expm1 _PARAMS((double));
|
||||
+#endif /* ! defined (__math_68881) */
|
||||
+
|
||||
+#ifndef _REENT_ONLY
|
||||
+extern double acosh _PARAMS((double));
|
||||
+extern double atanh _PARAMS((double));
|
||||
+extern double remainder _PARAMS((double, double));
|
||||
+extern double gamma _PARAMS((double));
|
||||
+extern double lgamma _PARAMS((double));
|
||||
+extern double erf _PARAMS((double));
|
||||
+extern double erfc _PARAMS((double));
|
||||
+extern double log2 _PARAMS((double));
|
||||
+
|
||||
+#ifndef __math_68881
|
||||
+extern double hypot _PARAMS((double, double));
|
||||
+#endif
|
||||
+
|
||||
+#endif /* ! defined (_REENT_ONLY) */
|
||||
+
|
||||
+/* Single precision versions of ANSI functions. */
|
||||
+
|
||||
+extern float atanf _PARAMS((float));
|
||||
+extern float cosf _PARAMS((float));
|
||||
+extern float sinf _PARAMS((float));
|
||||
+extern float tanf _PARAMS((float));
|
||||
+extern float tanhf _PARAMS((float));
|
||||
+extern float frexpf _PARAMS((float, int *));
|
||||
+extern float modff _PARAMS((float, float *));
|
||||
+extern float ceilf _PARAMS((float));
|
||||
+extern float fabsf _PARAMS((float));
|
||||
+extern float floorf _PARAMS((float));
|
||||
+
|
||||
+#ifndef _REENT_ONLY
|
||||
+extern float acosf _PARAMS((float));
|
||||
+extern float asinf _PARAMS((float));
|
||||
+extern float atan2f _PARAMS((float, float));
|
||||
+extern float coshf _PARAMS((float));
|
||||
+extern float sinhf _PARAMS((float));
|
||||
+extern float expf _PARAMS((float));
|
||||
+extern float ldexpf _PARAMS((float, int));
|
||||
+extern float logf _PARAMS((float));
|
||||
+extern float log10f _PARAMS((float));
|
||||
+extern float powf _PARAMS((float, float));
|
||||
+extern float sqrtf _PARAMS((float));
|
||||
+extern float fmodf _PARAMS((float, float));
|
||||
+#endif /* ! defined (_REENT_ONLY) */
|
||||
+
|
||||
+/* Other single precision functions. */
|
||||
+
|
||||
+extern float exp2f _PARAMS((float));
|
||||
+extern float scalblnf _PARAMS((float, long int));
|
||||
+extern float tgammaf _PARAMS((float));
|
||||
+extern float nearbyintf _PARAMS((float));
|
||||
+extern long int lrintf _PARAMS((float));
|
||||
+extern long long llrintf _PARAMS((float));
|
||||
+extern float roundf _PARAMS((float));
|
||||
+extern long int lroundf _PARAMS((float));
|
||||
+extern long long int llroundf _PARAMS((float));
|
||||
+extern float truncf _PARAMS((float));
|
||||
+extern float remquof _PARAMS((float, float, int *));
|
||||
+extern float fdimf _PARAMS((float, float));
|
||||
+extern float fmaxf _PARAMS((float, float));
|
||||
+extern float fminf _PARAMS((float, float));
|
||||
+extern float fmaf _PARAMS((float, float, float));
|
||||
+
|
||||
+extern float infinityf _PARAMS((void));
|
||||
+extern float nanf _PARAMS((const char *));
|
||||
+extern int finitef _PARAMS((float));
|
||||
+extern float copysignf _PARAMS((float, float));
|
||||
+extern float logbf _PARAMS((float));
|
||||
+extern int ilogbf _PARAMS((float));
|
||||
+
|
||||
+extern float asinhf _PARAMS((float));
|
||||
+extern float cbrtf _PARAMS((float));
|
||||
+extern float nextafterf _PARAMS((float, float));
|
||||
+extern float rintf _PARAMS((float));
|
||||
+extern float scalbnf _PARAMS((float, int));
|
||||
+extern float log1pf _PARAMS((float));
|
||||
+extern float expm1f _PARAMS((float));
|
||||
+
|
||||
+#ifndef _REENT_ONLY
|
||||
+extern float acoshf _PARAMS((float));
|
||||
+extern float atanhf _PARAMS((float));
|
||||
+extern float remainderf _PARAMS((float, float));
|
||||
+extern float gammaf _PARAMS((float));
|
||||
+extern float lgammaf _PARAMS((float));
|
||||
+extern float erff _PARAMS((float));
|
||||
+extern float erfcf _PARAMS((float));
|
||||
+extern float log2f _PARAMS((float));
|
||||
+extern float hypotf _PARAMS((float, float));
|
||||
+#endif /* ! defined (_REENT_ONLY) */
|
||||
+
|
||||
+/* On platforms where long double equals double. */
|
||||
+#ifdef _LDBL_EQ_DBL
|
||||
+/* Reentrant ANSI C functions. */
|
||||
+#ifndef __math_68881
|
||||
+extern long double atanl _PARAMS((long double));
|
||||
+extern long double cosl _PARAMS((long double));
|
||||
+extern long double sinl _PARAMS((long double));
|
||||
+extern long double tanl _PARAMS((long double));
|
||||
+extern long double tanhl _PARAMS((long double));
|
||||
+extern long double frexpl _PARAMS((long double value, int *));
|
||||
+extern long double modfl _PARAMS((long double, long double *));
|
||||
+extern long double ceill _PARAMS((long double));
|
||||
+extern long double fabsl _PARAMS((long double));
|
||||
+extern long double floorl _PARAMS((long double));
|
||||
+extern long double log1pl _PARAMS((long double));
|
||||
+extern long double expm1l _PARAMS((long double));
|
||||
+#endif /* ! defined (__math_68881) */
|
||||
+/* Non reentrant ANSI C functions. */
|
||||
+#ifndef _REENT_ONLY
|
||||
+#ifndef __math_68881
|
||||
+extern long double acosl _PARAMS((long double));
|
||||
+extern long double asinl _PARAMS((long double));
|
||||
+extern long double atan2l _PARAMS((long double, long double));
|
||||
+extern long double coshl _PARAMS((long double));
|
||||
+extern long double sinhl _PARAMS((long double));
|
||||
+extern long double expl _PARAMS((long double));
|
||||
+extern long double ldexpl _PARAMS((long double, int));
|
||||
+extern long double logl _PARAMS((long double));
|
||||
+extern long double log2l _PARAMS((long double));
|
||||
+extern long double log10l _PARAMS((long double));
|
||||
+extern long double powl _PARAMS((long double, long double));
|
||||
+extern long double sqrtl _PARAMS((long double));
|
||||
+extern long double fmodl _PARAMS((long double, long double));
|
||||
+extern long double hypotl _PARAMS((long double, long double));
|
||||
+#endif /* ! defined (__math_68881) */
|
||||
+#endif /* ! defined (_REENT_ONLY) */
|
||||
+extern long double copysignl _PARAMS((long double, long double));
|
||||
+extern long double nanl _PARAMS((const char *));
|
||||
+extern int ilogbl _PARAMS((long double));
|
||||
+extern long double asinhl _PARAMS((long double));
|
||||
+extern long double cbrtl _PARAMS((long double));
|
||||
+extern long double nextafterl _PARAMS((long double, long double));
|
||||
+extern long double rintl _PARAMS((long double));
|
||||
+extern long double scalbnl _PARAMS((long double, int));
|
||||
+extern long double exp2l _PARAMS((long double));
|
||||
+extern long double scalblnl _PARAMS((long double, long));
|
||||
+extern long double tgammal _PARAMS((long double));
|
||||
+extern long double nearbyintl _PARAMS((long double));
|
||||
+extern long int lrintl _PARAMS((long double));
|
||||
+extern long long int llrintl _PARAMS((long double));
|
||||
+extern long double roundl _PARAMS((long double));
|
||||
+extern long lroundl _PARAMS((long double));
|
||||
+extern long long int llroundl _PARAMS((long double));
|
||||
+extern long double truncl _PARAMS((long double));
|
||||
+extern long double remquol _PARAMS((long double, long double, int *));
|
||||
+extern long double fdiml _PARAMS((long double, long double));
|
||||
+extern long double fmaxl _PARAMS((long double, long double));
|
||||
+extern long double fminl _PARAMS((long double, long double));
|
||||
+extern long double fmal _PARAMS((long double, long double, long double));
|
||||
+#ifndef _REENT_ONLY
|
||||
+extern long double acoshl _PARAMS((long double));
|
||||
+extern long double atanhl _PARAMS((long double));
|
||||
+extern long double remainderl _PARAMS((long double, long double));
|
||||
+extern long double lgammal _PARAMS((long double));
|
||||
+extern long double erfl _PARAMS((long double));
|
||||
+extern long double erfcl _PARAMS((long double));
|
||||
+#endif /* ! defined (_REENT_ONLY) */
|
||||
+#else /* !_LDBL_EQ_DBL */
|
||||
+#ifdef __i386__
|
||||
+/* Other long double precision functions. */
|
||||
+extern _LONG_DOUBLE rintl _PARAMS((_LONG_DOUBLE));
|
||||
+extern long int lrintl _PARAMS((_LONG_DOUBLE));
|
||||
+extern long long llrintl _PARAMS((_LONG_DOUBLE));
|
||||
+#endif /* __i386__ */
|
||||
+#endif /* !_LDBL_EQ_DBL */
|
||||
+
|
||||
+#endif /* !defined (__STRICT_ANSI__) || defined(__cplusplus) || __STDC_VERSION__ >= 199901L */
|
||||
+
|
||||
+#if !defined (__STRICT_ANSI__) || defined(__cplusplus)
|
||||
+
|
||||
+extern double drem _PARAMS((double, double));
|
||||
+extern void sincos _PARAMS((double, double *, double *));
|
||||
+extern double gamma_r _PARAMS((double, int *));
|
||||
+extern double lgamma_r _PARAMS((double, int *));
|
||||
+
|
||||
+extern double y0 _PARAMS((double));
|
||||
+extern double y1 _PARAMS((double));
|
||||
+extern double yn _PARAMS((int, double));
|
||||
+extern double j0 _PARAMS((double));
|
||||
+extern double j1 _PARAMS((double));
|
||||
+extern double jn _PARAMS((int, double));
|
||||
+
|
||||
+extern float dremf _PARAMS((float, float));
|
||||
+extern void sincosf _PARAMS((float, float *, float *));
|
||||
+extern float gammaf_r _PARAMS((float, int *));
|
||||
+extern float lgammaf_r _PARAMS((float, int *));
|
||||
+
|
||||
+extern float y0f _PARAMS((float));
|
||||
+extern float y1f _PARAMS((float));
|
||||
+extern float ynf _PARAMS((int, float));
|
||||
+extern float j0f _PARAMS((float));
|
||||
+extern float j1f _PARAMS((float));
|
||||
+extern float jnf _PARAMS((int, float));
|
||||
+
|
||||
+/* GNU extensions */
|
||||
+# ifndef exp10
|
||||
+extern double exp10 _PARAMS((double));
|
||||
+# endif
|
||||
+# ifndef pow10
|
||||
+extern double pow10 _PARAMS((double));
|
||||
+# endif
|
||||
+# ifndef exp10f
|
||||
+extern float exp10f _PARAMS((float));
|
||||
+# endif
|
||||
+# ifndef pow10f
|
||||
+extern float pow10f _PARAMS((float));
|
||||
+# endif
|
||||
+
|
||||
+#endif /* !defined (__STRICT_ANSI__) || defined(__cplusplus) */
|
||||
+
|
||||
+#ifndef __STRICT_ANSI__
|
||||
+
|
||||
+/* The gamma functions use a global variable, signgam. */
|
||||
+#ifndef _REENT_ONLY
|
||||
+#define signgam (*__signgam())
|
||||
+extern int *__signgam _PARAMS((void));
|
||||
+#endif /* ! defined (_REENT_ONLY) */
|
||||
+
|
||||
+#define __signgam_r(ptr) _REENT_SIGNGAM(ptr)
|
||||
+
|
||||
+/* The exception structure passed to the matherr routine. */
|
||||
+/* We have a problem when using C++ since `exception' is a reserved
|
||||
+ * name in C++. */
|
||||
+#ifdef __cplusplus
|
||||
+struct __exception
|
||||
+#else
|
||||
+struct exception
|
||||
+#endif
|
||||
+{
|
||||
+ int type;
|
||||
+ char *name;
|
||||
+ double arg1;
|
||||
+ double arg2;
|
||||
+ double retval;
|
||||
+ int err;
|
||||
+};
|
||||
+
|
||||
+#ifdef __cplusplus
|
||||
+extern int matherr _PARAMS((struct __exception *e));
|
||||
+#else
|
||||
+extern int matherr _PARAMS((struct exception *e));
|
||||
+#endif
|
||||
+
|
||||
+/* Values for the type field of struct exception. */
|
||||
+
|
||||
+#define DOMAIN 1
|
||||
+#define SING 2
|
||||
+#define OVERFLOW 3
|
||||
+#define UNDERFLOW 4
|
||||
+#define TLOSS 5
|
||||
+#define PLOSS 6
|
||||
+
|
||||
+/* Useful constants. */
|
||||
+
|
||||
+#define MAXFLOAT 3.40282347e+38F
|
||||
+
|
||||
+#define M_E 2.7182818284590452354
|
||||
+#define M_LOG2E 1.4426950408889634074
|
||||
+#define M_LOG10E 0.43429448190325182765
|
||||
+#define M_LN2 _M_LN2
|
||||
+#define M_LN10 2.30258509299404568402
|
||||
+#define M_PI 3.14159265358979323846
|
||||
+#define M_TWOPI (M_PI * 2.0)
|
||||
+#define M_PI_2 1.57079632679489661923
|
||||
+#define M_PI_4 0.78539816339744830962
|
||||
+#define M_3PI_4 2.3561944901923448370E0
|
||||
+#define M_SQRTPI 1.77245385090551602792981
|
||||
+#define M_1_PI 0.31830988618379067154
|
||||
+#define M_2_PI 0.63661977236758134308
|
||||
+#define M_2_SQRTPI 1.12837916709551257390
|
||||
+#define M_DEG_TO_RAD 0.01745329251994
|
||||
+#define M_RAD_TO_DEG 57.2957795130823
|
||||
+#define M_SQRT2 1.41421356237309504880
|
||||
+#define M_SQRT1_2 0.70710678118654752440
|
||||
+#define M_LN2LO 1.9082149292705877000E-10
|
||||
+#define M_LN2HI 6.9314718036912381649E-1
|
||||
+#define M_SQRT3 1.73205080756887719000
|
||||
+#define M_IVLN10 0.43429448190325182765 /* 1 / log(10) */
|
||||
+#define M_LOG2_E _M_LN2
|
||||
+#define M_INVLN2 1.4426950408889633870E0 /* 1 / log(2) */
|
||||
+
|
||||
+
|
||||
+#define M_E_F 2.7182818284590452354f
|
||||
+#define M_LOG2E_F 1.4426950408889634074f
|
||||
+#define M_LOG10E_F 0.43429448190325182765f
|
||||
+#define M_LN2_F _M_LN2_F
|
||||
+#define M_LN10_F 2.30258509299404568402f
|
||||
+#define M_PI_F 3.14159265358979323846f
|
||||
+#define M_TWOPI_F (M_PI_F * 2.0f)
|
||||
+#define M_PI_2_F 1.57079632679489661923f
|
||||
+#define M_PI_4_F 0.78539816339744830962f
|
||||
+#define M_3PI_4_F 2.3561944901923448370E0f
|
||||
+#define M_SQRTPI_F 1.77245385090551602792981f
|
||||
+#define M_1_PI_F 0.31830988618379067154f
|
||||
+#define M_2_PI_F 0.63661977236758134308f
|
||||
+#define M_2_SQRTPI_F 1.12837916709551257390f
|
||||
+#define M_DEG_TO_RAD_F 0.01745329251994f
|
||||
+#define M_RAD_TO_DEG_F 57.2957795130823f
|
||||
+#define M_SQRT2_F 1.41421356237309504880f
|
||||
+#define M_SQRT1_2_F 0.70710678118654752440f
|
||||
+#define M_LN2LO_F 1.9082149292705877000E-10f
|
||||
+#define M_LN2HI_F 6.9314718036912381649E-1f
|
||||
+#define M_SQRT3_F 1.73205080756887719000f
|
||||
+#define M_IVLN10_F 0.43429448190325182765f /* 1 / log(10) */
|
||||
+#define M_LOG2_E_F _M_LN2_F
|
||||
+#define M_INVLN2_F 1.4426950408889633870E0f /* 1 / log(2) */
|
||||
+
|
||||
+/* Global control over fdlibm error handling. */
|
||||
+
|
||||
+enum __fdlibm_version
|
||||
+{
|
||||
+ __fdlibm_ieee = -1,
|
||||
+ __fdlibm_svid,
|
||||
+ __fdlibm_xopen,
|
||||
+ __fdlibm_posix
|
||||
+};
|
||||
+
|
||||
+#define _LIB_VERSION_TYPE enum __fdlibm_version
|
||||
+#define _LIB_VERSION __fdlib_version
|
||||
+
|
||||
+extern __IMPORT _LIB_VERSION_TYPE _LIB_VERSION;
|
||||
+
|
||||
+#define _IEEE_ __fdlibm_ieee
|
||||
+#define _SVID_ __fdlibm_svid
|
||||
+#define _XOPEN_ __fdlibm_xopen
|
||||
+#define _POSIX_ __fdlibm_posix
|
||||
+
|
||||
+#endif /* ! defined (__STRICT_ANSI__) */
|
||||
+
|
||||
+_END_STD_C
|
||||
+
|
||||
+#ifdef __FAST_MATH__
|
||||
+#include <machine/fastmath.h>
|
||||
+#endif
|
||||
+
|
||||
+#endif /* _MATH_H_ */
|
@ -1,64 +0,0 @@
@@ -1,64 +0,0 @@
|
||||
diff --git NuttX/nuttx/include/signal.h NuttX/nuttx/include/signal.h
|
||||
index bd8ee9f..7ee242a 100644
|
||||
--- NuttX/nuttx/include/signal.h
|
||||
+++ NuttX/nuttx/include/signal.h
|
||||
@@ -282,8 +282,11 @@ extern "C"
|
||||
|
||||
int kill(pid_t pid, int signo);
|
||||
int raise(int signo);
|
||||
+#pragma GCC diagnostic push
|
||||
+#pragma GCC diagnostic ignored "-Wshadow"
|
||||
int sigaction(int signo, FAR const struct sigaction *act,
|
||||
FAR struct sigaction *oact);
|
||||
+#pragma GCC diagnostic pop
|
||||
int sigaddset(FAR sigset_t *set, int signo);
|
||||
int sigdelset(FAR sigset_t *set, int signo);
|
||||
int sigemptyset(FAR sigset_t *set);
|
||||
diff --git NuttX/nuttx/include/stdlib.h NuttX/nuttx/include/stdlib.h
|
||||
index aa259c9..f2b0640 100644
|
||||
--- NuttX/nuttx/include/stdlib.h
|
||||
+++ NuttX/nuttx/include/stdlib.h
|
||||
@@ -202,7 +202,10 @@ FAR void *zalloc(size_t);
|
||||
FAR void *calloc(size_t, size_t);
|
||||
|
||||
#ifdef CONFIG_CAN_PASS_STRUCTS
|
||||
+#pragma GCC diagnostic push
|
||||
+#pragma GCC diagnostic ignored "-Wshadow"
|
||||
struct mallinfo mallinfo(void);
|
||||
+#pragma GCC diagnostic pop
|
||||
#else
|
||||
int mallinfo(FAR struct mallinfo *info);
|
||||
#endif
|
||||
diff --git NuttX/nuttx/include/sys/statfs.h NuttX/nuttx/include/sys/statfs.h
|
||||
index 1d1786a..12f802b 100644
|
||||
--- NuttX/nuttx/include/sys/statfs.h
|
||||
+++ NuttX/nuttx/include/sys/statfs.h
|
||||
@@ -139,8 +139,11 @@ extern "C"
|
||||
* form of the struct statfs.
|
||||
*/
|
||||
|
||||
+#pragma GCC diagnostic push
|
||||
+#pragma GCC diagnostic ignored "-Wshadow"
|
||||
int statfs(FAR const char *path, FAR struct statfs *buf);
|
||||
int fstatfs(int fd, FAR struct statfs *buf);
|
||||
+#pragma GCC diagnostic pop
|
||||
|
||||
#undef EXTERN
|
||||
#if defined(__cplusplus)
|
||||
diff --git NuttX/nuttx/include/sys/stat.h NuttX/nuttx/include/sys/stat.h
|
||||
index 4d82f62..4d35fcb 100644
|
||||
--- NuttX/nuttx/include/sys/stat.h
|
||||
+++ NuttX/nuttx/include/sys/stat.h
|
||||
@@ -154,9 +154,11 @@ extern "C"
|
||||
|
||||
int mkdir(FAR const char *pathname, mode_t mode);
|
||||
int mkfifo(FAR const char *pathname, mode_t mode);
|
||||
+#pragma GCC diagnostic push
|
||||
+#pragma GCC diagnostic ignored "-Wshadow"
|
||||
int stat(const char *path, FAR struct stat *buf);
|
||||
int fstat(int fd, FAR struct stat *buf);
|
||||
-
|
||||
+#pragma GCC diagnostic pop
|
||||
#undef EXTERN
|
||||
#if defined(__cplusplus)
|
||||
}
|
@ -1,271 +0,0 @@
@@ -1,271 +0,0 @@
|
||||
diff --git NuttX/apps/nshlib/nsh_parse.c NuttX/apps/nshlib/nsh_parse.c
|
||||
index 30f7ef5..f6fa2e0 100644
|
||||
--- NuttX/apps/nshlib/nsh_parse.c
|
||||
+++ NuttX/apps/nshlib/nsh_parse.c
|
||||
@@ -156,9 +156,9 @@ static FAR char *nsh_envexpand(FAR struct nsh_vtbl_s *vtbl,
|
||||
#endif
|
||||
|
||||
static FAR char *nsh_argexpand(FAR struct nsh_vtbl_s *vtbl, FAR char *cmdline,
|
||||
- FAR char **allocation);
|
||||
+ FAR char **allocation, int* isenvvar);
|
||||
static FAR char *nsh_argument(FAR struct nsh_vtbl_s *vtbl, char **saveptr,
|
||||
- FAR NSH_MEMLIST_TYPE *memlist);
|
||||
+ FAR NSH_MEMLIST_TYPE *memlist, int* isenvvar);
|
||||
|
||||
#ifndef CONFIG_NSH_DISABLESCRIPT
|
||||
#ifndef CONFIG_NSH_DISABLE_LOOPS
|
||||
@@ -1009,7 +1009,7 @@ static FAR char *nsh_envexpand(FAR struct nsh_vtbl_s *vtbl,
|
||||
|
||||
#if defined(CONFIG_NSH_ARGCAT) && defined(HAVE_MEMLIST)
|
||||
static FAR char *nsh_argexpand(FAR struct nsh_vtbl_s *vtbl, FAR char *cmdline,
|
||||
- FAR char **allocation)
|
||||
+ FAR char **allocation, int* isenvvar)
|
||||
{
|
||||
FAR char *working = cmdline;
|
||||
FAR char *argument = NULL;
|
||||
@@ -1128,8 +1128,8 @@ static FAR char *nsh_argexpand(FAR struct nsh_vtbl_s *vtbl, FAR char *cmdline,
|
||||
*allocation = argument;
|
||||
|
||||
/* Find the end of the environment variable reference. If the
|
||||
- * dollar sign ('$') is followed by a right bracket ('{') then the
|
||||
- * variable name is terminated with the left bracket character
|
||||
+ * dollar sign ('$') is followed by a left bracket ('{') then the
|
||||
+ * variable name is terminated with the right bracket character
|
||||
* ('}'). Otherwise, the variable name goes to the end of the
|
||||
* argument.
|
||||
*/
|
||||
@@ -1167,6 +1167,10 @@ static FAR char *nsh_argexpand(FAR struct nsh_vtbl_s *vtbl, FAR char *cmdline,
|
||||
* nsh_envexpand will return the NULL string.
|
||||
*/
|
||||
|
||||
+ if (isenvvar) {
|
||||
+ *isenvvar = 1;
|
||||
+ }
|
||||
+
|
||||
envstr = nsh_envexpand(vtbl, ptr);
|
||||
|
||||
/* Concatenate the result of the operation with the accumulated
|
||||
@@ -1187,7 +1191,7 @@ static FAR char *nsh_argexpand(FAR struct nsh_vtbl_s *vtbl, FAR char *cmdline,
|
||||
|
||||
#else
|
||||
static FAR char *nsh_argexpand(FAR struct nsh_vtbl_s *vtbl, FAR char *cmdline,
|
||||
- FAR char **allocation)
|
||||
+ FAR char **allocation, int* isenvvar)
|
||||
{
|
||||
FAR char *argument = (FAR char *)g_nullstring;
|
||||
|
||||
@@ -1223,6 +1227,9 @@ static FAR char *nsh_argexpand(FAR struct nsh_vtbl_s *vtbl, FAR char *cmdline,
|
||||
|
||||
if (*cmdline == '$')
|
||||
{
|
||||
+ if (isenvvar) {
|
||||
+ *isenvvar = 1;
|
||||
+ }
|
||||
argument = nsh_envexpand(vtbl, cmdline + 1);
|
||||
}
|
||||
else
|
||||
@@ -1245,7 +1252,7 @@ static FAR char *nsh_argexpand(FAR struct nsh_vtbl_s *vtbl, FAR char *cmdline,
|
||||
****************************************************************************/
|
||||
|
||||
static FAR char *nsh_argument(FAR struct nsh_vtbl_s *vtbl, FAR char **saveptr,
|
||||
- FAR NSH_MEMLIST_TYPE *memlist)
|
||||
+ FAR NSH_MEMLIST_TYPE *memlist, int* isenvvar)
|
||||
{
|
||||
FAR char *pbegin = *saveptr;
|
||||
FAR char *pend = NULL;
|
||||
@@ -1317,6 +1324,13 @@ static FAR char *nsh_argument(FAR struct nsh_vtbl_s *vtbl, FAR char **saveptr,
|
||||
|
||||
pbegin++;
|
||||
term = "\"";
|
||||
+
|
||||
+ /* If this is an environment variable in double quotes, we don't want it split into
|
||||
+ * multiple argument should CONFIG_NSH_ENABLEPX4PARSING be defined
|
||||
+ * So just invalidate the flag pointer which would otherwise communictate such
|
||||
+ * back up the call tree.
|
||||
+ */
|
||||
+ isenvvar = NULL;
|
||||
}
|
||||
else
|
||||
{
|
||||
@@ -1376,11 +1390,11 @@ static FAR char *nsh_argument(FAR struct nsh_vtbl_s *vtbl, FAR char **saveptr,
|
||||
|
||||
/* Perform expansions as necessary for the argument */
|
||||
|
||||
- argument = nsh_argexpand(vtbl, pbegin, &allocation);
|
||||
+ argument = nsh_argexpand(vtbl, pbegin, &allocation, isenvvar);
|
||||
}
|
||||
|
||||
/* If any memory was allocated for this argument, make sure that it is
|
||||
- * added to the list of memory to be freed at the end of commend
|
||||
+ * added to the list of memory to be freed at the end of command
|
||||
* processing.
|
||||
*/
|
||||
|
||||
@@ -1497,7 +1511,7 @@ static int nsh_loop(FAR struct nsh_vtbl_s *vtbl, FAR char **ppcmd,
|
||||
|
||||
/* Get the cmd following the "while" or "until" */
|
||||
|
||||
- *ppcmd = nsh_argument(vtbl, saveptr, memlist);
|
||||
+ *ppcmd = nsh_argument(vtbl, saveptr, memlist, 0);
|
||||
if (!*ppcmd)
|
||||
{
|
||||
nsh_output(vtbl, g_fmtarginvalid, "if");
|
||||
@@ -1554,7 +1568,7 @@ static int nsh_loop(FAR struct nsh_vtbl_s *vtbl, FAR char **ppcmd,
|
||||
{
|
||||
/* Get the cmd following the "do" -- there may or may not be one */
|
||||
|
||||
- *ppcmd = nsh_argument(vtbl, saveptr, memlist);
|
||||
+ *ppcmd = nsh_argument(vtbl, saveptr, memlist, 0);
|
||||
|
||||
/* Verify that "do" is valid in this context */
|
||||
|
||||
@@ -1574,7 +1588,7 @@ static int nsh_loop(FAR struct nsh_vtbl_s *vtbl, FAR char **ppcmd,
|
||||
{
|
||||
/* Get the cmd following the "done" -- there should be one */
|
||||
|
||||
- *ppcmd = nsh_argument(vtbl, saveptr, memlist);
|
||||
+ *ppcmd = nsh_argument(vtbl, saveptr, memlist, 0);
|
||||
if (*ppcmd)
|
||||
{
|
||||
nsh_output(vtbl, g_fmtarginvalid, "done");
|
||||
@@ -1679,7 +1693,7 @@ static int nsh_itef(FAR struct nsh_vtbl_s *vtbl, FAR char **ppcmd,
|
||||
{
|
||||
/* Get the cmd following the if */
|
||||
|
||||
- *ppcmd = nsh_argument(vtbl, saveptr, memlist);
|
||||
+ *ppcmd = nsh_argument(vtbl, saveptr, memlist, 0);
|
||||
if (!*ppcmd)
|
||||
{
|
||||
nsh_output(vtbl, g_fmtarginvalid, "if");
|
||||
@@ -1717,7 +1731,7 @@ static int nsh_itef(FAR struct nsh_vtbl_s *vtbl, FAR char **ppcmd,
|
||||
{
|
||||
/* Get the cmd following the "then" -- there may or may not be one */
|
||||
|
||||
- *ppcmd = nsh_argument(vtbl, saveptr, memlist);
|
||||
+ *ppcmd = nsh_argument(vtbl, saveptr, memlist, 0);
|
||||
|
||||
/* Verify that "then" is valid in this context */
|
||||
|
||||
@@ -1736,7 +1750,7 @@ static int nsh_itef(FAR struct nsh_vtbl_s *vtbl, FAR char **ppcmd,
|
||||
{
|
||||
/* Get the cmd following the "else" -- there may or may not be one */
|
||||
|
||||
- *ppcmd = nsh_argument(vtbl, saveptr, memlist);
|
||||
+ *ppcmd = nsh_argument(vtbl, saveptr, memlist, 0);
|
||||
|
||||
/* Verify that "else" is valid in this context */
|
||||
|
||||
@@ -1755,7 +1769,7 @@ static int nsh_itef(FAR struct nsh_vtbl_s *vtbl, FAR char **ppcmd,
|
||||
{
|
||||
/* Get the cmd following the fi -- there should be one */
|
||||
|
||||
- *ppcmd = nsh_argument(vtbl, saveptr, memlist);
|
||||
+ *ppcmd = nsh_argument(vtbl, saveptr, memlist, 0);
|
||||
if (*ppcmd)
|
||||
{
|
||||
nsh_output(vtbl, g_fmtarginvalid, "fi");
|
||||
@@ -1827,10 +1841,10 @@ static int nsh_nice(FAR struct nsh_vtbl_s *vtbl, FAR char **ppcmd,
|
||||
|
||||
/* Get the cmd (or -d option of nice command) */
|
||||
|
||||
- cmd = nsh_argument(vtbl, saveptr, memlist);
|
||||
+ cmd = nsh_argument(vtbl, saveptr, memlist, 0);
|
||||
if (cmd && strcmp(cmd, "-d") == 0)
|
||||
{
|
||||
- FAR char *val = nsh_argument(vtbl, saveptr, memlist);
|
||||
+ FAR char *val = nsh_argument(vtbl, saveptr, memlist, 0);
|
||||
if (val)
|
||||
{
|
||||
char *endptr;
|
||||
@@ -1841,7 +1855,7 @@ static int nsh_nice(FAR struct nsh_vtbl_s *vtbl, FAR char **ppcmd,
|
||||
nsh_output(vtbl, g_fmtarginvalid, "nice");
|
||||
return ERROR;
|
||||
}
|
||||
- cmd = nsh_argument(vtbl, saveptr, memlist);
|
||||
+ cmd = nsh_argument(vtbl, saveptr, memlist, 0);
|
||||
}
|
||||
}
|
||||
|
||||
@@ -1909,7 +1923,7 @@ static int nsh_parse_cmdparm(FAR struct nsh_vtbl_s *vtbl, FAR char *cmdline,
|
||||
/* Parse out the command at the beginning of the line */
|
||||
|
||||
saveptr = cmdline;
|
||||
- cmd = nsh_argument(vtbl, &saveptr, &memlist);
|
||||
+ cmd = nsh_argument(vtbl, &saveptr, &memlist, 0);
|
||||
|
||||
/* Check if any command was provided -OR- if command processing is
|
||||
* currently disabled.
|
||||
@@ -1943,7 +1957,7 @@ static int nsh_parse_cmdparm(FAR struct nsh_vtbl_s *vtbl, FAR char *cmdline,
|
||||
argv[0] = cmd;
|
||||
for (argc = 1; argc < MAX_ARGV_ENTRIES-1; argc++)
|
||||
{
|
||||
- argv[argc] = nsh_argument(vtbl, &saveptr, &memlist);
|
||||
+ argv[argc] = nsh_argument(vtbl, &saveptr, &memlist, 0);
|
||||
if (!argv[argc])
|
||||
{
|
||||
break;
|
||||
@@ -2010,7 +2024,7 @@ static int nsh_parse_command(FAR struct nsh_vtbl_s *vtbl, FAR char *cmdline)
|
||||
/* Parse out the command at the beginning of the line */
|
||||
|
||||
saveptr = cmdline;
|
||||
- cmd = nsh_argument(vtbl, &saveptr, &memlist);
|
||||
+ cmd = nsh_argument(vtbl, &saveptr, &memlist, 0);
|
||||
|
||||
#ifndef CONFIG_NSH_DISABLESCRIPT
|
||||
#ifndef CONFIG_NSH_DISABLE_LOOPS
|
||||
@@ -2078,15 +2092,54 @@ static int nsh_parse_command(FAR struct nsh_vtbl_s *vtbl, FAR char *cmdline)
|
||||
*/
|
||||
|
||||
argv[0] = cmd;
|
||||
+
|
||||
+#define CONFIG_NSH_ENABLEPX4PARSING
|
||||
+
|
||||
for (argc = 1; argc < MAX_ARGV_ENTRIES-1; argc++)
|
||||
{
|
||||
- argv[argc] = nsh_argument(vtbl, &saveptr, &memlist);
|
||||
+ int isenvvar = 0; /* flag for if an enviroment variable gets expanded */
|
||||
+ argv[argc] = nsh_argument(vtbl, &saveptr, &memlist, &isenvvar);
|
||||
if (!argv[argc])
|
||||
{
|
||||
break;
|
||||
}
|
||||
+
|
||||
+#ifdef CONFIG_NSH_ENABLEPX4PARSING
|
||||
+ if (isenvvar)
|
||||
+ {
|
||||
+ while (argc < MAX_ARGV_ENTRIES-1) /* TODO: check this bounds check is correct */
|
||||
+ {
|
||||
+ FAR char *pbegin = argv[argc];
|
||||
+
|
||||
+ /* Find the end of the current token */
|
||||
+ for (; *pbegin && !strchr(g_token_separator, *pbegin); pbegin++);
|
||||
+
|
||||
+ /* If end of string, we've processed the last token and we're done */
|
||||
+ if ('\0' == *pbegin)
|
||||
+ {
|
||||
+ break;
|
||||
+ }
|
||||
+
|
||||
+ /* Terminate the token to complete the argv variable */
|
||||
+ *pbegin = '\0';
|
||||
+
|
||||
+ /* We've inserted an extra parameter, so bump the count */
|
||||
+ argc++;
|
||||
+
|
||||
+ /* Move to the next character in the string of tokens */
|
||||
+ pbegin++;
|
||||
+
|
||||
+ /* Throw away any extra separator chars between tokens */
|
||||
+ for (; *pbegin && strchr(g_token_separator, *pbegin) != NULL; pbegin++);
|
||||
+
|
||||
+ /* Prepare to loop again on the next argument token */
|
||||
+ argv[argc] = pbegin;
|
||||
+ }
|
||||
+ }
|
||||
+#endif /* CONFIG_NSH_ENABLEPX4PARSING */
|
||||
}
|
||||
|
||||
+ /* Last argument vector must be empty */
|
||||
argv[argc] = NULL;
|
||||
|
||||
/* Check if the command should run in background */
|
@ -1,56 +0,0 @@
@@ -1,56 +0,0 @@
|
||||
diff --git NuttX/nuttx/tools/mkexport.sh NuttX/nuttx/tools/mkexport.sh
|
||||
index 348a14c..3cc9182 100755
|
||||
--- NuttX/nuttx/tools/mkexport.sh
|
||||
+++ NuttX/nuttx/tools/mkexport.sh
|
||||
@@ -34,19 +34,23 @@
|
||||
|
||||
# Get the input parameter list
|
||||
|
||||
-USAGE="USAGE: $0 [-d] [-z] [-u] [-w|wy|wn] -t <top-dir> [-x <lib-ext>] -l \"lib1 [lib2 [lib3 ...]]\""
|
||||
+USAGE="USAGE: $0 [-d] [-e] [-z] [-u] [-w|wy|wn] -t <top-dir> [-x <lib-ext>] -l \"lib1 [lib2 [lib3 ...]]\""
|
||||
unset TOPDIR
|
||||
unset LIBLIST
|
||||
unset TGZ
|
||||
USRONLY=n
|
||||
WINTOOL=n
|
||||
LIBEXT=.a
|
||||
+INSITU=y
|
||||
|
||||
while [ ! -z "$1" ]; do
|
||||
case $1 in
|
||||
-d )
|
||||
set -x
|
||||
;;
|
||||
+ -e )
|
||||
+ INSITU=n
|
||||
+ ;;
|
||||
-l )
|
||||
shift
|
||||
LIBLIST=$1
|
||||
@@ -373,13 +377,17 @@ done
|
||||
cd "${TOPDIR}" || \
|
||||
{ echo "MK: 'cd ${TOPDIR}' failed"; exit 1; }
|
||||
|
||||
-if [ "X${TGZ}" = "Xy" ]; then
|
||||
- tar cvf "${EXPORTSUBDIR}.tar" "${EXPORTSUBDIR}" 1>/dev/null 2>&1
|
||||
- gzip -f "${EXPORTSUBDIR}.tar"
|
||||
-else
|
||||
- zip -r "${EXPORTSUBDIR}.zip" "${EXPORTSUBDIR}" 1>/dev/null 2>&1
|
||||
-fi
|
||||
+# Should we leave the export insitu
|
||||
+
|
||||
+if [ "X${INSITU}" = "Xn" ]; then
|
||||
+ if [ "X${TGZ}" = "Xy" ]; then
|
||||
+ tar cvf "${EXPORTSUBDIR}.tar" "${EXPORTSUBDIR}" 1>/dev/null 2>&1
|
||||
+ gzip -f "${EXPORTSUBDIR}.tar"
|
||||
+ else
|
||||
+ zip -r "${EXPORTSUBDIR}.zip" "${EXPORTSUBDIR}" 1>/dev/null 2>&1
|
||||
+ fi
|
||||
|
||||
-# Clean up after ourselves
|
||||
+ # Clean up after ourselves
|
||||
|
||||
-rm -rf "${EXPORTSUBDIR}"
|
||||
+ rm -rf "${EXPORTSUBDIR}"
|
||||
+fi
|
||||
\ No newline at end of file
|
@ -1,24 +0,0 @@
@@ -1,24 +0,0 @@
|
||||
diff --git NuttX/nuttx/include/cxx/cstdint NuttX/nuttx/include/cxx/cstdint
|
||||
index d662c5d..95334e9 100644
|
||||
--- NuttX/nuttx/include/cxx/cstdint
|
||||
+++ NuttX/nuttx/include/cxx/cstdint
|
||||
@@ -46,6 +46,9 @@
|
||||
// Namespace
|
||||
//***************************************************************************
|
||||
|
||||
+ #define GCC_VERSION (__GNUC__ * 10000 \
|
||||
+ + __GNUC_MINOR__ * 100 \
|
||||
+ + __GNUC_PATCHLEVEL__)
|
||||
namespace std
|
||||
{
|
||||
using ::int8_t;
|
||||
@@ -72,7 +75,9 @@ namespace std
|
||||
using ::uint_fast64_t;
|
||||
using ::uint_least8_t;
|
||||
using ::uint_least16_t;
|
||||
+#if GCC_VERSION <= 40804
|
||||
using ::uint_least32_t;
|
||||
+#endif
|
||||
using ::uint_least64_t;
|
||||
using ::uintmax_t;
|
||||
using ::uintptr_t;
|
@ -1,40 +0,0 @@
@@ -1,40 +0,0 @@
|
||||
diff --git NuttX/apps/Makefile NuttX/apps/Makefile
|
||||
index 4093b0e..3bdc36a 100644
|
||||
--- NuttX/apps/Makefile
|
||||
+++ NuttX/apps/Makefile
|
||||
@@ -79,13 +79,13 @@ all: $(BIN)
|
||||
.PHONY: import install dirlinks context context_serialize context_rest .depdirs preconfig depend clean distclean
|
||||
|
||||
define MAKE_template
|
||||
- $(Q) cd $(1) && $(MAKE) $(2) TOPDIR="$(TOPDIR)" APPDIR="$(APPDIR)" BIN_DIR="$(BIN_DIR)"
|
||||
+ +$(Q) cd $(1) && $(MAKE) $(2) TOPDIR="$(TOPDIR)" APPDIR="$(APPDIR)" BIN_DIR="$(BIN_DIR)"
|
||||
|
||||
endef
|
||||
|
||||
define SDIR_template
|
||||
$(1)_$(2):
|
||||
- $(Q) cd $(1) && $(MAKE) $(2) TOPDIR="$(TOPDIR)" APPDIR="$(APPDIR)" BIN_DIR="$(BIN_DIR)"
|
||||
+ +$(Q) cd $(1) && $(MAKE) $(2) TOPDIR="$(TOPDIR)" APPDIR="$(APPDIR)" BIN_DIR="$(BIN_DIR)"
|
||||
|
||||
endef
|
||||
|
||||
@@ -108,7 +108,7 @@ install: $(BIN_DIR) .install
|
||||
.import: $(BIN) install
|
||||
|
||||
import:
|
||||
- $(Q) $(MAKE) .import TOPDIR="$(APPDIR)$(DELIM)import"
|
||||
+ +$(Q) $(MAKE) .import TOPDIR="$(APPDIR)$(DELIM)import"
|
||||
|
||||
dirlinks:
|
||||
$(Q) $(MAKE) -C platform dirlinks TOPDIR="$(TOPDIR)" APPDIR="$(APPDIR)"
|
||||
@@ -116,8 +116,8 @@ dirlinks:
|
||||
context_rest: $(foreach SDIR, $(CONFIGURED_APPS), $(SDIR)_context)
|
||||
|
||||
context_serialize:
|
||||
- $(Q) $(MAKE) -C builtin context TOPDIR="$(TOPDIR)" APPDIR="$(APPDIR)"
|
||||
- $(Q) $(MAKE) context_rest
|
||||
+ +$(Q) $(MAKE) -C builtin context TOPDIR="$(TOPDIR)" APPDIR="$(APPDIR)"
|
||||
+ +$(Q) $(MAKE) context_rest
|
||||
|
||||
context: context_serialize
|
||||
|
@ -1,13 +0,0 @@
@@ -1,13 +0,0 @@
|
||||
diff --git NuttX/nuttx/include/assert.h NuttX/nuttx/include/assert.h
|
||||
index 88254f6..b9fb6c2 100644
|
||||
--- NuttX/nuttx/include/assert.h
|
||||
+++ NuttX/nuttx/include/assert.h
|
||||
@@ -94,7 +94,7 @@
|
||||
*/
|
||||
|
||||
#ifndef __cplusplus
|
||||
-# define static_assert _Static_assert
|
||||
+//# define static_assert _Static_assert
|
||||
#endif
|
||||
|
||||
/****************************************************************************
|
@ -1,20 +0,0 @@
@@ -1,20 +0,0 @@
|
||||
diff --git NuttX/nuttx/include/ctype.h NuttX/nuttx/include/ctype.h
|
||||
index dcf918b..65706b7 100644
|
||||
--- NuttX/nuttx/include/ctype.h
|
||||
+++ NuttX/nuttx/include/ctype.h
|
||||
@@ -50,6 +50,8 @@
|
||||
/****************************************************************************
|
||||
* Pre-processor Definitions
|
||||
****************************************************************************/
|
||||
+#pragma GCC diagnostic push
|
||||
+#pragma GCC diagnostic ignored "-Wshadow"
|
||||
|
||||
/****************************************************************************
|
||||
* Name: isspace
|
||||
@@ -340,5 +342,6 @@ extern "C"
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
#endif
|
||||
+#pragma GCC diagnostic pop
|
||||
|
||||
#endif /* __INCLUDE_CTYPE_H */
|
@ -1,60 +0,0 @@
@@ -1,60 +0,0 @@
|
||||
diff --git NuttX/nuttx/sched/irq/irq.h NuttX/nuttx/sched/irq/irq.h
|
||||
index ffb6e98..f01318b 100644
|
||||
--- NuttX/nuttx/sched/irq/irq.h
|
||||
+++ NuttX/nuttx/sched/irq/irq.h
|
||||
@@ -72,7 +72,9 @@
|
||||
struct irq_info_s
|
||||
{
|
||||
xcpt_t handler; /* Address of the interrupt handler */
|
||||
+#if !defined(CONFIG_NOIRQARGS)
|
||||
FAR void *arg; /* The argument provided to the interrupt handler. */
|
||||
+#endif
|
||||
};
|
||||
|
||||
/****************************************************************************
|
||||
diff --git NuttX/nuttx/sched/irq/irq_attach.c NuttX/nuttx/sched/irq/irq_attach.c
|
||||
index 9d45d9c..3707906 100644
|
||||
--- NuttX/nuttx/sched/irq/irq_attach.c
|
||||
+++ NuttX/nuttx/sched/irq/irq_attach.c
|
||||
@@ -112,7 +112,11 @@ int irq_attach(int irq, xcpt_t isr, FAR void *arg)
|
||||
/* Save the new ISR and its argument in the table. */
|
||||
|
||||
g_irqvector[ndx].handler = isr;
|
||||
+#if defined(CONFIG_NOIRQARGS)
|
||||
+ ASSERT(arg == NULL);
|
||||
+#else
|
||||
g_irqvector[ndx].arg = arg;
|
||||
+#endif
|
||||
|
||||
leave_critical_section(flags);
|
||||
ret = OK;
|
||||
diff --git NuttX/nuttx/sched/irq/irq_dispatch.c NuttX/nuttx/sched/irq/irq_dispatch.c
|
||||
index b507c06..66cb1fe 100644
|
||||
--- NuttX/nuttx/sched/irq/irq_dispatch.c
|
||||
+++ NuttX/nuttx/sched/irq/irq_dispatch.c
|
||||
@@ -88,7 +88,11 @@ void irq_dispatch(int irq, FAR void *context)
|
||||
}
|
||||
#else
|
||||
vector = g_irqvector[irq].handler;
|
||||
- arg = g_irqvector[irq].arg;
|
||||
+# if defined(CONFIG_NOIRQARGS)
|
||||
+ arg = NULL;
|
||||
+# else
|
||||
+ arg = g_irqvector[irq].arg;
|
||||
+# endif
|
||||
#endif
|
||||
}
|
||||
|
||||
diff --git NuttX/nuttx/sched/irq/irq_initialize.c NuttX/nuttx/sched/irq/irq_initialize.c
|
||||
index 18bbafc..2018788 100644
|
||||
--- NuttX/nuttx/sched/irq/irq_initialize.c
|
||||
+++ NuttX/nuttx/sched/irq/irq_initialize.c
|
||||
@@ -88,6 +88,8 @@ void irq_initialize(void)
|
||||
for (i = 0; i < TAB_SIZE; i++)
|
||||
{
|
||||
g_irqvector[i].handler = irq_unexpected_isr;
|
||||
+#if !defined(CONFIG_NOIRQARGS)
|
||||
g_irqvector[i].arg = NULL;
|
||||
+#endif
|
||||
}
|
||||
}
|
@ -1,222 +0,0 @@
@@ -1,222 +0,0 @@
|
||||
diff --git NuttX/nuttx/arch/arm/src/stm32/stm32_serial.c NuttX/nuttx/arch/arm/src/stm32/stm32_serial.c
|
||||
index a6a2d07..ea8ba61 100644
|
||||
--- NuttX/nuttx/arch/arm/src/stm32/stm32_serial.c
|
||||
+++ NuttX/nuttx/arch/arm/src/stm32/stm32_serial.c
|
||||
@@ -315,6 +315,9 @@ struct up_dev_s
|
||||
const unsigned int rxdma_channel; /* DMA channel assigned */
|
||||
#endif
|
||||
|
||||
+#if defined(CONFIG_NOIRQARGS)
|
||||
+ int (*const vector)(int irq, void *context, void *arg); /* Interrupt handler */
|
||||
+#endif
|
||||
/* RX DMA state */
|
||||
|
||||
#ifdef SERIAL_HAVE_DMA
|
||||
@@ -371,6 +374,32 @@ static int up_pm_prepare(struct pm_callback_s *cb, int domain,
|
||||
enum pm_state_e pmstate);
|
||||
#endif
|
||||
|
||||
+#if defined(CONFIG_NOIRQARGS)
|
||||
+# ifdef CONFIG_STM32_USART1_SERIALDRIVER
|
||||
+static int up_interrupt_usart1(int irq, void *context, void *arg);
|
||||
+# endif
|
||||
+# ifdef CONFIG_STM32_USART2_SERIALDRIVER
|
||||
+static int up_interrupt_usart2(int irq, void *context, void *arg);
|
||||
+# endif
|
||||
+# ifdef CONFIG_STM32_USART3_SERIALDRIVER
|
||||
+static int up_interrupt_usart3(int irq, void *context, void *arg);
|
||||
+# endif
|
||||
+# ifdef CONFIG_STM32_UART4_SERIALDRIVER
|
||||
+static int up_interrupt_uart4(int irq, void *context, void *arg);
|
||||
+# endif
|
||||
+# ifdef CONFIG_STM32_UART5_SERIALDRIVER
|
||||
+static int up_interrupt_uart5(int irq, void *context, void *arg);
|
||||
+# endif
|
||||
+# ifdef CONFIG_STM32_USART6_SERIALDRIVER
|
||||
+static int up_interrupt_usart6(int irq, void *context, void *arg);
|
||||
+# endif
|
||||
+# ifdef CONFIG_STM32_UART7_SERIALDRIVER
|
||||
+static int up_interrupt_uart7(int irq, void *context, void *arg);
|
||||
+# endif
|
||||
+# ifdef CONFIG_STM32_UART8_SERIALDRIVER
|
||||
+static int up_interrupt_uart8(int irq, void *context, void *arg);
|
||||
+# endif
|
||||
+#endif
|
||||
/****************************************************************************
|
||||
* Private Data
|
||||
****************************************************************************/
|
||||
@@ -536,7 +565,9 @@ static struct up_dev_s g_usart1priv =
|
||||
.rxdma_channel = DMAMAP_USART1_RX,
|
||||
.rxfifo = g_usart1rxfifo,
|
||||
#endif
|
||||
-
|
||||
+#if defined(CONFIG_NOIRQARGS)
|
||||
+ .vector = up_interrupt_usart1,
|
||||
+#endif
|
||||
#ifdef CONFIG_USART1_RS485
|
||||
.rs485_dir_gpio = GPIO_USART1_RS485_DIR,
|
||||
# if (CONFIG_USART1_RS485_DIR_POLARITY == 0)
|
||||
@@ -597,6 +628,9 @@ static struct up_dev_s g_usart2priv =
|
||||
.rxdma_channel = DMAMAP_USART2_RX,
|
||||
.rxfifo = g_usart2rxfifo,
|
||||
#endif
|
||||
+#if defined(CONFIG_NOIRQARGS)
|
||||
+ .vector = up_interrupt_usart2,
|
||||
+#endif
|
||||
|
||||
#ifdef CONFIG_USART2_RS485
|
||||
.rs485_dir_gpio = GPIO_USART2_RS485_DIR,
|
||||
@@ -658,6 +692,9 @@ static struct up_dev_s g_usart3priv =
|
||||
.rxdma_channel = DMAMAP_USART3_RX,
|
||||
.rxfifo = g_usart3rxfifo,
|
||||
#endif
|
||||
+#if defined(CONFIG_NOIRQARGS)
|
||||
+ .vector = up_interrupt_usart3,
|
||||
+#endif
|
||||
|
||||
#ifdef CONFIG_USART3_RS485
|
||||
.rs485_dir_gpio = GPIO_USART3_RS485_DIR,
|
||||
@@ -723,6 +760,9 @@ static struct up_dev_s g_uart4priv =
|
||||
.rxdma_channel = DMAMAP_UART4_RX,
|
||||
.rxfifo = g_uart4rxfifo,
|
||||
#endif
|
||||
+#if defined(CONFIG_NOIRQARGS)
|
||||
+ .vector = up_interrupt_uart4,
|
||||
+#endif
|
||||
|
||||
#ifdef CONFIG_UART4_RS485
|
||||
.rs485_dir_gpio = GPIO_UART4_RS485_DIR,
|
||||
@@ -788,6 +828,9 @@ static struct up_dev_s g_uart5priv =
|
||||
.rxdma_channel = DMAMAP_UART5_RX,
|
||||
.rxfifo = g_uart5rxfifo,
|
||||
#endif
|
||||
+#if defined(CONFIG_NOIRQARGS)
|
||||
+ .vector = up_interrupt_uart5,
|
||||
+#endif
|
||||
|
||||
#ifdef CONFIG_UART5_RS485
|
||||
.rs485_dir_gpio = GPIO_UART5_RS485_DIR,
|
||||
@@ -849,6 +892,9 @@ static struct up_dev_s g_usart6priv =
|
||||
.rxdma_channel = DMAMAP_USART6_RX,
|
||||
.rxfifo = g_usart6rxfifo,
|
||||
#endif
|
||||
+#if defined(CONFIG_NOIRQARGS)
|
||||
+ .vector = up_interrupt_uart6,
|
||||
+#endif
|
||||
|
||||
#ifdef CONFIG_USART6_RS485
|
||||
.rs485_dir_gpio = GPIO_USART6_RS485_DIR,
|
||||
@@ -910,6 +956,9 @@ static struct up_dev_s g_uart7priv =
|
||||
.rxdma_channel = DMAMAP_UART7_RX,
|
||||
.rxfifo = g_uart7rxfifo,
|
||||
#endif
|
||||
+#if defined(CONFIG_NOIRQARGS)
|
||||
+ .vector = up_interrupt_uart7,
|
||||
+#endif
|
||||
|
||||
#ifdef CONFIG_UART7_RS485
|
||||
.rs485_dir_gpio = GPIO_UART7_RS485_DIR,
|
||||
@@ -971,6 +1020,9 @@ static struct up_dev_s g_uart8priv =
|
||||
.rxdma_channel = DMAMAP_UART8_RX,
|
||||
.rxfifo = g_uart8rxfifo,
|
||||
#endif
|
||||
+#if defined(CONFIG_NOIRQARGS)
|
||||
+ .vector = up_interrupt_uart8,
|
||||
+#endif
|
||||
|
||||
#ifdef CONFIG_UART8_RS485
|
||||
.rs485_dir_gpio = GPIO_UART8_RS485_DIR,
|
||||
@@ -1709,7 +1761,11 @@ static int up_attach(struct uart_dev_s *dev)
|
||||
|
||||
/* Attach and enable the IRQ */
|
||||
|
||||
+#if defined(CONFIG_NOIRQARGS)
|
||||
+ ret = irq_attach(priv->irq, priv->vector, NULL);
|
||||
+#else
|
||||
ret = irq_attach(priv->irq, up_interrupt, priv);
|
||||
+#endif
|
||||
if (ret == OK)
|
||||
{
|
||||
/* Enable the interrupt (RX and TX interrupts are still disabled
|
||||
@@ -1740,7 +1796,7 @@ static void up_detach(struct uart_dev_s *dev)
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
- * Name: up_interrupt
|
||||
+ * Name: up_interrupt_common
|
||||
*
|
||||
* Description:
|
||||
* This is the USART interrupt handler. It will be invoked when an
|
||||
@@ -2480,6 +2536,72 @@ static bool up_txready(struct uart_dev_s *dev)
|
||||
return ((up_serialin(priv, STM32_USART_SR_OFFSET) & USART_SR_TXE) != 0);
|
||||
}
|
||||
|
||||
+#if defined(CONFIG_NOIRQARGS)
|
||||
+/****************************************************************************
|
||||
+ * Name: up_interrupt_u[s]art[n]
|
||||
+ *
|
||||
+ * Description:
|
||||
+ * Interrupt handlers for U[S]ART[n] where n=1,..,6.
|
||||
+ *
|
||||
+ ****************************************************************************/
|
||||
+
|
||||
+# ifdef CONFIG_STM32_USART1_SERIALDRIVER
|
||||
+static int up_interrupt_usart1(int irq, void *context, void *arg)
|
||||
+{
|
||||
+ return up_interrupt(irq, context, &g_usart1priv);
|
||||
+}
|
||||
+# endif
|
||||
+
|
||||
+# ifdef CONFIG_STM32_USART2_SERIALDRIVER
|
||||
+static int up_interrupt_usart2(int irq, void *context, void *arg)
|
||||
+{
|
||||
+ return up_interrupt(irq, context, &g_usart2priv);
|
||||
+}
|
||||
+# endif
|
||||
+
|
||||
+# ifdef CONFIG_STM32_USART3_SERIALDRIVER
|
||||
+static int up_interrupt_usart3(int irq, void *context, void *arg)
|
||||
+{
|
||||
+ return up_interrupt(irq, context, &g_usart3priv);
|
||||
+}
|
||||
+# endif
|
||||
+
|
||||
+# ifdef CONFIG_STM32_UART4_SERIALDRIVER
|
||||
+static int up_interrupt_uart4(int irq, void *context, void *arg)
|
||||
+{
|
||||
+ return up_interrupt(irq, context, &g_uart4priv);
|
||||
+}
|
||||
+# endif
|
||||
+
|
||||
+# ifdef CONFIG_STM32_UART5_SERIALDRIVER
|
||||
+static int up_interrupt_uart5(int irq, void *context, void *arg)
|
||||
+{
|
||||
+ return up_interrupt(irq, context, &g_uart5priv);
|
||||
+}
|
||||
+# endif
|
||||
+
|
||||
+# ifdef CONFIG_STM32_USART6_SERIALDRIVER
|
||||
+static int up_interrupt_usart6(int irq, void *context, void *arg)
|
||||
+{
|
||||
+ return up_interrupt(irq, context, &g_usart6priv);
|
||||
+}
|
||||
+# endif
|
||||
+
|
||||
+# ifdef CONFIG_STM32_UART7_SERIALDRIVER
|
||||
+static int up_interrupt_uart7(int irq, void *context, void *arg)
|
||||
+{
|
||||
+ return up_interrupt(irq, context, &g_uart7priv);
|
||||
+}
|
||||
+# endif
|
||||
+
|
||||
+# ifdef CONFIG_STM32_UART8_SERIALDRIVER
|
||||
+static int up_interrupt_uart8(int irq, void *context, void *arg)
|
||||
+{
|
||||
+ return up_interrupt(irq, context, &g_uart8priv);
|
||||
+}
|
||||
+# endif
|
||||
+#endif
|
||||
+
|
||||
/****************************************************************************
|
||||
* Name: up_dma_rxcallback
|
||||
*
|
@ -0,0 +1,215 @@
@@ -0,0 +1,215 @@
|
||||
cmake_minimum_required(VERSION 3.2) |
||||
|
||||
if(NOT BOARD) |
||||
message(FATAL_ERROR "BOARD must be set (eg px4fmu-v2)") |
||||
endif() |
||||
|
||||
if(NOT nuttx_config_type) |
||||
# default to nsh if not specified |
||||
set(nuttx_config_type "nsh") |
||||
endif() |
||||
|
||||
project(NuttX_${BOARD} LANGUAGES ASM C CXX) |
||||
message(STATUS "NuttX: " ${BOARD} " " ${nuttx_config_type} " " ${CMAKE_SYSTEM_PROCESSOR}) |
||||
|
||||
if (CMAKE_HOST_APPLE OR TRUE) |
||||
# copy with rsync and create file dependencies |
||||
set(cp_cmd "rsync") |
||||
set(cp_opts) |
||||
list(APPEND cp_opts |
||||
-rp |
||||
--inplace |
||||
) |
||||
else() |
||||
# copy with hard links |
||||
# archive, recursive, force, link (hardlinks) |
||||
set(cp_cmd "cp") |
||||
set(cp_opts "-aRfl") |
||||
endif() |
||||
|
||||
file(GLOB_RECURSE copy_nuttx_files |
||||
LIST_DIRECTORIES false |
||||
${CMAKE_CURRENT_SOURCE_DIR}/nuttx/*) |
||||
|
||||
file(GLOB_RECURSE copy_apps_files |
||||
LIST_DIRECTORIES false |
||||
${CMAKE_CURRENT_SOURCE_DIR}/apps/*) |
||||
|
||||
# copy nuttx to build directory |
||||
add_custom_command(OUTPUT nuttx_copy.stamp |
||||
COMMAND ${cp_cmd} ${cp_opts} ${CMAKE_CURRENT_SOURCE_DIR}/nuttx ${CMAKE_CURRENT_BINARY_DIR} |
||||
COMMAND cmake -E touch nuttx_copy.stamp |
||||
DEPENDS ${copy_nuttx_files} |
||||
COMMENT "Copying NuttX/nuttx to ${CMAKE_CURRENT_BINARY_DIR}" |
||||
) |
||||
|
||||
set(NUTTX_DIR ${CMAKE_CURRENT_BINARY_DIR}/nuttx) |
||||
set(NUTTX_CONFIG_DIR ${PX4_SOURCE_DIR}/nuttx-configs) |
||||
|
||||
# copy apps to build directory |
||||
add_custom_command(OUTPUT apps_copy.stamp |
||||
COMMAND ${cp_cmd} ${cp_opts} ${CMAKE_CURRENT_SOURCE_DIR}/apps ${CMAKE_CURRENT_BINARY_DIR} |
||||
COMMAND cmake -E touch apps_copy.stamp |
||||
DEPENDS ${copy_apps_files} |
||||
COMMENT "Copying NuttX/apps to ${CMAKE_CURRENT_BINARY_DIR}" |
||||
) |
||||
set(APPS_DIR ${CMAKE_CURRENT_BINARY_DIR}/apps) |
||||
|
||||
# copy PX4 board config into nuttx |
||||
file(GLOB_RECURSE board_config_files ${NUTTX_CONFIG_DIR}/${BOARD}) |
||||
add_custom_command(OUTPUT |
||||
${NUTTX_DIR}/PX4_Config.mk |
||||
${NUTTX_DIR}/PX4_Warnings.mk |
||||
${NUTTX_DIR}/.config |
||||
${NUTTX_DIR}/Make.defs |
||||
${NUTTX_DIR}/configs/${BOARD}/${nuttx_config_type}/defconfig |
||||
COMMAND ${CMAKE_COMMAND} -E copy ${NUTTX_CONFIG_DIR}/PX4_Config.mk ${NUTTX_DIR}/PX4_Config.mk |
||||
COMMAND ${CMAKE_COMMAND} -E copy ${NUTTX_CONFIG_DIR}/PX4_Warnings.mk ${NUTTX_DIR}/PX4_Warnings.mk |
||||
COMMAND ${CMAKE_COMMAND} -E copy ${NUTTX_CONFIG_DIR}/${BOARD}/${nuttx_config_type}/defconfig ${NUTTX_DIR}/.config |
||||
COMMAND ${CMAKE_COMMAND} -E remove -f ${NUTTX_DIR}/include/nuttx/config.h |
||||
COMMAND ${CMAKE_COMMAND} -E copy ${NUTTX_CONFIG_DIR}/${BOARD}/${nuttx_config_type}/Make.defs ${NUTTX_DIR}/Make.defs |
||||
COMMAND ${cp_cmd} ${cp_opts} ${NUTTX_CONFIG_DIR}/${BOARD} ${NUTTX_DIR}/configs/ |
||||
DEPENDS |
||||
${NUTTX_CONFIG_DIR}/PX4_Config.mk |
||||
${NUTTX_CONFIG_DIR}/PX4_Warnings.mk |
||||
${NUTTX_CONFIG_DIR}/${BOARD}/${nuttx_config_type}/defconfig |
||||
${NUTTX_CONFIG_DIR}/${BOARD}/${nuttx_config_type}/Make.defs |
||||
${board_config_files} |
||||
nuttx_copy.stamp apps_copy.stamp |
||||
WORKING_DIRECTORY ${NUTTX_DIR}/tools |
||||
COMMENT "Copying NuttX config ${BOARD} and configuring" |
||||
) |
||||
add_custom_target(nuttx_configure DEPENDS ${NUTTX_DIR}/.config) |
||||
|
||||
# context |
||||
add_custom_command(OUTPUT ${NUTTX_DIR}/include/nuttx/version.h ${NUTTX_DIR}/include/nuttx/config.h |
||||
COMMAND make --no-print-directory --silent context > /dev/null |
||||
DEPENDS nuttx_configure ${NUTTX_DIR}/.config |
||||
WORKING_DIRECTORY ${NUTTX_DIR} |
||||
) |
||||
add_custom_target(nuttx_context DEPENDS ${NUTTX_DIR}/include/nuttx/version.h) |
||||
|
||||
# library of NuttX libraries |
||||
add_library(nuttx_build INTERFACE) |
||||
|
||||
# builtins |
||||
if ("${BOARD}" MATCHES "px4io") |
||||
# no apps for px4io |
||||
set(nuttx_builtin_list) |
||||
else() |
||||
# add additional commands to nuttx builtins |
||||
set(builtin_registry ${APPS_DIR}/builtin/registry) |
||||
set(nuttx_builtin_list) |
||||
foreach(module ${module_libraries}) |
||||
get_target_property(MAIN ${module} MAIN) |
||||
get_target_property(STACK_MAIN ${module} STACK_MAIN) |
||||
get_target_property(PRIORITY ${module} PRIORITY) |
||||
|
||||
if(MAIN) |
||||
add_custom_command(OUTPUT ${builtin_registry}/${MAIN}_main.bdat |
||||
COMMAND echo "{ \"${MAIN}\", ${PRIORITY}, ${STACK_MAIN}, ${MAIN}_main }," > ${builtin_registry}/${MAIN}_main.bdat |
||||
VERBATIM |
||||
) |
||||
list(APPEND nuttx_builtin_list ${builtin_registry}/${MAIN}_main.bdat) |
||||
|
||||
add_custom_command(OUTPUT ${builtin_registry}/${MAIN}_main.pdat |
||||
COMMAND echo "int ${MAIN}_main(int argc, char *argv[]);" > ${builtin_registry}/${MAIN}_main.pdat |
||||
VERBATIM |
||||
) |
||||
list(APPEND nuttx_builtin_list ${builtin_registry}/${MAIN}_main.pdat) |
||||
endif() |
||||
endforeach() |
||||
endif() |
||||
|
||||
# APPS |
||||
|
||||
# libapps.a |
||||
add_custom_command(OUTPUT ${APPS_DIR}/libapps.a |
||||
${APPS_DIR}/platform/.built |
||||
COMMAND find ${APPS_DIR} -name \*.o -o -name \*.built -delete |
||||
COMMAND make --silent --no-print-directory -C ../apps TOPDIR="${NUTTX_DIR}" libapps.a > /dev/null |
||||
DEPENDS nuttx_context ${nuttx_builtin_list} |
||||
WORKING_DIRECTORY ${NUTTX_DIR} |
||||
) |
||||
add_custom_target(nuttx_apps_build DEPENDS ${APPS_DIR}/libapps.a) |
||||
add_library(nuttx_apps STATIC IMPORTED GLOBAL) |
||||
set_property(TARGET nuttx_apps PROPERTY IMPORTED_LOCATION ${APPS_DIR}/libapps.a) |
||||
add_dependencies(nuttx_build nuttx_apps_build) |
||||
target_link_libraries(nuttx_build INTERFACE nuttx_apps) |
||||
|
||||
# libboard.a |
||||
add_custom_command(OUTPUT ${NUTTX_DIR}/arch/arm/src/board/libboard.a |
||||
COMMAND make --silent --no-print-directory -C board TOPDIR="${NUTTX_DIR}" libboard.a EXTRADEFINES=-D__KERNEL__ > /dev/null |
||||
DEPENDS nuttx_context |
||||
WORKING_DIRECTORY ${NUTTX_DIR}/arch/arm/src |
||||
) |
||||
add_custom_target(nuttx_board_build DEPENDS ${NUTTX_DIR}/arch/arm/src/board/libboard.a) |
||||
add_library(nuttx_board STATIC IMPORTED GLOBAL) |
||||
set_property(TARGET nuttx_board PROPERTY IMPORTED_LOCATION ${NUTTX_DIR}/arch/arm/src/board/libboard.a) |
||||
add_dependencies(nuttx_build nuttx_board_build) |
||||
target_link_libraries(nuttx_build INTERFACE nuttx_board) |
||||
|
||||
# helper for all targets |
||||
function(add_nuttx_dir nuttx_lib nuttx_lib_dir kernel extra) |
||||
file(GLOB_RECURSE nuttx_lib_files |
||||
LIST_DIRECTORIES false |
||||
${CMAKE_CURRENT_SOURCE_DIR}/nuttx/${nuttx_lib_dir}/*) |
||||
|
||||
add_custom_command(OUTPUT ${NUTTX_DIR}/${nuttx_lib_dir}/lib${nuttx_lib}.a |
||||
COMMAND find ${nuttx_lib_dir} -type f -name *.o -o -name .built -delete |
||||
COMMAND make -C ${nuttx_lib_dir} -j2 --silent --no-print-directory lib${nuttx_lib}.a TOPDIR="${NUTTX_DIR}" KERNEL=${kernel} EXTRADEFINES=${extra} > /dev/null |
||||
DEPENDS ${nuttx_lib_files} nuttx_context |
||||
WORKING_DIRECTORY ${NUTTX_DIR} |
||||
) |
||||
add_custom_target(nuttx_${nuttx_lib}_build DEPENDS ${NUTTX_DIR}/${nuttx_lib_dir}/lib${nuttx_lib}.a) |
||||
add_library(nuttx_${nuttx_lib} STATIC IMPORTED GLOBAL) |
||||
set_property(TARGET nuttx_${nuttx_lib} PROPERTY IMPORTED_LOCATION ${NUTTX_DIR}/${nuttx_lib_dir}/lib${nuttx_lib}.a) |
||||
add_dependencies(nuttx_build nuttx_${nuttx_lib}_build) |
||||
target_link_libraries(nuttx_build INTERFACE nuttx_${nuttx_lib}) |
||||
endfunction() |
||||
|
||||
# add_nuttx_dir(NAME DIRECTORY KERNEL EXTRA) |
||||
|
||||
add_nuttx_dir(arch arch/arm/src y -D__KERNEL__) |
||||
add_nuttx_dir(binfmt binfmt y -D__KERNEL__) |
||||
add_nuttx_dir(configs configs y -D__KERNEL__) |
||||
add_nuttx_dir(drivers drivers y -D__KERNEL__) |
||||
add_nuttx_dir(fs fs y -D__KERNEL__) |
||||
add_nuttx_dir(sched sched y -D__KERNEL__) |
||||
|
||||
add_nuttx_dir(c libc n "") |
||||
add_nuttx_dir(cxx libxx n "") |
||||
add_nuttx_dir(mm mm n "") |
||||
|
||||
|
||||
# oldconfig helper |
||||
add_custom_target(oldconfig |
||||
COMMAND make --no-print-directory -C ${NUTTX_DIR} CONFIG_ARCH_BOARD=${BOARD} oldconfig |
||||
COMMAND cp ${NUTTX_DIR}/.config ${NUTTX_CONFIG_DIR}/${BOARD}/${nuttx_config_type}/defconfig |
||||
COMMAND ${PX4_SOURCE_DIR}/Tools/nuttx_defconf_tool.sh ${NUTTX_CONFIG_DIR}/${BOARD}/${nuttx_config_type}/defconfig |
||||
DEPENDS nuttx_configure |
||||
WORKING_DIRECTORY ${NUTTX_DIR} |
||||
COMMENT "Running NuttX make oldconfig for ${BOARD} with ${nuttx_config_type}" |
||||
USES_TERMINAL |
||||
) |
||||
|
||||
# menuconfig helper |
||||
add_custom_target(menuconfig |
||||
COMMAND make --no-print-directory -C ${NUTTX_DIR} CONFIG_ARCH_BOARD=${BOARD} menuconfig |
||||
COMMAND cp ${NUTTX_DIR}/nuttx/.config ${NUTTX_CONFIG_DIR}/${BOARD}/${nuttx_config_type}/defconfig |
||||
COMMAND ${PX4_SOURCE_DIR}/Tools/nuttx_defconf_tool.sh ${NUTTX_CONFIG_DIR}/${BOARD}/${nuttx_config_type}/defconfig |
||||
DEPENDS nuttx_configure |
||||
WORKING_DIRECTORY ${NUTTX_DIR} |
||||
COMMENT "Running NuttX make menuconfig for ${BOARD} with ${nuttx_config_type}" |
||||
USES_TERMINAL |
||||
) |
||||
|
||||
# qconfig helper |
||||
add_custom_target(qconfig |
||||
COMMAND make --no-print-directory -C ${NUTTX_DIR} CONFIG_ARCH_BOARD=${BOARD} qconfig |
||||
COMMAND cp .config ${NUTTX_CONFIG_DIR}/${BOARD}/${nuttx_config_type}/defconfig |
||||
DEPENDS nuttx_configure |
||||
WORKING_DIRECTORY ${NUTTX_DIR} |
||||
COMMENT "Running NuttX make qconfig for ${BOARD} with ${nuttx_config_type}" |
||||
USES_TERMINAL |
||||
) |
@ -0,0 +1 @@
@@ -0,0 +1 @@
|
||||
Subproject commit 42dbbb2038c83532e367c6813f0ece691ea04524 |
@ -0,0 +1 @@
@@ -0,0 +1 @@
|
||||
Subproject commit 94da3bef49efaacee7ec5b1a1aa237c3e2915163 |
@ -0,0 +1,39 @@
@@ -0,0 +1,39 @@
|
||||
############################################################################ |
||||
# |
||||
# 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. |
||||
# |
||||
############################################################################ |
||||
|
||||
px4_add_library(board_kinetis |
||||
board_identity.c |
||||
board_mcu_version.c |
||||
board_reset.c |
||||
) |
||||
add_dependencies(board_kinetis nuttx_build) |
@ -0,0 +1,39 @@
@@ -0,0 +1,39 @@
|
||||
############################################################################ |
||||
# |
||||
# 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. |
||||
# |
||||
############################################################################ |
||||
|
||||
px4_add_library(board_samv7 |
||||
board_identity.c |
||||
board_mcu_version.c |
||||
board_reset.c |
||||
) |
||||
add_dependencies(board_samv7 nuttx_build) |
@ -0,0 +1,46 @@
@@ -0,0 +1,46 @@
|
||||
############################################################################ |
||||
# |
||||
# 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(SRCS |
||||
board_identity.c |
||||
) |
||||
|
||||
if (NOT ${LABEL} STREQUAL "bootloader") |
||||
list(APPEND SRCS |
||||
board_mcu_version.c |
||||
board_reset.c |
||||
) |
||||
endif() |
||||
|
||||
px4_add_library(board_stm32 ${SRCS}) |
||||
add_dependencies(board_stm32 nuttx_build) |
@ -0,0 +1,41 @@
@@ -0,0 +1,41 @@
|
||||
############################################################################ |
||||
# |
||||
# Copyright (c) 2015 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. |
||||
# |
||||
############################################################################ |
||||
px4_add_module( |
||||
MODULE drivers__boards__sitl |
||||
COMPILE_FLAGS |
||||
SRCS |
||||
sitl_led.c |
||||
DEPENDS |
||||
platforms__common |
||||
) |
||||
# vim: set noet ft=cmake fenc=utf-8 ff=unix : |
Some files were not shown because too many files have changed in this diff Show More
Loading…
Reference in new issue