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