mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-04-14 10:07:39 +08:00
selectively increase optimization -Os -> -O2
- targetted at modules/libraries that benefit without drastically increasing flash usage - ignored on boards with CONSTRAINED_FLASH set
This commit is contained in:
parent
7f73b9a131
commit
31fe7af454
@ -181,6 +181,18 @@ if(NOT CMAKE_BUILD_TYPE)
|
||||
set(CMAKE_BUILD_TYPE ${PX4_BUILD_TYPE} CACHE STRING "Build type" FORCE)
|
||||
endif()
|
||||
|
||||
if((CMAKE_BUILD_TYPE STREQUAL "Debug") OR (CMAKE_BUILD_TYPE STREQUAL "Coverage"))
|
||||
set(MAX_CUSTOM_OPT_LEVEL -O0)
|
||||
elseif(CMAKE_BUILD_TYPE MATCHES "Sanitizer")
|
||||
set(MAX_CUSTOM_OPT_LEVEL -O1)
|
||||
else()
|
||||
if(px4_constrained_flash_build)
|
||||
set(MAX_CUSTOM_OPT_LEVEL -Os)
|
||||
else()
|
||||
set(MAX_CUSTOM_OPT_LEVEL -O2)
|
||||
endif()
|
||||
endif()
|
||||
|
||||
set_property(CACHE CMAKE_BUILD_TYPE PROPERTY STRINGS "Debug;Release;RelWithDebInfo;MinSizeRel;Coverage;AddressSanitizer;UndefinedBehaviorSanitizer")
|
||||
message(STATUS "cmake build type: ${CMAKE_BUILD_TYPE}")
|
||||
|
||||
|
||||
@ -6,6 +6,7 @@ px4_add_board(
|
||||
TOOLCHAIN arm-none-eabi
|
||||
ARCHITECTURE cortex-m4
|
||||
ROMFSROOT px4fmu_common
|
||||
CONSTRAINED_FLASH
|
||||
DRIVERS
|
||||
barometer/lps25h
|
||||
distance_sensor/vl53l0x
|
||||
|
||||
@ -7,7 +7,7 @@ px4_add_board(
|
||||
TOOLCHAIN arm-none-eabi
|
||||
ARCHITECTURE cortex-m7
|
||||
ROMFSROOT px4fmu_common
|
||||
BUILD_BOOTLOADER
|
||||
#BUILD_BOOTLOADER
|
||||
IO px4_io-v2_default
|
||||
TESTING
|
||||
# UAVCAN_INTERFACES 2 - No H7 or FD can support in UAVCAN
|
||||
@ -23,7 +23,7 @@ px4_add_board(
|
||||
batt_smbus
|
||||
#camera_capture
|
||||
#camera_trigger
|
||||
differential_pressure # all available differential pressure drivers
|
||||
#differential_pressure # all available differential pressure drivers
|
||||
distance_sensor # all available distance sensor drivers
|
||||
#dshot
|
||||
gps
|
||||
@ -65,6 +65,7 @@ px4_add_board(
|
||||
commander
|
||||
dataman
|
||||
ekf2
|
||||
#esc_battery
|
||||
events
|
||||
fw_att_control
|
||||
fw_pos_control_l1
|
||||
@ -78,16 +79,17 @@ px4_add_board(
|
||||
mc_hover_thrust_estimator
|
||||
mc_pos_control
|
||||
mc_rate_control
|
||||
#micrortps_bridge
|
||||
navigator
|
||||
rc_update
|
||||
#rover_pos_control
|
||||
sensors
|
||||
#sih
|
||||
temperature_compensation
|
||||
vmount
|
||||
#temperature_compensation
|
||||
#vmount
|
||||
vtol_att_control
|
||||
SYSTEMCMDS
|
||||
bl_update
|
||||
#bl_update
|
||||
dmesg
|
||||
dumpfile
|
||||
esc_calib
|
||||
|
||||
@ -7,6 +7,7 @@ px4_add_board(
|
||||
TOOLCHAIN arm-none-eabi
|
||||
ARCHITECTURE cortex-m7
|
||||
ROMFSROOT px4fmu_common
|
||||
CONSTRAINED_FLASH
|
||||
SERIAL_PORTS
|
||||
TEL1:/dev/ttyS0 # UART1
|
||||
TEL2:/dev/ttyS1 # UART2
|
||||
|
||||
@ -47,7 +47,7 @@ px4_add_board(
|
||||
#pca9685
|
||||
#power_monitor/ina226
|
||||
#protocol_splitter
|
||||
pwm_input
|
||||
#pwm_input
|
||||
pwm_out_sim
|
||||
pwm_out
|
||||
px4io
|
||||
@ -61,7 +61,7 @@ px4_add_board(
|
||||
#uavcan
|
||||
MODULES
|
||||
airspeed_selector
|
||||
attitude_estimator_q
|
||||
#attitude_estimator_q
|
||||
battery_status
|
||||
#camera_feedback
|
||||
commander
|
||||
@ -84,11 +84,11 @@ px4_add_board(
|
||||
#micrortps_bridge
|
||||
navigator
|
||||
rc_update
|
||||
rover_pos_control
|
||||
#rover_pos_control
|
||||
sensors
|
||||
sih
|
||||
temperature_compensation
|
||||
vmount
|
||||
#sih
|
||||
#temperature_compensation
|
||||
#vmount
|
||||
vtol_att_control
|
||||
SYSTEMCMDS
|
||||
bl_update
|
||||
|
||||
@ -4,6 +4,7 @@ px4_add_board(
|
||||
VENDOR px4
|
||||
MODEL io-v2
|
||||
TOOLCHAIN arm-none-eabi
|
||||
CONSTRAINED_FLASH
|
||||
ARCHITECTURE cortex-m3
|
||||
DRIVERS
|
||||
MODULES
|
||||
|
||||
@ -65,7 +65,7 @@ static constexpr wq_config_t I2C3{"wq:I2C3", 1472, -11};
|
||||
static constexpr wq_config_t I2C4{"wq:I2C4", 1472, -12};
|
||||
|
||||
// PX4 att/pos controllers, highest priority after sensors.
|
||||
static constexpr wq_config_t attitude_ctrl{"wq:attitude_ctrl", 1536, -13};
|
||||
static constexpr wq_config_t attitude_ctrl{"wq:attitude_ctrl", 1600, -13};
|
||||
static constexpr wq_config_t navigation_and_controllers{"wq:navigation_and_controllers", 7200, -14};
|
||||
|
||||
static constexpr wq_config_t hp_default{"wq:hp_default", 1900, -15};
|
||||
|
||||
@ -43,4 +43,5 @@ if(PX4_TESTING)
|
||||
add_subdirectory(test)
|
||||
endif()
|
||||
|
||||
target_compile_options(px4_work_queue PRIVATE ${MAX_CUSTOM_OPT_LEVEL})
|
||||
target_link_libraries(px4_work_queue PRIVATE px4_platform)
|
||||
|
||||
@ -32,7 +32,7 @@
|
||||
############################################################################
|
||||
|
||||
# skip for px4_layer support on an IO board
|
||||
if (NOT ${PX4_BOARD} MATCHES "px4_io")
|
||||
if(NOT PX4_BOARD MATCHES "px4_io")
|
||||
|
||||
add_library(px4_layer
|
||||
board_crashdump.c
|
||||
|
||||
@ -34,3 +34,4 @@
|
||||
px4_add_library(arch_dshot
|
||||
dshot.c
|
||||
)
|
||||
target_compile_options(arch_dshot PRIVATE ${MAX_CUSTOM_OPT_LEVEL})
|
||||
|
||||
@ -34,5 +34,8 @@
|
||||
px4_add_library(arch_hrt
|
||||
hrt.c
|
||||
)
|
||||
target_compile_options(arch_hrt PRIVATE -Wno-cast-align) # TODO: fix and enable
|
||||
|
||||
target_compile_options(arch_hrt
|
||||
PRIVATE
|
||||
${MAX_CUSTOM_OPT_LEVEL}
|
||||
-Wno-cast-align # TODO: fix and enable
|
||||
)
|
||||
|
||||
@ -32,8 +32,9 @@
|
||||
############################################################################
|
||||
|
||||
px4_add_library(arch_io_pins
|
||||
input_capture.c
|
||||
io_timer.c
|
||||
pwm_servo.c
|
||||
pwm_trigger.c
|
||||
input_capture.c
|
||||
)
|
||||
target_compile_options(arch_io_pins PRIVATE ${MAX_CUSTOM_OPT_LEVEL})
|
||||
|
||||
@ -34,3 +34,4 @@
|
||||
px4_add_library(arch_spi
|
||||
spi.cpp
|
||||
)
|
||||
target_compile_options(arch_spi PRIVATE ${MAX_CUSTOM_OPT_LEVEL})
|
||||
|
||||
@ -35,9 +35,5 @@ px4_add_library(drivers_accelerometer
|
||||
PX4Accelerometer.cpp
|
||||
PX4Accelerometer.hpp
|
||||
)
|
||||
target_link_libraries(drivers_accelerometer
|
||||
PRIVATE
|
||||
conversion
|
||||
drivers__device
|
||||
mathlib
|
||||
)
|
||||
target_compile_options(drivers_accelerometer PRIVATE ${MAX_CUSTOM_OPT_LEVEL})
|
||||
target_link_libraries(drivers_accelerometer PRIVATE conversion drivers__device)
|
||||
|
||||
@ -35,4 +35,5 @@ px4_add_library(drivers_gyroscope
|
||||
PX4Gyroscope.cpp
|
||||
PX4Gyroscope.hpp
|
||||
)
|
||||
target_compile_options(drivers_gyroscope PRIVATE ${MAX_CUSTOM_OPT_LEVEL})
|
||||
target_link_libraries(drivers_gyroscope PRIVATE conversion drivers__device)
|
||||
|
||||
@ -33,3 +33,4 @@
|
||||
|
||||
add_library(perf perf_counter.cpp)
|
||||
add_dependencies(perf prebuild_targets)
|
||||
target_compile_options(perf PRIVATE ${MAX_CUSTOM_OPT_LEVEL})
|
||||
|
||||
@ -33,13 +33,17 @@
|
||||
|
||||
set(SRCS
|
||||
conversions.c
|
||||
conversions.h
|
||||
crc.c
|
||||
crc.h
|
||||
mavlink_log.cpp
|
||||
mavlink_log.h
|
||||
)
|
||||
|
||||
if(${PX4_PLATFORM} STREQUAL "nuttx")
|
||||
list(APPEND SRCS
|
||||
cpuload.c
|
||||
cpuload.h
|
||||
print_load_nuttx.c
|
||||
otp.c
|
||||
)
|
||||
@ -50,3 +54,4 @@ else()
|
||||
endif()
|
||||
|
||||
px4_add_library(systemlib ${SRCS})
|
||||
target_compile_options(systemlib PRIVATE ${MAX_CUSTOM_OPT_LEVEL})
|
||||
|
||||
@ -33,10 +33,9 @@
|
||||
|
||||
px4_add_library(AttitudeControl
|
||||
AttitudeControl.cpp
|
||||
AttitudeControl.hpp
|
||||
)
|
||||
target_include_directories(AttitudeControl
|
||||
PUBLIC
|
||||
${CMAKE_CURRENT_SOURCE_DIR}
|
||||
)
|
||||
target_compile_options(AttitudeControl PRIVATE ${MAX_CUSTOM_OPT_LEVEL})
|
||||
target_include_directories(AttitudeControl PUBLIC ${CMAKE_CURRENT_SOURCE_DIR})
|
||||
|
||||
px4_add_unit_gtest(SRC AttitudeControlTest.cpp LINKLIBS AttitudeControl)
|
||||
|
||||
@ -37,10 +37,12 @@ px4_add_module(
|
||||
MODULE modules__mc_att_control
|
||||
MAIN mc_att_control
|
||||
COMPILE_FLAGS
|
||||
${MAX_CUSTOM_OPT_LEVEL}
|
||||
SRCS
|
||||
mc_att_control_main.cpp
|
||||
mc_att_control.hpp
|
||||
DEPENDS
|
||||
mathlib
|
||||
AttitudeControl
|
||||
mathlib
|
||||
px4_work_queue
|
||||
)
|
||||
|
||||
@ -37,6 +37,7 @@ px4_add_module(
|
||||
MODULE modules__mc_rate_control
|
||||
MAIN mc_rate_control
|
||||
COMPILE_FLAGS
|
||||
${MAX_CUSTOM_OPT_LEVEL}
|
||||
SRCS
|
||||
MulticopterRateControl.cpp
|
||||
MulticopterRateControl.hpp
|
||||
|
||||
@ -33,12 +33,10 @@
|
||||
|
||||
px4_add_library(RateControl
|
||||
RateControl.cpp
|
||||
RateControl.hpp
|
||||
)
|
||||
target_include_directories(RateControl
|
||||
PUBLIC
|
||||
${CMAKE_CURRENT_SOURCE_DIR}
|
||||
)
|
||||
|
||||
target_compile_options(RateControl PRIVATE ${MAX_CUSTOM_OPT_LEVEL})
|
||||
target_include_directories(RateControl PUBLIC ${CMAKE_CURRENT_SOURCE_DIR})
|
||||
target_link_libraries(RateControl PRIVATE mathlib)
|
||||
|
||||
px4_add_unit_gtest(SRC RateControlTest.cpp LINKLIBS RateControl)
|
||||
|
||||
@ -35,3 +35,4 @@ px4_add_library(sensor_corrections
|
||||
SensorCorrections.cpp
|
||||
SensorCorrections.hpp
|
||||
)
|
||||
target_compile_options(sensor_corrections PRIVATE ${MAX_CUSTOM_OPT_LEVEL})
|
||||
|
||||
@ -35,6 +35,9 @@ px4_add_library(vehicle_acceleration
|
||||
VehicleAcceleration.cpp
|
||||
VehicleAcceleration.hpp
|
||||
)
|
||||
|
||||
target_compile_options(vehicle_acceleration PRIVATE ${MAX_CUSTOM_OPT_LEVEL})
|
||||
|
||||
target_link_libraries(vehicle_acceleration
|
||||
PRIVATE
|
||||
mathlib
|
||||
|
||||
@ -35,6 +35,9 @@ px4_add_library(vehicle_angular_velocity
|
||||
VehicleAngularVelocity.cpp
|
||||
VehicleAngularVelocity.hpp
|
||||
)
|
||||
|
||||
target_compile_options(vehicle_angular_velocity PRIVATE ${MAX_CUSTOM_OPT_LEVEL})
|
||||
|
||||
target_link_libraries(vehicle_angular_velocity
|
||||
PRIVATE
|
||||
mathlib
|
||||
|
||||
@ -37,4 +37,5 @@ px4_add_library(vehicle_imu
|
||||
VehicleIMU.cpp
|
||||
VehicleIMU.hpp
|
||||
)
|
||||
target_compile_options(vehicle_imu PRIVATE ${MAX_CUSTOM_OPT_LEVEL})
|
||||
target_link_libraries(vehicle_imu PRIVATE sensor_corrections px4_work_queue)
|
||||
|
||||
@ -31,7 +31,7 @@
|
||||
#
|
||||
############################################################################
|
||||
|
||||
if(NOT "${PX4_BOARD}" MATCHES "px4_io") # TODO: fix this hack (move uORB to platform layer)
|
||||
if(NOT PX4_BOARD MATCHES "px4_io") # TODO: fix this hack (move uORB to platform layer)
|
||||
|
||||
# this includes the generated topics directory
|
||||
include_directories(${CMAKE_CURRENT_BINARY_DIR})
|
||||
@ -39,6 +39,8 @@ if(NOT "${PX4_BOARD}" MATCHES "px4_io") # TODO: fix this hack (move uORB to plat
|
||||
px4_add_module(
|
||||
MODULE modules__uORB
|
||||
MAIN uorb
|
||||
COMPILE_FLAGS
|
||||
${MAX_CUSTOM_OPT_LEVEL}
|
||||
SRCS
|
||||
ORBSet.hpp
|
||||
Publication.hpp
|
||||
|
||||
Loading…
x
Reference in New Issue
Block a user