Added FMUv1 config

This commit is contained in:
Lorenz Meier 2015-10-03 17:25:49 +02:00
parent 41f08f658d
commit d0ca0ff837
3 changed files with 208 additions and 1 deletions

View File

@ -75,6 +75,9 @@ endef
# --------------------------------------------------------------------
# Do not put any spaces between function arguments.
px4fmu-v1_default:
$(call cmake-build,nuttx_px4fmu-v1_default)
px4fmu-v2_default:
$(call cmake-build,nuttx_px4fmu-v2_default)

View File

@ -0,0 +1,182 @@
include(nuttx/px4_impl_nuttx)
set(CMAKE_TOOLCHAIN_FILE cmake/toolchains/Toolchain-arm-none-eabi.cmake)
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-v1
drivers/ardrone_interface
drivers/rgbled
drivers/mpu6000
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
#
# 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/param
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
#
# 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
)
set(config_firmware_options
PARAM_XML # generate param xml
)
set(config_extra_builtin_cmds
serdis
sercon
)
set(config_io_board
px4io-v1
)
set(config_extra_libs
${CMAKE_SOURCE_DIR}/src/lib/mathlib/CMSIS/libarm_cortexM4lf_math.a
)
set(config_io_extra_libs
#${CMAKE_SOURCE_DIR}/src/lib/mathlib/CMSIS/libarm_cortexM3l_math.a
)
add_custom_target(sercon)
set_target_properties(sercon PROPERTIES
MAIN "sercon" STACK "2048")
add_custom_target(serdis)
set_target_properties(serdis PROPERTIES
MAIN "serdis" STACK "2048")

View File

@ -455,7 +455,7 @@ function(px4_os_add_flags)
set(added_exe_linker_flags) # none currently
set(cpu_flags)
if (${BOARD} STREQUAL "px4fmu-v2")
if (${BOARD} STREQUAL "px4fmu-v1")
set(cpu_flags
-mcpu=cortex-m4
-mthumb
@ -463,6 +463,28 @@ function(px4_os_add_flags)
-mfpu=fpv4-sp-d16
-mfloat-abi=hard
)
elseif (${BOARD} STREQUAL "px4fmu-v2")
set(cpu_flags
-mcpu=cortex-m4
-mthumb
-march=armv7e-m
-mfpu=fpv4-sp-d16
-mfloat-abi=hard
)
elseif (${BOARD} STREQUAL "aerocore")
set(cpu_flags
-mcpu=cortex-m4
-mthumb
-march=armv7e-m
-mfpu=fpv4-sp-d16
-mfloat-abi=hard
)
elseif (${BOARD} STREQUAL "px4io-v1")
set(cpu_flags
-mcpu=cortex-m3
-mthumb
-march=armv7-m
)
elseif (${BOARD} STREQUAL "px4io-v2")
set(cpu_flags
-mcpu=cortex-m3