Added defautl config for nuttx, nuttx now works over usb.

This commit is contained in:
James Goppert 2015-09-10 13:57:54 -04:00
parent f7fe33e6a4
commit 34eeee9fa9
9 changed files with 423 additions and 33 deletions

View File

@ -178,17 +178,17 @@ endforeach()
#=============================================================================
# git
#
if (${OS} STREQUAL "nuttx")
px4_add_git_submodule(TARGET git_nuttx PATH "NuttX")
endif()
px4_add_git_submodule(TARGET git_genmsg PATH "Tools/genmsg")
px4_add_git_submodule(TARGET git_gencpp PATH "Tools/gencpp")
px4_add_git_submodule(TARGET git_mavlink PATH "mavlink/include/mavlink/v1.0")
px4_add_git_submodule(TARGET git_gtest PATH "unittets/gtest")
px4_add_git_submodule(TARGET git_uavcan PATH "src/lib/uavcan")
if (NOT ${OS} STREQUAL "qurt")
px4_add_git_submodule(TARGET git_eigen PATH "src/lib/eigen")
endif()
if(${OS} STREQUAL "nuttx")
px4_add_git_submodule(TARGET git_nuttx PATH "NuttX")
endif()
add_custom_target(submodule_clean
WORKING_DIRECTORY ${CMAKE_SOURCE_DIR}
COMMAND git submodule deinit -f .

View File

@ -1,35 +1,62 @@
d=$(PWD)
#----------------------------------------------------------------------------
# OS: nuttx BOARD: px4fmu-v2 LABEL: simple
#
nuttx_px4fmu-v2_simple:
mkdir -p $d/build_$@ && cd $d/build_$@ && \
cmake .. -DCMAKE_TOOLCHAIN_FILE=../cmake/toolchains/Toolchain-arm-none-eabi.cmake \
-DOS=nuttx -DBOARD=px4fmu-v2 -DLABEL=simple && \
make -s && ctest -V && cpack -G ZIP
px4fmu-v2_simple: nuttx_px4fmu-v2_simple
nuttx_px4fmu-v2_simple_upload: nuttx_px4fmu-v2_simple
make -C build_$< upload
nuttx_px4fmu-v2_simple_test: nuttx_px4fmu-v2_simple
make -C build_$< test
#----------------------------------------------------------------------------
# OS: nuttx BOARD: px4fmu-v2 LABEL: default
#
nuttx_px4fmu-v2_default:
mkdir -p $d/build_$@ && cd $d/build_$@ && \
cmake .. -DCMAKE_TOOLCHAIN_FILE=../cmake/toolchains/Toolchain-arm-none-eabi.cmake \
-DOS=nuttx -DBOARD=px4fmu-v2 -DLABEL=default && \
make -s && ctest -V && cpack -G ZIP
nuttx_px4fmu-v2_default_upload: nuttx_px4fmu-v2_default
make -C build_$< upload
nuttx_px4fmu-v2_default_test: nuttx_px4fmu-v2_default
make -C build_$< test
#----------------------------------------------------------------------------
# OS: nuttx BOARD: sim LABEL: simple
#
nuttx_sim_simple:
mkdir -p $d/build_$@ && cd $d/build_$@ && \
cmake .. -DCMAKE_TOOLCHAIN_FILE=../cmake/toolchains/Toolchain-native.cmake \
-DOS=nuttx -DBOARD=sim -DLABEL=simple && \
make -s && ctest -V && cpack -G ZIP
nuttx_px4fmu-v2_simple_upload: nuttx_px4fmu-v2_simple
cd $d/build_$< && make upload
px4fmu-v2_simple_upload: nuttx_px4fmu-v2_simple_upload
#----------------------------------------------------------------------------
# OS: posix BOARD: sitl LABEL: simple
#
posix_sitl_simple:
mkdir -p $d/build_$@ && cd $d/build_$@ && \
cmake .. -DCMAKE_TOOLCHAIN_FILE=../cmake/toolchains/Toolchain-posix-clang-native.cmake \
-DOS=posix -DBOARD=sitl -DLABEL=simple && \
make -s && ctest -V && cpack -G ZIP
#----------------------------------------------------------------------------
# OS: qurt BOARD: hil LABEL: simple
#
qurt_hil_simple:
mkdir -p $d/build_$@ && cd $d/build_$@ && \
cmake .. -DQURT_ENABLE_STUBS=1 -DCMAKE_TOOLCHAIN_FILE=../cmake/toolchains/Toolchain-hexagon.cmake \
-DOS=qurt -DBOARD=hil -DLABEL=simple && \
make -s && ctest -V && cpack -G ZIP
#----------------------------------------------------------------------------
# misc targets
#
clean:
rm -rf build_*/

View File

@ -0,0 +1,185 @@
include(nuttx/px4_impl_nuttx)
function(px4_set_config_modules out_module_list)
set(config_module_list
#
# Board support modules
#
drivers/device
drivers/stm32
drivers/stm32/adc
drivers/stm32/tone_alarm
drivers/led
drivers/px4fmu
drivers/px4io
drivers/boards/px4fmu-v2
drivers/rgbled
drivers/mpu6000
drivers/mpu9250
drivers/lsm303d
drivers/l3gd20
drivers/hmc5883
drivers/ms5611
drivers/mb12xx
drivers/sf0x
drivers/ll40ls
drivers/trone
drivers/gps
drivers/pwm_out_sim
drivers/hott
drivers/hott/hott_telemetry
drivers/hott/hott_sensors
drivers/blinkm
drivers/airspeed
drivers/ets_airspeed
drivers/meas_airspeed
drivers/frsky_telemetry
modules/sensors
drivers/mkblctrl
drivers/px4flow
drivers/oreoled
drivers/gimbal
drivers/pwm_input
drivers/camera_trigger
#
# System commands
#
systemcmds/bl_update
systemcmds/mixer
systemcmds/param
systemcmds/perf
systemcmds/pwm
systemcmds/esc_calib
systemcmds/reboot
systemcmds/top
systemcmds/config
systemcmds/nshterm
systemcmds/mtd
systemcmds/dumpfile
systemcmds/ver
#
# General system control
#
modules/commander
modules/navigator
modules/mavlink
modules/gpio_led
#modules/uavcan # have to fix CMakeLists.txt
modules/land_detector
#
# Estimation modules (EKF/ SO3 / other filters)
#
# Too high RAM usage due to static allocations
# modules/attitude_estimator_ekf
modules/attitude_estimator_q
modules/ekf_att_pos_estimator
modules/position_estimator_inav
#
# Vehicle Control
#
# modules/segway # XXX Needs GCC 4.7 fix
modules/fw_pos_control_l1
modules/fw_att_control
modules/mc_att_control
modules/mc_pos_control
modules/vtol_att_control
#
# Logging
#
modules/sdlog2
#
# Library modules
#
modules/systemlib
modules/systemlib/mixer
modules/controllib
modules/uORB
modules/dataman
#
# Libraries
#
#lib/mathlib/CMSIS
lib/mathlib
lib/mathlib/math/filter
lib/ecl
lib/external_lgpl
lib/geo
lib/geo_lookup
lib/conversion
lib/launchdetection
platforms/nuttx
# had to add for cmake, not sure why wasn't in original config
platforms/common
platforms/nuttx/px4_layer
#
# OBC challenge
#
modules/bottle_drop
#
# PX4 flow estimator, good for indoors
#
examples/flow_position_estimator
#
# Rover apps
#
examples/rover_steering_control
#
# Demo apps
#
#examples/math_demo
# Tutorial code from
# https://px4.io/dev/px4_simple_app
#examples/px4_simple_app
# Tutorial code from
# https://px4.io/dev/daemon
#examples/px4_daemon_app
# Tutorial code from
# https://px4.io/dev/debug_values
#examples/px4_mavlink_debug
# Tutorial code from
# https://px4.io/dev/example_fixedwing_control
#examples/fixedwing_control
# Hardware test
#examples/hwtest
)
# TODO convert rest of makefile config below
# Generate parameter XML file
#GEN_PARAM_XML = 1
set(${out_module_list} ${config_module_list} PARENT_SCOPE)
endfunction()
function(px4_nuttx_builtin_extra_commands out)
add_custom_target(sercon_main)
set_target_properties(sercon_main PROPERTIES
MAIN "sercon" STACK "2048")
add_custom_target(serdis_main)
set_target_properties(serdis_main PROPERTIES
MAIN "serdis" STACK "2048")
set(${out} sercon_main serdis_main PARENT_SCOPE)
endfunction()

View File

@ -3,21 +3,139 @@ include(nuttx/px4_impl_nuttx)
function(px4_set_config_modules out_module_list)
set(config_module_list
platforms/nuttx
platforms/nuttx/px4_layer
platforms/common
drivers/led
#
# Board support modules
#
drivers/device
modules/systemlib
modules/uORB
examples/px4_simple_app
drivers/boards/px4fmu-v2
drivers/stm32
drivers/stm32/adc
drivers/stm32/tone_alarm
drivers/led
drivers/px4fmu
drivers/px4io
drivers/boards/px4fmu-v2
drivers/rgbled
drivers/mpu6000
drivers/mpu9250
drivers/lsm303d
drivers/l3gd20
drivers/hmc5883
drivers/ms5611
drivers/mb12xx
drivers/sf0x
drivers/ll40ls
drivers/trone
drivers/gps
drivers/pwm_out_sim
drivers/hott
drivers/hott/hott_telemetry
drivers/hott/hott_sensors
drivers/blinkm
drivers/airspeed
drivers/ets_airspeed
drivers/meas_airspeed
drivers/frsky_telemetry
modules/sensors
drivers/mkblctrl
drivers/px4flow
drivers/oreoled
drivers/gimbal
drivers/pwm_input
drivers/camera_trigger
#
# System commands
#
systemcmds/bl_update
systemcmds/mixer
systemcmds/param
systemcmds/perf
systemcmds/pwm
systemcmds/esc_calib
systemcmds/reboot
systemcmds/top
systemcmds/config
systemcmds/nshterm
systemcmds/mtd
systemcmds/dumpfile
systemcmds/ver
#
# Logging
#
modules/sdlog2
#
# Library modules
#
modules/systemlib
modules/systemlib/mixer
modules/controllib
modules/uORB
modules/dataman
#
# Libraries
#
#lib/mathlib/CMSIS
lib/mathlib
lib/mathlib/math/filter
lib/ecl
lib/external_lgpl
lib/geo
lib/geo_lookup
lib/conversion
lib/launchdetection
platforms/nuttx
# had to add for cmake, not sure why wasn't in original config
platforms/common
platforms/nuttx/px4_layer
#
# Demo apps
#
#examples/math_demo
# Tutorial code from
# https://px4.io/dev/px4_simple_app
examples/px4_simple_app
# Tutorial code from
# https://px4.io/dev/daemon
examples/px4_daemon_app
# Tutorial code from
# https://px4.io/dev/debug_values
examples/px4_mavlink_debug
# Tutorial code from
# https://px4.io/dev/example_fixedwing_control
examples/fixedwing_control
# Hardware test
examples/hwtest
)
# TODO convert rest of makefile config below
# Generate parameter XML file
#GEN_PARAM_XML = 1
set(${out_module_list} ${config_module_list} PARENT_SCOPE)
endfunction()
function(px4_nuttx_builtin_extra_commands out)
add_custom_target(sercon_main)
set_target_properties(sercon_main PROPERTIES
MAIN "sercon" STACK "2048")
add_custom_target(serdis_main)
set_target_properties(serdis_main PROPERTIES
MAIN "serdis" STACK "2048")
set(${out} sercon_main serdis_main PARENT_SCOPE)
endfunction()

View File

@ -96,7 +96,7 @@ endfunction()
# px4_nuttx_generate_builtin_commands
#
# This function generates the builtin_commands.c src for nuttx
#
# Usage:
# px4_nuttx_generate_builtin_commands(
# MODULE_LIST <in-list>
@ -119,10 +119,12 @@ function(px4_nuttx_generate_builtin_commands)
MULTI_VALUE MODULE_LIST
REQUIRED MODULE_LIST OUT
ARGN ${ARGN})
message(STATUS "argn: ${ARGN}")
set(builtin_apps_string)
set(builtin_apps_decl_string)
set(command_count 0)
foreach(module ${MODULE_LIST})
message("generating builtin for: ${module}")
# default
set(MAIN_DEFAULT MAIN-NOTFOUND)
set(STACK_DEFAULT 1024)

View File

@ -210,17 +210,18 @@ static struct sdio_dev_s *sdio;
#include <math.h>
#ifdef __cplusplus
__EXPORT int matherr(struct __exception *e)
{
return 1;
}
#else
__EXPORT int matherr(struct exception *e)
{
return 1;
}
#endif
/* TODO XXX commented this out to get cmake build working */
/*#ifdef __cplusplus*/
/*__EXPORT int matherr(struct __exception *e)*/
/*{*/
/*return 1;*/
/*}*/
/*#else*/
/*__EXPORT int matherr(struct exception *e)*/
/*{*/
/*return 1;*/
/*}*/
/*#endif*/
__EXPORT int nsh_archinitialize(void)
{

View File

@ -1,6 +1,9 @@
px4_nuttx_builtin_extra_commands(builtin_extra_cmds)
message(STATUS "builtin extra: ${builtin_extra_cmds}")
px4_nuttx_generate_builtin_commands(
OUT builtin_commands.c
MODULE_LIST ${module_libraries})
MODULE_LIST ${module_libraries} ${builtin_extra_cmds})
px4_nuttx_generate_romfs(OUT romfs.o
ROOT ROMFS/px4fmu_common)
@ -15,9 +18,12 @@ set(main_link_flags
px4_join(OUT main_link_flags LIST ${main_link_flags} GLUE " ")
set_target_properties(firmware_nuttx PROPERTIES LINK_FLAGS ${main_link_flags})
set(cmsis_lib ${CMAKE_SOURCE_DIR}/src/lib/mathlib/CMSIS/libarm_cortexM4lf_math.a)
target_link_libraries(firmware_nuttx
-Wl,--start-group
${module_libraries}
${cmsis_lib}
apps nuttx nosys m gcc
-Wl,--end-group)

View File

@ -37,11 +37,61 @@ px4_add_module(
COMPILE_FLAGS
-O3
SRCS
# Main
uavcan_main.cpp
uavcan_servers.cpp
uavcan_clock.cpp
uavcan_params.c
# Actuators
actuators/esc.cpp
# Sensors
sensors/sensor_bridge.cpp
sensors/gnss.cpp
sensors/mag.cpp
sensors/baro.cpp
DEPENDS
platforms__common
)
# vim: set noet ft=cmake fenc=utf-8 ff=unix :
# TODO convert rest of module.mk
##
## libuavcan
##
#include $(PX4_LIB_DIR)uavcan/libuavcan/include.mk
## Use the relitive path to keep the genrated files in the BUILD_DIR
#SRCS += $(subst $(PX4_MODULE_SRC),../../,$(LIBUAVCAN_SRC))
#INCLUDE_DIRS += $(LIBUAVCAN_INC)
## Since actual compiler mode is C++11, the library will default to UAVCAN_CPP11, but it will fail to compile
## because this platform lacks most of the standard library and STL. Hence we need to force C++03 mode.
#override EXTRADEFINES := $(EXTRADEFINES) \
#-DUAVCAN_CPP_VERSION=UAVCAN_CPP03 \
#-DUAVCAN_NO_ASSERTIONS \
#-DUAVCAN_MEM_POOL_BLOCK_SIZE=48 \
#-DUAVCAN_MAX_NETWORK_SIZE_HINT=16
##
## libuavcan drivers for STM32
##
#include $(PX4_LIB_DIR)uavcan/libuavcan_drivers/stm32/driver/include.mk
## Use the relitive path to keep the genrated files in the BUILD_DIR
#SRCS += $(subst $(PX4_MODULE_SRC),../../,$(LIBUAVCAN_STM32_SRC))
#INCLUDE_DIRS += $(LIBUAVCAN_STM32_INC)
#override EXTRADEFINES := $(EXTRADEFINES) -DUAVCAN_STM32_NUTTX -DUAVCAN_STM32_NUM_IFACES=2
##
## libuavcan drivers for posix
##
#include $(PX4_LIB_DIR)uavcan/libuavcan_drivers/posix/include.mk
#INCLUDE_DIRS += $(LIBUAVCAN_POSIX_INC)
##
## Invoke DSDL compiler
##
#$(info $(shell $(LIBUAVCAN_DSDLC) $(UAVCAN_DSDL_DIR)))
#INCLUDE_DIRS += dsdlc_generated
## vim: set noet ft=cmake fenc=utf-8 ff=unix :

View File

@ -34,6 +34,7 @@ set(depends
msg_gen
prebuild_targets
git_mavlink
git_uavcan
)
if(${OS} STREQUAL "posix" OR ${BOARD} STREQUAL "sim")