forked from Archive/PX4-Autopilot
STACK_MAIN increase default 1024 -> 2048
This commit is contained in:
parent
9ed2daef48
commit
78ef8aab2d
|
@ -36,7 +36,6 @@ px4_add_module(
|
|||
MAIN syslink
|
||||
COMPILE_FLAGS
|
||||
-Wno-cast-align # TODO: fix and enable
|
||||
STACK_MAIN 1300
|
||||
SRCS
|
||||
syslink_main.cpp
|
||||
syslink_bridge.cpp
|
||||
|
|
|
@ -33,7 +33,6 @@
|
|||
px4_add_module(
|
||||
MODULE drivers__navio_sysfs_rc_in
|
||||
MAIN navio_sysfs_rc_in
|
||||
STACK_MAIN 1200
|
||||
COMPILE_FLAGS
|
||||
SRCS
|
||||
navio_sysfs_rc_in.cpp
|
||||
|
|
|
@ -42,7 +42,6 @@ include(px4_base)
|
|||
# Usage:
|
||||
# px4_add_module(MODULE <string>
|
||||
# MAIN <string>
|
||||
# [ STACK <string> ] !!!!!DEPRECATED, USE STACK_MAIN INSTEAD!!!!!!!!!
|
||||
# [ STACK_MAIN <string> ]
|
||||
# [ STACK_MAX <string> ]
|
||||
# [ COMPILE_FLAGS <list> ]
|
||||
|
@ -87,7 +86,7 @@ function(px4_add_module)
|
|||
|
||||
px4_parse_function_args(
|
||||
NAME px4_add_module
|
||||
ONE_VALUE MODULE MAIN STACK STACK_MAIN STACK_MAX PRIORITY
|
||||
ONE_VALUE MODULE MAIN STACK_MAIN STACK_MAX PRIORITY
|
||||
MULTI_VALUE COMPILE_FLAGS LINK_FLAGS SRCS INCLUDES DEPENDS MODULE_CONFIG
|
||||
OPTIONS EXTERNAL DYNAMIC UNITY_BUILD
|
||||
REQUIRED MODULE MAIN
|
||||
|
@ -166,7 +165,7 @@ function(px4_add_module)
|
|||
|
||||
# set defaults if not set
|
||||
set(MAIN_DEFAULT MAIN-NOTFOUND)
|
||||
set(STACK_MAIN_DEFAULT 1024)
|
||||
set(STACK_MAIN_DEFAULT 2048)
|
||||
set(PRIORITY_DEFAULT SCHED_PRIORITY_DEFAULT)
|
||||
|
||||
foreach(property MAIN STACK_MAIN PRIORITY)
|
||||
|
|
|
@ -35,9 +35,7 @@ px4_add_module(
|
|||
MODULE drivers__bmp280
|
||||
MAIN bmp280
|
||||
COMPILE_FLAGS
|
||||
-Wno-cast-align # TODO: fix and enable
|
||||
STACK_MAIN
|
||||
1200
|
||||
-Wno-cast-align # TODO: fix and enable
|
||||
SRCS
|
||||
bmp280_spi.cpp
|
||||
bmp280_i2c.cpp
|
||||
|
|
|
@ -33,7 +33,6 @@
|
|||
px4_add_module(
|
||||
MODULE drivers__lps25h
|
||||
MAIN lps25h
|
||||
STACK_MAIN 1200
|
||||
COMPILE_FLAGS
|
||||
-Wno-cast-align # TODO: fix and enable
|
||||
SRCS
|
||||
|
|
|
@ -33,7 +33,6 @@
|
|||
px4_add_module(
|
||||
MODULE drivers__mpl3115a2
|
||||
MAIN mpl3115a2
|
||||
STACK_MAIN 1200
|
||||
COMPILE_FLAGS
|
||||
-Wno-cast-align # TODO: fix and enable
|
||||
SRCS
|
||||
|
|
|
@ -34,7 +34,6 @@
|
|||
px4_add_module(
|
||||
MODULE drivers__ms5611
|
||||
MAIN ms5611
|
||||
STACK_MAIN 1500
|
||||
COMPILE_FLAGS
|
||||
-Wno-cast-align # TODO: fix and enable
|
||||
SRCS
|
||||
|
|
|
@ -33,7 +33,6 @@
|
|||
px4_add_module(
|
||||
MODULE drivers__batt_smbus
|
||||
MAIN batt_smbus
|
||||
STACK_MAIN 1100
|
||||
COMPILE_FLAGS
|
||||
SRCS
|
||||
batt_smbus.cpp
|
||||
|
|
|
@ -33,7 +33,6 @@
|
|||
px4_add_module(
|
||||
MODULE drivers__camera_trigger
|
||||
MAIN camera_trigger
|
||||
STACK_MAIN 1200
|
||||
COMPILE_FLAGS
|
||||
SRCS
|
||||
camera_trigger.cpp
|
||||
|
|
|
@ -33,7 +33,6 @@
|
|||
px4_add_module(
|
||||
MODULE drivers__ets_airspeed
|
||||
MAIN ets_airspeed
|
||||
STACK_MAIN 1200
|
||||
COMPILE_FLAGS
|
||||
SRCS
|
||||
ets_airspeed.cpp
|
||||
|
|
|
@ -33,7 +33,6 @@
|
|||
px4_add_module(
|
||||
MODULE drivers__ms4525_airspeed
|
||||
MAIN ms4525_airspeed
|
||||
STACK_MAIN 1200
|
||||
COMPILE_FLAGS
|
||||
SRCS
|
||||
ms4525_airspeed.cpp
|
||||
|
|
|
@ -33,7 +33,6 @@
|
|||
px4_add_module(
|
||||
MODULE drivers__ms5525_airspeed
|
||||
MAIN ms5525_airspeed
|
||||
STACK_MAIN 1200
|
||||
COMPILE_FLAGS
|
||||
SRCS
|
||||
MS5525.cpp
|
||||
|
|
|
@ -33,7 +33,6 @@
|
|||
px4_add_module(
|
||||
MODULE drivers__sdp3x_airspeed
|
||||
MAIN sdp3x_airspeed
|
||||
STACK_MAIN 1200
|
||||
COMPILE_FLAGS
|
||||
SRCS
|
||||
SDP3X.cpp
|
||||
|
|
|
@ -33,7 +33,6 @@
|
|||
px4_add_module(
|
||||
MODULE drivers__cm8jl65
|
||||
MAIN cm8jl65
|
||||
STACK_MAIN 1200
|
||||
SRCS
|
||||
cm8jl65.cpp
|
||||
MODULE_CONFIG
|
||||
|
|
|
@ -34,9 +34,8 @@
|
|||
px4_add_module(
|
||||
MODULE drivers__hc_sr04
|
||||
MAIN hc_sr04
|
||||
STACK_MAIN 1200
|
||||
COMPILE_FLAGS
|
||||
SRCS
|
||||
hc_sr04.cpp
|
||||
DEPENDS
|
||||
)
|
||||
)
|
||||
|
|
|
@ -33,7 +33,6 @@
|
|||
px4_add_module(
|
||||
MODULE drivers__leddar_one
|
||||
MAIN leddar_one
|
||||
STACK_MAIN 1200
|
||||
COMPILE_FLAGS
|
||||
-Wno-cast-align # TODO: fix and enable
|
||||
SRCS
|
||||
|
|
|
@ -35,8 +35,6 @@ px4_add_module(
|
|||
MAIN ll40ls
|
||||
COMPILE_FLAGS
|
||||
-Wno-cast-align # TODO: fix and enable
|
||||
STACK_MAIN
|
||||
1500
|
||||
SRCS
|
||||
ll40ls.cpp
|
||||
LidarLite.cpp
|
||||
|
|
|
@ -33,7 +33,6 @@
|
|||
px4_add_module(
|
||||
MODULE drivers__mappydot
|
||||
MAIN mappydot
|
||||
STACK_MAIN 1200
|
||||
SRCS
|
||||
MappyDot.cpp
|
||||
)
|
||||
|
|
|
@ -33,7 +33,6 @@
|
|||
px4_add_module(
|
||||
MODULE drivers__mb12xx
|
||||
MAIN mb12xx
|
||||
STACK_MAIN 1400
|
||||
COMPILE_FLAGS
|
||||
-Wno-cast-align # TODO: fix and enable
|
||||
SRCS
|
||||
|
|
|
@ -33,7 +33,6 @@
|
|||
px4_add_module(
|
||||
MODULE drivers__srf02
|
||||
MAIN srf02
|
||||
STACK_MAIN 1500
|
||||
COMPILE_FLAGS
|
||||
-Wno-cast-align # TODO: fix and enable
|
||||
SRCS
|
||||
|
|
|
@ -33,7 +33,6 @@
|
|||
px4_add_module(
|
||||
MODULE drivers__teraranger
|
||||
MAIN teraranger
|
||||
STACK_MAIN 1200
|
||||
COMPILE_FLAGS
|
||||
-Wno-cast-align # TODO: fix and enable
|
||||
SRCS
|
||||
|
|
|
@ -36,7 +36,6 @@ px4_add_git_submodule(TARGET git_gps_devices PATH "devices")
|
|||
px4_add_module(
|
||||
MODULE drivers__gps
|
||||
MAIN gps
|
||||
STACK_MAIN 1200
|
||||
COMPILE_FLAGS
|
||||
-Wno-cast-align # TODO: fix and enable
|
||||
SRCS
|
||||
|
|
|
@ -33,7 +33,6 @@
|
|||
px4_add_module(
|
||||
MODULE drivers__heater
|
||||
MAIN heater
|
||||
STACK_MAIN 1024
|
||||
COMPILE_FLAGS
|
||||
SRCS
|
||||
heater.cpp
|
||||
|
|
|
@ -33,7 +33,6 @@
|
|||
px4_add_module(
|
||||
MODULE drivers__imu__adis16448
|
||||
MAIN adis16448
|
||||
STACK_MAIN 1400
|
||||
COMPILE_FLAGS
|
||||
-Wno-cast-align # TODO: fix and enable
|
||||
SRCS
|
||||
|
|
|
@ -33,7 +33,6 @@
|
|||
px4_add_module(
|
||||
MODULE drivers__imu__adis16477
|
||||
MAIN adis16477
|
||||
STACK_MAIN 1200
|
||||
COMPILE_FLAGS
|
||||
-Wno-cast-align # TODO: fix and enable
|
||||
SRCS
|
||||
|
|
|
@ -33,7 +33,6 @@
|
|||
px4_add_module(
|
||||
MODULE drivers__imu__adis16497
|
||||
MAIN adis16497
|
||||
STACK_MAIN 1200
|
||||
COMPILE_FLAGS
|
||||
-Wno-cast-align # TODO: fix and enable
|
||||
SRCS
|
||||
|
|
|
@ -33,10 +33,9 @@
|
|||
px4_add_module(
|
||||
MODULE drivers__bmi055
|
||||
MAIN bmi055
|
||||
STACK_MAIN 1500
|
||||
COMPILE_FLAGS
|
||||
-Wno-cast-align # TODO: fix and enable
|
||||
SRCS
|
||||
SRCS
|
||||
BMI055_accel.cpp
|
||||
BMI055_gyro.cpp
|
||||
bmi055_main.cpp
|
||||
|
|
|
@ -33,7 +33,6 @@
|
|||
px4_add_module(
|
||||
MODULE drivers__bmi88
|
||||
MAIN bmi088
|
||||
STACK_MAIN 1500
|
||||
COMPILE_FLAGS
|
||||
-Wno-cast-align # TODO: fix and enable
|
||||
SRCS
|
||||
|
|
|
@ -33,7 +33,6 @@
|
|||
px4_add_module(
|
||||
MODULE drivers__bmi160
|
||||
MAIN bmi160
|
||||
STACK_MAIN 1200
|
||||
COMPILE_FLAGS
|
||||
-Wno-cast-align # TODO: fix and enable
|
||||
SRCS
|
||||
|
|
|
@ -33,7 +33,6 @@
|
|||
px4_add_module(
|
||||
MODULE drivers__fxas21002c
|
||||
MAIN fxas21002c
|
||||
STACK_MAIN 1500
|
||||
COMPILE_FLAGS
|
||||
-Wno-cast-align # TODO: fix and enable
|
||||
SRCS
|
||||
|
|
|
@ -33,7 +33,6 @@
|
|||
px4_add_module(
|
||||
MODULE drivers__fxos8701cq
|
||||
MAIN fxos8701cq
|
||||
STACK_MAIN 1500
|
||||
COMPILE_FLAGS
|
||||
-Wno-cast-align # TODO: fix and enable
|
||||
SRCS
|
||||
|
|
|
@ -33,7 +33,6 @@
|
|||
px4_add_module(
|
||||
MODULE drivers__icm20948
|
||||
MAIN icm20948
|
||||
STACK_MAIN 1500
|
||||
COMPILE_FLAGS
|
||||
SRCS
|
||||
icm20948.cpp
|
||||
|
|
|
@ -33,7 +33,6 @@
|
|||
px4_add_module(
|
||||
MODULE drivers__l3gd20
|
||||
MAIN l3gd20
|
||||
STACK_MAIN 1500
|
||||
COMPILE_FLAGS
|
||||
-Wno-cast-align # TODO: fix and enable
|
||||
SRCS
|
||||
|
|
|
@ -33,7 +33,6 @@
|
|||
px4_add_module(
|
||||
MODULE drivers__lsm303d
|
||||
MAIN lsm303d
|
||||
STACK_MAIN 1500
|
||||
COMPILE_FLAGS
|
||||
-Wno-cast-align # TODO: fix and enable
|
||||
SRCS
|
||||
|
|
|
@ -33,7 +33,6 @@
|
|||
px4_add_module(
|
||||
MODULE drivers__mpu6000
|
||||
MAIN mpu6000
|
||||
STACK_MAIN 1500
|
||||
SRCS
|
||||
MPU6000.cpp
|
||||
MPU6000_I2C.cpp
|
||||
|
|
|
@ -33,7 +33,6 @@
|
|||
px4_add_module(
|
||||
MODULE drivers__mpu9250
|
||||
MAIN mpu9250
|
||||
STACK_MAIN 1500
|
||||
COMPILE_FLAGS
|
||||
SRCS
|
||||
AK8963_I2C.cpp
|
||||
|
|
|
@ -33,7 +33,6 @@
|
|||
px4_add_module(
|
||||
MODULE drivers__oreoled
|
||||
MAIN oreoled
|
||||
STACK_MAIN 1024
|
||||
COMPILE_FLAGS
|
||||
SRCS
|
||||
oreoled.cpp
|
||||
|
|
|
@ -34,8 +34,6 @@
|
|||
px4_add_module(
|
||||
MODULE drivers__rgbled
|
||||
MAIN rgbled
|
||||
STACK_MAIN
|
||||
1500
|
||||
SRCS
|
||||
rgbled.cpp
|
||||
DEPENDS
|
||||
|
|
|
@ -34,8 +34,6 @@
|
|||
px4_add_module(
|
||||
MODULE drivers__rgbled_ncp5623c
|
||||
MAIN rgbled_ncp5623c
|
||||
STACK_MAIN
|
||||
1500
|
||||
SRCS
|
||||
rgbled_ncp5623c.cpp
|
||||
DEPENDS
|
||||
|
|
|
@ -34,8 +34,6 @@
|
|||
px4_add_module(
|
||||
MODULE drivers__rgbled_pwm
|
||||
MAIN rgbled_pwm
|
||||
STACK_MAIN
|
||||
1500
|
||||
SRCS
|
||||
rgbled_pwm.cpp
|
||||
DEPENDS
|
||||
|
|
|
@ -33,7 +33,6 @@
|
|||
px4_add_module(
|
||||
MODULE drivers__ak09916
|
||||
MAIN ak09916
|
||||
STACK_MAIN 1200
|
||||
COMPILE_FLAGS
|
||||
-Wno-cast-align # TODO: fix and enable
|
||||
SRCS
|
||||
|
|
|
@ -33,7 +33,6 @@
|
|||
px4_add_module(
|
||||
MODULE drivers__bmm150
|
||||
MAIN bmm150
|
||||
STACK_MAIN 1200
|
||||
COMPILE_FLAGS
|
||||
-Wno-cast-align # TODO: fix and enable
|
||||
SRCS
|
||||
|
|
|
@ -33,7 +33,6 @@
|
|||
px4_add_module(
|
||||
MODULE drivers__hmc5883
|
||||
MAIN hmc5883
|
||||
STACK_MAIN 1500
|
||||
COMPILE_FLAGS
|
||||
-Wno-cast-align # TODO: fix and enable
|
||||
SRCS
|
||||
|
|
|
@ -35,7 +35,6 @@ px4_add_module(
|
|||
MAIN ist8310
|
||||
COMPILE_FLAGS
|
||||
-Wno-cast-align # TODO: fix and enable
|
||||
STACK_MAIN 1500
|
||||
SRCS
|
||||
ist8310.cpp
|
||||
DEPENDS
|
||||
|
|
|
@ -33,7 +33,6 @@
|
|||
px4_add_module(
|
||||
MODULE drivers__lis3mdl
|
||||
MAIN lis3mdl
|
||||
STACK_MAIN 1500
|
||||
COMPILE_FLAGS
|
||||
-Wno-cast-align # TODO: fix and enable
|
||||
SRCS
|
||||
|
|
|
@ -33,7 +33,6 @@
|
|||
px4_add_module(
|
||||
MODULE drivers__qmc5883
|
||||
MAIN qmc5883
|
||||
STACK_MAIN 1500
|
||||
COMPILE_FLAGS
|
||||
-Wno-cast-align # TODO: fix and enable
|
||||
SRCS
|
||||
|
|
|
@ -33,7 +33,6 @@
|
|||
px4_add_module(
|
||||
MODULE drivers__rm3100
|
||||
MAIN rm3100
|
||||
STACK_MAIN 1200
|
||||
COMPILE_FLAGS
|
||||
-Wno-cast-align # TODO: fix and enable
|
||||
SRCS
|
||||
|
|
|
@ -34,7 +34,6 @@
|
|||
px4_add_module(
|
||||
MODULE drivers__optical_flow__paw3902
|
||||
MAIN paw3902
|
||||
STACK_MAIN 1500
|
||||
SRCS
|
||||
paw3902_main.cpp
|
||||
PAW3902.cpp
|
||||
|
|
|
@ -36,7 +36,6 @@ px4_add_module(
|
|||
MAIN pmw3901
|
||||
COMPILE_FLAGS
|
||||
-Wno-cast-align # TODO: fix and enable
|
||||
STACK_MAIN 1400
|
||||
SRCS
|
||||
pmw3901.cpp
|
||||
)
|
||||
|
|
|
@ -33,7 +33,6 @@
|
|||
px4_add_module(
|
||||
MODULE drivers__px4flow
|
||||
MAIN px4flow
|
||||
STACK_MAIN 1500
|
||||
COMPILE_FLAGS
|
||||
-Wno-cast-align # TODO: fix and enable
|
||||
SRCS
|
||||
|
|
|
@ -33,7 +33,6 @@
|
|||
px4_add_module(
|
||||
MODULE drivers__protocol_splitter
|
||||
MAIN protocol_splitter
|
||||
STACK_MAIN 1200
|
||||
SRCS
|
||||
protocol_splitter.cpp
|
||||
DEPENDS
|
||||
|
|
|
@ -33,7 +33,6 @@
|
|||
px4_add_module(
|
||||
MODULE drivers__pwm_input
|
||||
MAIN pwm_input
|
||||
STACK_MAIN 1024
|
||||
COMPILE_FLAGS
|
||||
-Wno-pmf-conversions
|
||||
-Wno-cast-align # TODO: fix and enable
|
||||
|
|
|
@ -33,7 +33,6 @@
|
|||
px4_add_module(
|
||||
MODULE drivers__px4fmu
|
||||
MAIN fmu
|
||||
STACK_MAIN 1200
|
||||
COMPILE_FLAGS
|
||||
SRCS
|
||||
fmu.cpp
|
||||
|
|
|
@ -33,7 +33,6 @@
|
|||
px4_add_module(
|
||||
MODULE drivers__px4io
|
||||
MAIN px4io
|
||||
STACK_MAIN 1816
|
||||
COMPILE_FLAGS
|
||||
-Wno-cast-align # TODO: fix and enable
|
||||
SRCS
|
||||
|
|
|
@ -47,7 +47,6 @@ set_target_properties(mpu9x50 PROPERTIES IMPORTED_LOCATION ${FC_ADDON}/flight_co
|
|||
px4_add_module(
|
||||
MODULE platforms__qurt__fc_addon__mpu_spi
|
||||
MAIN mpu9x50
|
||||
STACK_MAIN 1200
|
||||
INCLUDES
|
||||
${FC_ADDON}/flight_controller/hexagon/inc
|
||||
SRCS
|
||||
|
|
|
@ -47,7 +47,6 @@ set_target_properties(rc_receiver PROPERTIES IMPORTED_LOCATION ${FC_ADDON}/fligh
|
|||
px4_add_module(
|
||||
MODULE platforms__qurt__fc_addon__rc_receiver
|
||||
MAIN rc_receiver
|
||||
STACK_MAIN 1200
|
||||
INCLUDES
|
||||
${FC_ADDON}/flight_controller/hexagon/inc
|
||||
SRCS
|
||||
|
|
|
@ -47,7 +47,6 @@ set_target_properties(uart_esc PROPERTIES IMPORTED_LOCATION ${FC_ADDON}/flight_c
|
|||
px4_add_module(
|
||||
MODULE platforms__qurt__fc_addon__uart_esc
|
||||
MAIN uart_esc
|
||||
STACK_MAIN 1200
|
||||
INCLUDES
|
||||
${FC_ADDON}/flight_controller/hexagon/inc
|
||||
SRCS
|
||||
|
|
|
@ -33,7 +33,6 @@
|
|||
px4_add_module(
|
||||
MODULE drivers__rc_input
|
||||
MAIN rc_input
|
||||
STACK_MAIN 1200
|
||||
COMPILE_FLAGS
|
||||
SRCS
|
||||
RCInput.cpp
|
||||
|
|
|
@ -33,7 +33,6 @@
|
|||
px4_add_module(
|
||||
MODULE drivers__rpi_rc_in
|
||||
MAIN rpi_rc_in
|
||||
STACK_MAIN 1200
|
||||
COMPILE_FLAGS
|
||||
SRCS
|
||||
rpi_rc_in.cpp
|
||||
|
|
|
@ -34,8 +34,6 @@
|
|||
px4_add_module(
|
||||
MODULE drivers__safety_button
|
||||
MAIN safety_button
|
||||
STACK_MAIN
|
||||
1500
|
||||
SRCS
|
||||
SafetyButton.cpp
|
||||
DEPENDS
|
||||
|
|
|
@ -33,7 +33,6 @@
|
|||
px4_add_module(
|
||||
MODULE drivers__bst
|
||||
MAIN bst
|
||||
STACK_MAIN 1200
|
||||
COMPILE_FLAGS
|
||||
SRCS
|
||||
bst.cpp
|
||||
|
|
|
@ -33,7 +33,6 @@
|
|||
px4_add_module(
|
||||
MODULE drivers__frsky_telemetry
|
||||
MAIN frsky_telemetry
|
||||
STACK_MAIN 1500
|
||||
COMPILE_FLAGS
|
||||
SRCS
|
||||
frsky_data.cpp
|
||||
|
|
|
@ -34,7 +34,6 @@ px4_add_module(
|
|||
MODULE drivers__iridiumsbd
|
||||
MAIN iridiumsbd
|
||||
STACK 1024
|
||||
STACK_MAIN 1024
|
||||
COMPILE_FLAGS
|
||||
SRCS
|
||||
IridiumSBD.cpp
|
||||
|
|
|
@ -33,7 +33,6 @@
|
|||
px4_add_module(
|
||||
MODULE drivers__test_ppm
|
||||
MAIN test_ppm
|
||||
STACK_MAIN 1200
|
||||
COMPILE_FLAGS
|
||||
SRCS
|
||||
test_ppm.cpp
|
||||
|
|
|
@ -92,8 +92,6 @@ add_custom_target(px4_uavcan_dsdlc DEPENDS px4_uavcan_dsdlc_run.stamp)
|
|||
px4_add_module(
|
||||
MODULE modules__uavcan
|
||||
MAIN uavcan
|
||||
STACK_MAIN 3200
|
||||
STACK_MAX 1500
|
||||
INCLUDES
|
||||
${DSDLC_OUTPUT}
|
||||
${PX4_SOURCE_DIR}/mavlink/include/mavlink
|
||||
|
|
|
@ -33,7 +33,6 @@
|
|||
px4_add_module(
|
||||
MODULE modules__bottle_drop
|
||||
MAIN bottle_drop
|
||||
STACK_MAIN 1200
|
||||
COMPILE_FLAGS
|
||||
SRCS
|
||||
bottle_drop.cpp
|
||||
|
|
|
@ -33,7 +33,6 @@
|
|||
px4_add_module(
|
||||
MODULE examples__fixedwing_control
|
||||
MAIN ex_fixedwing_control
|
||||
STACK_MAIN 1200
|
||||
STACK_MAX 1300
|
||||
SRCS
|
||||
main.cpp
|
||||
|
|
|
@ -33,7 +33,6 @@
|
|||
px4_add_module(
|
||||
MODULE examples__hwtest
|
||||
MAIN ex_hwtest
|
||||
STACK_MAIN 2000
|
||||
SRCS
|
||||
hwtest.c
|
||||
DEPENDS
|
||||
|
|
|
@ -33,7 +33,6 @@
|
|||
px4_add_module(
|
||||
MODULE examples__matlab_csv_serial
|
||||
MAIN matlab_csv_serial
|
||||
STACK_MAIN 2000
|
||||
SRCS
|
||||
matlab_csv_serial.c
|
||||
DEPENDS
|
||||
|
|
|
@ -33,7 +33,6 @@
|
|||
px4_add_module(
|
||||
MODULE examples__px4_mavlink_debug
|
||||
MAIN px4_mavlink_debug
|
||||
STACK_MAIN 2000
|
||||
SRCS
|
||||
px4_mavlink_debug.cpp
|
||||
DEPENDS
|
||||
|
|
|
@ -33,7 +33,6 @@
|
|||
px4_add_module(
|
||||
MODULE examples__px4_simple_app
|
||||
MAIN px4_simple_app
|
||||
STACK_MAIN 2000
|
||||
SRCS
|
||||
px4_simple_app.c
|
||||
DEPENDS
|
||||
|
|
|
@ -33,7 +33,6 @@
|
|||
px4_add_module(
|
||||
MODULE examples__rover_steering_control
|
||||
MAIN rover_steering_control
|
||||
STACK_MAIN 1200
|
||||
STACK_MAX 1300
|
||||
SRCS
|
||||
main.cpp
|
||||
|
|
|
@ -33,8 +33,6 @@
|
|||
px4_add_module(
|
||||
MODULE examples__segway
|
||||
MAIN segway
|
||||
STACK_MAIN 1400
|
||||
STACK_MAX 1400
|
||||
SRCS
|
||||
blocks.cpp
|
||||
segway_main.cpp
|
||||
|
|
|
@ -33,7 +33,6 @@
|
|||
px4_add_module(
|
||||
MODULE examples__uuv_example_app
|
||||
MAIN uuv_example_app
|
||||
STACK_MAIN 2000
|
||||
SRCS
|
||||
uuv_example_app.cpp
|
||||
DEPENDS
|
||||
|
|
|
@ -35,7 +35,6 @@ px4_add_module(
|
|||
MODULE modules__attitude_estimator_q
|
||||
MAIN attitude_estimator_q
|
||||
COMPILE_FLAGS
|
||||
STACK_MAIN 1200
|
||||
STACK_MAX 1600
|
||||
SRCS
|
||||
attitude_estimator_q_main.cpp
|
||||
|
|
|
@ -36,8 +36,6 @@ add_subdirectory(failure_detector)
|
|||
px4_add_module(
|
||||
MODULE modules__commander
|
||||
MAIN commander
|
||||
STACK_MAIN 4096
|
||||
STACK_MAX 2450
|
||||
COMPILE_FLAGS
|
||||
SRCS
|
||||
accelerometer_calibration.cpp
|
||||
|
|
|
@ -33,7 +33,6 @@
|
|||
px4_add_module(
|
||||
MODULE modules__dataman
|
||||
MAIN dataman
|
||||
STACK_MAIN 1200
|
||||
COMPILE_FLAGS
|
||||
-Wno-cast-align # TODO: fix and enable
|
||||
SRCS
|
||||
|
|
|
@ -34,8 +34,7 @@ px4_add_module(
|
|||
MODULE modules__ekf2
|
||||
MAIN ekf2
|
||||
COMPILE_FLAGS
|
||||
STACK_MAIN 2500
|
||||
STACK_MAX 4000
|
||||
STACK_MAX 2400
|
||||
SRCS
|
||||
ekf2_main.cpp
|
||||
DEPENDS
|
||||
|
|
|
@ -34,7 +34,6 @@
|
|||
px4_add_module(
|
||||
MODULE modules__events
|
||||
MAIN send_event
|
||||
STACK_MAIN 2200
|
||||
COMPILE_FLAGS
|
||||
SRCS
|
||||
rc_loss_alarm.cpp
|
||||
|
|
|
@ -37,7 +37,6 @@ add_subdirectory(runway_takeoff)
|
|||
px4_add_module(
|
||||
MODULE modules__fw_pos_control_l1
|
||||
MAIN fw_pos_control_l1
|
||||
STACK_MAIN 1200
|
||||
SRCS
|
||||
FixedwingPositionControl.cpp
|
||||
DEPENDS
|
||||
|
|
|
@ -33,7 +33,6 @@
|
|||
px4_add_module(
|
||||
MODULE modules__land_detector
|
||||
MAIN land_detector
|
||||
STACK_MAIN 1200
|
||||
COMPILE_FLAGS
|
||||
SRCS
|
||||
land_detector_main.cpp
|
||||
|
|
|
@ -34,7 +34,6 @@
|
|||
px4_add_module(
|
||||
MODULE modules__landing_target_estimator
|
||||
MAIN landing_target_estimator
|
||||
STACK_MAIN 1200
|
||||
COMPILE_FLAGS
|
||||
SRCS
|
||||
landing_target_estimator_main.cpp
|
||||
|
|
|
@ -33,7 +33,6 @@
|
|||
px4_add_module(
|
||||
MODULE modules__load_mon
|
||||
MAIN load_mon
|
||||
STACK_MAIN 1200
|
||||
COMPILE_FLAGS
|
||||
SRCS
|
||||
load_mon.cpp
|
||||
|
|
|
@ -35,7 +35,6 @@ px4_add_module(
|
|||
MODULE modules__logger
|
||||
MAIN logger
|
||||
PRIORITY "SCHED_PRIORITY_MAX-30"
|
||||
STACK_MAIN 2200
|
||||
COMPILE_FLAGS
|
||||
-Wno-cast-align # TODO: fix and enable
|
||||
SRCS
|
||||
|
|
|
@ -36,8 +36,6 @@ px4_add_git_submodule(TARGET git_mavlink_v2 PATH "${PX4_SOURCE_DIR}/mavlink/incl
|
|||
px4_add_module(
|
||||
MODULE modules__mavlink
|
||||
MAIN mavlink
|
||||
STACK_MAIN 1600
|
||||
STACK_MAX 1600
|
||||
COMPILE_FLAGS
|
||||
-Wno-cast-align # TODO: fix and enable
|
||||
-Wno-address-of-packed-member # TODO: fix in c_library_v2
|
||||
|
|
|
@ -36,7 +36,6 @@ add_subdirectory(AttitudeControl)
|
|||
px4_add_module(
|
||||
MODULE modules__mc_att_control
|
||||
MAIN mc_att_control
|
||||
STACK_MAIN 1200
|
||||
STACK_MAX 3500
|
||||
COMPILE_FLAGS
|
||||
SRCS
|
||||
|
|
|
@ -38,7 +38,6 @@ px4_add_module(
|
|||
MAIN mc_pos_control
|
||||
COMPILE_FLAGS
|
||||
-Wno-implicit-fallthrough # TODO: fix and remove
|
||||
STACK_MAIN 1500
|
||||
SRCS
|
||||
mc_pos_control_main.cpp
|
||||
PositionControl.cpp
|
||||
|
|
|
@ -34,8 +34,6 @@
|
|||
px4_add_module(
|
||||
MODULE modules__navigator
|
||||
MAIN navigator
|
||||
STACK_MAIN 1300
|
||||
COMPILE_FLAGS
|
||||
SRCS
|
||||
navigator_main.cpp
|
||||
navigator_mode.cpp
|
||||
|
|
|
@ -34,8 +34,6 @@ px4_add_module(
|
|||
MODULE modules__replay
|
||||
MAIN replay
|
||||
COMPILE_FLAGS
|
||||
STACK_MAIN 1000
|
||||
STACK_MAX 4000
|
||||
SRCS
|
||||
replay_main.cpp
|
||||
DEPENDS
|
||||
|
|
|
@ -38,7 +38,6 @@ px4_add_module(
|
|||
MODULE modules__sensors
|
||||
MAIN sensors
|
||||
PRIORITY "SCHED_PRIORITY_MAX-5"
|
||||
STACK_MAIN 1500
|
||||
SRCS
|
||||
voted_sensors_update.cpp
|
||||
rc_update.cpp
|
||||
|
|
|
@ -34,7 +34,6 @@
|
|||
px4_add_module(
|
||||
MODULE modules__sih
|
||||
MAIN sih
|
||||
STACK_MAIN 1200
|
||||
STACK_MAX 1024
|
||||
COMPILE_FLAGS
|
||||
SRCS
|
||||
|
|
|
@ -39,7 +39,6 @@ if(NOT "${PX4_BOARD}" MATCHES "px4_io") # TODO: fix this hack (move uORB to plat
|
|||
px4_add_module(
|
||||
MODULE modules__uORB
|
||||
MAIN uorb
|
||||
STACK_MAIN 2100
|
||||
SRCS
|
||||
ORBSet.hpp
|
||||
Publication.hpp
|
||||
|
|
|
@ -34,7 +34,6 @@
|
|||
px4_add_module(
|
||||
MODULE modules__uORB__uORB_tests
|
||||
MAIN uorb_tests
|
||||
STACK_MAIN 2048
|
||||
PRIORITY "SCHED_PRIORITY_MAX"
|
||||
SRCS
|
||||
uORB_tests_main.cpp
|
||||
|
|
|
@ -34,7 +34,6 @@ px4_add_module(
|
|||
MODULE drivers__vmount
|
||||
MAIN vmount
|
||||
COMPILE_FLAGS
|
||||
STACK_MAIN 1024
|
||||
SRCS
|
||||
input.cpp
|
||||
input_mavlink.cpp
|
||||
|
@ -48,4 +47,4 @@ px4_add_module(
|
|||
git_ecl
|
||||
ecl_geo
|
||||
)
|
||||
|
||||
|
||||
|
|
|
@ -33,8 +33,6 @@
|
|||
px4_add_module(
|
||||
MODULE modules__vtol_att_control
|
||||
MAIN vtol_att_control
|
||||
STACK_MAIN 1300
|
||||
COMPILE_FLAGS
|
||||
SRCS
|
||||
vtol_att_control_main.cpp
|
||||
tiltrotor.cpp
|
||||
|
|
|
@ -33,7 +33,6 @@
|
|||
px4_add_module(
|
||||
MODULE systemcmds__dmesg
|
||||
MAIN dmesg
|
||||
STACK_MAIN 900
|
||||
SRCS
|
||||
dmesg.cpp
|
||||
)
|
||||
|
|
|
@ -33,7 +33,6 @@
|
|||
px4_add_module(
|
||||
MODULE systemcmds__hardfault_log
|
||||
MAIN hardfault_log
|
||||
STACK_MAIN 2100
|
||||
COMPILE_FLAGS
|
||||
-Wno-cast-align # TODO: fix and enable
|
||||
SRCS
|
||||
|
|
|
@ -33,7 +33,6 @@
|
|||
px4_add_module(
|
||||
MODULE systemcmds__led_control
|
||||
MAIN led_control
|
||||
STACK_MAIN 2500
|
||||
COMPILE_FLAGS
|
||||
SRCS
|
||||
led_control.cpp
|
||||
|
|
|
@ -33,7 +33,6 @@
|
|||
px4_add_module(
|
||||
MODULE systemcmds__motor_ramp
|
||||
MAIN motor_ramp
|
||||
STACK_MAIN 1200
|
||||
COMPILE_FLAGS
|
||||
-Wno-write-strings
|
||||
SRCS
|
||||
|
|
|
@ -33,7 +33,6 @@
|
|||
px4_add_module(
|
||||
MODULE systemcmds__mtd
|
||||
MAIN mtd
|
||||
STACK_MAIN 1500
|
||||
COMPILE_FLAGS
|
||||
SRCS
|
||||
mtd.c
|
||||
|
|
Some files were not shown because too many files have changed in this diff Show More
Loading…
Reference in New Issue