forked from Archive/PX4-Autopilot
add px4fmu-v{3,4,5} stackcheck configs
This commit is contained in:
parent
7e12815f81
commit
7cc0e69fcd
|
@ -31,7 +31,7 @@ pipeline {
|
|||
}
|
||||
}
|
||||
|
||||
stage('px4fmu-v4') {
|
||||
stage('px4fmu-v4 (stackcheck)') {
|
||||
agent {
|
||||
docker {
|
||||
image 'px4io/px4-dev-nuttx:2018-08-05'
|
||||
|
@ -43,10 +43,10 @@ pipeline {
|
|||
sh 'make distclean'
|
||||
sh 'ccache -z'
|
||||
sh 'git fetch --tags'
|
||||
sh 'make nuttx_px4fmu-v4_default'
|
||||
sh 'make nuttx_px4fmu-v4_stackcheck'
|
||||
sh 'make sizes'
|
||||
sh 'ccache -s'
|
||||
stash includes: 'build/nuttx_px4fmu-v4_default/nuttx_px4fmu-v4_default.elf', name: 'px4fmu-v4_default'
|
||||
stash includes: 'build/nuttx_px4fmu-v4_stackcheck/nuttx_px4fmu-v4_stackcheck.elf', name: 'px4fmu-v4_stackcheck'
|
||||
stash includes: 'Tools/HIL/monitor_firmware_upload.py, Tools/HIL/run_tests.py', name: 'scripts-px4fmu-v4'
|
||||
}
|
||||
post {
|
||||
|
@ -107,7 +107,7 @@ pipeline {
|
|||
sh 'export'
|
||||
sh 'find /dev/serial'
|
||||
unstash 'scripts-px4fmu-v4'
|
||||
unstash 'px4fmu-v4_default'
|
||||
unstash 'px4fmu-v4_stackcheck'
|
||||
sh ''' gdb -nx --batch \
|
||||
-ex "target extended-remote `find /dev/serial -name *Black_Magic_Probe_*-if00`" \
|
||||
-ex "monitor version" \
|
||||
|
@ -116,7 +116,7 @@ pipeline {
|
|||
-ex "attach 1" \
|
||||
-ex "load" \
|
||||
-ex "kill" \
|
||||
build/nuttx_px4fmu-v4_default/nuttx_px4fmu-v4_default.elf
|
||||
build/nuttx_px4fmu-v4_stackcheck/nuttx_px4fmu-v4_stackcheck.elf
|
||||
'''
|
||||
sh './Tools/HIL/monitor_firmware_upload.py --device `find /dev/serial -name *Black_Magic_Probe_*-if02` --baudrate 57600'
|
||||
sh './Tools/HIL/run_tests.py --device `find /dev/serial -name *Black_Magic_Probe_*-if02`'
|
||||
|
|
|
@ -0,0 +1,128 @@
|
|||
|
||||
# FMUv3 is FMUv2 with access to the full 2MB flash
|
||||
set(BOARD px4fmu-v2 CACHE string "" FORCE)
|
||||
set(FW_NAME nuttx_px4fmu-v3_default.elf CACHE string "" FORCE)
|
||||
set(FW_PROTOTYPE px4fmu-v3 CACHE string "" FORCE)
|
||||
set(LD_SCRIPT ld_full.script CACHE string "" FORCE)
|
||||
|
||||
px4_nuttx_configure(HWCLASS m4 CONFIG stackcheck ROMFS y ROMFSROOT px4fmu_common IO px4io-v2)
|
||||
|
||||
set(config_uavcan_num_ifaces 2)
|
||||
|
||||
set(config_module_list
|
||||
#
|
||||
# Board support modules
|
||||
#
|
||||
drivers/barometer
|
||||
drivers/differential_pressure
|
||||
drivers/distance_sensor
|
||||
drivers/magnetometer
|
||||
drivers/telemetry
|
||||
|
||||
drivers/batt_smbus
|
||||
drivers/blinkm
|
||||
drivers/camera_trigger
|
||||
drivers/gps
|
||||
drivers/imu/adis16448
|
||||
drivers/imu/bmi160
|
||||
drivers/imu/l3gd20
|
||||
drivers/imu/lsm303d
|
||||
drivers/imu/mpu6000
|
||||
drivers/imu/mpu9250
|
||||
drivers/irlock
|
||||
drivers/mkblctrl
|
||||
drivers/oreoled
|
||||
drivers/protocol_splitter
|
||||
drivers/pwm_input
|
||||
drivers/pwm_out_sim
|
||||
drivers/px4flow
|
||||
drivers/px4fmu
|
||||
drivers/px4io
|
||||
drivers/rgbled
|
||||
drivers/stm32
|
||||
drivers/stm32/adc
|
||||
drivers/stm32/tone_alarm
|
||||
drivers/tap_esc
|
||||
drivers/vmount
|
||||
modules/sensors
|
||||
|
||||
#
|
||||
# System commands
|
||||
#
|
||||
systemcmds/bl_update
|
||||
systemcmds/config
|
||||
systemcmds/dumpfile
|
||||
systemcmds/esc_calib
|
||||
systemcmds/hardfault_log
|
||||
systemcmds/led_control
|
||||
systemcmds/mixer
|
||||
systemcmds/motor_ramp
|
||||
systemcmds/motor_test
|
||||
systemcmds/mtd
|
||||
systemcmds/nshterm
|
||||
systemcmds/param
|
||||
systemcmds/perf
|
||||
systemcmds/pwm
|
||||
systemcmds/reboot
|
||||
systemcmds/sd_bench
|
||||
systemcmds/top
|
||||
systemcmds/topic_listener
|
||||
systemcmds/tune_control
|
||||
systemcmds/ver
|
||||
|
||||
#
|
||||
# Testing
|
||||
#
|
||||
drivers/distance_sensor/sf0x/sf0x_tests
|
||||
drivers/test_ppm
|
||||
lib/controllib/controllib_test
|
||||
#lib/rc/rc_tests
|
||||
modules/commander/commander_tests
|
||||
modules/mavlink/mavlink_tests
|
||||
modules/uORB/uORB_tests
|
||||
systemcmds/tests
|
||||
|
||||
#
|
||||
# General system control
|
||||
#
|
||||
modules/camera_feedback
|
||||
modules/commander
|
||||
modules/events
|
||||
modules/gpio_led
|
||||
modules/land_detector
|
||||
modules/load_mon
|
||||
modules/mavlink
|
||||
modules/navigator
|
||||
#modules/uavcan
|
||||
|
||||
#
|
||||
# Estimation modules
|
||||
#
|
||||
#modules/attitude_estimator_q
|
||||
modules/ekf2
|
||||
#modules/landing_target_estimator
|
||||
#modules/local_position_estimator
|
||||
#modules/position_estimator_inav
|
||||
modules/wind_estimator
|
||||
|
||||
#
|
||||
# Vehicle Control
|
||||
#
|
||||
modules/fw_att_control
|
||||
modules/fw_pos_control_l1
|
||||
modules/gnd_att_control
|
||||
modules/gnd_pos_control
|
||||
modules/mc_att_control
|
||||
modules/mc_pos_control
|
||||
modules/vtol_att_control
|
||||
|
||||
#
|
||||
# Logging
|
||||
#
|
||||
modules/logger
|
||||
|
||||
#
|
||||
# Library modules
|
||||
#
|
||||
modules/dataman
|
||||
)
|
|
@ -0,0 +1,116 @@
|
|||
|
||||
px4_nuttx_configure(HWCLASS m4 CONFIG stackcheck ROMFS y ROMFSROOT px4fmu_common)
|
||||
|
||||
set(config_uavcan_num_ifaces 1)
|
||||
|
||||
set(config_module_list
|
||||
#
|
||||
# Board support modules
|
||||
#
|
||||
drivers/barometer
|
||||
drivers/differential_pressure
|
||||
drivers/distance_sensor
|
||||
drivers/magnetometer
|
||||
drivers/telemetry
|
||||
drivers/imu
|
||||
|
||||
drivers/batt_smbus
|
||||
drivers/blinkm
|
||||
drivers/camera_trigger
|
||||
drivers/gps
|
||||
drivers/irlock
|
||||
drivers/mkblctrl
|
||||
drivers/oreoled
|
||||
drivers/pca9685
|
||||
drivers/pwm_input
|
||||
drivers/pwm_out_sim
|
||||
drivers/px4flow
|
||||
drivers/px4fmu
|
||||
drivers/rgbled
|
||||
drivers/rc_input
|
||||
drivers/stm32
|
||||
drivers/stm32/adc
|
||||
drivers/stm32/tone_alarm
|
||||
drivers/tap_esc
|
||||
drivers/vmount
|
||||
modules/sensors
|
||||
|
||||
#
|
||||
# System commands
|
||||
#
|
||||
systemcmds/bl_update
|
||||
systemcmds/config
|
||||
systemcmds/dumpfile
|
||||
systemcmds/esc_calib
|
||||
systemcmds/hardfault_log
|
||||
systemcmds/led_control
|
||||
systemcmds/mixer
|
||||
systemcmds/motor_ramp
|
||||
systemcmds/mtd
|
||||
systemcmds/nshterm
|
||||
systemcmds/param
|
||||
systemcmds/perf
|
||||
systemcmds/pwm
|
||||
systemcmds/reboot
|
||||
systemcmds/sd_bench
|
||||
systemcmds/top
|
||||
systemcmds/topic_listener
|
||||
systemcmds/tune_control
|
||||
systemcmds/ver
|
||||
|
||||
#
|
||||
# Testing
|
||||
#
|
||||
drivers/distance_sensor/sf0x/sf0x_tests
|
||||
drivers/test_ppm
|
||||
#lib/rc/rc_tests
|
||||
modules/commander/commander_tests
|
||||
lib/controllib/controllib_test
|
||||
modules/mavlink/mavlink_tests
|
||||
modules/uORB/uORB_tests
|
||||
systemcmds/tests
|
||||
|
||||
#
|
||||
# General system control
|
||||
#
|
||||
modules/camera_feedback
|
||||
modules/commander
|
||||
modules/events
|
||||
modules/gpio_led
|
||||
modules/land_detector
|
||||
modules/load_mon
|
||||
modules/mavlink
|
||||
modules/navigator
|
||||
#modules/uavcan
|
||||
|
||||
#
|
||||
# Estimation modules
|
||||
#
|
||||
modules/attitude_estimator_q
|
||||
modules/ekf2
|
||||
modules/landing_target_estimator
|
||||
modules/local_position_estimator
|
||||
modules/position_estimator_inav
|
||||
modules/wind_estimator
|
||||
|
||||
#
|
||||
# Vehicle Control
|
||||
#
|
||||
modules/fw_att_control
|
||||
modules/fw_pos_control_l1
|
||||
modules/gnd_att_control
|
||||
modules/gnd_pos_control
|
||||
modules/mc_att_control
|
||||
modules/mc_pos_control
|
||||
modules/vtol_att_control
|
||||
|
||||
#
|
||||
# Logging
|
||||
#
|
||||
modules/logger
|
||||
|
||||
#
|
||||
# Library modules
|
||||
#
|
||||
modules/dataman
|
||||
)
|
|
@ -0,0 +1,121 @@
|
|||
|
||||
px4_nuttx_configure(HWCLASS m7 CONFIG stackcheck ROMFS y ROMFSROOT px4fmu_common IO px4io-v2)
|
||||
|
||||
set(config_uavcan_num_ifaces 2)
|
||||
|
||||
set(config_module_list
|
||||
#
|
||||
# Board support modules
|
||||
#
|
||||
drivers/barometer
|
||||
drivers/differential_pressure
|
||||
drivers/distance_sensor
|
||||
drivers/magnetometer
|
||||
drivers/telemetry
|
||||
|
||||
drivers/batt_smbus
|
||||
drivers/blinkm
|
||||
drivers/camera_trigger
|
||||
drivers/gps
|
||||
drivers/imu/bma180
|
||||
drivers/imu/bmi055
|
||||
drivers/imu/bmi160
|
||||
drivers/imu/mpu6000
|
||||
drivers/imu/mpu9250
|
||||
drivers/irlock
|
||||
drivers/mkblctrl
|
||||
drivers/oreoled
|
||||
drivers/pwm_input
|
||||
drivers/pwm_out_sim
|
||||
drivers/px4flow
|
||||
drivers/px4fmu
|
||||
drivers/px4io
|
||||
drivers/rc_input
|
||||
drivers/rgbled
|
||||
#drivers/rgbled_pwm # Enable to put the three leds into PWM RGB mode
|
||||
drivers/stm32
|
||||
drivers/stm32/adc
|
||||
drivers/stm32/tone_alarm
|
||||
drivers/tap_esc
|
||||
drivers/vmount
|
||||
modules/sensors
|
||||
|
||||
#
|
||||
# System commands
|
||||
#
|
||||
systemcmds/bl_update
|
||||
systemcmds/config
|
||||
systemcmds/dumpfile
|
||||
systemcmds/esc_calib
|
||||
systemcmds/hardfault_log
|
||||
systemcmds/led_control
|
||||
systemcmds/mixer
|
||||
systemcmds/motor_ramp
|
||||
systemcmds/mtd
|
||||
systemcmds/nshterm
|
||||
systemcmds/param
|
||||
systemcmds/perf
|
||||
systemcmds/pwm
|
||||
systemcmds/reboot
|
||||
systemcmds/sd_bench
|
||||
systemcmds/top
|
||||
systemcmds/topic_listener
|
||||
systemcmds/tune_control
|
||||
systemcmds/ver
|
||||
|
||||
#
|
||||
# Testing
|
||||
#
|
||||
drivers/distance_sensor/sf0x/sf0x_tests
|
||||
drivers/test_ppm
|
||||
#lib/rc/rc_tests
|
||||
modules/commander/commander_tests
|
||||
lib/controllib/controllib_test
|
||||
modules/mavlink/mavlink_tests
|
||||
modules/uORB/uORB_tests
|
||||
systemcmds/tests
|
||||
|
||||
#
|
||||
# General system control
|
||||
#
|
||||
modules/commander
|
||||
modules/events
|
||||
modules/gpio_led
|
||||
modules/land_detector
|
||||
modules/load_mon
|
||||
modules/mavlink
|
||||
modules/navigator
|
||||
#modules/uavcan
|
||||
modules/camera_feedback
|
||||
|
||||
#
|
||||
# Estimation modules
|
||||
#
|
||||
modules/attitude_estimator_q
|
||||
modules/ekf2
|
||||
modules/landing_target_estimator
|
||||
modules/local_position_estimator
|
||||
modules/position_estimator_inav
|
||||
modules/wind_estimator
|
||||
|
||||
#
|
||||
# Vehicle Control
|
||||
#
|
||||
modules/fw_att_control
|
||||
modules/fw_pos_control_l1
|
||||
modules/gnd_att_control
|
||||
modules/gnd_pos_control
|
||||
modules/mc_att_control
|
||||
modules/mc_pos_control
|
||||
modules/vtol_att_control
|
||||
|
||||
#
|
||||
# Logging
|
||||
#
|
||||
modules/logger
|
||||
|
||||
#
|
||||
# Library modules
|
||||
#
|
||||
modules/dataman
|
||||
)
|
|
@ -195,7 +195,7 @@ function(px4_os_add_flags)
|
|||
)
|
||||
|
||||
if("${CONFIG_ARMV7M_STACKCHECK}" STREQUAL "y")
|
||||
message(WARNING !!!!!!!!! CONFIG_ARMV7M_STACKCHECK=${CONFIG_ARMV7M_STACKCHECK} !!!!!!)
|
||||
message(STATUS "NuttX Stack Checking (CONFIG_ARMV7M_STACKCHECK) enabled")
|
||||
set(instrument_flags
|
||||
-finstrument-functions
|
||||
-ffixed-r10
|
||||
|
@ -245,7 +245,7 @@ function(px4_os_prebuild_targets)
|
|||
add_dependencies(${OUT} DEPENDS nuttx_context uorb_headers)
|
||||
|
||||
# parse nuttx config options for cmake
|
||||
file(STRINGS ${PX4_SOURCE_DIR}/platforms/nuttx/nuttx-configs/${BOARD}/nsh/defconfig ConfigContents)
|
||||
file(STRINGS ${PX4_SOURCE_DIR}/platforms/nuttx/nuttx-configs/${BOARD}/${nuttx_config_type}/defconfig ConfigContents)
|
||||
foreach(NameAndValue ${ConfigContents})
|
||||
# Strip leading spaces
|
||||
string(REGEX REPLACE "^[ ]+" "" NameAndValue ${NameAndValue})
|
||||
|
@ -309,6 +309,11 @@ function(px4_nuttx_configure)
|
|||
set(CMAKE_SYSTEM_PROCESSOR ${CMAKE_SYSTEM_PROCESSOR} CACHE INTERNAL "system processor" FORCE)
|
||||
set(CMAKE_TOOLCHAIN_FILE ${PX4_SOURCE_DIR}/cmake/toolchains/Toolchain-arm-none-eabi.cmake CACHE INTERNAL "toolchain file" FORCE)
|
||||
|
||||
if (CONFIG)
|
||||
set(nuttx_config_type ${CONFIG})
|
||||
set(nuttx_config_type ${nuttx_config_type} PARENT_SCOPE)
|
||||
endif()
|
||||
|
||||
# ROMFS
|
||||
if("${ROMFS}" STREQUAL "y")
|
||||
if (NOT DEFINED ROMFSROOT)
|
||||
|
|
File diff suppressed because it is too large
Load Diff
File diff suppressed because it is too large
Load Diff
File diff suppressed because it is too large
Load Diff
|
@ -39,7 +39,7 @@ set(srcs
|
|||
px4_add_module(
|
||||
MODULE drivers__ms5611
|
||||
MAIN ms5611
|
||||
STACK_MAIN 1200
|
||||
STACK_MAIN 1500
|
||||
COMPILE_FLAGS
|
||||
SRCS ${srcs}
|
||||
DEPENDS
|
||||
|
|
|
@ -33,7 +33,7 @@
|
|||
px4_add_module(
|
||||
MODULE drivers__l3gd20
|
||||
MAIN l3gd20
|
||||
STACK_MAIN 1200
|
||||
STACK_MAIN 1500
|
||||
COMPILE_FLAGS
|
||||
SRCS
|
||||
l3gd20.cpp
|
||||
|
|
|
@ -33,7 +33,7 @@
|
|||
px4_add_module(
|
||||
MODULE drivers__lsm303d
|
||||
MAIN lsm303d
|
||||
STACK_MAIN 1200
|
||||
STACK_MAIN 1500
|
||||
COMPILE_FLAGS
|
||||
SRCS
|
||||
lsm303d.cpp
|
||||
|
|
|
@ -33,7 +33,7 @@
|
|||
px4_add_module(
|
||||
MODULE drivers__mpu9250
|
||||
MAIN mpu9250
|
||||
STACK_MAIN 1200
|
||||
STACK_MAIN 1500
|
||||
COMPILE_FLAGS
|
||||
SRCS
|
||||
mpu9250.cpp
|
||||
|
|
|
@ -33,7 +33,7 @@
|
|||
px4_add_module(
|
||||
MODULE drivers__hmc5883
|
||||
MAIN hmc5883
|
||||
STACK_MAIN 1200
|
||||
STACK_MAIN 1500
|
||||
COMPILE_FLAGS
|
||||
SRCS
|
||||
hmc5883_i2c.cpp
|
||||
|
|
|
@ -33,7 +33,7 @@
|
|||
px4_add_module(
|
||||
MODULE systemcmds__hardfault_log
|
||||
MAIN hardfault_log
|
||||
STACK_MAIN 2048
|
||||
STACK_MAIN 2100
|
||||
COMPILE_FLAGS
|
||||
SRCS
|
||||
hardfault_log.c
|
||||
|
|
Loading…
Reference in New Issue