Compare commits

..

36 Commits

Author SHA1 Message Date
Daniel Agar 6823cbc414 sensors/vehicle_angular_velocity: add IMU_GYRO_RATEMAX constraints 2022-06-07 16:23:01 -04:00
Daniel Agar beaebe4d0b sensors/vehicle_imu: don't bother checking IMU_GYRO_RATEMAX 2022-06-07 16:22:54 -04:00
Daniel Agar 0bddca6b9b boards: NuttX update all boards to preallocated sem holder list
- CONFIG_SEM_PREALLOCHOLDERS=32
 - CONFIG_SEM_NNESTPRIO=16 (default)
2022-05-29 13:49:01 -04:00
Daniel Agar c50c1e3982 update NuttX and apps to latest with sem holder fixes and updated ostest 2022-05-29 13:48:15 -04:00
Daniel Agar a249b77647 boards: reduce SPI DMA buffers on older STM32F4 boards
- on common IMUs like the mpu6000, mpu9250, icm20602, etc each FIFO
sample is only 12 bytes so this is still more than large enough for the
worst case transfer
2022-05-27 16:28:26 -04:00
Daniel Agar 17de164e95 boards: pixhawk 2 cube skip starting low quality l3gd20 gyro to save memory and cpu
- free memory is getting tight on these older boards (depending on
configuratoin) and the pixhawk 2 cube still has 2 other superior IMUs, so this is just
dropping dead weight
2022-05-27 16:28:22 -04:00
David Sidrane a057b38c40 Update all H7 Bootloders 2022-05-27 14:52:00 -04:00
David Sidrane 39e53711d5 flash_cache:Flush complete cache line 2022-05-27 14:44:54 -04:00
David Sidrane 1294851bb6 boards: STM32H7 pad to 256 bit - 32 bytes (#19724) 2022-05-27 14:44:51 -04:00
David Sidrane 1c15a1a7f4 px4_fmu-v6c:Fix mag rotation 2022-05-27 14:43:47 -04:00
David Sidrane 21567ca187 boards: new px4_fmu-v6c board support (#19544) 2022-05-27 14:42:55 -04:00
bresch 8e789bcc7f ekf2_post-processing: use estimator_status_flags instead of bitmasks 2022-05-24 10:30:52 -04:00
Julian Oes d699d5f27e sitl_gazebo: update submodule
This fixes the issue where HITL doesn't connect over USB.
2022-05-24 09:43:05 -04:00
Julian Oes 4ae97c505f commander: lockdown is not termination
We use lockdown to prevent outputs like motors and servos from being
active in HITL simulation. This means that we can't treat the lockdown
flag as a flight_terminated, otherwise we can't arm in HITL at all.
2022-05-24 09:42:38 -04:00
Daniel Agar b8ce2a6039 icm42688p: only check configured registers periodically (as intended) 2022-05-23 14:58:37 -04:00
bresch 1f399e5b33 ekf2: use explicit flags instead of bitmask position
This prevents bitmask mismatch when a new flag is inserted
2022-05-23 14:57:17 -04:00
Serhat Aksun d67cddae7d sensors/vehicle_magnetometer: fix multi_mode check
Signed-off-by: Serhat Aksun <serhat.aksun@maxwell-innovations.com>
2022-05-23 10:10:22 -04:00
Julian Oes 0290282b17 ROMFS: disable UAVCAN in HITL
Without this, uavcan creates MixingOutput classes which then create
empty actuator_outputs publications. This then prevents the motor
output in HITL to be forwarded to the simulator via mavlink.
2022-05-22 10:27:07 -04:00
Nicolas MARTIN 39d1c79f48 HITL: undefined time_remaining_s should be NAN 2022-05-20 09:40:28 -04:00
Nico van Duijn ad410a2512 Commander: ignore MAV_CMD_REQUEST_MSG
This commit adds the MAV_CMD_REQUEST_MESSAGE to the list of vehicle
commands which are ignored without generating a warning sound.
2022-05-20 09:40:22 -04:00
Daniel Agar 453acdce31 .vscode/.gitignore ignore all log files 2022-05-20 09:40:07 -04:00
Beat Küng afb2538da3 output drivers: init SmartLock after exit_and_cleanup
This fixes an invalid memory access when exiting the module:
exit_and_cleanup destroys the object, but lock_guard is destructed after
and accesses the lock.
2022-05-12 08:17:15 -04:00
alexklimaj af58c412c3 Fix uavcan battery causing immediate RTL time remaining low 2022-05-11 21:49:13 -04:00
Daniel Agar d5226b28ce drivers/rc_input: ensure RC inversion is disabled initially and latch RC_INPUT_PROTO conservatively
- this allows jumping straight to a non-SBUS RC protocol
 - increased the scan time per protocol 300->500 ms, which the newer DSM parser seems to need in some cases.
 - only set RC_INPUT_PROTO if we've had a successful RC lock for > 3 seconds
2022-05-11 14:31:51 -04:00
Beat Küng b091ea9fd9 log_writer_file: fix corner case when mission log is enabled
Normally _should_run for mission is only ever true if _should_run for the
normal log is. There are exceptions though:
- the log buffer fails to allocate
- there was a write failure (e.g. due to SD card removal)
In that situation, the writer would not wait anymore but busy-loop.
2022-05-11 10:07:46 -04:00
Beat Küng 9e91ca8294 log_writer_file: protect access to _should_run, use px4::atomicbool for _exit_thread 2022-05-11 10:07:46 -04:00
Igor Mišić 8302f076e7 uavcan: use timer 6 by default on stm32f7 2022-05-10 12:43:26 -04:00
Thomas Stastny de26ffa6e0 fw pos ctrl: turn back to takeoff point with npfg 2022-05-06 13:08:07 -04:00
Thomas Stastny f60d38db65 fw pos ctrl: add missing guidance control interval setting to control_manual_position() 2022-05-06 13:08:07 -04:00
Thomas Stastny 5e3c8d2fa0 fw pos ctrl: fix state switching logic for takeoff and landing 2022-05-06 13:08:07 -04:00
Matthias Grob 90998837ec Commander: ensure diconnected battery is cleared from bit field 2022-05-06 10:46:40 -04:00
Beat Küng 8cff9a1e04 commander: fix incorrect return in set_link_loss_nav_state()
If both local position and altitude were not valid, then both RC loss and
datalink loss would not trigger any failsafe at all, independently from
the configured action.
2022-05-06 10:15:30 -04:00
bresch f8ff34f82d ekf2: optimize KHP computation
Calculating K(HP) takes less operations than (KH)P because K and H are
vectors.

Without considering the sparsity optimization:
- KH (24*24 operations) is then a 24x24 matrix an it takes
24^3 operations to multiply it with P. Total: 14400 op

- HP (24*(24+24-1) operations) is a row vector
and it takes 24 operations to left-multiply it by K. Total:1152 op
2022-05-06 10:15:26 -04:00
Beat Küng e69d9ec48f dshot: avoid using pwm failsafe params when dynamic mixing is enabled 2022-05-02 11:43:51 +02:00
Beat Küng f033e164fe fix dshot: remove setAllFailsafeValues
Fixes a regression from c1e5e666f0,
where with static mixers the dshot outputs would go to max instead of 0
in a failsafe case.
2022-04-28 13:29:40 -04:00
Daniel Agar 41191765ad drivers/rc_input: RC_INPUT_PROTO parameter minimal implementation (#19539)
Co-authored-by: chris1seto <chris12892@gmail.com>

Co-authored-by: chris1seto <chris12892@gmail.com>
2022-04-28 13:27:15 -04:00
495 changed files with 6380 additions and 9957 deletions
+6 -9
View File
@@ -61,20 +61,18 @@ pipeline {
"holybro_kakutef7_default",
"holybro_kakuteh7_default",
"holybro_pix32v5_default",
"matek_h743-slim",
"matek_gnss-m9n-f4_canbootloader",
"matek_gnss-m9n-f4_default",
"matek_h743-mini_default",
"matek_h743-slim_default",
"matek_h743_default",
"modalai_fc-v1_default",
"modalai_fc-v1_rtps",
"modalai_fc-v2_default",
"mro_ctrl-zero-f7_default",
"mro_ctrl-zero-f7-oem_default",
"mro_ctrl-zero-h7-oem_default",
"mro_ctrl-zero-h7-oem_rtps",
"mro_ctrl-zero-h7_default",
"mro_ctrl-zero-h7_rtps",
"mro_ctrl-zero-h7-oem_default",
"mro_ctrl-zero-h7-oem_rtps",
"mro_pixracerpro_default",
"mro_pixracerpro_rtps",
"mro_x21-777_default",
@@ -89,26 +87,25 @@ pipeline {
"nxp_ucans32k146_canbootloader",
"nxp_ucans32k146_default",
"omnibus_f4sd_default",
"raspberrypi_pico_default",
"px4_fmu-v2_default",
"px4_fmu-v2_fixedwing",
"px4_fmu-v2_lto",
"px4_fmu-v2_multicopter",
"px4_fmu-v2_rover",
"px4_fmu-v3_default",
"px4_fmu-v4_default",
"px4_fmu-v4pro_default",
"px4_fmu-v5_cyphal",
"px4_fmu-v5_debug",
"px4_fmu-v5_default",
"px4_fmu-v5_lto",
"px4_fmu-v5_rtps",
"px4_fmu-v5_stackcheck",
"px4_fmu-v5_uavcanv0periph",
"px4_fmu-v5_uavcanv1",
"px4_fmu-v5x_default",
"px4_fmu-v6c_default",
"px4_fmu-v6u_default",
"px4_fmu-v6x_default",
"px4_io-v2_default",
"raspberrypi_pico_default",
"sky-drones_smartap-airlink_default",
"spracing_h7extreme_default",
"uvify_core_default"
+3 -4
View File
@@ -37,10 +37,8 @@ jobs:
holybro_kakutef7,
holybro_kakuteh7,
holybro_pix32v5,
matek_gnss-m9n-f4,
matek_h743,
matek_h743-mini,
matek_h743-slim,
matek_gnss-m9n-f4,
modalai_fc-v1,
modalai_fc-v2,
mro_ctrl-zero-f7,
@@ -55,15 +53,16 @@ jobs:
nxp_fmurt1062-v1,
nxp_ucans32k146,
omnibus_f4sd,
raspberrypi_pico,
px4_fmu-v2,
px4_fmu-v3,
px4_fmu-v4,
px4_fmu-v4pro,
px4_fmu-v5,
px4_fmu-v5x,
px4_fmu-v6c,
px4_fmu-v6u,
px4_fmu-v6x,
raspberrypi_pico,
sky-drones_smartap-airlink,
spracing_h7extreme,
uvify_core
+8 -8
View File
@@ -36,14 +36,14 @@
[submodule "Tools/jsbsim_bridge"]
path = Tools/jsbsim_bridge
url = https://github.com/PX4/px4-jsbsim-bridge.git
[submodule "src/drivers/cyphal/libcanard"]
path = src/drivers/cyphal/libcanard
url = https://github.com/opencyphal/libcanard.git
[submodule "src/drivers/cyphal/public_regulated_data_types"]
path = src/drivers/cyphal/public_regulated_data_types
url = https://github.com/opencyphal/public_regulated_data_types.git
[submodule "src/drivers/cyphal/legacy_data_types"]
path = src/drivers/cyphal/legacy_data_types
[submodule "src/drivers/uavcan_v1/libcanard"]
path = src/drivers/uavcan_v1/libcanard
url = https://github.com/UAVCAN/libcanard.git
[submodule "src/drivers/uavcan_v1/public_regulated_data_types"]
path = src/drivers/uavcan_v1/public_regulated_data_types
url = https://github.com/UAVCAN/public_regulated_data_types.git
[submodule "src/drivers/uavcan_v1/legacy_data_types"]
path = src/drivers/uavcan_v1/legacy_data_types
url = https://github.com/PX4/public_regulated_data_types.git
branch = legacy
[submodule "src/lib/crypto/monocypher"]
+1 -9
View File
@@ -99,7 +99,7 @@
#
#=============================================================================
cmake_minimum_required(VERSION 3.9 FATAL_ERROR)
cmake_minimum_required(VERSION 3.2 FATAL_ERROR)
set(PX4_SOURCE_DIR "${CMAKE_CURRENT_SOURCE_DIR}" CACHE FILEPATH "PX4 source directory" FORCE)
set(PX4_BINARY_DIR "${CMAKE_CURRENT_BINARY_DIR}" CACHE FILEPATH "PX4 binary directory" FORCE)
@@ -234,14 +234,6 @@ message(STATUS "cmake build type: ${CMAKE_BUILD_TYPE}")
#
project(px4 CXX C ASM)
# Check if LTO option and check if toolchain supports it
if(LTO)
include(CheckIPOSupported)
check_ipo_supported()
message(AUTHOR_WARNING "LTO enabled: LTO is highly experimental and should not be used in production")
set(CMAKE_INTERPROCEDURAL_OPTIMIZATION TRUE)
endif()
set(package-contact "px4users@googlegroups.com")
set(CMAKE_CXX_STANDARD 14)
-7
View File
@@ -51,13 +51,6 @@ menu "Toolchain"
string "Architecture"
default ""
config BOARD_LTO
bool "(EXPERIMENTAL) Link Time Optimization (LTO)"
default n
help
Enables LTO flag in linker
Note: Highly EXPERIMENTAL, furthermore make sure you're using a modern compiler GCC 9 or later
config BOARD_FULL_OPTIMIZATION
bool "Full optmization (O3)"
default n
+2 -1
View File
@@ -325,12 +325,13 @@ px4io_update: px4_io-v2_default cubepilot_io-v2_default
cp build/px4_io-v2_default/px4_io-v2_default.bin boards/px4/fmu-v5/extras/px4_io-v2_default.bin
cp build/px4_io-v2_default/px4_io-v2_default.bin boards/px4/fmu-v5x/extras/px4_io-v2_default.bin
cp build/px4_io-v2_default/px4_io-v2_default.bin boards/px4/fmu-v6x/extras/px4_io-v2_default.bin
cp build/px4_io-v2_default/px4_io-v2_default.bin boards/px4/fmu-v6c/extras/px4_io-v2_default.bin
# cubepilot_io-v2_default
cp build/cubepilot_io-v2_default/cubepilot_io-v2_default.bin boards/cubepilot/cubeorange/extras/cubepilot_io-v2_default.bin
cp build/cubepilot_io-v2_default/cubepilot_io-v2_default.bin boards/cubepilot/cubeyellow/extras/cubepilot_io-v2_default.bin
git status
bootloaders_update: cuav_nora_bootloader cuav_x7pro_bootloader cubepilot_cubeorange_bootloader holybro_durandal-v1_bootloader matek_h743_bootloader matek_h743-mini_bootloader matek_h743-slim_bootloader modalai_fc-v2_bootloader mro_ctrl-zero-classic_bootloader mro_ctrl-zero-h7_bootloader mro_ctrl-zero-h7-oem_bootloader mro_pixracerpro_bootloader px4_fmu-v6u_bootloader px4_fmu-v6x_bootloader
bootloaders_update: cuav_nora_bootloader cuav_x7pro_bootloader cubepilot_cubeorange_bootloader holybro_durandal-v1_bootloader holybro_kakuteh7_bootloader matek_h743-slim_bootloader modalai_fc-v2_bootloader mro_ctrl-zero-classic_bootloader mro_ctrl-zero-h7_bootloader mro_ctrl-zero-h7-oem_bootloader mro_pixracerpro_bootloader px4_fmu-v6c_bootloader px4_fmu-v6u_bootloader px4_fmu-v6x_bootloader
git status
.PHONY: coverity_scan
@@ -25,8 +25,6 @@ param set-default FW_P_LIM_MIN -15
param set-default FW_RR_FF 0.1
param set-default FW_RR_P 0.3
param set-default FW_SPOILERS_LND 0.4
param set-default FW_THR_MAX 0.6
param set-default FW_THR_MIN 0.05
param set-default FW_THR_CRUISE 0.25
@@ -7,11 +7,6 @@
. ${R}etc/init.d/rc.vtol_defaults
# TODO: Enable motor failure detection when the
# VTOL no longer reports 0A for all ESCs in SITL
param set-default FD_ACT_EN 0
param set-default FD_ACT_MOT_TOUT 500
# param set-default SYS_CTRL_ALLOC 1
param set-default CA_AIRFRAME 2
@@ -9,7 +9,7 @@
param set-default MAV_TYPE 21
param set-default SYS_CTRL_ALLOC 1
# param set-default SYS_CTRL_ALLOC 1
param set-default CA_AIRFRAME 3
param set-default CA_ROTOR_COUNT 4
@@ -27,7 +27,9 @@ param set-default CA_ROTOR3_PY 0.1875
param set-default CA_ROTOR3_KM -0.05
param set-default CA_ROTOR0_TILT 1
param set-default CA_ROTOR1_TILT 2
param set-default CA_ROTOR2_TILT 3
param set-default CA_ROTOR3_TILT 4
param set-default CA_SV_CS0_TRQ_R -0.5
param set-default CA_SV_CS0_TYPE 1
param set-default CA_SV_CS1_TRQ_R 0.5
@@ -1,4 +1,6 @@
mixer append /dev/pwm_output0 etc/mixers/mount_legs.aux.mix
mavlink start -x -u 14558 -r 4000 -f -m onboard -o 14530 -p
# shellcheck disable=SC2154
@@ -61,6 +61,8 @@ param set-default HIL_ACT_FUNC6 400
param set SYS_HITL 1
param set UAVCAN_ENABLE 0
# disable some checks to allow to fly
# - with usb
param set-default CBRK_USB_CHK 197848
@@ -0,0 +1,40 @@
#!/bin/sh
#
# @name Steadidrone QU4D
#
# @type Quadrotor Wide
# @class Copter
#
# @output MAIN1 motor 1
# @output MAIN2 motor 2
# @output MAIN3 motor 3
# @output MAIN4 motor 4
# @output MAIN5 feed-through of RC AUX1 channel
# @output MAIN6 feed-through of RC AUX2 channel
#
# @output AUX1 feed-through of RC AUX1 channel
# @output AUX2 feed-through of RC AUX2 channel
# @output AUX3 feed-through of RC AUX3 channel
# @output AUX4 feed-through of RC FLAPS channel
#
# @maintainer Lorenz Meier <lorenz@px4.io>
#
# @board px4_fmu-v2 exclude
# @board bitcraze_crazyflie exclude
#
. ${R}etc/init.d/rc.mc_defaults
param set-default BAT1_N_CELLS 4
param set-default MC_ROLL_P 7
param set-default MC_ROLLRATE_P 0.13
param set-default MC_ROLLRATE_I 0.05
param set-default MC_ROLLRATE_D 0.004
param set-default MC_PITCH_P 7
param set-default MC_PITCHRATE_P 0.19
param set-default MC_PITCHRATE_I 0.05
param set-default MC_PITCHRATE_D 0.004
param set-default MC_YAW_P 4
set MIXER quad_w
@@ -15,6 +15,8 @@ set MIXER quad_x
param set SYS_HITL 1
param set UAVCAN_ENABLE 0
param set-default CA_ROTOR_COUNT 4
param set-default CA_ROTOR0_PX 0.15
param set-default CA_ROTOR0_PY 0.15
@@ -94,6 +94,8 @@ param set-default HIL_ACT_FUNC8 203
param set SYS_HITL 1
param set UAVCAN_ENABLE 0
# disable some checks to allow to fly
# - with usb
param set-default CBRK_USB_CHK 197848
@@ -0,0 +1,48 @@
#!/bin/sh
#
# @name Steadidrone MAVRIK
#
# @type Octo Coax Wide
# @class Copter
#
# @output MAIN1 motor 1
# @output MAIN2 motor 2
# @output MAIN3 motor 3
# @output MAIN4 motor 4
# @output MAIN5 motor 5
# @output MAIN6 motor 6
# @output MAIN7 motor 7
# @output MAIN8 motor 8
#
# @maintainer Simon Wilks <simon@uaventure.com>
#
# @board px4_fmu-v2 exclude
# @board bitcraze_crazyflie exclude
#
. ${R}etc/init.d/rc.mc_defaults
param set-default MC_PITCH_P 4
param set-default MC_PITCHRATE_P 0.24
param set-default MC_PITCHRATE_I 0.09
param set-default MC_PITCHRATE_D 0.013
param set-default MC_PITCHRATE_MAX 180
param set-default MC_ROLL_P 4
param set-default MC_ROLLRATE_P 0.16
param set-default MC_ROLLRATE_I 0.07
param set-default MC_ROLLRATE_D 0.009
param set-default MC_ROLLRATE_MAX 180
param set-default MC_YAW_P 3
param set-default MPC_HOLD_MAX_XY 0.25
param set-default MPC_THR_MIN 0.15
param set-default MPC_Z_VEL_MAX_DN 2
param set-default BAT1_N_CELLS 4
set MIXER octo_cox_w
set PWM_OUT 12345678
@@ -0,0 +1,37 @@
#!/bin/sh
#
# @name CruiseAder Claire
#
# @type VTOL Tiltrotor
# @class VTOL
#
# @maintainer Samay Siga <samay_s@icloud.com>
#
# @board px4_fmu-v2 exclude
# @board bitcraze_crazyflie exclude
#
. ${R}etc/init.d/rc.vtol_defaults
param set-default MAV_TYPE 21
param set-default PWM_AUX_DISARM 1000
param set-default PWM_AUX_MAX 2000
param set-default PWM_AUX_MIN 1000
param set-default PWM_AUX_RATE 50
param set-default PWM_MAIN_MAX 2000
param set-default VT_MOT_ID 1234
param set-default VT_FW_MOT_OFFID 13
param set-default VT_IDLE_PWM_MC 1080
param set-default VT_TILT_FW 0.9
param set-default VT_TILT_MC 0.08
param set-default VT_TILT_TRANS 0.5
param set-default VT_ELEV_MC_LOCK 0
param set-default VT_TYPE 1
set MIXER claire
set MIXER_AUX claire
set PWM_OUT 1234
@@ -69,9 +69,4 @@ param set-default VT_TYPE 1
set MIXER vtol_convergence
if ! ver hwcmp MATEK_H743
then
set PWM_OUT 1234
else
set PWM_OUT 3456
fi
set PWM_OUT 1234
@@ -131,6 +131,7 @@ param set-default VT_F_TRANS_DUR 1
param set-default VT_IDLE_PWM_MC 1025
param set-default VT_B_REV_OUT 0.5
param set-default VT_B_TRANS_THR 0.7
param set-default VT_FW_PERM_STAB 1
param set-default VT_TRANS_TIMEOUT 22
param set-default VT_F_TRANS_RAMP 4
@@ -0,0 +1,45 @@
#!/bin/sh
#
# @name IO Camflyer
#
# @type Flying Wing
# @class Plane
#
# @output MAIN1 left aileron
# @output MAIN2 right aileron
# @output MAIN4 throttle
#
# @output AUX1 feed-through of RC AUX1 channel
# @output AUX2 feed-through of RC AUX2 channel
# @output AUX3 feed-through of RC AUX3 channel
#
# @maintainer Simon Wilks <simon@uaventure.com>
#
# @board px4_fmu-v2 exclude
# @board bitcraze_crazyflie exclude
#
. ${R}etc/init.d/rc.fw_defaults
param set-default FW_AIRSPD_MAX 15
param set-default FW_AIRSPD_TRIM 13
param set-default FW_R_TC 0.3
param set-default FW_P_TC 0.3
param set-default FW_L1_DAMPING 0.74
param set-default FW_L1_PERIOD 16
param set-default FW_LND_ANG 15
param set-default FW_LND_FLALT 5
param set-default FW_LND_HVIRT 13
param set-default FW_LND_TLALT 5
param set-default FW_THR_LND_MAX 0
param set-default FW_PR_FF 0.35
param set-default FW_RR_FF 0.6
param set-default FW_RR_P 0.04
param set-default PWM_MAIN_DISARM 1000
set MIXER fw_generic_wing
# Provide ESC a constant 1000 us pulse while disarmed
set PWM_OUT 4
@@ -0,0 +1,29 @@
#!/bin/sh
#
# @name FX-79 Buffalo Flying Wing
#
# @type Flying Wing
# @class Plane
#
# @output MAIN1 right aileron
# @output MAIN2 left aileron
# @output MAIN4 throttle
#
# @output AUX1 feed-through of RC AUX1 channel
# @output AUX2 feed-through of RC AUX2 channel
# @output AUX3 feed-through of RC AUX3 channel
#
# @maintainer Simon Wilks <simon@uaventure.com>
#
# @board px4_fmu-v2 exclude
# @board bitcraze_crazyflie exclude
#
. ${R}etc/init.d/rc.fw_defaults
param set-default FW_AIRSPD_MAX 30
param set-default FW_AIRSPD_MIN 13
param set-default NAV_LOITER_RAD 150
set MIXER fw_generic_wing
@@ -0,0 +1,23 @@
#!/bin/sh
#
# @name Viper
#
# @type Flying Wing
# @class Plane
# @output MAIN1 left aileron
# @output MAIN2 right aileron
# @output MAIN4 throttle
#
# @output AUX1 feed-through of RC AUX1 channel
# @output AUX2 feed-through of RC AUX2 channel
# @output AUX3 feed-through of RC AUX3 channel
#
# @maintainer Simon Wilks <simon@uaventure.com>
#
# @board px4_fmu-v2 exclude
# @board bitcraze_crazyflie exclude
#
. ${R}etc/init.d/rc.fw_defaults
set MIXER Viper
@@ -0,0 +1,53 @@
#!/bin/sh
#
# @name Modified Parrot Disco
#
# @url
#
# @type Flying Wing
# @class Plane
#
# @output MAIN1 left aileron
# @output MAIN2 right aileron
# @output MAIN4 throttle
#
# @output AUX1 feed-through of RC AUX1 channel
# @output AUX2 feed-through of RC AUX2 channel
# @output AUX3 feed-through of RC AUX3 channel
#
# @maintainer Jan Liphardt <JTLiphardt@gmail.com>
#
# @board px4_fmu-v2 exclude
# @board bitcraze_crazyflie exclude
#
. ${R}etc/init.d/rc.fw_defaults
####################################
# Airspeed
####################################
param set-default FW_AIRSPD_MAX 27 # = 52 knots
####################################
# Pitch
####################################
# Pitch rate feed forward (def = 0.5 %/rad/sec)
param set-default FW_PR_FF 0.35
####################################
# Roll
####################################
# Basic limits (def = 50 deg)
param set-default FW_R_LIM 40
# Roll rate upper limit (def = 70 deg/s)
param set-default FW_R_RMAX 50
param set-default PWM_MAIN_DISARM 1000
set MIXER fw_generic_wing.main.mix
# Provide ESC a constant 1000 us pulse
set PWM_OUT 4
@@ -0,0 +1,21 @@
#!/bin/sh
#
# @name DJI F330 w/ DJI ESCs
#
# @type Quadrotor x
# @class Copter
#
# @maintainer Lorenz Meier <lorenz@px4.io>
# @board px4_fmu-v2 exclude
#
. ${R}etc/init.d/rc.mc_defaults
param set-default MC_ROLL_P 7
param set-default MC_ROLLRATE_I 0.05
param set-default MC_PITCH_P 7
param set-default MC_PITCHRATE_I 0.05
# DJI ESCs do not support calibration and need a higher min
param set-default PWM_MAIN_MIN 1230
@@ -0,0 +1,20 @@
#!/bin/sh
#
# @name DJI F450 w/ DJI ESCs
#
# @type Quadrotor x
# @class Copter
#
# @maintainer Lorenz Meier <lorenz@px4.io>
#
. ${R}etc/init.d/rc.mc_defaults
param set-default MC_ROLL_P 7
param set-default MC_ROLLRATE_I 0.05
param set-default MC_PITCH_P 7
param set-default MC_PITCHRATE_I 0.05
param set-default MC_YAWRATE_P 0.3
# DJI ESCs do not support calibration and need a higher min
param set-default PWM_MAIN_MIN 1230
@@ -0,0 +1,27 @@
#!/bin/sh
#
# @name DJI Matrice 100
#
# @type Quadrotor x
# @class Copter
#
# @maintainer James Goppert <james.goppert@gmail.com>
#
# @board px4_fmu-v2 exclude
# @board bitcraze_crazyflie exclude
#
. ${R}etc/init.d/rc.mc_defaults
param set-default BAT1_N_CELLS 6
param set-default MC_ROLLRATE_P 0.05
param set-default MC_ROLLRATE_I 0.05
param set-default MC_ROLLRATE_D 0.001
param set-default MC_PITCHRATE_P 0.05
param set-default MC_PITCHRATE_I 0.05
param set-default MC_PITCHRATE_D 0.001
param set-default MC_YAWRATE_I 0
param set-default PWM_MAIN_MIN 1200
@@ -52,16 +52,22 @@ px4_add_romfs_files(
# [3000, 3999] Flying wing"
3000_generic_wing
3030_io_camflyer
3031_phantom
3032_skywalker_x5
3033_wingwing
3034_fx79
3035_viper
3036_pigeon
3037_parrot_disco_mod
3100_tbs_caipirinha
# [4000, 4999] Quadrotor x"
4001_quad_x
4003_qavr5
4009_qav250
4010_dji_f330
4011_dji_f450
4014_s500
4015_holybro_s500
4016_holybro_px4vision
@@ -75,6 +81,7 @@ px4_add_romfs_files(
4051_s250aq
4052_holybro_qav250
4053_holybro_kopis2
4060_dji_matrice_100
4061_atl_mantis_edu
4071_ifo
4072_draco
@@ -105,6 +112,7 @@ px4_add_romfs_files(
# [10000, 10999] Quadrotor Wide arm / H frame"
10015_tbs_discovery
10016_3dr_iris
10017_steadidrone_qu4d
10018_tbs_endurance
# [11000, 11999] Hexa Cox
@@ -112,6 +120,7 @@ px4_add_romfs_files(
# [12000, 12999] Octo Cox
12001_octo_cox
12002_steadidrone_mavrik
# [13000, 13999] VTOL
13000_generic_vtol_standard
@@ -124,6 +133,7 @@ px4_add_romfs_files(
13007_vtol_AAVVT_quad
13008_QuadRanger
13009_vtol_spt_ranger
13010_claire
13012_convergence
13013_deltaquad
13014_vtol_babyshark
-24
View File
@@ -181,30 +181,6 @@ then
pcf8583 start -X -a 0x51
fi
# INA226 digital power monitor
if param compare SENS_EN_INA226 1
then
ina226 -X start
fi
# INA228 digital power monitor
if param compare SENS_EN_INA228 1
then
ina228 -X start
fi
# INA231 digital power monitor
if param compare SENS_EN_INA231 1
then
ina231 -X start
fi
# INA238 digital power monitor
if param compare SENS_EN_INA238 1
then
ina238 -X start
fi
# probe for optional external I2C devices
if param compare SENS_EXT_I2C_PRB 1
then
+2 -2
View File
@@ -298,9 +298,9 @@ else
tune_control play error
fi
else
if param greater -s CYPHAL_ENABLE 0
if param greater -s UAVCAN_V1_ENABLE 0
then
cyphal start
uavcan_v1 start
fi
fi
@@ -21,16 +21,14 @@ O: 10000 10000 0 -10000 10000
S: 0 3 0 20000 -10000 -10000 10000
# mixer for the left aileron
M: 2
M: 1
O: 10000 10000 0 -10000 10000
S: 0 0 -10000 -10000 0 -10000 10000
S: 0 5 10000 10000 0 -10000 10000
# mixer for the right aileron
M: 2
M: 1
O: 10000 10000 0 -10000 10000
S: 0 0 10000 10000 0 -10000 10000
S: 0 5 10000 10000 0 -10000 10000
# mixer for the elevator
M: 1
@@ -8,22 +8,22 @@ R: 4x
# tilt servo motor 1
M: 1
O: 10000 10000 0 -10000 10000
S: 1 8 0 20000 -10000 -10000 10000
S: 1 4 0 20000 -10000 -10000 10000
# tilt servo motor 2
M: 1
O: 10000 10000 0 -10000 10000
S: 1 8 0 20000 -10000 -10000 10000
S: 1 4 0 20000 -10000 -10000 10000
# tilt servo motor 3
M: 1
O: 10000 10000 0 -10000 10000
S: 1 8 0 20000 -10000 -10000 10000
S: 1 4 0 20000 -10000 -10000 10000
# tilt servo motor 4
M: 1
O: 10000 10000 0 -10000 10000
S: 1 8 0 20000 -10000 -10000 10000
S: 1 4 0 20000 -10000 -10000 10000
# mixer for the left aileron
M: 1
+3 -3
View File
@@ -10,7 +10,7 @@ to output 4 and the wheel to output 5.
Inputs to the mixer come from channel group 0 (vehicle attitude), channels 0
(roll), 1 (pitch), 2 (yaw) and 3 (thrust) 4 (flaps).
Aileron mixer (roll + spoiler)
Aileron mixer (roll + flaperon)
---------------------------------
This mixer assumes that the aileron servos are set up correctly mechanically;
@@ -20,11 +20,11 @@ endpoints to suit.
M: 2
S: 0 0 10000 10000 0 -10000 10000
S: 0 5 10000 10000 0 -10000 10000
S: 0 6 10000 10000 0 -10000 10000
M: 2
S: 0 0 10000 10000 0 -10000 10000
S: 0 5 -10000 -10000 0 -10000 10000
S: 0 6 -10000 -10000 0 -10000 10000
Elevator mixer
------------
+3 -3
View File
@@ -11,7 +11,7 @@ to output 4, the wheel to output 5 and the flaps to output 6 and 7.
Inputs to the mixer come from channel group 0 (vehicle attitude), channels 0
(roll), 1 (pitch), 2 (yaw) and 3 (thrust) 4 (flaps) 6 (flaperon).
Aileron mixer (roll + spoiler)
Aileron mixer (roll + flaperon)
---------------------------------
This mixer assumes that the aileron servos are set up correctly mechanically;
@@ -21,11 +21,11 @@ endpoints to suit.
M: 2
S: 0 0 10000 10000 0 -10000 10000
S: 0 5 10000 10000 0 -10000 10000
S: 0 6 10000 10000 0 -10000 10000
M: 2
S: 0 0 10000 10000 0 -10000 10000
S: 0 5 -10000 -10000 0 -10000 10000
S: 0 6 -10000 -10000 0 -10000 10000
V-tail mixers
-------------
@@ -9,20 +9,20 @@ output 0 and 1, the tail servos to output 2 and 3, the throttle
to output 4, the wheel to output 5 and the flaps to output 6 and 7.
Inputs to the mixer come from channel group 0 (vehicle attitude), channels 0
(roll), 1 (pitch), 2 (yaw), 3 (thrust) 4 (flaps), 5 (spoiler).
(roll), 1 (pitch), 2 (yaw) and 3 (thrust) 4 (flaps) 6 (flaperon).
Aileron mixer (roll + spoiler)
Aileron mixer (roll + flaperon)
---------------------------------
This mixer assumes that the aileron servos are set up mechanically reversed.
M: 2
S: 0 0 -10000 -10000 0 -10000 10000
S: 0 5 10000 10000 0 -10000 10000
S: 0 6 10000 10000 0 -10000 10000
M: 2
S: 0 0 -10000 -10000 0 -10000 10000
S: 0 5 -10000 -10000 0 -10000 10000
S: 0 6 -10000 -10000 0 -10000 10000
V-tail mixers
-------------
@@ -40,6 +40,8 @@ px4_add_romfs_files(
babyshark.main.mix
blade130.main.mix
CCPM.main.mix
claire.aux.mix
claire.main.mix
cloudship.main.mix
coax.main.mix
delta.main.mix
@@ -81,6 +83,7 @@ px4_add_romfs_files(
tri_y_yaw-.main.mix
uuv_x.main.mix
vectored6dof.main.mix
Viper.main.mix
vtol_AAERT.aux.mix
vtol_AAVVT.aux.mix
vtol_TTTTAAER.aux.mix
+66
View File
@@ -0,0 +1,66 @@
Viper Delta-wing mixer
=================================
# @board px4_fmu-v2 exclude
Designed for Viper.
TODO (sjwilks): Add mixers for flaps.
This file defines mixers suitable for controlling a delta wing aircraft using
PX4FMU. The configuration assumes the elevon servos are connected to PX4FMU
servo outputs 0 and 1 and the motor speed control to output 3. Output 2 is
assumed to be unused.
Inputs to the mixer come from channel group 0 (vehicle attitude), channels 0
(roll), 1 (pitch) and 3 (thrust).
See the README for more information on the scaler format.
Elevon mixers
-------------
Three scalers total (output, roll, pitch).
On the assumption that the two elevon servos are physically reversed, the pitch
input is inverted between the two servos.
The scaling factor for roll inputs is adjusted to implement differential travel
for the elevons.
M: 2
S: 0 0 7500 7500 0 -10000 10000
S: 0 1 8000 8000 0 -10000 10000
M: 2
S: 0 0 7500 7500 0 -10000 10000
S: 0 1 -8000 -8000 0 -10000 10000
Output 2
--------
This mixer is empty.
Z:
Motor speed mixer
-----------------
Two scalers total (output, thrust).
This mixer generates a full-range output (-1 to 1) from an input in the (0 - 1)
range. Inputs below zero are treated as zero.
M: 1
S: 0 3 0 20000 -10000 -10000 10000
Inputs to the mixer come from channel group 2 (payload), channels 0
(bay servo 1), 1 (bay servo 2) and 3 (drop release).
-----------------------------------------------------
M: 1
S: 2 0 10000 10000 0 -10000 10000
M: 1
S: 2 1 10000 10000 0 -10000 10000
M: 1
S: 2 2 -8000 -8000 0 -10000 10000
+28
View File
@@ -0,0 +1,28 @@
# mixer for the CruiseAder Claire tilt mechansim servo and elevons
=======================================================================
Tilt mechanism servo mixer
---------------------------
M: 1
S: 1 4 10000 10000 0 -10000 10000
Elevon mixers
-------------
M: 2
S: 1 0 7500 7500 0 -10000 10000
S: 1 1 7500 7500 0 -10000 10000
M: 2
S: 1 0 7500 7500 0 -10000 10000
S: 1 1 -7500 -7500 0 -10000 10000
@@ -0,0 +1,8 @@
# CruiseAder Claire Main Multirotor mixer for PX4FMU
# @board px4_fmu-v2 exclude
#
#===========================
R: 4x
+1 -1
View File
@@ -6,7 +6,7 @@
Tilt mechanism servo mixer
---------------------------
M: 1
S: 1 8 0 20000 -10000 -10000 10000
S: 1 4 0 20000 -10000 -10000 10000
Elevon mixers
-------------
@@ -5,14 +5,14 @@ Aileron/v-tail/throttle VTOL mixer for PX4FMU
This file defines mixers suitable for controlling a fixed wing aircraft with
aileron, v-tail (rudder, elevator) and throttle using PX4FMU.
The configuration assumes the aileron servos are connected to PX4FMU
The configuration assumes the aileron servos are connected to PX4FMU
AUX servo output 0 and 1, the tail servos to output 2 and 3, the throttle
to output 4.
Inputs to the mixer come from channel group 0 (vehicle attitude), channels 0
(roll), 1 (pitch), 2 (yaw) and 3 (thrust) 4 (flaps) 6 (flaperon).
Aileron mixer (roll + spoiler)
Aileron mixer (roll + flaperon)
---------------------------------
This mixer assumes that the aileron servos are set up correctly mechanically;
@@ -22,11 +22,11 @@ endpoints to suit.
M: 2
S: 1 0 -10000 -10000 0 -10000 10000
S: 1 5 10000 10000 0 -10000 10000
S: 1 6 10000 10000 0 -10000 10000
M: 2
S: 1 0 -10000 -10000 0 -10000 10000
S: 1 5 -10000 -10000 0 -10000 10000
S: 1 6 -10000 -10000 0 -10000 10000
V-tail mixers
@@ -6,19 +6,19 @@
---------------------------
# front left up:2000 down:1000
M: 1
S: 1 8 0 -20000 10000 -10000 10000
S: 1 4 0 -20000 10000 -10000 10000
# front right up:1000 down:2000
M: 1
S: 1 8 0 20000 -10000 -10000 10000
S: 1 4 0 20000 -10000 -10000 10000
# rear left up:2000 down:1000
M: 1
S: 1 8 0 -20000 10000 -10000 10000
S: 1 4 0 -20000 10000 -10000 10000
# rear right up:1000 down:2000
M: 1
S: 1 8 0 20000 -10000 -10000 10000
S: 1 4 0 20000 -10000 -10000 10000
# Aileron mixer
@@ -10,12 +10,12 @@ Tilt mechanism servo mixer
---------------------------
#RIGHT up:2000 down:1000
M: 2
S: 1 8 0 -20000 10000 -10000 10000
S: 1 4 0 -20000 10000 -10000 10000
S: 0 2 8000 8000 0 -10000 10000
#LEFT up:1000 down:2000
M: 2
S: 1 8 0 20000 -10000 -10000 10000
S: 1 4 0 20000 -10000 -10000 10000
S: 0 2 8000 8000 0 -10000 10000
Elevon mixers
+3 -3
View File
@@ -10,7 +10,7 @@ to output 4 and the wheel to output 5.
Inputs to the mixer come from channel group 0 (vehicle attitude), channels 0
(roll), 1 (pitch), 2 (yaw) and 3 (thrust) 4 (flaps).
Aileron mixer (roll + spoiler)
Aileron mixer (roll + flaperon)
---------------------------------
This mixer assumes that the aileron servos are set up correctly mechanically;
@@ -21,12 +21,12 @@ endpoints to suit.
M: 2
O: 10000 10000 0 -10000 10000
S: 0 0 10000 10000 0 -10000 10000
S: 0 5 10000 10000 0 -10000 10000
S: 0 6 10000 10000 0 -10000 10000
M: 2
O: 10000 10000 0 -10000 10000
S: 0 0 10000 10000 0 -10000 10000
S: 0 5 -10000 -10000 0 -10000 10000
S: 0 6 -10000 -10000 0 -10000 10000
Elevator mixer
------------
+4 -4
View File
@@ -9,9 +9,9 @@ output 0 and 1, the tail servos to output 2 and 3, the throttle
to output 4, the wheel to output 5 and the flaps to output 6 and 7.
Inputs to the mixer come from channel group 0 (vehicle attitude), channels 0
(roll), 1 (pitch), 2 (yaw) and 3 (thrust) 4 (flaps) 5 (spoiler).
(roll), 1 (pitch), 2 (yaw) and 3 (thrust) 4 (flaps) 6 (flaperon).
Aileron mixer (roll + spoiler)
Aileron mixer (roll + flaperon)
---------------------------------
This mixer assumes that the aileron servos are set up correctly mechanically;
@@ -22,12 +22,12 @@ endpoints to suit.
M: 2
O: 10000 10000 0 -10000 10000
S: 0 0 10000 10000 0 -10000 10000
S: 0 5 10000 10000 0 -10000 10000
S: 0 6 10000 10000 0 -10000 10000
M: 2
O: 10000 10000 0 -10000 10000
S: 0 0 10000 10000 0 -10000 10000
S: 0 5 -10000 -10000 0 -10000 10000
S: 0 6 -10000 -10000 0 -10000 10000
V-tail mixers
-------------
+2 -2
View File
@@ -10,13 +10,13 @@ Tilt mechanism servo mixer
#RIGHT up:2000 down:1000
M: 2
O: 10000 10000 0 -10000 10000
S: 1 8 0 -20000 9000 -10000 10000
S: 1 4 0 -20000 9000 -10000 10000
S: 0 2 4000 4000 0 -10000 10000
#LEFT up:1000 down:2000
M: 2
O: 10000 10000 0 -10000 10000
S: 1 8 0 20000 -10000 -10000 10000
S: 1 4 0 20000 -10000 -10000 10000
S: 0 2 4000 4000 0 -10000 10000
Elevon mixers
+5 -5
View File
@@ -3,14 +3,14 @@ Aileron/v-tail/throttle VTOL mixer for PX4FMU
This file defines mixers suitable for controlling a fixed wing aircraft with
aileron, v-tail (rudder, elevator) and throttle using PX4FMU.
The configuration assumes the aileron servos are connected to PX4FMU
The configuration assumes the aileron servos are connected to PX4FMU
AUX servo output 0 and 1, the tail servos to output 2 and 3, the throttle
to output 4.
Inputs to the mixer come from channel group 0 (vehicle attitude), channels 0
(roll), 1 (pitch), 2 (yaw) and 3 (thrust) 4 (flaps) 5 (spoiler).
(roll), 1 (pitch), 2 (yaw) and 3 (thrust) 4 (flaps) 6 (flaperon).
Aileron mixer (roll + spoiler)
Aileron mixer (roll + flaperon)
---------------------------------
This mixer assumes that the aileron servos are set up correctly mechanically;
@@ -21,12 +21,12 @@ endpoints to suit.
M: 2
O: 10000 10000 0 -10000 10000
S: 1 0 10000 10000 0 -10000 10000
S: 1 5 10000 10000 0 -10000 10000
S: 1 6 10000 10000 0 -10000 10000
M: 2
O: 10000 10000 0 -10000 10000
S: 1 0 10000 10000 0 -10000 10000
S: 1 5 -10000 -10000 0 -10000 10000
S: 1 6 -10000 -10000 0 -10000 10000
V-tail mixers
@@ -10,13 +10,13 @@ Tilt mechanism servo mixer
#RIGHT up:2000 down:1000
M: 2
O: 10000 10000 0 -10000 10000
S: 1 8 0 -20000 10000 -10000 10000
S: 1 4 0 -20000 10000 -10000 10000
S: 0 2 8000 8000 0 -10000 10000
#LEFT up:1000 down:2000
M: 2
O: 10000 10000 0 -10000 10000
S: 1 8 0 20000 -10000 -10000 10000
S: 1 4 0 20000 -10000 -10000 10000
S: 0 2 8000 8000 0 -10000 10000
Elevon mixers
+2 -1
View File
@@ -13,7 +13,8 @@ exec find boards msg src platforms test \
-path platforms/qurt/dspal -prune -o \
-path src/drivers/uavcan/libuavcan -prune -o \
-path src/drivers/uavcan/uavcan_drivers/kinetis/driver/include/uavcan_kinetis -prune -o \
-path src/drivers/cyphal/libcanard -prune -o \
-path src/drivers/uavcan_v1/libcanard -prune -o \
-path src/drivers/uavcannode_gps_demo/libcanard -prune -o \
-path src/lib/crypto/monocypher -prune -o \
-path src/lib/events/libevents -prune -o \
-path src/lib/parameters/uthash -prune -o \
+18 -12
View File
@@ -11,7 +11,7 @@ from pyulog import ULog
from analysis.detectors import InAirDetector, PreconditionError
from analysis.metrics import calculate_ecl_ekf_metrics
from analysis.checks import perform_ecl_ekf_checks
from analysis.post_processing import get_estimator_check_flags
from analysis.post_processing import get_gps_check_fail_flags
def analyse_ekf(
ulog: ULog, check_levels: Dict[str, float], multi_instance: int = 0,
@@ -40,6 +40,11 @@ def analyse_ekf(
except:
raise PreconditionError('could not find estimator_status instance', multi_instance)
try:
estimator_status_flags = ulog.get_dataset('estimator_status_flags', multi_instance).data
except:
raise PreconditionError('could not find estimator_status_flags instance', multi_instance)
try:
_ = ulog.get_dataset('estimator_innovations', multi_instance).data
except:
@@ -61,14 +66,14 @@ def analyse_ekf(
'in_air_transition_time': round(in_air.take_off + in_air.log_start, 2),
'on_ground_transition_time': round(in_air.landing + in_air.log_start, 2)}
control_mode, innov_flags, gps_fail_flags = get_estimator_check_flags(estimator_status)
gps_fail_flags = get_gps_check_fail_flags(estimator_status)
sensor_checks, innov_fail_checks = find_checks_that_apply(
control_mode, estimator_status,
estimator_status_flags, estimator_status,
pos_checks_when_sensors_not_fused=pos_checks_when_sensors_not_fused)
metrics = calculate_ecl_ekf_metrics(
ulog, innov_flags, innov_fail_checks, sensor_checks, in_air, in_air_no_ground_effects,
ulog, estimator_status_flags, innov_fail_checks, sensor_checks, in_air, in_air_no_ground_effects,
multi_instance, red_thresh=red_thresh, amb_thresh=amb_thresh)
check_status, master_status = perform_ecl_ekf_checks(
@@ -78,12 +83,12 @@ def analyse_ekf(
def find_checks_that_apply(
control_mode: dict, estimator_status: dict, pos_checks_when_sensors_not_fused: bool = False) ->\
estimator_status_flags: dict, estimator_status: dict, pos_checks_when_sensors_not_fused: bool = False) ->\
Tuple[List[str], List[str]]:
"""
finds the checks that apply and stores them in lists for the std checks and the innovation
fail checks.
:param control_mode:
:param estimator_status_flags:
:param estimator_status:
:param b_pos_only_when_sensors_fused:
:return: a tuple of two lists that contain strings for the std checks and for the innovation
@@ -97,7 +102,7 @@ def find_checks_that_apply(
innov_fail_checks.append('posv')
# Magnetometer Sensor Checks
if (np.amax(control_mode['yaw_aligned']) > 0.5):
if (np.amax(estimator_status_flags['cs_yaw_align']) > 0.5):
sensor_checks.append('mag')
innov_fail_checks.append('magx')
@@ -106,13 +111,14 @@ def find_checks_that_apply(
innov_fail_checks.append('yaw')
# Velocity Sensor Checks
if (np.amax(control_mode['using_gps']) > 0.5):
if (np.amax(estimator_status_flags['cs_gps']) > 0.5):
sensor_checks.append('vel')
innov_fail_checks.append('vel')
innov_fail_checks.append('velh')
innov_fail_checks.append('velv')
# Position Sensor Checks
if (pos_checks_when_sensors_not_fused or (np.amax(control_mode['using_gps']) > 0.5)
or (np.amax(control_mode['using_evpos']) > 0.5)):
if (pos_checks_when_sensors_not_fused or (np.amax(estimator_status_flags['cs_gps']) > 0.5)
or (np.amax(estimator_status_flags['cs_ev_pos']) > 0.5)):
sensor_checks.append('pos')
innov_fail_checks.append('posh')
@@ -128,7 +134,7 @@ def find_checks_that_apply(
innov_fail_checks.append('hagl')
# optical flow sensor checks
if (np.amax(control_mode['using_optflow']) > 0.5):
if (np.amax(estimator_status_flags['cs_opt_flow']) > 0.5):
innov_fail_checks.append('ofx')
innov_fail_checks.append('ofy')
+2 -1
View File
@@ -123,7 +123,8 @@ def perform_sensor_innov_checks(
('magy', 'magy_fail_percentage', 'mag'),
('magz', 'magz_fail_percentage', 'mag'),
('yaw', 'yaw_fail_percentage', 'yaw'),
('vel', 'vel_fail_percentage', 'vel'),
('velh', 'vel_fail_percentage', 'vel'),
('velv', 'vel_fail_percentage', 'vel'),
('posh', 'pos_fail_percentage', 'pos'),
('tas', 'tas_fail_percentage', 'tas'),
('hagl', 'hagl_fail_percentage', 'hagl'),
+18 -17
View File
@@ -11,7 +11,7 @@ import numpy as np
from analysis.detectors import InAirDetector
def calculate_ecl_ekf_metrics(
ulog: ULog, innov_flags: Dict[str, float], innov_fail_checks: List[str],
ulog: ULog, estimator_status_flags: Dict[str, float], innov_fail_checks: List[str],
sensor_checks: List[str], in_air: InAirDetector, in_air_no_ground_effects: InAirDetector,
multi_instance: int = 0, red_thresh: float = 1.0, amb_thresh: float = 0.5) -> Tuple[dict, dict, dict, dict]:
@@ -20,7 +20,7 @@ def calculate_ecl_ekf_metrics(
red_thresh=red_thresh, amb_thresh=amb_thresh)
innov_fail_metrics = calculate_innov_fail_metrics(
innov_flags, innov_fail_checks, in_air, in_air_no_ground_effects)
estimator_status_flags, innov_fail_checks, in_air, in_air_no_ground_effects)
imu_metrics = calculate_imu_metrics(ulog, multi_instance, in_air_no_ground_effects)
@@ -90,10 +90,10 @@ def calculate_sensor_metrics(
def calculate_innov_fail_metrics(
innov_flags: dict, innov_fail_checks: List[str], in_air: InAirDetector,
estimator_status_flags: dict, innov_fail_checks: List[str], in_air: InAirDetector,
in_air_no_ground_effects: InAirDetector) -> dict:
"""
:param innov_flags:
:param estimator_status_flags:
:param innov_fail_checks:
:param in_air:
:param in_air_no_ground_effects:
@@ -103,17 +103,18 @@ def calculate_innov_fail_metrics(
innov_fail_metrics = dict()
# calculate innovation check fail metrics
for signal_id, signal, result in [('posv', 'posv_innov_fail', 'hgt_fail_percentage'),
('magx', 'magx_innov_fail', 'magx_fail_percentage'),
('magy', 'magy_innov_fail', 'magy_fail_percentage'),
('magz', 'magz_innov_fail', 'magz_fail_percentage'),
('yaw', 'yaw_innov_fail', 'yaw_fail_percentage'),
('vel', 'vel_innov_fail', 'vel_fail_percentage'),
('posh', 'posh_innov_fail', 'pos_fail_percentage'),
('tas', 'tas_innov_fail', 'tas_fail_percentage'),
('hagl', 'hagl_innov_fail', 'hagl_fail_percentage'),
('ofx', 'ofx_innov_fail', 'ofx_fail_percentage'),
('ofy', 'ofy_innov_fail', 'ofy_fail_percentage')]:
for signal_id, signal, result in [('posv', 'reject_ver_pos', 'hgt_fail_percentage'),
('magx', 'reject_mag_x', 'magx_fail_percentage'),
('magy', 'reject_mag_y', 'magy_fail_percentage'),
('magz', 'reject_mag_z', 'magz_fail_percentage'),
('yaw', 'reject_yaw', 'yaw_fail_percentage'),
('velh', 'reject_hor_vel', 'vel_fail_percentage'),
('velv', 'reject_ver_vel', 'vel_fail_percentage'),
('posh', 'reject_hor_pos', 'pos_fail_percentage'),
('tas', 'reject_airspeed', 'tas_fail_percentage'),
('hagl', 'reject_hagl', 'hagl_fail_percentage'),
('ofx', 'reject_optflow_x', 'ofx_fail_percentage'),
('ofy', 'reject_optflow_y', 'ofy_fail_percentage')]:
# only run innov fail checks, if they apply.
if signal_id in innov_fail_checks:
@@ -125,7 +126,7 @@ def calculate_innov_fail_metrics(
in_air_detector = in_air
innov_fail_metrics[result] = calculate_stat_from_signal(
innov_flags, 'estimator_status', signal, in_air_detector,
estimator_status_flags, 'estimator_status_flags', signal, in_air_detector,
lambda x: 100.0 * np.mean(x > 0.5))
return innov_fail_metrics
@@ -152,7 +153,7 @@ def calculate_imu_metrics(ulog: ULog, multi_instance, in_air_no_ground_effects:
if vehicle_imu_status_data['accel_device_id'][0] == estimator_status_data['accel_device_id'][0]:
for signal, result in [('delta_angle_coning_metric', 'imu_coning'),
for signal, result in [('gyro_coning_vibration', 'imu_coning'),
('gyro_vibration_metric', 'imu_hfgyro'),
('accel_vibration_metric', 'imu_hfaccel')]:
-109
View File
@@ -7,115 +7,6 @@ from typing import Tuple
import numpy as np
def get_estimator_check_flags(estimator_status: dict) -> Tuple[dict, dict, dict]:
"""
:param estimator_status:
:return:
"""
control_mode = get_control_mode_flags(estimator_status)
innov_flags = get_innovation_check_flags(estimator_status)
gps_fail_flags = get_gps_check_fail_flags(estimator_status)
return control_mode, innov_flags, gps_fail_flags
def get_control_mode_flags(estimator_status: dict) -> dict:
"""
:param estimator_status:
:return:
"""
control_mode = dict()
# extract control mode metadata from estimator_status.control_mode_flags
# 0 - true if the filter tilt alignment is complete
# 1 - true if the filter yaw alignment is complete
# 2 - true if GPS measurements are being fused
# 3 - true if optical flow measurements are being fused
# 4 - true if a simple magnetic yaw heading is being fused
# 5 - true if 3-axis magnetometer measurement are being fused
# 6 - true if synthetic magnetic declination measurements are being fused
# 7 - true when the vehicle is airborne
# 8 - true when wind velocity is being estimated
# 9 - true when baro height is being fused as a primary height reference
# 10 - true when range finder height is being fused as a primary height reference
# 11 - true when range finder height is being fused as a primary height reference
# 12 - true when local position data from external vision is being fused
# 13 - true when yaw data from external vision measurements is being fused
# 14 - true when height data from external vision measurements is being fused
# 15 - true when synthetic sideslip measurements are being fused
# 16 - true true when the mag field does not match the expected strength
# 17 - true true when the vehicle is operating as a fixed wing vehicle
# 18 - true when the magnetometer has been declared faulty and is no longer being used
# 19 - true true when airspeed measurements are being fused
# 20 - true true when protection from ground effect induced static pressure rise is active
# 21 - true when rng data wasn't ready for more than 10s and new rng values haven't changed enough
# 22 - true when yaw (not ground course) data from a GPS receiver is being fused
# 23 - true when the in-flight mag field alignment has been completed
# 24 - true when local earth frame velocity data from external vision measurements are being fused
# 25 - true when we are using a synthesized measurement for the magnetometer Z component
control_mode['tilt_aligned'] = ((2 ** 0 & estimator_status['control_mode_flags']) > 0) * 1
control_mode['yaw_aligned'] = ((2 ** 1 & estimator_status['control_mode_flags']) > 0) * 1
control_mode['using_gps'] = ((2 ** 2 & estimator_status['control_mode_flags']) > 0) * 1
control_mode['using_optflow'] = ((2 ** 3 & estimator_status['control_mode_flags']) > 0) * 1
control_mode['using_magyaw'] = ((2 ** 4 & estimator_status['control_mode_flags']) > 0) * 1
control_mode['using_mag3d'] = ((2 ** 5 & estimator_status['control_mode_flags']) > 0) * 1
control_mode['using_magdecl'] = ((2 ** 6 & estimator_status['control_mode_flags']) > 0) * 1
control_mode['airborne'] = ((2 ** 7 & estimator_status['control_mode_flags']) > 0) * 1
control_mode['estimating_wind'] = ((2 ** 8 & estimator_status['control_mode_flags']) > 0) * 1
control_mode['using_barohgt'] = ((2 ** 9 & estimator_status['control_mode_flags']) > 0) * 1
control_mode['using_rnghgt'] = ((2 ** 10 & estimator_status['control_mode_flags']) > 0) * 1
control_mode['using_gpshgt'] = ((2 ** 11 & estimator_status['control_mode_flags']) > 0) * 1
control_mode['using_evpos'] = ((2 ** 12 & estimator_status['control_mode_flags']) > 0) * 1
control_mode['using_evyaw'] = ((2 ** 13 & estimator_status['control_mode_flags']) > 0) * 1
control_mode['using_evhgt'] = ((2 ** 14 & estimator_status['control_mode_flags']) > 0) * 1
control_mode['fuse_beta'] = ((2 ** 15 & estimator_status['control_mode_flags']) > 0) * 1
control_mode['mag_field_disturbed'] = ((2 ** 16 & estimator_status['control_mode_flags']) > 0) * 1
control_mode['fixed_wing'] = ((2 ** 17 & estimator_status['control_mode_flags']) > 0) * 1
control_mode['mag_fault'] = ((2 ** 18 & estimator_status['control_mode_flags']) > 0) * 1
control_mode['fuse_aspd'] = ((2 ** 19 & estimator_status['control_mode_flags']) > 0) * 1
control_mode['gnd_effect'] = ((2 ** 20 & estimator_status['control_mode_flags']) > 0) * 1
control_mode['rng_stuck'] = ((2 ** 21 & estimator_status['control_mode_flags']) > 0) * 1
control_mode['gps_yaw'] = ((2 ** 22 & estimator_status['control_mode_flags']) > 0) * 1
control_mode['mag_aligned_in_flight'] = ((2 ** 23 & estimator_status['control_mode_flags']) > 0) * 1
control_mode['ev_vel'] = ((2 ** 24 & estimator_status['control_mode_flags']) > 0) * 1
control_mode['synthetic_mag_z'] = ((2 ** 25 & estimator_status['control_mode_flags']) > 0) * 1
return control_mode
def get_innovation_check_flags(estimator_status: dict) -> dict:
"""
:param estimator_status:
:return:
"""
innov_flags = dict()
# innovation_check_flags summary
# 0 - true if velocity observations have been rejected
# 1 - true if horizontal position observations have been rejected
# 2 - true if true if vertical position observations have been rejected
# 3 - true if the X magnetometer observation has been rejected
# 4 - true if the Y magnetometer observation has been rejected
# 5 - true if the Z magnetometer observation has been rejected
# 6 - true if the yaw observation has been rejected
# 7 - true if the airspeed observation has been rejected
# 8 - true if synthetic sideslip observation has been rejected
# 9 - true if the height above ground observation has been rejected
# 10 - true if the X optical flow observation has been rejected
# 11 - true if the Y optical flow observation has been rejected
innov_flags['vel_innov_fail'] = ((2 ** 0 & estimator_status['innovation_check_flags']) > 0) * 1
innov_flags['posh_innov_fail'] = ((2 ** 1 & estimator_status['innovation_check_flags']) > 0) * 1
innov_flags['posv_innov_fail'] = ((2 ** 2 & estimator_status['innovation_check_flags']) > 0) * 1
innov_flags['magx_innov_fail'] = ((2 ** 3 & estimator_status['innovation_check_flags']) > 0) * 1
innov_flags['magy_innov_fail'] = ((2 ** 4 & estimator_status['innovation_check_flags']) > 0) * 1
innov_flags['magz_innov_fail'] = ((2 ** 5 & estimator_status['innovation_check_flags']) > 0) * 1
innov_flags['yaw_innov_fail'] = ((2 ** 6 & estimator_status['innovation_check_flags']) > 0) * 1
innov_flags['tas_innov_fail'] = ((2 ** 7 & estimator_status['innovation_check_flags']) > 0) * 1
innov_flags['sli_innov_fail'] = ((2 ** 8 & estimator_status['innovation_check_flags']) > 0) * 1
innov_flags['hagl_innov_fail'] = ((2 ** 9 & estimator_status['innovation_check_flags']) > 0) * 1
innov_flags['ofx_innov_fail'] = ((2 ** 10 & estimator_status['innovation_check_flags']) > 0) * 1
innov_flags['ofy_innov_fail'] = ((2 ** 11 & estimator_status['innovation_check_flags']) > 0) * 1
return innov_flags
def get_gps_check_fail_flags(estimator_status: dict) -> dict:
"""
:param estimator_status:
+34 -28
View File
@@ -11,7 +11,7 @@ import numpy as np
from matplotlib.backends.backend_pdf import PdfPages
from pyulog import ULog
from analysis.post_processing import magnetic_field_estimates_from_states, get_estimator_check_flags
from analysis.post_processing import magnetic_field_estimates_from_states, get_gps_check_fail_flags
from plotting.data_plots import TimeSeriesPlot, InnovationPlot, ControlModeSummaryPlot, \
CheckFlagsPlot
from analysis.detectors import PreconditionError
@@ -33,6 +33,11 @@ def create_pdf_report(ulog: ULog, multi_instance: int, output_plot_filename: str
except:
raise PreconditionError('could not find estimator_status instance', multi_instance)
try:
estimator_status_flags = ulog.get_dataset('estimator_status_flags', multi_instance).data
except:
raise PreconditionError('could not find estimator_status_flags instance', multi_instance)
try:
estimator_states = ulog.get_dataset('estimator_states', multi_instance).data
except:
@@ -68,12 +73,13 @@ def create_pdf_report(ulog: ULog, multi_instance: int, output_plot_filename: str
except:
raise PreconditionError('could not find innovation data')
control_mode, innov_flags, gps_fail_flags = get_estimator_check_flags(estimator_status)
gps_fail_flags = get_gps_check_fail_flags(estimator_status)
status_time = 1e-6 * estimator_status['timestamp']
status_flags_time = 1e-6 * estimator_status_flags['timestamp']
b_finishes_in_air, b_starts_in_air, in_air_duration, in_air_transition_time, \
on_ground_transition_time = detect_airtime(control_mode, status_time)
on_ground_transition_time = detect_airtime(estimator_status_flags, status_flags_time)
with PdfPages(output_plot_filename) as pdf_pages:
@@ -173,9 +179,9 @@ def create_pdf_report(ulog: ULog, multi_instance: int, output_plot_filename: str
# plot control mode summary A
data_plot = ControlModeSummaryPlot(
status_time, control_mode, [['tilt_aligned', 'yaw_aligned'],
['using_gps', 'using_optflow', 'using_evpos'], ['using_barohgt', 'using_gpshgt',
'using_rnghgt', 'using_evhgt'], ['using_magyaw', 'using_mag3d', 'using_magdecl']],
status_flags_time, estimator_status_flags, [['cs_tilt_align', 'cs_yaw_align'],
['cs_gps', 'cs_opt_flow', 'cs_ev_pos'], ['cs_baro_hgt', 'cs_gps_hgt',
'cs_rng_hgt', 'cs_ev_hgt'], ['cs_mag_hdg', 'cs_mag_3d', 'cs_mag_dec']],
x_label='time (sec)', y_labels=['aligned', 'pos aiding', 'hgt aiding', 'mag aiding'],
annotation_text=[['tilt alignment', 'yaw alignment'], ['GPS aiding', 'optical flow aiding',
'external vision aiding'], ['Baro aiding', 'GPS aiding', 'rangefinder aiding',
@@ -188,7 +194,7 @@ def create_pdf_report(ulog: ULog, multi_instance: int, output_plot_filename: str
# plot control mode summary B
# construct additional annotations for the airborne plot
airborne_annotations = list()
if np.amin(np.diff(control_mode['airborne'])) > -0.5:
if np.amin(np.diff(estimator_status_flags['cs_in_air'])) > -0.5:
airborne_annotations.append(
(on_ground_transition_time, 'air to ground transition not detected'))
else:
@@ -197,7 +203,7 @@ def create_pdf_report(ulog: ULog, multi_instance: int, output_plot_filename: str
if in_air_duration > 0.0:
airborne_annotations.append(((in_air_transition_time + on_ground_transition_time) / 2,
'duration = {:.1f} sec'.format(in_air_duration)))
if np.amax(np.diff(control_mode['airborne'])) < 0.5:
if np.amax(np.diff(estimator_status_flags['cs_in_air'])) < 0.5:
airborne_annotations.append(
(in_air_transition_time, 'ground to air transition not detected'))
else:
@@ -205,7 +211,7 @@ def create_pdf_report(ulog: ULog, multi_instance: int, output_plot_filename: str
(in_air_transition_time, 'in-air at {:.1f} sec'.format(in_air_transition_time)))
data_plot = ControlModeSummaryPlot(
status_time, control_mode, [['airborne'], ['estimating_wind']],
status_flags_time, estimator_status_flags, [['cs_in_air'], ['cs_wind']],
x_label='time (sec)', y_labels=['airborne', 'estimating wind'], annotation_text=[[], []],
additional_annotation=[airborne_annotations, []],
plot_title='EKF Control Status - Figure B', pdf_handle=pdf_pages)
@@ -214,15 +220,15 @@ def create_pdf_report(ulog: ULog, multi_instance: int, output_plot_filename: str
# plot innovation_check_flags summary
data_plot = CheckFlagsPlot(
status_time, innov_flags, [['vel_innov_fail', 'posh_innov_fail'], ['posv_innov_fail',
'hagl_innov_fail'],
['magx_innov_fail', 'magy_innov_fail', 'magz_innov_fail',
'yaw_innov_fail'], ['tas_innov_fail'], ['sli_innov_fail'],
['ofx_innov_fail',
'ofy_innov_fail']], x_label='time (sec)',
status_flags_time, estimator_status_flags, [['reject_hor_vel', 'reject_hor_pos'], ['reject_ver_vel', 'reject_ver_pos',
'reject_hagl'],
['reject_mag_x', 'reject_mag_y', 'reject_mag_z',
'reject_yaw'], ['reject_airspeed'], ['reject_sideslip'],
['reject_optflow_x',
'reject_optflow_y']], x_label='time (sec)',
y_labels=['failed', 'failed', 'failed', 'failed', 'failed', 'failed'],
y_lim=(-0.1, 1.1),
legend=[['vel NED', 'pos NE'], ['hgt absolute', 'hgt above ground'],
legend=[['vel NE', 'pos NE'], ['vel D', 'hgt absolute', 'hgt above ground'],
['mag_x', 'mag_y', 'mag_z', 'yaw'], ['airspeed'], ['sideslip'],
['flow X', 'flow Y']],
plot_title='EKF Innovation Test Fails', annotate=False, pdf_handle=pdf_pages)
@@ -344,33 +350,33 @@ def create_pdf_report(ulog: ULog, multi_instance: int, output_plot_filename: str
data_plot.close()
def detect_airtime(control_mode, status_time):
def detect_airtime(estimator_status_flags, status_flags_time):
# define flags for starting and finishing in air
b_starts_in_air = False
b_finishes_in_air = False
# calculate in-air transition time
if (np.amin(control_mode['airborne']) < 0.5) and (np.amax(control_mode['airborne']) > 0.5):
in_air_transtion_time_arg = np.argmax(np.diff(control_mode['airborne']))
in_air_transition_time = status_time[in_air_transtion_time_arg]
elif (np.amax(control_mode['airborne']) > 0.5):
in_air_transition_time = np.amin(status_time)
if (np.amin(estimator_status_flags['cs_in_air']) < 0.5) and (np.amax(estimator_status_flags['cs_in_air']) > 0.5):
in_air_transtion_time_arg = np.argmax(np.diff(estimator_status_flags['cs_in_air']))
in_air_transition_time = status_flags_time[in_air_transtion_time_arg]
elif (np.amax(estimator_status_flags['cs_in_air']) > 0.5):
in_air_transition_time = np.amin(status_flags_time)
print('log starts while in-air at ' + str(round(in_air_transition_time, 1)) + ' sec')
b_starts_in_air = True
else:
in_air_transition_time = float('NaN')
print('always on ground')
# calculate on-ground transition time
if (np.amin(np.diff(control_mode['airborne'])) < 0.0):
on_ground_transition_time_arg = np.argmin(np.diff(control_mode['airborne']))
on_ground_transition_time = status_time[on_ground_transition_time_arg]
elif (np.amax(control_mode['airborne']) > 0.5):
on_ground_transition_time = np.amax(status_time)
if (np.amin(np.diff(estimator_status_flags['cs_in_air'])) < 0.0):
on_ground_transition_time_arg = np.argmin(np.diff(estimator_status_flags['cs_in_air']))
on_ground_transition_time = status_flags_time[on_ground_transition_time_arg]
elif (np.amax(estimator_status_flags['cs_in_air']) > 0.5):
on_ground_transition_time = np.amax(status_flags_time)
print('log finishes while in-air at ' + str(round(on_ground_transition_time, 1)) + ' sec')
b_finishes_in_air = True
else:
on_ground_transition_time = float('NaN')
print('always on ground')
if (np.amax(np.diff(control_mode['airborne'])) > 0.5) and (np.amin(np.diff(control_mode['airborne'])) < -0.5):
if (np.amax(np.diff(estimator_status_flags['cs_in_air'])) > 0.5) and (np.amin(np.diff(estimator_status_flags['cs_in_air'])) < -0.5):
if ((on_ground_transition_time - in_air_transition_time) > 0.0):
in_air_duration = on_ground_transition_time - in_air_transition_time
else:
+5 -14
View File
@@ -200,12 +200,13 @@ if [[ $INSTALL_SIM == "true" ]]; then
if [[ "${UBUNTU_RELEASE}" == "18.04" ]]; then
java_version=11
gazebo_version=9
elif [[ "${UBUNTU_RELEASE}" == "20.04" ]]; then
java_version=13
elif [[ "${UBUNTU_RELEASE}" == "22.04" ]]; then
java_version=11
gazebo_version=11
else
java_version=14
gazebo_version=11
fi
# Java (jmavsim or fastrtps)
sudo DEBIAN_FRONTEND=noninteractive apt-get -y --quiet --no-install-recommends install \
@@ -219,30 +220,20 @@ if [[ $INSTALL_SIM == "true" ]]; then
sudo update-alternatives --set java $(update-alternatives --list java | grep "java-$java_version")
# Gazebo
if [[ "${UBUNTU_RELEASE}" == "18.04" ]]; then
gazebo_version=9
gazebo_packages="gazebo$gazebo_version libgazebo$gazebo_version-dev"
elif [[ "${UBUNTU_RELEASE}" == "22.04" ]]; then
gazebo_packages="gazebo libgazebo-dev"
else
# default and Ubuntu 20.04
gazebo_version=11
gazebo_packages="gazebo$gazebo_version libgazebo$gazebo_version-dev"
fi
sudo sh -c 'echo "deb http://packages.osrfoundation.org/gazebo/ubuntu-stable `lsb_release -cs` main" > /etc/apt/sources.list.d/gazebo-stable.list'
wget http://packages.osrfoundation.org/gazebo.key -O - | sudo apt-key add -
# Update list, since new gazebo-stable.list has been added
sudo apt-get update -y --quiet
sudo DEBIAN_FRONTEND=noninteractive apt-get -y --quiet --no-install-recommends install \
dmidecode \
$gazebo_packages \
gazebo$gazebo_version \
gstreamer1.0-plugins-bad \
gstreamer1.0-plugins-base \
gstreamer1.0-plugins-good \
gstreamer1.0-plugins-ugly \
gstreamer1.0-libav \
libeigen3-dev \
libgazebo$gazebo_version-dev \
libgstreamer-plugins-base1.0-dev \
libimage-exiftool-perl \
libopencv-dev \
@@ -130,8 +130,7 @@ CONFIG_SCHED_LPWORKSTACKSIZE=1632
CONFIG_SCHED_WAITPID=y
CONFIG_SDCLONE_DISABLE=y
CONFIG_SDIO_BLOCKSETUP=y
CONFIG_SEM_NNESTPRIO=8
CONFIG_SEM_PREALLOCHOLDERS=0
CONFIG_SEM_PREALLOCHOLDERS=32
CONFIG_SERIAL_IFLOWCONTROL_WATERMARKS=y
CONFIG_SERIAL_TERMIOS=y
CONFIG_SIG_DEFAULT=y
@@ -174,7 +173,7 @@ CONFIG_STM32_SPI1=y
CONFIG_STM32_SPI2=y
CONFIG_STM32_SPI4=y
CONFIG_STM32_SPI4_DMA=y
CONFIG_STM32_SPI4_DMA_BUFFER=1024
CONFIG_STM32_SPI4_DMA_BUFFER=512
CONFIG_STM32_SPI_DMA=y
CONFIG_STM32_SPI_DMATHRESHOLD=8
CONFIG_STM32_TIM10=y
@@ -105,8 +105,7 @@ CONFIG_SCHED_LPWORK=y
CONFIG_SCHED_LPWORKPRIORITY=50
CONFIG_SCHED_LPWORKSTACKSIZE=1632
CONFIG_SCHED_WAITPID=y
CONFIG_SEM_NNESTPRIO=8
CONFIG_SEM_PREALLOCHOLDERS=0
CONFIG_SEM_PREALLOCHOLDERS=32
CONFIG_SERIAL_TERMIOS=y
CONFIG_SIG_DEFAULT=y
CONFIG_SIG_SIGALRM_ACTION=y
@@ -107,8 +107,7 @@ CONFIG_SCHED_LPWORK=y
CONFIG_SCHED_LPWORKPRIORITY=50
CONFIG_SCHED_LPWORKSTACKSIZE=1632
CONFIG_SCHED_WAITPID=y
CONFIG_SEM_NNESTPRIO=8
CONFIG_SEM_PREALLOCHOLDERS=0
CONFIG_SEM_PREALLOCHOLDERS=32
CONFIG_SERIAL_TERMIOS=y
CONFIG_SIG_DEFAULT=y
CONFIG_SIG_SIGALRM_ACTION=y
@@ -107,8 +107,7 @@ CONFIG_SCHED_LPWORK=y
CONFIG_SCHED_LPWORKPRIORITY=50
CONFIG_SCHED_LPWORKSTACKSIZE=1632
CONFIG_SCHED_WAITPID=y
CONFIG_SEM_NNESTPRIO=8
CONFIG_SEM_PREALLOCHOLDERS=0
CONFIG_SEM_PREALLOCHOLDERS=32
CONFIG_SERIAL_TERMIOS=y
CONFIG_SIG_DEFAULT=y
CONFIG_SIG_SIGALRM_ACTION=y
@@ -107,8 +107,7 @@ CONFIG_SCHED_LPWORK=y
CONFIG_SCHED_LPWORKPRIORITY=50
CONFIG_SCHED_LPWORKSTACKSIZE=1632
CONFIG_SCHED_WAITPID=y
CONFIG_SEM_NNESTPRIO=8
CONFIG_SEM_PREALLOCHOLDERS=0
CONFIG_SEM_PREALLOCHOLDERS=32
CONFIG_SERIAL_TERMIOS=y
CONFIG_SIG_DEFAULT=y
CONFIG_SIG_SIGALRM_ACTION=y
@@ -140,8 +140,7 @@ CONFIG_SCHED_WAITPID=y
CONFIG_SDCLONE_DISABLE=y
CONFIG_SDMMC1_SDIO_MODE=y
CONFIG_SDMMC1_SDIO_PULLUP=y
CONFIG_SEM_NNESTPRIO=8
CONFIG_SEM_PREALLOCHOLDERS=0
CONFIG_SEM_PREALLOCHOLDERS=32
CONFIG_SERIAL_IFLOWCONTROL_WATERMARKS=y
CONFIG_SERIAL_TERMIOS=y
CONFIG_SIG_DEFAULT=y
+1 -2
View File
@@ -162,8 +162,7 @@ CONFIG_SCHED_WAITPID=y
CONFIG_SDCLONE_DISABLE=y
CONFIG_SDMMC1_SDIO_MODE=y
CONFIG_SDMMC1_SDIO_PULLUP=y
CONFIG_SEM_NNESTPRIO=8
CONFIG_SEM_PREALLOCHOLDERS=0
CONFIG_SEM_PREALLOCHOLDERS=32
CONFIG_SERIAL_TERMIOS=y
CONFIG_SIG_DEFAULT=y
CONFIG_SIG_SIGALRM_ACTION=y
@@ -126,8 +126,7 @@ CONFIG_SCHED_LPWORKPRIORITY=50
CONFIG_SCHED_LPWORKSTACKSIZE=1632
CONFIG_SCHED_WAITPID=y
CONFIG_SDCLONE_DISABLE=y
CONFIG_SEM_NNESTPRIO=8
CONFIG_SEM_PREALLOCHOLDERS=0
CONFIG_SEM_PREALLOCHOLDERS=32
CONFIG_SERIAL_TERMIOS=y
CONFIG_SIG_DEFAULT=y
CONFIG_SIG_SIGALRM_ACTION=y
@@ -125,8 +125,7 @@ CONFIG_SCHED_LPWORKPRIORITY=50
CONFIG_SCHED_LPWORKSTACKSIZE=1632
CONFIG_SCHED_WAITPID=y
CONFIG_SDCLONE_DISABLE=y
CONFIG_SEM_NNESTPRIO=8
CONFIG_SEM_PREALLOCHOLDERS=0
CONFIG_SEM_PREALLOCHOLDERS=32
CONFIG_SERIAL_TERMIOS=y
CONFIG_SIG_DEFAULT=y
CONFIG_SIG_SIGALRM_ACTION=y
@@ -108,8 +108,7 @@ CONFIG_SCHED_LPWORK=y
CONFIG_SCHED_LPWORKPRIORITY=50
CONFIG_SCHED_LPWORKSTACKSIZE=1632
CONFIG_SCHED_WAITPID=y
CONFIG_SEM_NNESTPRIO=8
CONFIG_SEM_PREALLOCHOLDERS=0
CONFIG_SEM_PREALLOCHOLDERS=32
CONFIG_SERIAL_TERMIOS=y
CONFIG_SIG_DEFAULT=y
CONFIG_SIG_SIGALRM_ACTION=y
Binary file not shown.
+1 -2
View File
@@ -139,8 +139,7 @@ CONFIG_SCHED_LPWORKSTACKSIZE=1632
CONFIG_SCHED_WAITPID=y
CONFIG_SDCLONE_DISABLE=y
CONFIG_SDMMC1_SDIO_PULLUP=y
CONFIG_SEM_NNESTPRIO=8
CONFIG_SEM_PREALLOCHOLDERS=0
CONFIG_SEM_PREALLOCHOLDERS=32
CONFIG_SERIAL_IFLOWCONTROL_WATERMARKS=y
CONFIG_SERIAL_TERMIOS=y
CONFIG_SIG_DEFAULT=y
@@ -111,6 +111,7 @@ MEMORY
{
ITCM_RAM (rwx) : ORIGIN = 0x00000000, LENGTH = 64K
FLASH (rx) : ORIGIN = 0x08020000, LENGTH = 1920K
DTCM1_RAM (rwx) : ORIGIN = 0x20000000, LENGTH = 64K
DTCM2_RAM (rwx) : ORIGIN = 0x20010000, LENGTH = 64K
AXI_SRAM (rwx) : ORIGIN = 0x24000000, LENGTH = 512K /* D1 domain AXI bus */
@@ -186,7 +187,12 @@ SECTIONS
*(.gnu.linkonce.d.*)
CONSTRUCTORS
_edata = ABSOLUTE(.);
} > AXI_SRAM AT > FLASH
/* Pad out last section as the STM32H7 Flash write size is 256 bits. 32 bytes */
. = ALIGN(16);
FILL(0xffff)
. += 16;
} > AXI_SRAM AT > FLASH = 0xffff
.bss : {
_sbss = ABSOLUTE(.);
Binary file not shown.
+1 -2
View File
@@ -138,8 +138,7 @@ CONFIG_SCHED_LPWORKSTACKSIZE=1632
CONFIG_SCHED_WAITPID=y
CONFIG_SDCLONE_DISABLE=y
CONFIG_SDMMC1_SDIO_PULLUP=y
CONFIG_SEM_NNESTPRIO=8
CONFIG_SEM_PREALLOCHOLDERS=0
CONFIG_SEM_PREALLOCHOLDERS=32
CONFIG_SERIAL_IFLOWCONTROL_WATERMARKS=y
CONFIG_SERIAL_TERMIOS=y
CONFIG_SIG_DEFAULT=y
@@ -111,6 +111,7 @@ MEMORY
{
ITCM_RAM (rwx) : ORIGIN = 0x00000000, LENGTH = 64K
FLASH (rx) : ORIGIN = 0x08020000, LENGTH = 1920K
DTCM1_RAM (rwx) : ORIGIN = 0x20000000, LENGTH = 64K
DTCM2_RAM (rwx) : ORIGIN = 0x20010000, LENGTH = 64K
AXI_SRAM (rwx) : ORIGIN = 0x24000000, LENGTH = 512K /* D1 domain AXI bus */
@@ -186,7 +187,12 @@ SECTIONS
*(.gnu.linkonce.d.*)
CONSTRUCTORS
_edata = ABSOLUTE(.);
} > AXI_SRAM AT > FLASH
/* Pad out last section as the STM32H7 Flash write size is 256 bits. 32 bytes */
. = ALIGN(16);
FILL(0xffff)
. += 16;
} > AXI_SRAM AT > FLASH = 0xffff
.bss : {
_sbss = ABSOLUTE(.);
-1
View File
@@ -4,7 +4,6 @@ CONFIG_DRIVERS_IRLOCK=n
CONFIG_DRIVERS_PCA9685=n
CONFIG_DRIVERS_PCA9685_PWM_OUT=n
CONFIG_DRIVERS_RPM=n
CONFIG_DRIVERS_UAVCAN=n
CONFIG_MODULES_ATTITUDE_ESTIMATOR_Q=n
CONFIG_MODULES_LOCAL_POSITION_ESTIMATOR=n
CONFIG_MODULES_ROVER_POS_CONTROL=n
@@ -140,8 +140,7 @@ CONFIG_SCHED_LPWORKSTACKSIZE=1632
CONFIG_SCHED_WAITPID=y
CONFIG_SDCLONE_DISABLE=y
CONFIG_SDMMC1_SDIO_PULLUP=y
CONFIG_SEM_NNESTPRIO=8
CONFIG_SEM_PREALLOCHOLDERS=0
CONFIG_SEM_PREALLOCHOLDERS=32
CONFIG_SERIAL_IFLOWCONTROL_WATERMARKS=y
CONFIG_SERIAL_TERMIOS=y
CONFIG_SIG_DEFAULT=y
@@ -187,7 +187,12 @@ SECTIONS
*(.gnu.linkonce.d.*)
CONSTRUCTORS
_edata = ABSOLUTE(.);
} > AXI_SRAM AT > FLASH
/* Pad out last section as the STM32H7 Flash write size is 256 bits. 32 bytes */
. = ALIGN(16);
FILL(0xffff)
. += 16;
} > AXI_SRAM AT > FLASH = 0xffff
.bss : {
_sbss = ABSOLUTE(.);
@@ -138,8 +138,7 @@ CONFIG_SCHED_LPWORKSTACKSIZE=1632
CONFIG_SCHED_WAITPID=y
CONFIG_SDCLONE_DISABLE=y
CONFIG_SDMMC1_SDIO_PULLUP=y
CONFIG_SEM_NNESTPRIO=8
CONFIG_SEM_PREALLOCHOLDERS=0
CONFIG_SEM_PREALLOCHOLDERS=32
CONFIG_SERIAL_IFLOWCONTROL_WATERMARKS=y
CONFIG_SERIAL_TERMIOS=y
CONFIG_SIG_DEFAULT=y
@@ -4,7 +4,6 @@ CONFIG_DRIVERS_IRLOCK=n
CONFIG_DRIVERS_PCA9685=n
CONFIG_DRIVERS_PCA9685_PWM_OUT=n
CONFIG_DRIVERS_RPM=n
CONFIG_DRIVERS_UAVCAN=n
CONFIG_EXAMPLES_FAKE_GPS=n
CONFIG_MODULES_ATTITUDE_ESTIMATOR_Q=n
CONFIG_MODULES_LOCAL_POSITION_ESTIMATOR=n
@@ -141,8 +141,7 @@ CONFIG_SCHED_WAITPID=y
CONFIG_SDCLONE_DISABLE=y
CONFIG_SDMMC1_SDIO_MODE=y
CONFIG_SDMMC1_SDIO_PULLUP=y
CONFIG_SEM_NNESTPRIO=8
CONFIG_SEM_PREALLOCHOLDERS=0
CONFIG_SEM_PREALLOCHOLDERS=32
CONFIG_SERIAL_IFLOWCONTROL_WATERMARKS=y
CONFIG_SERIAL_TERMIOS=y
CONFIG_SIG_DEFAULT=y
@@ -4,7 +4,7 @@ CONFIG_BOARD_CONSTRAINED_FLASH=y
CONFIG_BOARD_NO_HELP=y
CONFIG_BOARD_CONSTRAINED_MEMORY=y
CONFIG_BOARD_EXTERNAL_METADATA=y
CONFIG_BOARD_SERIAL_URT6="/dev/ttyS2"
CONFIG_BOARD_SERIAL_GPS1="/dev/ttyS2"
CONFIG_BOARD_SERIAL_TEL2="/dev/ttyS1"
CONFIG_DRIVERS_ADC_BOARD_ADC=y
CONFIG_DRIVERS_BAROMETER_BMP280=y
@@ -23,10 +23,10 @@ CONFIG_MODULES_BATTERY_STATUS=y
CONFIG_MODULES_COMMANDER=y
CONFIG_MODULES_CONTROL_ALLOCATOR=y
CONFIG_MODULES_DATAMAN=y
CONFIG_MODULES_EKF2=y
CONFIG_MODULES_EKF2=n
CONFIG_MODULES_FLIGHT_MODE_MANAGER=y
CONFIG_MODULES_LAND_DETECTOR=y
CONFIG_MODULES_LOAD_MON=y
CONFIG_MODULES_LOGGER=y
CONFIG_MODULES_MANUAL_CONTROL=y
CONFIG_MODULES_MAVLINK=y
CONFIG_MODULES_MC_ATT_CONTROL=y
@@ -120,8 +120,7 @@ CONFIG_SCHED_LPWORKPRIORITY=50
CONFIG_SCHED_LPWORKSTACKSIZE=1632
CONFIG_SCHED_WAITPID=y
CONFIG_SDCLONE_DISABLE=y
CONFIG_SEM_NNESTPRIO=8
CONFIG_SEM_PREALLOCHOLDERS=0
CONFIG_SEM_PREALLOCHOLDERS=32
CONFIG_SERIAL_TERMIOS=y
CONFIG_SIG_DEFAULT=y
CONFIG_SIG_SIGALRM_ACTION=y
@@ -158,7 +157,7 @@ CONFIG_STM32_SERIALBRK_BSDCOMPAT=y
CONFIG_STM32_SERIAL_DISABLE_REORDERING=y
CONFIG_STM32_SPI1=y
CONFIG_STM32_SPI1_DMA=y
CONFIG_STM32_SPI1_DMA_BUFFER=1024
CONFIG_STM32_SPI1_DMA_BUFFER=512
CONFIG_STM32_SPI2=y
CONFIG_STM32_SPI2_DMA=y
CONFIG_STM32_SPI3=y
@@ -122,8 +122,7 @@ CONFIG_SCHED_LPWORK=y
CONFIG_SCHED_LPWORKPRIORITY=50
CONFIG_SCHED_LPWORKSTACKSIZE=1632
CONFIG_SCHED_WAITPID=y
CONFIG_SEM_NNESTPRIO=8
CONFIG_SEM_PREALLOCHOLDERS=0
CONFIG_SEM_PREALLOCHOLDERS=32
CONFIG_SERIAL_TERMIOS=y
CONFIG_SIG_DEFAULT=y
CONFIG_SIG_SIGALRM_ACTION=y
@@ -108,8 +108,7 @@ CONFIG_SCHED_LPWORK=y
CONFIG_SCHED_LPWORKPRIORITY=50
CONFIG_SCHED_LPWORKSTACKSIZE=1632
CONFIG_SCHED_WAITPID=y
CONFIG_SEM_NNESTPRIO=8
CONFIG_SEM_PREALLOCHOLDERS=0
CONFIG_SEM_PREALLOCHOLDERS=32
CONFIG_SERIAL_TERMIOS=y
CONFIG_SIG_DEFAULT=y
CONFIG_SIG_SIGALRM_ACTION=y
@@ -140,8 +140,7 @@ CONFIG_SCHED_LPWORKSTACKSIZE=1632
CONFIG_SCHED_WAITPID=y
CONFIG_SDCLONE_DISABLE=y
CONFIG_SDMMC1_SDIO_PULLUP=y
CONFIG_SEM_NNESTPRIO=8
CONFIG_SEM_PREALLOCHOLDERS=0
CONFIG_SEM_PREALLOCHOLDERS=32
CONFIG_SERIAL_IFLOWCONTROL_WATERMARKS=y
CONFIG_SERIAL_TERMIOS=y
CONFIG_SIG_DEFAULT=y
@@ -109,16 +109,17 @@
MEMORY
{
itcm (rwx) : ORIGIN = 0x00000000, LENGTH = 64K
flash (rx) : ORIGIN = 0x08020000, LENGTH = 1920K
dtcm1 (rwx) : ORIGIN = 0x20000000, LENGTH = 64K
dtcm2 (rwx) : ORIGIN = 0x20010000, LENGTH = 64K
sram (rwx) : ORIGIN = 0x24000000, LENGTH = 512K
sram1 (rwx) : ORIGIN = 0x30000000, LENGTH = 128K
sram2 (rwx) : ORIGIN = 0x30020000, LENGTH = 128K
sram3 (rwx) : ORIGIN = 0x30040000, LENGTH = 32K
sram4 (rwx) : ORIGIN = 0x38000000, LENGTH = 64K
bbram (rwx) : ORIGIN = 0x38800000, LENGTH = 4K
ITCM_RAM (rwx) : ORIGIN = 0x00000000, LENGTH = 64K
FLASH (rx) : ORIGIN = 0x08020000, LENGTH = 1920K
DTCM1_RAM (rwx) : ORIGIN = 0x20000000, LENGTH = 64K
DTCM2_RAM (rwx) : ORIGIN = 0x20010000, LENGTH = 64K
AXI_SRAM (rwx) : ORIGIN = 0x24000000, LENGTH = 512K /* D1 domain AXI bus */
SRAM1 (rwx) : ORIGIN = 0x30000000, LENGTH = 128K /* D2 domain AHB bus */
SRAM2 (rwx) : ORIGIN = 0x30020000, LENGTH = 128K /* D2 domain AHB bus */
SRAM3 (rwx) : ORIGIN = 0x30040000, LENGTH = 32K /* D2 domain AHB bus */
SRAM4 (rwx) : ORIGIN = 0x38000000, LENGTH = 64K /* D3 domain */
BKPRAM (rwx) : ORIGIN = 0x38800000, LENGTH = 4K
}
OUTPUT_ARCH(arm)
@@ -156,7 +157,7 @@ SECTIONS
*(.gnu.linkonce.r.*)
_etext = ABSOLUTE(.);
} > flash
} > FLASH
/*
* Init functions (static constructors and the like)
@@ -165,17 +166,17 @@ SECTIONS
_sinit = ABSOLUTE(.);
KEEP(*(.init_array .init_array.*))
_einit = ABSOLUTE(.);
} > flash
} > FLASH
.ARM.extab : {
*(.ARM.extab*)
} > flash
} > FLASH
__exidx_start = ABSOLUTE(.);
.ARM.exidx : {
*(.ARM.exidx*)
} > flash
} > FLASH
__exidx_end = ABSOLUTE(.);
_eronly = ABSOLUTE(.);
@@ -186,7 +187,12 @@ SECTIONS
*(.gnu.linkonce.d.*)
CONSTRUCTORS
_edata = ABSOLUTE(.);
} > sram AT > flash
/* Pad out last section as the STM32H7 Flash write size is 256 bits. 32 bytes */
. = ALIGN(16);
FILL(0xffff)
. += 16;
} > AXI_SRAM AT > FLASH = 0xffff
.bss : {
_sbss = ABSOLUTE(.);
@@ -195,7 +201,7 @@ SECTIONS
*(COMMON)
. = ALIGN(4);
_ebss = ABSOLUTE(.);
} > sram
} > AXI_SRAM
/* Emit the the D3 power domain section for locating BDMA data */
@@ -204,7 +210,7 @@ SECTIONS
*(.sram4)
. = ALIGN(4);
_sram4_heap_start = ABSOLUTE(.);
} > sram4
} > SRAM4
/* Stabs debugging sections. */
.stab 0 : { *(.stab) }
+1
View File
@@ -31,6 +31,7 @@ CONFIG_MODULES_MC_RATE_CONTROL=y
CONFIG_MODULES_NAVIGATOR=y
CONFIG_MODULES_RC_UPDATE=y
CONFIG_MODULES_SENSORS=y
CONFIG_SYSTEMCMDS_HARDFAULT_LOG=y
CONFIG_SYSTEMCMDS_MIXER=y
CONFIG_SYSTEMCMDS_PARAM=y
CONFIG_SYSTEMCMDS_PWM=y
@@ -140,8 +140,7 @@ CONFIG_SCHED_LPWORKPRIORITY=50
CONFIG_SCHED_LPWORKSTACKSIZE=1632
CONFIG_SCHED_WAITPID=y
CONFIG_SDCLONE_DISABLE=y
CONFIG_SEM_NNESTPRIO=8
CONFIG_SEM_PREALLOCHOLDERS=0
CONFIG_SEM_PREALLOCHOLDERS=32
CONFIG_SERIAL_TERMIOS=y
CONFIG_SIG_DEFAULT=y
CONFIG_SIG_SIGALRM_ACTION=y
@@ -30,7 +30,7 @@ CONFIG_BOARD_RESET_ON_ASSERT=2
CONFIG_C99_BOOL8=y
CONFIG_CDCACM=y
CONFIG_CDCACM_IFLOWCONTROL=y
CONFIG_CDCACM_PRODUCTID=0x0050
CONFIG_CDCACM_PRODUCTID=0x004b
CONFIG_CDCACM_PRODUCTSTR="PX4 BL Holybro KakuteH7"
CONFIG_CDCACM_RXBUFSIZE=600
CONFIG_CDCACM_TXBUFSIZE=12000
@@ -139,8 +139,7 @@ CONFIG_SCHED_LPWORKPRIORITY=50
CONFIG_SCHED_LPWORKSTACKSIZE=1632
CONFIG_SCHED_WAITPID=y
CONFIG_SDCLONE_DISABLE=y
CONFIG_SEM_NNESTPRIO=8
CONFIG_SEM_PREALLOCHOLDERS=0
CONFIG_SEM_PREALLOCHOLDERS=32
CONFIG_SERIAL_IFLOWCONTROL_WATERMARKS=y
CONFIG_SERIAL_TERMIOS=y
CONFIG_SIG_DEFAULT=y
@@ -109,16 +109,17 @@
MEMORY
{
itcm (rwx) : ORIGIN = 0x00000000, LENGTH = 64K
flash (rx) : ORIGIN = 0x08020000, LENGTH = 1792K /* params in last sector */
dtcm1 (rwx) : ORIGIN = 0x20000000, LENGTH = 64K
dtcm2 (rwx) : ORIGIN = 0x20010000, LENGTH = 64K
sram (rwx) : ORIGIN = 0x24000000, LENGTH = 512K
sram1 (rwx) : ORIGIN = 0x30000000, LENGTH = 128K
sram2 (rwx) : ORIGIN = 0x30020000, LENGTH = 128K
sram3 (rwx) : ORIGIN = 0x30040000, LENGTH = 32K
sram4 (rwx) : ORIGIN = 0x38000000, LENGTH = 64K
bbram (rwx) : ORIGIN = 0x38800000, LENGTH = 4K
ITCM_RAM (rwx) : ORIGIN = 0x00000000, LENGTH = 64K
FLASH (rx) : ORIGIN = 0x08020000, LENGTH = 1792K /* params in last sector */
DTCM1_RAM (rwx) : ORIGIN = 0x20000000, LENGTH = 64K
DTCM2_RAM (rwx) : ORIGIN = 0x20010000, LENGTH = 64K
AXI_SRAM (rwx) : ORIGIN = 0x24000000, LENGTH = 512K /* D1 domain AXI bus */
SRAM1 (rwx) : ORIGIN = 0x30000000, LENGTH = 128K /* D2 domain AHB bus */
SRAM2 (rwx) : ORIGIN = 0x30020000, LENGTH = 128K /* D2 domain AHB bus */
SRAM3 (rwx) : ORIGIN = 0x30040000, LENGTH = 32K /* D2 domain AHB bus */
SRAM4 (rwx) : ORIGIN = 0x38000000, LENGTH = 64K /* D3 domain */
BKPRAM (rwx) : ORIGIN = 0x38800000, LENGTH = 4K
}
OUTPUT_ARCH(arm)
@@ -156,7 +157,7 @@ SECTIONS
*(.gnu.linkonce.r.*)
_etext = ABSOLUTE(.);
} > flash
} > FLASH
/*
* Init functions (static constructors and the like)
@@ -165,17 +166,17 @@ SECTIONS
_sinit = ABSOLUTE(.);
KEEP(*(.init_array .init_array.*))
_einit = ABSOLUTE(.);
} > flash
} > FLASH
.ARM.extab : {
*(.ARM.extab*)
} > flash
} > FLASH
__exidx_start = ABSOLUTE(.);
.ARM.exidx : {
*(.ARM.exidx*)
} > flash
} > FLASH
__exidx_end = ABSOLUTE(.);
_eronly = ABSOLUTE(.);
@@ -186,7 +187,12 @@ SECTIONS
*(.gnu.linkonce.d.*)
CONSTRUCTORS
_edata = ABSOLUTE(.);
} > sram AT > flash
/* Pad out last section as the STM32H7 Flash write size is 256 bits. 32 bytes */
. = ALIGN(16);
FILL(0xffff)
. += 16;
} > AXI_SRAM AT > FLASH = 0xffff
.bss : {
_sbss = ABSOLUTE(.);
@@ -195,7 +201,7 @@ SECTIONS
*(COMMON)
. = ALIGN(4);
_ebss = ABSOLUTE(.);
} > sram
} > AXI_SRAM
/* Emit the the D3 power domain section for locating BDMA data */
@@ -204,7 +210,7 @@ SECTIONS
*(.sram4)
. = ALIGN(4);
_sram4_heap_start = ABSOLUTE(.);
} > sram4
} > SRAM4
/* Stabs debugging sections. */
.stab 0 : { *(.stab) }
@@ -140,8 +140,7 @@ CONFIG_SCHED_WAITPID=y
CONFIG_SDCLONE_DISABLE=y
CONFIG_SDMMC1_SDIO_MODE=y
CONFIG_SDMMC1_SDIO_PULLUP=y
CONFIG_SEM_NNESTPRIO=8
CONFIG_SEM_PREALLOCHOLDERS=0
CONFIG_SEM_PREALLOCHOLDERS=32
CONFIG_SERIAL_IFLOWCONTROL_WATERMARKS=y
CONFIG_SERIAL_TERMIOS=y
CONFIG_SIG_DEFAULT=y
@@ -126,8 +126,7 @@ CONFIG_SCHED_LPWORK=y
CONFIG_SCHED_LPWORKPRIORITY=50
CONFIG_SCHED_LPWORKSTACKSIZE=1632
CONFIG_SCHED_WAITPID=y
CONFIG_SEM_NNESTPRIO=8
CONFIG_SEM_PREALLOCHOLDERS=0
CONFIG_SEM_PREALLOCHOLDERS=32
CONFIG_SERIAL_PASSTHRU_UBLOX=y
CONFIG_SERIAL_TERMIOS=y
CONFIG_SIG_DEFAULT=y
-90
View File
@@ -1,90 +0,0 @@
CONFIG_BOARD_TOOLCHAIN="arm-none-eabi"
CONFIG_BOARD_ARCHITECTURE="cortex-m7"
CONFIG_BOARD_SERIAL_GPS1="/dev/ttyS1"
CONFIG_BOARD_SERIAL_TEL1="/dev/ttyS2"
CONFIG_BOARD_SERIAL_TEL2="/dev/ttyS3"
CONFIG_BOARD_SERIAL_TEL3="/dev/ttyS5"
CONFIG_BOARD_SERIAL_TEL4="/dev/ttyS6"
CONFIG_DRIVERS_ADC_BOARD_ADC=y
CONFIG_DRIVERS_BAROMETER_DPS310=y
CONFIG_DRIVERS_CAMERA_CAPTURE=n
CONFIG_DRIVERS_CAMERA_TRIGGER=n
CONFIG_DRIVERS_DSHOT=y
CONFIG_DRIVERS_GPS=y
CONFIG_DRIVERS_IMU_INVENSENSE_MPU6000=y
CONFIG_DRIVERS_IMU_INVENSENSE_ICM20602=y
CONFIG_DRIVERS_IMU_INVENSENSE_ICM42605=y
CONFIG_DRIVERS_MAGNETOMETER_QMC5883L=y
CONFIG_COMMON_DISTANCE_SENSOR=n
CONFIG_COMMON_LIGHT=n
CONFIG_COMMON_MAGNETOMETER=n
CONFIG_COMMON_OPTICAL_FLOW=y
CONFIG_DRIVERS_OSD=y
CONFIG_DRIVERS_PWM_OUT=y
CONFIG_DRIVERS_PWM_OUT_SIM=n
CONFIG_DRIVERS_RC_INPUT=y
CONFIG_DRIVERS_RPM=n
CONFIG_COMMON_TELEMETRY=y
CONFIG_DRIVERS_TONE_ALARM=y
CONFIG_DRIVERS_UAVCAN=y
CONFIG_BOARD_UAVCAN_INTERFACES=1
CONFIG_MODULES_ATTITUDE_ESTIMATOR_Q=y
CONFIG_MODULES_BATTERY_STATUS=y
CONFIG_MODULES_COMMANDER=y
CONFIG_MODULES_CONTROL_ALLOCATOR=y
CONFIG_MODULES_DATAMAN=y
CONFIG_MODULES_EKF2=y
CONFIG_MODULES_EVENTS=y
CONFIG_MODULES_FLIGHT_MODE_MANAGER=y
CONFIG_MODULES_FW_ATT_CONTROL=y
CONFIG_MODULES_FW_POS_CONTROL_L1=y
CONFIG_MODULES_GYRO_CALIBRATION=y
CONFIG_MODULES_GYRO_FFT=y
CONFIG_MODULES_LAND_DETECTOR=y
CONFIG_MODULES_LANDING_TARGET_ESTIMATOR=y
CONFIG_MODULES_LOAD_MON=y
CONFIG_MODULES_LOCAL_POSITION_ESTIMATOR=y
CONFIG_MODULES_LOGGER=y
CONFIG_MODULES_MAG_BIAS_ESTIMATOR=y
CONFIG_MODULES_MANUAL_CONTROL=y
CONFIG_MODULES_MAVLINK=y
CONFIG_MODULES_MC_ATT_CONTROL=y
CONFIG_MODULES_MC_AUTOTUNE_ATTITUDE_CONTROL=n
CONFIG_MODULES_MC_HOVER_THRUST_ESTIMATOR=y
CONFIG_MODULES_MC_POS_CONTROL=y
CONFIG_MODULES_MC_RATE_CONTROL=y
CONFIG_MODULES_NAVIGATOR=y
CONFIG_MODULES_RC_UPDATE=y
CONFIG_MODULES_SENSORS=y
CONFIG_MODULES_TEMPERATURE_COMPENSATION=n
CONFIG_MODULES_VTOL_ATT_CONTROL=y
CONFIG_MODULES_GIMBAL=n
CONFIG_SYSTEMCMDS_BL_UPDATE=n
CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y
CONFIG_SYSTEMCMDS_DMESG=y
CONFIG_SYSTEMCMDS_DUMPFILE=n
CONFIG_SYSTEMCMDS_GPIO=y
CONFIG_SYSTEMCMDS_HARDFAULT_LOG=y
CONFIG_SYSTEMCMDS_I2CDETECT=y
CONFIG_SYSTEMCMDS_LED_CONTROL=n
CONFIG_SYSTEMCMDS_MFT=n
CONFIG_SYSTEMCMDS_MIXER=y
CONFIG_SYSTEMCMDS_MOTOR_TEST=n
CONFIG_SYSTEMCMDS_MTD=n
CONFIG_SYSTEMCMDS_NSHTERM=y
CONFIG_SYSTEMCMDS_PARAM=y
CONFIG_SYSTEMCMDS_PERF=y
CONFIG_SYSTEMCMDS_PWM=y
CONFIG_SYSTEMCMDS_REBOOT=y
CONFIG_SYSTEMCMDS_SD_BENCH=n
CONFIG_SYSTEMCMDS_SD_STRESS=n
CONFIG_SYSTEMCMDS_SERIAL_TEST=n
CONFIG_SYSTEMCMDS_SYSTEM_TIME=y
CONFIG_SYSTEMCMDS_TOP=y
CONFIG_SYSTEMCMDS_TOPIC_LISTENER=y
CONFIG_SYSTEMCMDS_TUNE_CONTROL=n
CONFIG_SYSTEMCMDS_UORB=y
CONFIG_SYSTEMCMDS_USB_CONNECTED=y
CONFIG_SYSTEMCMDS_VER=y
CONFIG_SYSTEMCMDS_WORK_QUEUE=y
CONFIG_EXAMPLES_FAKE_GPS=n
-13
View File
@@ -1,13 +0,0 @@
{
"board_id": 1013,
"magic": "PX4FWv1",
"description": "Firmware for the MatekH743-slim board",
"image": "",
"build_time": 0,
"summary": "MatekH743-mini",
"version": "0.1",
"image_size": 0,
"image_maxsize": 1966080,
"git_identity": "",
"board_revision": 0
}
@@ -1,16 +0,0 @@
#!/bin/sh
#
# board specific extras init
#------------------------------------------------------------------------------
# if ! param compare OSD_ATXXXX_CFG 0
# then
# atxxxx start -s
# fi
atxxxx start -s
# DShot telemetry is always on UART7
# dshot telemetry /dev/ttyS5
@@ -1,22 +0,0 @@
#!/bin/sh
#
# board specific sensors init
#------------------------------------------------------------------------------
board_adc start
# Internal SPI bus ICM-42605
if ! icm42605 -R 14 -s start
then
# internal SPI bus ICM-20602
icm20602 -R 12 -s start
fi
# Internal SPI bus MPU-6000
mpu6000 -R 12 -s start
# Internal baro
dps310 -I start -a 118
# External mag
qmc5883l -X start -a 13
@@ -1,225 +0,0 @@
#
# This file is autogenerated: PLEASE DO NOT EDIT IT.
#
# You can use "make menuconfig" to make any modifications to the installed .config file.
# You can then do "make savedefconfig" to generate a new defconfig file that includes your
# modifications.
#
# CONFIG_DISABLE_ENVIRON is not set
# CONFIG_DISABLE_PSEUDOFS_OPERATIONS is not set
# CONFIG_MMCSD_HAVE_CARDDETECT is not set
# CONFIG_MMCSD_HAVE_WRITEPROTECT is not set
# CONFIG_MMCSD_MMCSUPPORT is not set
# CONFIG_MMCSD_SPI is not set
# CONFIG_NSH_DISABLEBG is not set
# CONFIG_NSH_DISABLESCRIPT is not set
# CONFIG_NSH_DISABLE_DF is not set
# CONFIG_NSH_DISABLE_EXEC is not set
# CONFIG_NSH_DISABLE_EXIT is not set
# CONFIG_NSH_DISABLE_GET is not set
# CONFIG_NSH_DISABLE_ITEF is not set
# CONFIG_NSH_DISABLE_LOOPS is not set
# CONFIG_NSH_DISABLE_SEMICOLON is not set
# CONFIG_NSH_DISABLE_TIME is not set
CONFIG_ARCH="arm"
CONFIG_ARCH_BOARD_CUSTOM=y
CONFIG_ARCH_BOARD_CUSTOM_DIR="../../../../boards/matek/h743-mini/nuttx-config"
CONFIG_ARCH_BOARD_CUSTOM_DIR_RELPATH=y
CONFIG_ARCH_BOARD_CUSTOM_NAME="px4"
CONFIG_ARCH_CHIP="stm32h7"
CONFIG_ARCH_CHIP_STM32H743VI=y
CONFIG_ARCH_CHIP_STM32H7=y
CONFIG_ARCH_INTERRUPTSTACK=512
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARMV7M_BASEPRI_WAR=y
CONFIG_ARMV7M_DCACHE=y
CONFIG_ARMV7M_DTCM=y
CONFIG_ARMV7M_ICACHE=y
CONFIG_ARMV7M_MEMCPY=y
CONFIG_ARMV7M_USEBASEPRI=y
CONFIG_BOARDCTL_RESET=y
CONFIG_BOARD_CRASHDUMP=y
CONFIG_BOARD_LOOPSPERMSEC=95150
CONFIG_BOARD_RESET_ON_ASSERT=2
CONFIG_BUILTIN=y
CONFIG_C99_BOOL8=y
CONFIG_CDCACM=y
CONFIG_CDCACM_PRODUCTID=0x0036
CONFIG_CDCACM_PRODUCTSTR="MatekH743-mini"
CONFIG_CDCACM_RXBUFSIZE=600
CONFIG_CDCACM_TXBUFSIZE=12000
CONFIG_CDCACM_VENDORID=0x1B8C
CONFIG_CDCACM_VENDORSTR="Matek"
CONFIG_CLOCK_MONOTONIC=y
CONFIG_DEBUG_FULLOPT=y
CONFIG_DEBUG_HARDFAULT_ALERT=y
CONFIG_DEBUG_MEMFAULT=y
CONFIG_DEBUG_SYMBOLS=y
CONFIG_DEFAULT_SMALL=y
CONFIG_DEV_FIFO_SIZE=0
CONFIG_DEV_PIPE_MAXSIZE=1024
CONFIG_DEV_PIPE_SIZE=70
CONFIG_EXPERIMENTAL=y
CONFIG_FAT_DMAMEMORY=y
CONFIG_FAT_LCNAMES=y
CONFIG_FAT_LFN=y
CONFIG_FAT_LFN_ALIAS_HASH=y
CONFIG_FDCLONE_STDIO=y
CONFIG_FS_BINFS=y
CONFIG_FS_CROMFS=y
CONFIG_FS_FAT=y
CONFIG_FS_FATTIME=y
CONFIG_FS_PROCFS=y
CONFIG_FS_PROCFS_INCLUDE_PROGMEM=y
CONFIG_FS_PROCFS_MAX_TASKS=64
CONFIG_FS_PROCFS_REGISTER=y
CONFIG_FS_ROMFS=y
CONFIG_GRAN=y
CONFIG_GRAN_INTR=y
CONFIG_HAVE_CXX=y
CONFIG_HAVE_CXXINITIALIZE=y
CONFIG_I2C=y
CONFIG_I2C_RESET=y
CONFIG_IDLETHREAD_STACKSIZE=750
CONFIG_LIBC_FLOATINGPOINT=y
CONFIG_LIBC_LONG_LONG=y
CONFIG_LIBC_STRERROR=y
CONFIG_MEMSET_64BIT=y
CONFIG_MEMSET_OPTSPEED=y
CONFIG_MMCSD=y
CONFIG_MMCSD_SDIO=y
CONFIG_MMCSD_SDIOWAIT_WRCOMPLETE=y
CONFIG_MM_REGIONS=4
CONFIG_NAME_MAX=40
CONFIG_NSH_ARCHINIT=y
CONFIG_NSH_ARGCAT=y
CONFIG_NSH_BUILTIN_APPS=y
CONFIG_NSH_CMDPARMS=y
CONFIG_NSH_CROMFSETC=y
CONFIG_NSH_LINELEN=128
CONFIG_NSH_MAXARGUMENTS=15
CONFIG_NSH_NESTDEPTH=8
CONFIG_NSH_QUOTE=y
CONFIG_NSH_ROMFSETC=y
CONFIG_NSH_ROMFSSECTSIZE=128
CONFIG_NSH_STRERROR=y
CONFIG_NSH_VARS=y
CONFIG_OTG_ID_GPIO_DISABLE=y
CONFIG_PIPES=y
CONFIG_PREALLOC_TIMERS=50
CONFIG_PRIORITY_INHERITANCE=y
CONFIG_PTHREAD_MUTEX_ROBUST=y
CONFIG_PTHREAD_STACK_MIN=512
CONFIG_RAM_SIZE=245760
CONFIG_RAM_START=0x20010000
CONFIG_RAW_BINARY=y
CONFIG_RTC_DATETIME=y
CONFIG_SCHED_ATEXIT=y
CONFIG_SCHED_HPWORK=y
CONFIG_SCHED_HPWORKPRIORITY=249
CONFIG_SCHED_HPWORKSTACKSIZE=1280
CONFIG_SCHED_INSTRUMENTATION=y
CONFIG_SCHED_INSTRUMENTATION_EXTERNAL=y
CONFIG_SCHED_LPWORK=y
CONFIG_SCHED_LPWORKPRIORITY=50
CONFIG_SCHED_LPWORKSTACKSIZE=1632
CONFIG_SCHED_WAITPID=y
CONFIG_SDCLONE_DISABLE=y
CONFIG_SDMMC1_SDIO_PULLUP=y
CONFIG_SEM_NNESTPRIO=8
CONFIG_SEM_PREALLOCHOLDERS=0
CONFIG_SERIAL_IFLOWCONTROL_WATERMARKS=y
CONFIG_SERIAL_TERMIOS=y
CONFIG_SIG_DEFAULT=y
CONFIG_SIG_SIGALRM_ACTION=y
CONFIG_SIG_SIGUSR1_ACTION=y
CONFIG_SIG_SIGUSR2_ACTION=y
CONFIG_SIG_SIGWORK=4
CONFIG_STACK_COLORATION=y
CONFIG_START_DAY=30
CONFIG_START_MONTH=11
CONFIG_STDIO_BUFFER_SIZE=256
CONFIG_STM32H7_ADC1=y
CONFIG_STM32H7_ADC3=y
CONFIG_STM32H7_BBSRAM=y
CONFIG_STM32H7_BBSRAM_FILES=5
CONFIG_STM32H7_BDMA=y
CONFIG_STM32H7_BKPSRAM=y
CONFIG_STM32H7_DMA1=y
CONFIG_STM32H7_DMA2=y
CONFIG_STM32H7_DMACAPABLE=y
CONFIG_STM32H7_FLOWCONTROL_BROKEN=y
CONFIG_STM32H7_I2C1=y
CONFIG_STM32H7_I2C2=y
CONFIG_STM32H7_I2C_DYNTIMEO=y
CONFIG_STM32H7_I2C_DYNTIMEO_STARTSTOP=10
CONFIG_STM32H7_OTGFS=y
CONFIG_STM32H7_PROGMEM=y
CONFIG_STM32H7_RTC=y
CONFIG_STM32H7_RTC_HSECLOCK=y
CONFIG_STM32H7_RTC_MAGIC_REG=1
CONFIG_STM32H7_SAVE_CRASHDUMP=y
CONFIG_STM32H7_SDMMC1=y
CONFIG_STM32H7_SERIALBRK_BSDCOMPAT=y
CONFIG_STM32H7_SERIAL_DISABLE_REORDERING=y
CONFIG_STM32H7_SPI1=y
CONFIG_STM32H7_SPI1_DMA=y
CONFIG_STM32H7_SPI1_DMA_BUFFER=2048
CONFIG_STM32H7_SPI2=y
CONFIG_STM32H7_SPI3=y
CONFIG_STM32H7_SPI4=y
CONFIG_STM32H7_SPI4_DMA=y
CONFIG_STM32H7_SPI4_DMA_BUFFER=2048
CONFIG_STM32H7_SPI_DMA=y
CONFIG_STM32H7_SPI_DMATHRESHOLD=8
CONFIG_STM32H7_TIM15=y
CONFIG_STM32H7_TIM1=y
CONFIG_STM32H7_TIM2=y
CONFIG_STM32H7_TIM4=y
CONFIG_STM32H7_TIM5=y
CONFIG_STM32H7_TIM8=y
CONFIG_STM32H7_UART4=y
CONFIG_STM32H7_UART7=y
CONFIG_STM32H7_UART8=y
CONFIG_STM32H7_USART1=y
CONFIG_STM32H7_USART2=y
CONFIG_STM32H7_USART3=y
CONFIG_STM32H7_USART6=y
CONFIG_STM32H7_USART_BREAKS=y
CONFIG_STM32H7_USART_INVERT=y
CONFIG_STM32H7_USART_SINGLEWIRE=y
CONFIG_STM32H7_USART_SWAP=y
CONFIG_SYSTEM_CDCACM=y
CONFIG_SYSTEM_NSH=y
CONFIG_TASK_NAME_SIZE=24
CONFIG_UART4_BAUD=57600
CONFIG_UART4_RXBUFSIZE=600
CONFIG_UART4_TXBUFSIZE=1500
CONFIG_UART7_BAUD=57600
CONFIG_UART7_IFLOWCONTROL=y
CONFIG_UART7_OFLOWCONTROL=y
CONFIG_UART7_RXBUFSIZE=600
CONFIG_UART7_TXBUFSIZE=1500
CONFIG_UART8_BAUD=57600
CONFIG_UART8_RXBUFSIZE=600
CONFIG_UART8_TXBUFSIZE=1500
CONFIG_USART1_BAUD=57600
CONFIG_USART1_RXBUFSIZE=600
CONFIG_USART1_SERIAL_CONSOLE=y
CONFIG_USART1_TXBUFSIZE=1500
CONFIG_USART2_BAUD=57600
CONFIG_USART2_RXBUFSIZE=600
CONFIG_USART2_TXBUFSIZE=1500
CONFIG_USART3_BAUD=57600
CONFIG_USART3_RXBUFSIZE=600
CONFIG_USART3_TXBUFSIZE=1500
CONFIG_USART6_BAUD=57600
CONFIG_USART6_RXBUFSIZE=600
CONFIG_USART6_TXBUFSIZE=1500
CONFIG_USBDEV=y
CONFIG_USBDEV_BUSPOWERED=y
CONFIG_USBDEV_MAXPOWER=500
CONFIG_USEC_PER_TICK=1000
CONFIG_USERMAIN_STACKSIZE=2944
CONFIG_USER_ENTRYPOINT="nsh_main"
CONFIG_WATCHDOG=y
-237
View File
@@ -1,237 +0,0 @@
/****************************************************************************
*
* Copyright (c) 2021 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/**
* @file board_config.h
*
* Board internal definitions
*/
#pragma once
/****************************************************************************************************
* Included Files
****************************************************************************************************/
#include <px4_platform_common/px4_config.h>
#include <nuttx/compiler.h>
#include <stdint.h>
#include <stm32_gpio.h>
/****************************************************************************************************
* Definitions
****************************************************************************************************/
// #define FLASH_BASED_PARAMS
/* LEDs are driven with push open drain to support Anode to 5V or 3.3V */
#define GPIO_nLED_BLUE /* PE3 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN3)
#define GPIO_nLED_GREEN /* PE4 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTE|GPIO_PIN4)
#define BOARD_HAS_CONTROL_STATUS_LEDS 1
#define BOARD_ARMED_STATE_LED 1 // Green LED
#define BOARD_OVERLOAD_LED 0 // Blue LED
/*
* ADC channels
*
* These are the channel numbers of the ADCs of the microcontroller that
* can be used by the Px4 Firmware in the adc driver
*/
/* ADC defines to be used in sensors.cpp to read from a particular channel */
#define ADC1_CH(n) (n)
/* Define GPIO pins used as ADC N.B. Channel numbers must match below */
#define PX4_ADC_GPIO \
/* PC0 */ GPIO_ADC123_INP10, \
/* PC1 */ GPIO_ADC123_INP11, \
/* PA4 */ GPIO_ADC12_INP18, \
/* PA7 */ GPIO_ADC12_INP7, \
/* PC4 */ GPIO_ADC12_INP4, \
/* PC5 */ GPIO_ADC12_INP8
/* Define Channel numbers must match above GPIO pin IN(n)*/
#define ADC_BATTERY_VOLTAGE_CHANNEL /* PC0 */ ADC1_CH(10)
#define ADC_BATTERY_CURRENT_CHANNEL /* PC1 */ ADC1_CH(11)
#define ADC_BATTERY2_VOLTAGE_CHANNEL /* PA4 */ ADC1_CH(18)
#define ADC_BATTERY2_CURRENT_CHANNEL /* PA7 */ ADC1_CH(7)
#define ADC_AIRSPEED_IN_CHANNEL /* PC4 */ ADC1_CH(4)
#define ADC_RSSI_IN_CHANNEL /* PC5 */ ADC1_CH(8)
#define ADC_CHANNELS \
((1 << ADC_BATTERY_VOLTAGE_CHANNEL) | \
(1 << ADC_BATTERY_CURRENT_CHANNEL) | \
(1 << ADC_BATTERY2_VOLTAGE_CHANNEL) | \
(1 << ADC_BATTERY2_CURRENT_CHANNEL) | \
(1 << ADC_AIRSPEED_IN_CHANNEL) | \
(1 << ADC_RSSI_IN_CHANNEL))
/* Define Battery 1 Voltage Divider and A per V
*/
#define BOARD_BATTERY1_V_DIV (11.0f) /* measured with the provided PM board */
#define BOARD_BATTERY1_A_PER_V (40.0f)
#define BOARD_BATTERY2_V_DIV (11.0f) /* measured with the provided PM board */
/* CAN Silence
*
* Silent mode control \ ESC Mux select
*/
#define GPIO_CAN1_SILENT_S0 /* PD3 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTD|GPIO_PIN3)
/* PWM
*/
#define DIRECT_PWM_OUTPUT_CHANNELS 12
#define DIRECT_INPUT_TIMER_CHANNELS 12
#define BOARD_HAS_PWM DIRECT_PWM_OUTPUT_CHANNELS
/* Spare GPIO */
// #define GPIO_PG6 /* PG6 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTG|GPIO_PIN6)
// #define GPIO_PD15 /* PD15 */ (GPIO_INPUT|GPIO_FLOAT|GPIO_PORTD|GPIO_PIN15)
// #define GPIO_PG15 /* PG15 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTG|GPIO_PIN15)
/* Tone alarm output */
#define GPIO_TONE_ALARM_IDLE /* PA15 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN15)
#define GPIO_TONE_ALARM_GPIO /* PA15 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN15)
// #define TONE_ALARM_TIMER 2 /* Timer 2 */
// #define TONE_ALARM_CHANNEL 1 /* PA15 GPIO_TIM2_CH1OUT_2 */
// #define GPIO_TONE_ALARM_IDLE /* PA15 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN15)
// #define GPIO_TONE_ALARM GPIO_TIM2_CH1OUT_2
/* USB OTG FS
*
* PE2 OTG_FS_VBUS VBUS sensing
*/
#define GPIO_OTGFS_VBUS /* PE2 */ (GPIO_INPUT|GPIO_PULLDOWN|GPIO_SPEED_100MHz|GPIO_PORTE|GPIO_PIN2)
/* High-resolution timer */
#define HRT_TIMER 2 /* use timer8 for the HRT */
#define HRT_TIMER_CHANNEL 1 /* use capture/compare channel 3 */
/* RC Serial port */
#define RC_SERIAL_PORT "/dev/ttyS4"
#define BOARD_SUPPORTS_RC_SERIAL_PORT_OUTPUT
// #define GPIO_RSSI_IN /* PC5 */ (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTC|GPIO_PIN5)
/* SD Card */
#define SDIO_SLOTNO 0 /* Only one slot */
#define SDIO_MINOR 0
/* This board provides a DMA pool and APIs */
#define BOARD_DMA_ALLOC_POOL_SIZE 5120
/* This board provides the board_on_reset interface */
#define BOARD_HAS_ON_RESET 1
#define PX4_GPIO_INIT_LIST { \
PX4_ADC_GPIO, \
GPIO_CAN1_TX, \
GPIO_CAN1_RX, \
GPIO_CAN1_SILENT_S0, \
GPIO_nLED_BLUE, \
GPIO_nLED_GREEN, \
GPIO_TONE_ALARM_IDLE, \
}
#define BOARD_ENABLE_CONSOLE_BUFFER
#define BOARD_NUM_IO_TIMERS 4
__BEGIN_DECLS
/****************************************************************************************************
* Public Types
****************************************************************************************************/
/****************************************************************************************************
* Public data
****************************************************************************************************/
#ifndef __ASSEMBLY__
/****************************************************************************************************
* Public Functions
****************************************************************************************************/
/****************************************************************************
* Name: stm32_sdio_initialize
*
* Description:
* Initialize SDIO-based MMC/SD card support
*
****************************************************************************/
int stm32_sdio_initialize(void);
/****************************************************************************************************
* Name: stm32_spiinitialize
*
* Description:
* Called to configure SPI chip select GPIO pins for the board.
*
****************************************************************************************************/
extern void stm32_spiinitialize(void);
extern void stm32_usbinitialize(void);
extern void board_peripheral_reset(int ms);
#include <px4_platform_common/board_common.h>
#endif /* __ASSEMBLY__ */
__END_DECLS

Some files were not shown because too many files have changed in this diff Show More