mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-04-14 10:07:39 +08:00
NuttX stackcheck exclude PX4 Matrix and Param
- instrumenting PX4 Matrix and Param methods is too burdensome - partially restore px4_fmu-v5_stackcheck and holybro_durandal-v1_stackcheck to match default configs
This commit is contained in:
parent
5adf23a6a8
commit
7166b867e1
@ -116,6 +116,7 @@ pipeline {
|
||||
// configure
|
||||
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "param set CBRK_BUZZER 782097"' // disable buzzer
|
||||
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "param set SYS_AUTOSTART 13000"' // generic vtol standard
|
||||
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "param save"'
|
||||
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "reboot"' // reboot to apply
|
||||
}
|
||||
}
|
||||
@ -188,6 +189,7 @@ pipeline {
|
||||
// configure
|
||||
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "param set CBRK_BUZZER 782097"' // disable buzzer
|
||||
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "param set SYS_AUTOSTART 4001"' // generic multicopter
|
||||
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "param save"'
|
||||
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "reboot"' // reboot to apply
|
||||
}
|
||||
}
|
||||
@ -260,6 +262,7 @@ pipeline {
|
||||
// configure
|
||||
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "param set CBRK_BUZZER 782097"' // disable buzzer
|
||||
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "param set SYS_AUTOSTART 13000"' // generic vtol standard
|
||||
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "param save"'
|
||||
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "reboot"' // reboot to apply
|
||||
}
|
||||
}
|
||||
@ -332,6 +335,7 @@ pipeline {
|
||||
// configure
|
||||
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "param set CBRK_BUZZER 782097"' // disable buzzer
|
||||
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "param set SYS_AUTOSTART 13000"' // generic vtol standard
|
||||
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "param save"'
|
||||
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "reboot"' // reboot to apply
|
||||
}
|
||||
}
|
||||
@ -404,6 +408,7 @@ pipeline {
|
||||
// configure
|
||||
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-SEGGER_*` --cmd "param set CBRK_BUZZER 782097"' // disable buzzer
|
||||
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-SEGGER_*` --cmd "param set SYS_AUTOSTART 4001"' // generic vtol standardulticopter
|
||||
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-SEGGER_*` --cmd "param save"'
|
||||
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-SEGGER_*` --cmd "reboot"' // reboot to apply
|
||||
}
|
||||
}
|
||||
@ -477,6 +482,7 @@ pipeline {
|
||||
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "param set CBRK_BUZZER 782097"' // disable buzzer
|
||||
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "param set SYS_AUTOSTART 13000"' // generic vtol standard
|
||||
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "param set SYS_BL_UPDATE 1"' // update bootloader
|
||||
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "param save"'
|
||||
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "reboot"' // reboot to apply
|
||||
}
|
||||
}
|
||||
@ -548,7 +554,10 @@ pipeline {
|
||||
steps {
|
||||
// configure
|
||||
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "param set CBRK_BUZZER 782097"' // disable buzzer
|
||||
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "param set SYS_AUTOSTART 4001"' // generic vtol standard
|
||||
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "param set SYS_AUTOSTART 13000"' // generic vtol standard
|
||||
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "param set SYS_BL_UPDATE 1"' // update bootloader
|
||||
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "param save"'
|
||||
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "reboot"' // reboot to apply
|
||||
}
|
||||
}
|
||||
stage("status") {
|
||||
@ -582,7 +591,7 @@ pipeline {
|
||||
}
|
||||
}
|
||||
options {
|
||||
timeout(time: 40, unit: 'MINUTES')
|
||||
timeout(time: 60, unit: 'MINUTES')
|
||||
}
|
||||
} // stage test
|
||||
}
|
||||
@ -633,6 +642,7 @@ pipeline {
|
||||
// configure
|
||||
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "param set CBRK_BUZZER 782097"' // disable buzzer
|
||||
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "param set SYS_AUTOSTART 4001"' // generic multicopter
|
||||
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "param save"'
|
||||
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "reboot"' // reboot to apply
|
||||
}
|
||||
}
|
||||
|
||||
@ -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
|
||||
@ -25,14 +25,14 @@ px4_add_board(
|
||||
#camera_trigger
|
||||
differential_pressure # all available differential pressure drivers
|
||||
distance_sensor # all available distance sensor drivers
|
||||
# dshot -- todo needslooking at
|
||||
#dshot
|
||||
gps
|
||||
heater
|
||||
#imu # all available imu drivers
|
||||
#imu/adis16448
|
||||
#imu/adis16477
|
||||
#imu/adis16497
|
||||
#imu/bmi088
|
||||
imu/bmi088
|
||||
imu/mpu6000
|
||||
#imu/mpu9250
|
||||
#irlock
|
||||
@ -78,14 +78,15 @@ px4_add_board(
|
||||
mc_pos_control
|
||||
mc_rate_control
|
||||
navigator
|
||||
rc_update
|
||||
#rover_pos_control
|
||||
sensors
|
||||
#sih
|
||||
vmount
|
||||
vtol_att_control
|
||||
SYSTEMCMDS
|
||||
#bl_update
|
||||
#config
|
||||
bl_update
|
||||
config
|
||||
dmesg
|
||||
dumpfile
|
||||
esc_calib
|
||||
|
||||
@ -41,6 +41,7 @@ px4_add_board(
|
||||
magnetometer # all available magnetometer drivers
|
||||
#mkblctrl
|
||||
optical_flow # all available optical flow drivers
|
||||
#osd
|
||||
#pca9685
|
||||
#power_monitor/ina226
|
||||
#protocol_splitter
|
||||
@ -68,14 +69,15 @@ px4_add_board(
|
||||
fw_att_control
|
||||
fw_pos_control_l1
|
||||
land_detector
|
||||
landing_target_estimator
|
||||
#landing_target_estimator
|
||||
load_mon
|
||||
local_position_estimator
|
||||
#local_position_estimator
|
||||
logger
|
||||
mavlink
|
||||
mc_att_control
|
||||
mc_pos_control
|
||||
mc_rate_control
|
||||
#micrortps_bridge
|
||||
navigator
|
||||
rc_update
|
||||
rover_pos_control
|
||||
@ -104,7 +106,7 @@ px4_add_board(
|
||||
reflect
|
||||
sd_bench
|
||||
shutdown
|
||||
#tests # tests and test runner
|
||||
tests # tests and test runner
|
||||
top
|
||||
topic_listener
|
||||
tune_control
|
||||
|
||||
@ -78,9 +78,11 @@ function(px4_os_add_flags)
|
||||
if("${CONFIG_ARMV7M_STACKCHECK}" STREQUAL "y")
|
||||
message(STATUS "NuttX Stack Checking (CONFIG_ARMV7M_STACKCHECK) enabled")
|
||||
add_compile_options(
|
||||
-finstrument-functions
|
||||
-ffixed-r10
|
||||
)
|
||||
-finstrument-functions
|
||||
# instrumenting PX4 Matrix and Param methods is too burdensome
|
||||
-finstrument-functions-exclude-file-list=matrix/Matrix.hpp,px4_platform_common/param.h
|
||||
)
|
||||
endif()
|
||||
|
||||
endfunction()
|
||||
|
||||
@ -84,7 +84,7 @@ struct GPS_Sat_Info {
|
||||
struct satellite_info_s _data;
|
||||
};
|
||||
|
||||
static constexpr int TASK_STACK_SIZE = 1620;
|
||||
static constexpr int TASK_STACK_SIZE = 1760;
|
||||
|
||||
|
||||
class GPS : public ModuleBase<GPS>
|
||||
|
||||
Loading…
x
Reference in New Issue
Block a user