forked from Archive/PX4-Autopilot
Merge pull request #4265 from jgoppert/cmake_stack
Modified cmake to use STACK_MAX and STACK_MAIN Looked over the reported sitl failure with jenkins, but it shows all tests passed, and this is happening on all branches, so going to merge.
This commit is contained in:
commit
831bce67bc
|
@ -225,7 +225,9 @@ endfunction()
|
|||
# Usage:
|
||||
# px4_add_module(MODULE <string>
|
||||
# [ MAIN <string> ]
|
||||
# [ STACK <string> ]
|
||||
# [ STACK <string> ] !!!!!DEPRECATED, USE STACK_MAIN INSTEAD!!!!!!!!!
|
||||
# [ STACK_MAIN <string> ]
|
||||
# [ STACK_MAX <string> ]
|
||||
# [ COMPILE_FLAGS <list> ]
|
||||
# [ INCLUDES <list> ]
|
||||
# [ DEPENDS <string> ]
|
||||
|
@ -234,7 +236,9 @@ endfunction()
|
|||
# Input:
|
||||
# MODULE : unique name of module
|
||||
# MAIN : entry point, if not given, assumed to be library
|
||||
# STACK : size of stack
|
||||
# STACK : deprecated use stack main instead
|
||||
# STACK_MAIN : size of stack for main function
|
||||
# STACK_MAX : maximum stack size of any frame
|
||||
# COMPILE_FLAGS : compile flags
|
||||
# LINK_FLAGS : link flags
|
||||
# SRCS : source files
|
||||
|
@ -248,7 +252,7 @@ endfunction()
|
|||
# px4_add_module(MODULE test
|
||||
# SRCS
|
||||
# file.cpp
|
||||
# STACK 1024
|
||||
# STACK_MAIN 1024
|
||||
# DEPENDS
|
||||
# git_nuttx
|
||||
# )
|
||||
|
@ -257,15 +261,43 @@ function(px4_add_module)
|
|||
|
||||
px4_parse_function_args(
|
||||
NAME px4_add_module
|
||||
ONE_VALUE MODULE MAIN STACK PRIORITY
|
||||
ONE_VALUE MODULE MAIN STACK STACK_MAIN STACK_MAX PRIORITY
|
||||
MULTI_VALUE COMPILE_FLAGS LINK_FLAGS SRCS INCLUDES DEPENDS
|
||||
REQUIRED MODULE
|
||||
ARGN ${ARGN})
|
||||
|
||||
add_library(${MODULE} STATIC EXCLUDE_FROM_ALL ${SRCS})
|
||||
|
||||
# set defaults if not set
|
||||
set(MAIN_DEFAULT MAIN-NOTFOUND)
|
||||
set(STACK_MAIN_DEFAULT 1024)
|
||||
set(PRIORITY_DEFAULT SCHED_PRIORITY_DEFAULT)
|
||||
|
||||
# default stack max to stack main
|
||||
if(NOT STACK_MAIN AND STACK)
|
||||
set(STACK_MAIN ${STACK})
|
||||
message(AUTHOR_WARNING "STACK deprecated, USE STACK_MAIN instead!!!!!!!!!!!!")
|
||||
endif()
|
||||
|
||||
foreach(property MAIN STACK_MAIN PRIORITY)
|
||||
if(NOT ${property})
|
||||
set(${property} ${${property}_DEFAULT})
|
||||
endif()
|
||||
set_target_properties(${MODULE} PROPERTIES ${property}
|
||||
${${property}})
|
||||
endforeach()
|
||||
|
||||
# default stack max to stack main
|
||||
if(NOT STACK_MAX)
|
||||
set(STACK_MAX ${STACK_MAIN})
|
||||
endif()
|
||||
set_target_properties(${MODULE} PROPERTIES STACK_MAX
|
||||
${STACK_MAX})
|
||||
|
||||
if(${OS} STREQUAL "qurt" )
|
||||
set_property(TARGET ${MODULE} PROPERTY POSITION_INDEPENDENT_CODE TRUE)
|
||||
elseif(${OS} STREQUAL "nuttx" )
|
||||
list(APPEND COMPILE_FLAGS -Wframe-larger-than=${STACK_MAX})
|
||||
endif()
|
||||
|
||||
if(MAIN)
|
||||
|
@ -290,8 +322,8 @@ function(px4_add_module)
|
|||
|
||||
# store module properties in target
|
||||
# COMPILE_FLAGS and LINK_FLAGS are passed to compiler/linker by cmake
|
||||
# STACK, MAIN, PRIORITY are PX4 specific
|
||||
foreach (prop COMPILE_FLAGS LINK_FLAGS STACK MAIN PRIORITY)
|
||||
# STACK_MAIN, MAIN, PRIORITY are PX4 specific
|
||||
foreach (prop COMPILE_FLAGS LINK_FLAGS STACK_MAIN MAIN PRIORITY)
|
||||
if (${prop})
|
||||
set_target_properties(${MODULE} PROPERTIES ${prop} ${${prop}})
|
||||
endif()
|
||||
|
@ -530,10 +562,6 @@ function(px4_add_common_flags)
|
|||
# but generates too many false positives
|
||||
)
|
||||
|
||||
if (${OS} STREQUAL "nuttx")
|
||||
list(APPEND warnings -Wframe-larger-than=1024)
|
||||
endif()
|
||||
|
||||
if (${CMAKE_C_COMPILER_ID} MATCHES ".*Clang.*")
|
||||
# QuRT 6.4.X compiler identifies as Clang but does not support this option
|
||||
if (NOT ${OS} STREQUAL "qurt")
|
||||
|
|
|
@ -189,8 +189,10 @@ set(config_io_extra_libs
|
|||
|
||||
add_custom_target(sercon)
|
||||
set_target_properties(sercon PROPERTIES
|
||||
MAIN "sercon" STACK "2048")
|
||||
PRIORITY "SCHED_PRIORITY_DEFAULT"
|
||||
MAIN "sercon" STACK_MAIN "2048")
|
||||
|
||||
add_custom_target(serdis)
|
||||
set_target_properties(serdis PROPERTIES
|
||||
MAIN "serdis" STACK "2048")
|
||||
PRIORITY "SCHED_PRIORITY_DEFAULT"
|
||||
MAIN "serdis" STACK_MAIN "2048")
|
||||
|
|
|
@ -80,8 +80,12 @@ set(config_extra_builtin_cmds
|
|||
|
||||
add_custom_target(sercon)
|
||||
set_target_properties(sercon PROPERTIES
|
||||
MAIN "sercon" STACK "2048")
|
||||
PRIORITY "SCHED_PRIORITY_DEFAULT"
|
||||
MAIN "sercon"
|
||||
STACK_MAIN "2048")
|
||||
|
||||
add_custom_target(serdis)
|
||||
set_target_properties(serdis PROPERTIES
|
||||
MAIN "serdis" STACK "2048")
|
||||
PRIORITY "SCHED_PRIORITY_DEFAULT"
|
||||
MAIN "serdis"
|
||||
STACK_MAIN "2048")
|
||||
|
|
|
@ -171,8 +171,12 @@ set(config_io_extra_libs
|
|||
|
||||
add_custom_target(sercon)
|
||||
set_target_properties(sercon PROPERTIES
|
||||
MAIN "sercon" STACK "2048")
|
||||
PRIORITY "SCHED_PRIORITY_DEFAULT"
|
||||
MAIN "sercon"
|
||||
STACK_MAIN "2048")
|
||||
|
||||
add_custom_target(serdis)
|
||||
set_target_properties(serdis PROPERTIES
|
||||
MAIN "serdis" STACK "2048")
|
||||
PRIORITY "SCHED_PRIORITY_DEFAULT"
|
||||
MAIN "serdis"
|
||||
STACK_MAIN "2048")
|
||||
|
|
|
@ -183,8 +183,10 @@ set(config_io_extra_libs
|
|||
|
||||
add_custom_target(sercon)
|
||||
set_target_properties(sercon PROPERTIES
|
||||
MAIN "sercon" STACK "2048")
|
||||
PRIORITY "SCHED_PRIORITY_DEFAULT"
|
||||
MAIN "sercon" STACK_MAIN "2048")
|
||||
|
||||
add_custom_target(serdis)
|
||||
set_target_properties(serdis PROPERTIES
|
||||
MAIN "serdis" STACK "2048")
|
||||
PRIORITY "SCHED_PRIORITY_DEFAULT"
|
||||
MAIN "serdis" STACK_MAIN "2048")
|
||||
|
|
|
@ -182,8 +182,10 @@ set(config_io_extra_libs
|
|||
|
||||
add_custom_target(sercon)
|
||||
set_target_properties(sercon PROPERTIES
|
||||
MAIN "sercon" STACK "2048")
|
||||
PRIORITY "SCHED_PRIORITY_DEFAULT"
|
||||
MAIN "sercon" STACK_MAIN "2048")
|
||||
|
||||
add_custom_target(serdis)
|
||||
set_target_properties(serdis PROPERTIES
|
||||
MAIN "serdis" STACK "2048")
|
||||
PRIORITY "SCHED_PRIORITY_DEFAULT"
|
||||
MAIN "serdis" STACK_MAIN "2048")
|
||||
|
|
|
@ -179,8 +179,12 @@ set(config_io_extra_libs
|
|||
|
||||
add_custom_target(sercon)
|
||||
set_target_properties(sercon PROPERTIES
|
||||
MAIN "sercon" STACK "2048")
|
||||
PRIORITY "SCHED_PRIORITY_DEFAULT"
|
||||
MAIN "sercon"
|
||||
STACK_MAIN "2048")
|
||||
|
||||
add_custom_target(serdis)
|
||||
set_target_properties(serdis PROPERTIES
|
||||
MAIN "serdis" STACK "2048")
|
||||
PRIORITY "SCHED_PRIORITY_DEFAULT"
|
||||
MAIN "serdis"
|
||||
STACK_MAIN "2048")
|
||||
|
|
|
@ -88,13 +88,3 @@ set(config_sitl_debugger
|
|||
)
|
||||
set_property(CACHE config_sitl_debugger
|
||||
PROPERTY STRINGS "disable;gdb;lldb")
|
||||
|
||||
|
||||
|
||||
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")
|
||||
|
|
|
@ -87,13 +87,3 @@ set(config_sitl_debugger
|
|||
)
|
||||
set_property(CACHE config_sitl_debugger
|
||||
PROPERTY STRINGS "disable;gdb;lldb")
|
||||
|
||||
|
||||
|
||||
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")
|
||||
|
|
|
@ -50,13 +50,3 @@ set(config_sitl_debugger
|
|||
)
|
||||
set_property(CACHE config_sitl_debugger
|
||||
PROPERTY STRINGS "disable;gdb;lldb")
|
||||
|
||||
|
||||
|
||||
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")
|
||||
|
|
|
@ -137,20 +137,12 @@ function(px4_nuttx_generate_builtin_commands)
|
|||
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)
|
||||
set(PRIORITY_DEFAULT SCHED_PRIORITY_DEFAULT)
|
||||
foreach(property MAIN STACK PRIORITY)
|
||||
foreach(property MAIN STACK_MAIN PRIORITY)
|
||||
get_target_property(${property} ${module} ${property})
|
||||
if(NOT ${property})
|
||||
set(${property} ${${property}_DEFAULT})
|
||||
endif()
|
||||
endforeach()
|
||||
if (MAIN)
|
||||
set(builtin_apps_string
|
||||
"${builtin_apps_string}\t{\"${MAIN}\", ${PRIORITY}, ${STACK}, ${MAIN}_main},\n")
|
||||
"${builtin_apps_string}\t{\"${MAIN}\", ${PRIORITY}, ${STACK_MAIN}, ${MAIN}_main},\n")
|
||||
set(builtin_apps_decl_string
|
||||
"${builtin_apps_decl_string}extern int ${MAIN}_main(int argc, char *argv[]);\n")
|
||||
math(EXPR command_count "${command_count}+1")
|
||||
|
|
|
@ -84,15 +84,8 @@ function(px4_qurt_generate_builtin_commands)
|
|||
set(builtin_apps_decl_string)
|
||||
set(command_count 0)
|
||||
foreach(module ${MODULE_LIST})
|
||||
# default
|
||||
set(MAIN_DEFAULT MAIN-NOTFOUND)
|
||||
set(STACK_DEFAULT 1024)
|
||||
set(PRIORITY_DEFAULT SCHED_PRIORITY_DEFAULT)
|
||||
foreach(property MAIN STACK PRIORITY)
|
||||
foreach(property MAIN STACK_MAIN PRIORITY)
|
||||
get_target_property(${property} ${module} ${property})
|
||||
if(NOT ${property})
|
||||
set(${property} ${${property}_DEFAULT})
|
||||
endif()
|
||||
endforeach()
|
||||
if (MAIN)
|
||||
set(builtin_apps_string
|
||||
|
|
|
@ -33,7 +33,7 @@
|
|||
px4_add_module(
|
||||
MODULE drivers__ardrone_interface
|
||||
MAIN ardrone_interface
|
||||
STACK 1200
|
||||
STACK_MAIN 1200
|
||||
COMPILE_FLAGS
|
||||
-Os
|
||||
SRCS
|
||||
|
|
|
@ -33,7 +33,7 @@
|
|||
px4_add_module(
|
||||
MODULE drivers__bst
|
||||
MAIN bst
|
||||
STACK 1200
|
||||
STACK_MAIN 1200
|
||||
COMPILE_FLAGS
|
||||
-Os
|
||||
SRCS
|
||||
|
|
|
@ -33,7 +33,7 @@
|
|||
px4_add_module(
|
||||
MODULE drivers__camera_trigger
|
||||
MAIN camera_trigger
|
||||
STACK 1200
|
||||
STACK_MAIN 1200
|
||||
COMPILE_FLAGS
|
||||
-Os
|
||||
SRCS
|
||||
|
|
|
@ -33,7 +33,7 @@
|
|||
px4_add_module(
|
||||
MODULE drivers__ets_airspeed
|
||||
MAIN ets_airspeed
|
||||
STACK 1200
|
||||
STACK_MAIN 1200
|
||||
COMPILE_FLAGS
|
||||
-Os
|
||||
SRCS
|
||||
|
|
|
@ -33,7 +33,7 @@
|
|||
px4_add_module(
|
||||
MODULE drivers__frsky_telemetry
|
||||
MAIN frsky_telemetry
|
||||
STACK 1200
|
||||
STACK_MAIN 1200
|
||||
COMPILE_FLAGS
|
||||
-Os
|
||||
SRCS
|
||||
|
|
|
@ -33,6 +33,7 @@
|
|||
px4_add_module(
|
||||
MODULE drivers__gimbal
|
||||
MAIN gimbal
|
||||
STACK_MAIN 1024
|
||||
COMPILE_FLAGS
|
||||
-Os
|
||||
SRCS
|
||||
|
|
|
@ -33,7 +33,7 @@
|
|||
px4_add_module(
|
||||
MODULE drivers__gps
|
||||
MAIN gps
|
||||
STACK 1200
|
||||
STACK_MAIN 1200
|
||||
COMPILE_FLAGS
|
||||
-Os
|
||||
SRCS
|
||||
|
|
|
@ -33,7 +33,7 @@
|
|||
px4_add_module(
|
||||
MODULE drivers__hmc5883
|
||||
MAIN hmc5883
|
||||
STACK 1200
|
||||
STACK_MAIN 1200
|
||||
COMPILE_FLAGS
|
||||
-Weffc++
|
||||
-Os
|
||||
|
|
|
@ -33,7 +33,7 @@
|
|||
px4_add_module(
|
||||
MODULE drivers__l3gd20
|
||||
MAIN l3gd20
|
||||
STACK 1200
|
||||
STACK_MAIN 1200
|
||||
COMPILE_FLAGS
|
||||
-Weffc++
|
||||
-Os
|
||||
|
|
|
@ -33,7 +33,7 @@
|
|||
px4_add_module(
|
||||
MODULE drivers__lsm303d
|
||||
MAIN lsm303d
|
||||
STACK 1200
|
||||
STACK_MAIN 1200
|
||||
COMPILE_FLAGS
|
||||
-Weffc++
|
||||
-Os
|
||||
|
|
|
@ -33,7 +33,7 @@
|
|||
px4_add_module(
|
||||
MODULE drivers__meas_airspeed
|
||||
MAIN meas_airspeed
|
||||
STACK 1200
|
||||
STACK_MAIN 1200
|
||||
COMPILE_FLAGS
|
||||
-Weffc++
|
||||
-Os
|
||||
|
|
|
@ -33,7 +33,7 @@
|
|||
px4_add_module(
|
||||
MODULE drivers__mpu6000
|
||||
MAIN mpu6000
|
||||
STACK 1200
|
||||
STACK_MAIN 1200
|
||||
COMPILE_FLAGS
|
||||
-Weffc++
|
||||
-Os
|
||||
|
|
|
@ -33,7 +33,7 @@
|
|||
px4_add_module(
|
||||
MODULE drivers__mpu9250
|
||||
MAIN mpu9250
|
||||
STACK 1200
|
||||
STACK_MAIN 1200
|
||||
COMPILE_FLAGS
|
||||
-Weffc++
|
||||
-Os
|
||||
|
|
|
@ -33,6 +33,7 @@
|
|||
px4_add_module(
|
||||
MODULE drivers__oreoled
|
||||
MAIN oreoled
|
||||
STACK_MAIN 1024
|
||||
COMPILE_FLAGS
|
||||
-Os
|
||||
SRCS
|
||||
|
|
|
@ -33,9 +33,9 @@
|
|||
px4_add_module(
|
||||
MODULE drivers__pwm_input
|
||||
MAIN pwm_input
|
||||
STACK_MAIN 1024
|
||||
COMPILE_FLAGS
|
||||
-Wno-pmf-conversions
|
||||
|
||||
SRCS
|
||||
pwm_input.cpp
|
||||
DEPENDS
|
||||
|
|
|
@ -33,7 +33,7 @@
|
|||
px4_add_module(
|
||||
MODULE drivers__pwm_out_sim
|
||||
MAIN pwm_out_sim
|
||||
STACK 1200
|
||||
STACK_MAIN 1200
|
||||
COMPILE_FLAGS
|
||||
-Os
|
||||
SRCS
|
||||
|
|
|
@ -33,7 +33,7 @@
|
|||
px4_add_module(
|
||||
MODULE drivers__px4flow
|
||||
MAIN px4flow
|
||||
STACK 1200
|
||||
STACK_MAIN 1200
|
||||
COMPILE_FLAGS
|
||||
-Wno-attributes
|
||||
-Os
|
||||
|
|
|
@ -33,7 +33,7 @@
|
|||
px4_add_module(
|
||||
MODULE drivers__px4fmu
|
||||
MAIN fmu
|
||||
STACK 1200
|
||||
STACK_MAIN 1200
|
||||
COMPILE_FLAGS
|
||||
-Os
|
||||
SRCS
|
||||
|
|
|
@ -33,7 +33,7 @@
|
|||
px4_add_module(
|
||||
MODULE drivers__px4io
|
||||
MAIN px4io
|
||||
STACK 1800
|
||||
STACK_MAIN 1800
|
||||
COMPILE_FLAGS
|
||||
-Os
|
||||
SRCS
|
||||
|
|
|
@ -33,7 +33,7 @@
|
|||
px4_add_module(
|
||||
MODULE drivers__trone
|
||||
MAIN trone
|
||||
STACK 1200
|
||||
STACK_MAIN 1200
|
||||
COMPILE_FLAGS
|
||||
-Os
|
||||
SRCS
|
||||
|
|
|
@ -33,10 +33,8 @@
|
|||
px4_add_module(
|
||||
MODULE examples__fixedwing_control
|
||||
MAIN ex_fixedwing_control
|
||||
STACK 1200
|
||||
COMPILE_FLAGS
|
||||
-Wframe-larger-than=1300
|
||||
|
||||
STACK_MAIN 1200
|
||||
STACK_MAX 1300
|
||||
SRCS
|
||||
main.c
|
||||
params.c
|
||||
|
|
|
@ -33,7 +33,7 @@
|
|||
px4_add_module(
|
||||
MODULE examples__hwtest
|
||||
MAIN ex_hwtest
|
||||
STACK 2000
|
||||
STACK_MAIN 2000
|
||||
SRCS
|
||||
hwtest.c
|
||||
DEPENDS
|
||||
|
|
|
@ -33,7 +33,7 @@
|
|||
px4_add_module(
|
||||
MODULE examples__matlab_csv_serial
|
||||
MAIN matlab_csv_serial
|
||||
STACK 2000
|
||||
STACK_MAIN 2000
|
||||
SRCS
|
||||
matlab_csv_serial.c
|
||||
DEPENDS
|
||||
|
|
|
@ -33,7 +33,7 @@
|
|||
px4_add_module(
|
||||
MODULE examples__publisher
|
||||
MAIN publisher
|
||||
STACK 1200
|
||||
STACK_MAIN 1200
|
||||
SRCS
|
||||
publisher_main.cpp
|
||||
publisher_start_nuttx.cpp
|
||||
|
|
|
@ -33,7 +33,7 @@
|
|||
px4_add_module(
|
||||
MODULE examples__px4_daemon_app
|
||||
MAIN px4_daemon_app
|
||||
STACK 1200
|
||||
STACK_MAIN 1200
|
||||
SRCS
|
||||
px4_daemon_app.c
|
||||
DEPENDS
|
||||
|
|
|
@ -33,7 +33,7 @@
|
|||
px4_add_module(
|
||||
MODULE examples__px4_mavlink_debug
|
||||
MAIN px4_mavlink_debug
|
||||
STACK 2000
|
||||
STACK_MAIN 2000
|
||||
SRCS
|
||||
px4_mavlink_debug.c
|
||||
DEPENDS
|
||||
|
|
|
@ -33,7 +33,7 @@
|
|||
px4_add_module(
|
||||
MODULE examples__px4_simple_app
|
||||
MAIN px4_simple_app
|
||||
STACK 2000
|
||||
STACK_MAIN 2000
|
||||
SRCS
|
||||
px4_simple_app.c
|
||||
DEPENDS
|
||||
|
|
|
@ -33,10 +33,8 @@
|
|||
px4_add_module(
|
||||
MODULE examples__rover_steering_control
|
||||
MAIN rover_steering_control
|
||||
STACK 1200
|
||||
COMPILE_FLAGS
|
||||
-Wframe-larger-than=1300
|
||||
|
||||
STACK_MAIN 1200
|
||||
STACK_MAX 1300
|
||||
SRCS
|
||||
main.cpp
|
||||
params.c
|
||||
|
|
|
@ -33,7 +33,7 @@
|
|||
px4_add_module(
|
||||
MODULE examples__subscriber
|
||||
MAIN subscriber
|
||||
STACK 2400
|
||||
STACK_MAIN 2400
|
||||
SRCS
|
||||
subscriber_main.cpp
|
||||
subscriber_start_nuttx.cpp
|
||||
|
|
|
@ -32,6 +32,7 @@
|
|||
############################################################################
|
||||
px4_add_module(
|
||||
MODULE lib__tailsitter_recovery
|
||||
STACK_MAIN 400
|
||||
COMPILE_FLAGS
|
||||
-Os
|
||||
SRCS
|
||||
|
|
|
@ -32,6 +32,7 @@
|
|||
############################################################################
|
||||
px4_add_module(
|
||||
MODULE lib__terrain_estimation
|
||||
STACK_MAIN 1024
|
||||
COMPILE_FLAGS
|
||||
-Os
|
||||
SRCS
|
||||
|
|
|
@ -33,7 +33,7 @@
|
|||
px4_add_module(
|
||||
MODULE modules__attitude_estimator_ekf
|
||||
MAIN attitude_estimator_ekf
|
||||
STACK 1200
|
||||
STACK_MAIN 1200
|
||||
COMPILE_FLAGS
|
||||
-Wno-float-equal
|
||||
SRCS
|
||||
|
|
|
@ -31,14 +31,12 @@
|
|||
#
|
||||
#############################################################################
|
||||
set(MODULE_CFLAGS)
|
||||
if (${OS} STREQUAL "nuttx")
|
||||
list(APPEND MODULE_CFLAGS -Wframe-larger-than=1600)
|
||||
endif()
|
||||
px4_add_module(
|
||||
MODULE modules__attitude_estimator_q
|
||||
MAIN attitude_estimator_q
|
||||
COMPILE_FLAGS ${MODULE_CFLAGS}
|
||||
STACK 1200
|
||||
STACK_MAIN 1200
|
||||
STACK_MAX 1600
|
||||
SRCS
|
||||
attitude_estimator_q_main.cpp
|
||||
DEPENDS
|
||||
|
|
|
@ -33,7 +33,7 @@
|
|||
px4_add_module(
|
||||
MODULE modules__bottle_drop
|
||||
MAIN bottle_drop
|
||||
STACK 1200
|
||||
STACK_MAIN 1200
|
||||
COMPILE_FLAGS
|
||||
-Os
|
||||
SRCS
|
||||
|
|
|
@ -30,16 +30,12 @@
|
|||
# POSSIBILITY OF SUCH DAMAGE.
|
||||
#
|
||||
############################################################################
|
||||
set(MODULE_CFLAGS -Os)
|
||||
if(${OS} STREQUAL "nuttx")
|
||||
list(APPEND MODULE_CFLAGS -Wframe-larger-than=2450)
|
||||
endif()
|
||||
px4_add_module(
|
||||
MODULE modules__commander
|
||||
MAIN commander
|
||||
STACK 4096
|
||||
STACK_MAIN 4096
|
||||
STACK_MAX 2450
|
||||
COMPILE_FLAGS
|
||||
${MODULE_CFLAGS}
|
||||
-Os
|
||||
SRCS
|
||||
commander.cpp
|
||||
|
|
|
@ -33,7 +33,7 @@
|
|||
px4_add_module(
|
||||
MODULE modules__dataman
|
||||
MAIN dataman
|
||||
STACK 1200
|
||||
STACK_MAIN 1200
|
||||
COMPILE_FLAGS
|
||||
-Os
|
||||
SRCS
|
||||
|
|
|
@ -30,15 +30,12 @@
|
|||
# POSSIBILITY OF SUCH DAMAGE.
|
||||
#
|
||||
#############################################################################
|
||||
set(MODULE_CFLAGS)
|
||||
if (${OS} STREQUAL "nuttx")
|
||||
list(APPEND MODULE_CFLAGS -Wframe-larger-than=4000)
|
||||
endif()
|
||||
px4_add_module(
|
||||
MODULE modules__ekf2
|
||||
MAIN ekf2
|
||||
COMPILE_FLAGS ${MODULE_CFLAGS}
|
||||
STACK 1000
|
||||
COMPILE_FLAGS
|
||||
STACK_MAIN 2500
|
||||
STACK_MAX 4000
|
||||
SRCS
|
||||
ekf2_main.cpp
|
||||
DEPENDS
|
||||
|
|
|
@ -30,15 +30,12 @@
|
|||
# POSSIBILITY OF SUCH DAMAGE.
|
||||
#
|
||||
#############################################################################
|
||||
set(MODULE_CFLAGS)
|
||||
if (${OS} STREQUAL "nuttx")
|
||||
list(APPEND MODULE_CFLAGS -Wframe-larger-than=4000)
|
||||
endif()
|
||||
px4_add_module(
|
||||
MODULE modules__ekf2_replay
|
||||
MAIN ekf2_replay
|
||||
COMPILE_FLAGS ${MODULE_CFLAGS}
|
||||
STACK 1000
|
||||
COMPILE_FLAGS
|
||||
STACK_MAIN 1000
|
||||
STACK_MAX 4000
|
||||
SRCS
|
||||
ekf2_replay_main.cpp
|
||||
DEPENDS
|
||||
|
|
|
@ -31,16 +31,11 @@
|
|||
#
|
||||
############################################################################
|
||||
|
||||
set(MODULE_CFLAGS )
|
||||
if(${OS} STREQUAL "nuttx")
|
||||
list(APPEND MODULE_CFLAGS -Wframe-larger-than=3400)
|
||||
endif()
|
||||
|
||||
px4_add_module(
|
||||
MODULE modules__ekf_att_pos_estimator
|
||||
MAIN ekf_att_pos_estimator
|
||||
STACK 3000
|
||||
COMPILE_FLAGS ${MODULE_CFLAGS}
|
||||
STACK_MAIN 3000
|
||||
STACK_MAX 3400
|
||||
SRCS
|
||||
ekf_att_pos_estimator_main.cpp
|
||||
estimator_22states.cpp
|
||||
|
|
|
@ -33,7 +33,7 @@
|
|||
px4_add_module(
|
||||
MODULE modules__fw_att_control
|
||||
MAIN fw_att_control
|
||||
STACK 1200
|
||||
STACK_MAIN 1200
|
||||
COMPILE_FLAGS
|
||||
-Os
|
||||
SRCS
|
||||
|
|
|
@ -33,7 +33,7 @@
|
|||
px4_add_module(
|
||||
MODULE modules__fw_pos_control_l1
|
||||
MAIN fw_pos_control_l1
|
||||
STACK 1200
|
||||
STACK_MAIN 1200
|
||||
COMPILE_FLAGS
|
||||
-Wno-float-equal
|
||||
-Os
|
||||
|
|
|
@ -33,7 +33,7 @@
|
|||
px4_add_module(
|
||||
MODULE modules__land_detector
|
||||
MAIN land_detector
|
||||
STACK 1200
|
||||
STACK_MAIN 1200
|
||||
COMPILE_FLAGS
|
||||
-Os
|
||||
SRCS
|
||||
|
|
|
@ -30,21 +30,12 @@
|
|||
# POSSIBILITY OF SUCH DAMAGE.
|
||||
#
|
||||
############################################################################
|
||||
if(${OS} STREQUAL "nuttx")
|
||||
list(APPEND MODULE_CFLAGS -Wframe-larger-than=10000)
|
||||
elseif(${OS} STREQUAL "posix")
|
||||
list(APPEND MODULE_CFLAGS -Wno-error)
|
||||
endif()
|
||||
|
||||
# use custom matrix lib instead of Eigen
|
||||
add_definitions(-DUSE_MATRIX_LIB)
|
||||
|
||||
|
||||
px4_add_module(
|
||||
MODULE modules__local_position_estimator
|
||||
MAIN local_position_estimator
|
||||
STACK 9216
|
||||
COMPILE_FLAGS ${MODULE_CFLAGS}
|
||||
COMPILE_FLAGS -Os
|
||||
STACK_MAIN 5700
|
||||
STACK_MAX 10000
|
||||
SRCS
|
||||
local_position_estimator_main.cpp
|
||||
BlockLocalPositionEstimator.cpp
|
||||
|
|
|
@ -30,15 +30,12 @@
|
|||
# POSSIBILITY OF SUCH DAMAGE.
|
||||
#
|
||||
############################################################################
|
||||
if (${OS} STREQUAL "nuttx")
|
||||
list(APPEND MODULE_CFLAGS -Wframe-larger-than=1500)
|
||||
endif()
|
||||
px4_add_module(
|
||||
MODULE modules__mavlink
|
||||
MAIN mavlink
|
||||
STACK 1200
|
||||
STACK_MAIN 1200
|
||||
STACK_MAX 1500
|
||||
COMPILE_FLAGS
|
||||
${MODULE_CFLAGS}
|
||||
-Wno-attributes
|
||||
-Wno-packed
|
||||
-DMAVLINK_COMM_NUM_BUFFERS=4
|
||||
|
|
|
@ -33,7 +33,7 @@
|
|||
px4_add_module(
|
||||
MODULE modules__mavlink__mavlink_tests
|
||||
MAIN mavlink_tests
|
||||
STACK 5000
|
||||
STACK_MAIN 5000
|
||||
COMPILE_FLAGS
|
||||
-Weffc++
|
||||
-DMAVLINK_FTP_UNIT_TEST
|
||||
|
|
|
@ -30,14 +30,12 @@
|
|||
# POSSIBILITY OF SUCH DAMAGE.
|
||||
#
|
||||
############################################################################
|
||||
if (${OS} STREQUAL "nuttx")
|
||||
list(APPEND MODULE_CFLAGS -Wframe-larger-than=3500)
|
||||
endif()
|
||||
px4_add_module(
|
||||
MODULE modules__mc_att_control
|
||||
MAIN mc_att_control
|
||||
STACK 1200
|
||||
COMPILE_FLAGS ${MODULE_CFLAGS}
|
||||
STACK_MAIN 1200
|
||||
STACK_MAX 3500
|
||||
COMPILE_FLAGS
|
||||
SRCS
|
||||
mc_att_control_main.cpp
|
||||
DEPENDS
|
||||
|
|
|
@ -33,7 +33,7 @@
|
|||
px4_add_module(
|
||||
MODULE modules__mc_pos_control
|
||||
MAIN mc_pos_control
|
||||
STACK 1200
|
||||
STACK_MAIN 1200
|
||||
SRCS
|
||||
mc_pos_control_main.cpp
|
||||
DEPENDS
|
||||
|
|
|
@ -33,7 +33,7 @@
|
|||
px4_add_module(
|
||||
MODULE modules__navigator
|
||||
MAIN navigator
|
||||
STACK 1200
|
||||
STACK_MAIN 1200
|
||||
COMPILE_FLAGS
|
||||
-Wno-sign-compare
|
||||
-Os
|
||||
|
|
|
@ -31,16 +31,12 @@
|
|||
#
|
||||
############################################################################
|
||||
|
||||
set(MODULE_CFLAGS )
|
||||
if(${OS} STREQUAL "nuttx")
|
||||
list(APPEND MODULE_CFLAGS -Wframe-larger-than=4000)
|
||||
endif()
|
||||
|
||||
px4_add_module(
|
||||
MODULE modules__position_estimator_inav
|
||||
MAIN position_estimator_inav
|
||||
STACK 1200
|
||||
COMPILE_FLAGS ${MODULE_CFLAGS}
|
||||
STACK_MAIN 1200
|
||||
STACK_MAX 4000
|
||||
COMPILE_FLAGS
|
||||
SRCS
|
||||
position_estimator_inav_main.cpp
|
||||
position_estimator_inav_params.cpp
|
||||
|
|
|
@ -30,14 +30,12 @@
|
|||
# POSSIBILITY OF SUCH DAMAGE.
|
||||
#
|
||||
############################################################################
|
||||
if (${OS} STREQUAL "nuttx")
|
||||
list(APPEND MODULE_CFLAGS -Wframe-larger-than=1600)
|
||||
endif()
|
||||
px4_add_module(
|
||||
MODULE modules__sdlog2
|
||||
MAIN sdlog2
|
||||
PRIORITY "SCHED_PRIORITY_MAX-30"
|
||||
STACK 1200
|
||||
STACK_MAIN 1200
|
||||
STACK_MAX 1600
|
||||
COMPILE_FLAGS
|
||||
${MODULE_CFLAGS}
|
||||
-Os
|
||||
|
|
|
@ -43,7 +43,7 @@ px4_add_module(
|
|||
MODULE modules__sensors
|
||||
MAIN sensors
|
||||
PRIORITY "SCHED_PRIORITY_MAX-5"
|
||||
STACK 1200
|
||||
STACK_MAIN 1200
|
||||
COMPILE_FLAGS
|
||||
-Wno-type-limits
|
||||
-O3
|
||||
|
|
|
@ -73,7 +73,7 @@ endif()
|
|||
px4_add_module(
|
||||
MODULE modules__uORB
|
||||
MAIN uorb
|
||||
STACK 2048
|
||||
STACK_MAIN 2048
|
||||
COMPILE_FLAGS
|
||||
-Os
|
||||
SRCS ${SRCS}
|
||||
|
|
|
@ -56,9 +56,9 @@ include_directories(libuavcan/libuavcan_drivers/stm32/driver/include)
|
|||
px4_add_module(
|
||||
MODULE modules__uavcan
|
||||
MAIN uavcan
|
||||
STACK 3200
|
||||
STACK_MAIN 3200
|
||||
STACK_MAX 1500
|
||||
COMPILE_FLAGS
|
||||
-Wframe-larger-than=1500
|
||||
-Wno-deprecated-declarations
|
||||
-Os
|
||||
SRCS
|
||||
|
|
|
@ -33,7 +33,7 @@
|
|||
px4_add_module(
|
||||
MODULE platforms__posix__drivers__gyrosim
|
||||
MAIN gyrosim
|
||||
STACK 1200
|
||||
STACK_MAIN 1200
|
||||
COMPILE_FLAGS
|
||||
-Os
|
||||
SRCS
|
||||
|
|
|
@ -33,7 +33,7 @@
|
|||
px4_add_module(
|
||||
MODULE systemcmds__bl_update
|
||||
MAIN bl_update
|
||||
STACK 4096
|
||||
STACK_MAIN 4096
|
||||
COMPILE_FLAGS
|
||||
-Os
|
||||
SRCS
|
||||
|
|
|
@ -33,7 +33,7 @@
|
|||
px4_add_module(
|
||||
MODULE systemcmds__config
|
||||
MAIN config
|
||||
STACK 4096
|
||||
STACK_MAIN 4096
|
||||
COMPILE_FLAGS
|
||||
-Os
|
||||
SRCS
|
||||
|
|
|
@ -33,7 +33,7 @@
|
|||
px4_add_module(
|
||||
MODULE systemcmds__esc_calib
|
||||
MAIN esc_calib
|
||||
STACK 4096
|
||||
STACK_MAIN 4096
|
||||
COMPILE_FLAGS
|
||||
-Os
|
||||
SRCS
|
||||
|
|
|
@ -31,14 +31,12 @@
|
|||
#
|
||||
############################################################################
|
||||
set(MIXER_CFLAGS -Os)
|
||||
if(${OS} STREQUAL "nuttx")
|
||||
list(APPEND MIXER_CFLAGS -Wframe-larger-than=2100)
|
||||
endif()
|
||||
|
||||
px4_add_module(
|
||||
MODULE systemcmds__mixer
|
||||
MAIN mixer
|
||||
STACK 4096
|
||||
STACK_MAIN 4096
|
||||
STACK_MAX 2100
|
||||
COMPILE_FLAGS ${MIXER_CFLAGS}
|
||||
SRCS
|
||||
mixer.cpp
|
||||
|
|
|
@ -33,7 +33,7 @@
|
|||
px4_add_module(
|
||||
MODULE systemcmds__motor_test
|
||||
MAIN motor_test
|
||||
STACK 4096
|
||||
STACK_MAIN 4096
|
||||
COMPILE_FLAGS
|
||||
-Os
|
||||
SRCS
|
||||
|
|
|
@ -34,7 +34,7 @@ px4_add_module(
|
|||
MODULE systemcmds__nshterm
|
||||
MAIN nshterm
|
||||
PRIORITY "SCHED_PRIORITY_DEFAULT-30"
|
||||
STACK 1500
|
||||
STACK_MAIN 1500
|
||||
COMPILE_FLAGS
|
||||
-Os
|
||||
SRCS
|
||||
|
|
|
@ -33,7 +33,7 @@
|
|||
px4_add_module(
|
||||
MODULE systemcmds__param
|
||||
MAIN param
|
||||
STACK 2500
|
||||
STACK_MAIN 2500
|
||||
COMPILE_FLAGS
|
||||
-Os
|
||||
SRCS
|
||||
|
|
|
@ -33,7 +33,7 @@
|
|||
px4_add_module(
|
||||
MODULE systemcmds__perf
|
||||
MAIN perf
|
||||
STACK 1800
|
||||
STACK_MAIN 1800
|
||||
COMPILE_FLAGS
|
||||
-Os
|
||||
SRCS
|
||||
|
|
|
@ -33,7 +33,7 @@
|
|||
px4_add_module(
|
||||
MODULE systemcmds__pwm
|
||||
MAIN pwm
|
||||
STACK 2400
|
||||
STACK_MAIN 2400
|
||||
COMPILE_FLAGS
|
||||
-Os
|
||||
SRCS
|
||||
|
|
|
@ -33,7 +33,7 @@
|
|||
px4_add_module(
|
||||
MODULE systemcmds__reboot
|
||||
MAIN reboot
|
||||
STACK 800
|
||||
STACK_MAIN 800
|
||||
COMPILE_FLAGS
|
||||
-Os
|
||||
SRCS
|
||||
|
|
|
@ -69,7 +69,7 @@ endif()
|
|||
px4_add_module(
|
||||
MODULE systemcmds__tests
|
||||
MAIN tests
|
||||
STACK 8000
|
||||
STACK_MAIN 8000
|
||||
COMPILE_FLAGS
|
||||
-Wframe-larger-than=6000
|
||||
-Wno-float-equal
|
||||
|
|
|
@ -33,7 +33,7 @@
|
|||
px4_add_module(
|
||||
MODULE systemcmds__top
|
||||
MAIN top
|
||||
STACK 1700
|
||||
STACK_MAIN 1700
|
||||
COMPILE_FLAGS
|
||||
-Os
|
||||
SRCS
|
||||
|
|
|
@ -43,7 +43,7 @@ add_custom_target(generate_topic_listener
|
|||
px4_add_module(
|
||||
MODULE systemcmds__topic_listener
|
||||
MAIN listener
|
||||
STACK 1800
|
||||
STACK_MAIN 1800
|
||||
COMPILE_FLAGS
|
||||
-Os
|
||||
SRCS
|
||||
|
|
|
@ -33,7 +33,7 @@
|
|||
px4_add_module(
|
||||
MODULE systemcmds__ver
|
||||
MAIN ver
|
||||
STACK 1024
|
||||
STACK_MAIN 1024
|
||||
COMPILE_FLAGS
|
||||
-Os
|
||||
SRCS
|
||||
|
|
Loading…
Reference in New Issue