Compare commits

..

14 Commits

Author SHA1 Message Date
JacobCrabill 8e01fe661a fixup! Update submodule nuttx 2022-03-18 10:56:44 -07:00
JacobCrabill 64863fe54e uavcan_v1: Add Publishers dir to includes 2022-03-18 09:03:48 -07:00
JacobCrabill 73b1de85cb uavcan_v1: SocketCAN set 'can_fd' based on CONFIG 2022-03-18 09:03:06 -07:00
JacobCrabill fd3662097f fixup! Update submodule nuttx 2022-03-18 09:02:00 -07:00
JacobCrabill 76da12fce3 uavcan_v1: Immediate transmit() from Publishers
Add 'do_transmit()' to UavcanNode
Add 'transmit()' to Publisher base class to call do_transmit()
Call transmit() after canardTxPush from Publishers
2022-03-17 17:01:54 -07:00
JacobCrabill 9531900afa mro/ctrl-zero-h7-oem: Start adding socketcan support 2022-03-16 10:21:10 -07:00
JacobCrabill 25271a3f04 fixup! Update submodule nuttx 2022-03-16 10:20:29 -07:00
JacobCrabill 4048ac57bf fixup! Update submodule nuttx 2022-03-15 18:53:13 -07:00
JacobCrabill 399ab35a4f fixup! HACK: Disable SO_TIMESTAMP in uavcan_v1 temporarily while bringing up H7 SocketCAN driver 2022-03-15 18:52:00 -07:00
JacobCrabill f4f8eee02d cubeorange: Add TX_DEADLINE support 2022-03-15 18:24:03 -07:00
JacobCrabill dec15b4fa9 Update submodule nuttx 2022-03-15 18:23:22 -07:00
JacobCrabill 7db8d3ad78 HACK: Disable SO_TIMESTAMP in uavcan_v1 temporarily while bringing up H7 SocketCAN driver 2022-03-15 17:45:34 -07:00
JacobCrabill 7e34806046 mavlink: Replace CONFIG_NET with CONFIG_NET_UDP
Allows use of SocketCAN w/o also enabling UDP support in NuttX
2022-03-15 17:22:27 -07:00
JacobCrabill 9f18ef6688 Orange Cube: Add socketcan target 2022-03-15 17:11:42 -07:00
468 changed files with 4948 additions and 11893 deletions
+1 -2
View File
@@ -28,7 +28,7 @@ pipeline {
]
def base_builds = [
target: ["px4_sitl_default"],
target: ["px4_sitl_rtps"],
image: docker_images.base,
archive: false
]
@@ -58,7 +58,6 @@ pipeline {
"holybro_can-gps-v1_default",
"holybro_durandal-v1_default",
"holybro_kakutef7_default",
"holybro_kakuteh7_default",
"holybro_pix32v5_default",
"matek_h743-slim",
"matek_gnss-m9n-f4_canbootloader",
+4 -7
View File
@@ -705,21 +705,18 @@ void quickCalibrate() {
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "gyro_calibration status || true"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "commander calibrate accel quick; sleep 1"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "commander calibrate accel quick"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "param show CAL_ACC*"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "commander calibrate gyro; sleep 2"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "commander calibrate gyro"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "param show CAL_GYRO*"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "commander calibrate level; sleep 2"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "commander calibrate level"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "param show SENS*"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "commander calibrate mag quick; sleep 1"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "commander calibrate mag quick"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "param show CAL_MAG*"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "commander calibrate baro; sleep 5"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "param show CAL_BARO*"'
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "param show CAL_*"' // parameters after
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "sensors status"'
}
+2 -5
View File
@@ -24,8 +24,8 @@
branch = master
[submodule "platforms/nuttx/NuttX/nuttx"]
path = platforms/nuttx/NuttX/nuttx
url = https://github.com/PX4/NuttX.git
branch = px4_firmware_nuttx-10.1.0+
url = https://github.com/JacobCrabill/incubator-nuttx.git
branch = dev-h7-socketcan
[submodule "platforms/nuttx/NuttX/apps"]
path = platforms/nuttx/NuttX/apps
url = https://github.com/PX4/NuttX-apps.git
@@ -64,6 +64,3 @@
path = src/lib/crypto/libtommath
url = https://github.com/PX4/libtommath.git
branch = px4
[submodule "src/modules/microdds_client/Micro-XRCE-DDS-Client"]
path = src/modules/microdds_client/Micro-XRCE-DDS-Client
url = https://github.com/eProsima/Micro-XRCE-DDS-Client.git
-7
View File
@@ -412,7 +412,6 @@ endif()
# subdirectories
#
add_library(parameters_interface INTERFACE)
add_library(kernel_parameters_interface INTERFACE)
include(px4_add_library)
add_subdirectory(src/lib EXCLUDE_FROM_ALL)
@@ -435,13 +434,7 @@ add_subdirectory(src/lib/metadata EXCLUDE_FROM_ALL)
# must be the last module before firmware
add_subdirectory(src/lib/parameters EXCLUDE_FROM_ALL)
if(${PX4_PLATFORM} STREQUAL "nuttx" AND NOT CONFIG_BUILD_FLAT)
target_link_libraries(parameters_interface INTERFACE usr_parameters)
target_link_libraries(kernel_parameters_interface INTERFACE parameters)
else()
target_link_libraries(parameters_interface INTERFACE parameters)
endif()
# firmware added last to generate the builtin for included modules
add_subdirectory(platforms/${PX4_PLATFORM})
@@ -10,7 +10,6 @@
# enable fusion of landing target velocity
param set-default LTEST_MODE 1
param set-default PLD_HACC_RAD 0.1
param set-default RTL_PLD_MD 2
# Start up Landing Target Estimator module
landing_target_estimator start
@@ -8,5 +8,8 @@
# disable circuit breaker for airspeed sensor
param set-default CBRK_AIRSPD_CHK 162128
set MAV_TYPE 12
param set MAV_TYPE ${MAV_TYPE}
set MIXER_FILE etc/mixers-sitl/uuv_x_sitl.main.mix
set MIXER custom
@@ -8,5 +8,8 @@
# disable circuit breaker for airspeed sensor
param set-default CBRK_AIRSPD_CHK 162128
set MAV_TYPE 12
param set MAV_TYPE ${MAV_TYPE}
set MIXER_FILE etc/mixers-sitl/uuv_x_sitl.main.mix
set MIXER custom
@@ -67,3 +67,4 @@ param set-default PWM_MAIN_FUNC7 107
param set-default PWM_MAIN_FUNC8 108
set MIXER skip
@@ -80,5 +80,7 @@ param set-default VT_FW_MOT_OFFID 1234
param set-default VT_B_TRANS_DUR 8
param set-default VT_TYPE 2
set MAV_TYPE 22
set MIXER_FILE etc/mixers-sitl/standard_vtol_sitl.main.mix
set MIXER custom
@@ -7,8 +7,6 @@
. ${R}etc/init.d/rc.vtol_defaults
param set-default MAV_TYPE 20
# param set-default SYS_CTRL_ALLOC 1
param set-default CA_AIRFRAME 4
@@ -80,5 +78,7 @@ param set-default VT_TYPE 0
param set-default WV_EN 0
set MAV_TYPE 20
set MIXER_FILE etc/mixers-sitl/quad_x_vtol.main.mix
set MIXER custom
@@ -7,8 +7,6 @@
. ${R}etc/init.d/rc.vtol_defaults
param set-default MAV_TYPE 21
# param set-default SYS_CTRL_ALLOC 1
param set-default CA_AIRFRAME 3
@@ -90,5 +88,7 @@ param set-default VT_MOT_ID 1234
param set-default VT_TILT_TRANS 0.6
param set-default VT_TYPE 1
set MAV_TYPE 21
set MIXER_FILE etc/mixers-sitl/tiltrotor_sitl.main.mix
set MIXER custom
@@ -51,5 +51,7 @@ param set-default RC_MAP_AUX1 8
param set-default RC_MAP_AUX2 9
param set-default RC_MAP_AUX3 10
set MAV_TYPE 22
set MIXER_FILE etc/mixers-sitl/standard_vtol_sitl.main.mix
set MIXER custom
@@ -37,4 +37,6 @@ param set-default PWM_MAIN_FUNC2 201
param set-default PWM_MAIN_FUNC6 101
param set-default PWM_MAIN_FUNC7 101
set MAV_TYPE 10
set MIXER_FILE skip
@@ -37,4 +37,6 @@ param set-default PWM_MAIN_FUNC2 101
param set-default PWM_MAIN_FUNC6 102
param set-default PWM_MAIN_FUNC7 102
set MAV_TYPE 10
set MIXER_FILE skip
@@ -10,8 +10,6 @@
. ${R}etc/init.d/rc.rover_defaults
param set-default MAV_TYPE 10
param set-default GND_L1_DIST 5
param set-default GND_SP_CTRL_MODE 1
param set-default GND_SPEED_D 3
@@ -35,4 +33,6 @@ param set-default CBRK_AIRSPD_CHK 162128
param set-default GND_MAX_ANG 0.6
param set-default GND_WHEEL_BASE 3.0
set MAV_TYPE 10
set MIXER_FILE etc/mixers-sitl/rover_ackermann_sitl.main.mix
@@ -47,4 +47,6 @@ param set-default CA_R_REV 3
param set-default PWM_MAIN_FUNC1 101
param set-default PWM_MAIN_FUNC2 102
set MAV_TYPE 11
set MIXER skip
@@ -9,8 +9,6 @@
. ${R}etc/init.d/rc.mc_defaults
param set-default MAV_TYPE 13
param set-default MC_PITCHRATE_P 0.1
param set-default MC_PITCHRATE_I 0.05
param set-default MC_PITCH_P 6.0
@@ -26,4 +24,6 @@ param set-default TRIG_MODE 4
param set-default MNT_MODE_IN 4
param set-default MNT_DO_STAB 2
set MAV_TYPE 13
set MIXER hexa_x
@@ -7,8 +7,6 @@
. ${R}etc/init.d/rc.mc_defaults
param set-default MAV_TYPE 13
param set-default MC_PITCHRATE_P 0.0800
param set-default MC_PITCHRATE_I 0.0400
param set-default MC_PITCHRATE_D 0.0010
@@ -28,4 +26,6 @@ param set-default MNT_MODE_IN 4
param set-default MNT_MODE_OUT 2
param set-default MAV_PROTO_VER 2
set MAV_TYPE 13
set MIXER hexa_x
@@ -7,8 +7,6 @@
. ${R}etc/init.d/rc.mc_defaults
param set-default MAV_TYPE 13
param set-default SYS_CTRL_ALLOC 1
param set-default MC_PITCHRATE_P 0.0800
@@ -60,5 +58,7 @@ param set-default PWM_MAIN_FUNC4 104
param set-default PWM_MAIN_FUNC5 105
param set-default PWM_MAIN_FUNC6 106
set MAV_TYPE 13
set MIXER skip
set MIXER_AUX none
+7 -7
View File
@@ -24,6 +24,7 @@ fi
# initialize script variables
set IO_PRESENT no
set MAV_TYPE none
set MIXER none
set MIXER_AUX none
set MIXER_FILE none
@@ -223,13 +224,6 @@ rc_update start
manual_control start
sensors start
commander start
# Configure vehicle type specific parameters.
# Note: rc.vehicle_setup is the entry point for rc.interface,
# rc.fw_apps, rc.mc_apps, rc.rover_apps, and rc.vtol_apps.
#
. ${R}etc/init.d/rc.vehicle_setup
navigator start
# Try to start the micrortps_client with UDP transport if module exists
@@ -259,6 +253,12 @@ then
gyro_calibration start
fi
# Configure vehicle type specific parameters.
# Note: rc.vehicle_setup is the entry point for rc.interface,
# rc.fw_apps, rc.mc_apps, rc.rover_apps, and rc.vtol_apps.
#
. ${R}etc/init.d/rc.vehicle_setup
#user defined mavlink streams for instances can be in PATH
. px4-rc.mavlink
@@ -36,5 +36,4 @@ 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
@@ -104,7 +104,7 @@ param set-default CBRK_SUPPLY_CHK 894281
param set-default COM_PREARM_MODE 0
param set-default CBRK_IO_SAFETY 22027
param set-default MAV_TYPE 22
set MAV_TYPE 22
set MIXER standard_vtol_hitl
@@ -47,7 +47,7 @@ param set-default HIL_ACT_FUNC6 201
param set-default HIL_ACT_REV 32
param set-default MAV_TYPE 19
set MAV_TYPE 19
set MIXER vtol_tailsitter_duo_sat
set PWM_OUT 1234
@@ -54,8 +54,7 @@ param set-default PWM_AUX_DIS5 950
param set-default VT_TYPE 2
param set-default VT_MOT_ID 1234
param set-default VT_FW_MOT_OFFID 1234
param set-default MAV_TYPE 22
set MAV_TYPE 22
set MIXER quad_x
set MIXER_AUX vtol_AAERT
@@ -19,6 +19,7 @@
. ${R}etc/init.d/rc.vtol_defaults
param set-default MAV_TYPE 19
param set-default MC_ROLL_P 6
@@ -37,6 +38,7 @@ param set-default VT_IDLE_PWM_MC 1080
param set-default VT_ELEV_MC_LOCK 0
param set-default VT_MOT_ID 12
param set-default VT_TYPE 0
set MAV_TYPE 19
set MIXER vtol_tailsitter_duo
@@ -23,7 +23,6 @@
. ${R}etc/init.d/rc.vtol_defaults
param set-default MAV_TYPE 21
param set-default MC_ROLL_P 7
param set-default MC_ROLLRATE_P 0.19
@@ -46,6 +45,7 @@ param set-default VT_TILT_TRANS 0.5
param set-default VT_TILT_FW 0.9
param set-default VT_ELEV_MC_LOCK 0
param set-default VT_TYPE 1
set MAV_TYPE 21
set MIXER firefly6
set MIXER_AUX firefly6
@@ -13,8 +13,6 @@
. ${R}etc/init.d/rc.vtol_defaults
param set-default MAV_TYPE 20
param set-default CA_AIRFRAME 4
param set-default CA_ROTOR_COUNT 4
param set-default CA_ROTOR0_PX 0.15
@@ -40,6 +38,7 @@ param set-default PWM_MAIN_MAX 2000
param set-default VT_MOT_ID 1234
param set-default VT_IDLE_PWM_MC 1080
param set-default VT_TYPE 0
set MAV_TYPE 20
set MIXER quad_x_vtol
@@ -22,13 +22,13 @@
. ${R}etc/init.d/rc.vtol_defaults
param set-default MAV_TYPE 20
param set-default PWM_MAIN_MAX 2000
param set-default VT_IDLE_PWM_MC 1080
param set-default VT_TYPE 0
set MAV_TYPE 20
set MIXER quad_+_vtol
set PWM_OUT 1234
@@ -52,6 +52,7 @@ param set-default VT_MOT_ID 1234
param set-default VT_FW_MOT_OFFID 1234
param set-default VT_IDLE_PWM_MC 1080
param set-default VT_TYPE 2
set MAV_TYPE 22
set MIXER quad_x
set MIXER_AUX vtol_AAERT
@@ -41,6 +41,7 @@ param set-default VT_FW_MOT_OFFID 1234
param set-default VT_F_TRANS_THR 0.75
param set-default VT_IDLE_PWM_MC 1080
param set-default VT_TYPE 2
set MAV_TYPE 22
set MIXER quad_x
set MIXER_AUX vtol_delta
@@ -33,6 +33,7 @@ param set-default VT_MOT_ID 1234
param set-default VT_FW_MOT_OFFID 1234
param set-default VT_IDLE_PWM_MC 1080
param set-default VT_TYPE 2
set MAV_TYPE 22
set MIXER quad_x
set MIXER_AUX vtol_AAVVT
@@ -46,6 +46,7 @@ param set-default VT_IDLE_PWM_MC 1080
param set-default VT_MOT_ID 1234
param set-default VT_FW_MOT_OFFID 1234
param set-default VT_TYPE 2
set MAV_TYPE 22
set MIXER quad_x
set MIXER_AUX vtol_AAERT
@@ -77,6 +77,8 @@ param set-default VT_TRANS_MIN_TM 5
param set-default VT_TRANS_TIMEOUT 30
param set-default VT_TYPE 2
set MAV_TYPE 22
set MIXER quad_x
set MIXER_AUX vtol_AAERT
@@ -13,8 +13,6 @@
. ${R}etc/init.d/rc.vtol_defaults
param set-defualt MAV_TYPE 21
param set-default PWM_AUX_DISARM 1000
param set-default PWM_AUX_MAX 2000
param set-default PWM_AUX_MIN 1000
@@ -30,6 +28,7 @@ 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 MAV_TYPE 21
set MIXER claire
set MIXER_AUX claire
@@ -22,8 +22,6 @@
. ${R}etc/init.d/rc.vtol_defaults
param set-defualt MAV_TYPE 21
param set-default CBRK_AIRSPD_CHK 162128
param set-default FW_ARSP_MODE 1
@@ -66,6 +64,7 @@ param set-default VT_TRANS_MIN_TM 1.2
param set-default VT_TRANS_P2_DUR 1.3
param set-default VT_ELEV_MC_LOCK 0
param set-default VT_TYPE 1
set MAV_TYPE 21
set MIXER vtol_convergence
@@ -22,8 +22,6 @@
. ${R}etc/init.d/rc.vtol_defaults
param set-default MAV_TYPE 22
param set-default BAT1_CAPACITY 23000
param set-default BAT1_N_CELLS 4
param set-default BAT1_R_INTERNAL 0.0025
@@ -136,6 +134,7 @@ param set-default VT_TRANS_TIMEOUT 22
param set-default VT_F_TRANS_RAMP 4
param set-default COM_RC_OVERRIDE 0
set MAV_TYPE 22
set MIXER deltaquad
set MIXER_AUX pass
@@ -23,8 +23,6 @@
. ${R}etc/init.d/rc.vtol_defaults
param set-default MAV_TYPE 22
param set-default BAT1_N_CELLS 6
param set-default FW_AIRSPD_MAX 30
@@ -96,6 +94,8 @@ param set-default VT_PSHER_RMP_DT 2
param set-default VT_TRANS_MIN_TM 4
param set-default VT_TYPE 2
set MAV_TYPE 22
set MIXER babyshark
set MIXER_AUX pass
@@ -27,8 +27,6 @@
. ${R}etc/init.d/rc.vtol_defaults
param set-default MAV_TYPE 21
param set-default VT_IDLE_PWM_MC 1100
param set-default VT_TYPE 1
param set-default VT_MOT_ID 1234
@@ -59,6 +57,8 @@ param set-default CA_SV_CS3_TRQ_Y 1.0
param set-default CA_SV_CS3_TYPE 4
param set-default CA_SV_TL_COUNT 4
set MAV_TYPE 21
set MIXER quad_x
set MIXER_AUX vtol_TTTTAAER
@@ -31,6 +31,7 @@ param set-default PWM_AUX_DIS5 950
param set-default VT_TYPE 2
param set-default VT_MOT_ID 12345678
param set-default VT_FW_MOT_OFFID 12345678
set MAV_TYPE 22
set MIXER octo_cox
set MIXER_AUX vtol_AAERT
@@ -19,8 +19,6 @@
. ${R}etc/init.d/rc.vtol_defaults
param set-default MAV_TYPE 19
param set-default VT_ELEV_MC_LOCK 0
param set-default VT_MOT_COUNT 2
param set-default VT_TYPE 0
@@ -39,6 +37,8 @@ param set-default CA_SV_CS1_TRQ_P 0.5
param set-default CA_SV_CS1_TRQ_Y -0.5
param set-default CA_SV_CS1_TYPE 6
param set-default MAV_TYPE 19
set MAV_TYPE 19
set MIXER vtol_tailsitter_duo
set PWM_OUT 1234
@@ -18,7 +18,4 @@
. ${R}etc/init.d/rc.mc_defaults
# MAV_TYPE_TRICOPTER 15
param set-default MAV_TYPE 15
set MIXER tri_y_yaw+
@@ -18,7 +18,4 @@
. ${R}etc/init.d/rc.mc_defaults
# MAV_TYPE_TRICOPTER 15
param set-default MAV_TYPE 15
set MIXER tri_y_yaw-
@@ -17,9 +17,7 @@
#
. ${R}etc/init.d/rc.mc_defaults
# MAV_TYPE_COAXIAL 3
param set-default MAV_TYPE 3
set MIXER coax
param set-default MC_ROLLRATE_P 0.17
param set-default MC_ROLLRATE_I 0.05
@@ -38,9 +36,6 @@ param set-default PWM_MAIN_RATE 400
param set-default RTL_RETURN_ALT 30
param set-default RTL_DESCEND_ALT 10
set MIXER coax
# This is the gimbal pass mixer
set MIXER_AUX pass
@@ -20,7 +20,7 @@
. ${R}etc/init.d/rc.mc_defaults
# Configure as helicopter (number 4 defined in commander_helper.cpp)
param set-default MAV_TYPE 4
set MAV_TYPE 4
set MIXER blade130
@@ -41,6 +41,5 @@ param set-default FW_R_LIM 40
param set-default FW_P_LIM_MAX 25
param set-default FW_P_LIM_MIN -5
param set-default FW_P_RMAX_NEG 20
set MIXER TF-G2
set MIXER_AUX pass
@@ -24,5 +24,8 @@ param set-default MAV_0_CONFIG 102
param set-default GPS_UBX_DYNMODEL 8
param set-default SER_TEL2_BAUD 9600
set MAV_TYPE 8
param set MAV_TYPE ${MAV_TYPE}
set MIXER IO_pass
set MIXER_AUX pass
@@ -26,7 +26,7 @@
# @board px4_fmu-v2 exclude
#
. ${R}etc/init.d/rc.mc_defaults
set VEHICLE_TYPE mc
param set-default NAV_ACC_RAD 2
@@ -39,7 +39,6 @@ param set-default PWM_MAIN_RATE 400
param set-default RTL_DESCEND_ALT 10
param set-default RTL_RETURN_ALT 30
set MIXER dodeca_top_cox
set MIXER_AUX dodeca_bottom_cox
@@ -41,6 +41,9 @@ param set-default FW_RR_P 0.04
param set-default PWM_MAIN_DISARM 1000
# Configure this as plane.
set MAV_TYPE 1
# Set mixer.
set MIXER fw_generic_wing
@@ -24,6 +24,8 @@
set MIXER quad_s250aq
set MAV_TYPE 2
param set-default ATT_BIAS_MAX 0
param set-default CBRK_IO_SAFETY 22027
@@ -21,7 +21,10 @@
# @board cuav_x7pro exclude
#
. ${R}etc/init.d/rc.mc_defaults
set VEHICLE_TYPE mc
set MIXER quad_x
set PWM_OUT 1234
# Attitude & rate gains
param set-default MC_ROLLRATE_D 0.0013
@@ -21,7 +21,10 @@
# @maintainer Hyon Lim <lim@uvify.com>
#
. ${R}etc/init.d/rc.mc_defaults
set VEHICLE_TYPE mc
set MIXER quad_x
set PWM_OUT 1234
# Attitude & rate gains
param set-default MC_ROLLRATE_D 0.0013
@@ -24,6 +24,10 @@
. ${R}etc/init.d/rc.mc_defaults
# Configure this as Quadrotor
# set MAV_TYPE 14
# Set mixer
set MIXER tilt_quad
set MIXER_AUX tilt_quad
@@ -48,6 +48,8 @@ param set-default NAV_ACC_RAD 0.5
param set-default PWM_MAIN_DISARM 1500
param set-default PWM_MAIN_MAX 2000
param set-default PWM_MAIN_MIN 1000
# Configure this as rover
set MAV_TYPE 10
# Set mixer
set MIXER rover_generic
@@ -76,6 +76,9 @@ param set-default RBCLW_SER_CFG 104
# Start this driver after setting parameters, because the driver uses some of those parameters.
# roboclaw start /dev/ttyS3
# Configure this as rover
set MAV_TYPE 10
# Set mixer
set MIXER generic_diff_rover
@@ -65,6 +65,9 @@ param set-default PWM_MAIN_MIN4 970
# Enable Airspeed check circuit breaker because Rovers will have no airspeed sensor
param set-default CBRK_AIRSPD_CHK 162128
# Configure this as rover
set MAV_TYPE 10
# Set mixer
set MIXER rover_diff_and_servo
@@ -16,4 +16,7 @@
# disable circuit breaker for airspeed sensor
param set-default CBRK_AIRSPD_CHK 162128
set MAV_TYPE 12
param set MAV_TYPE ${MAV_TYPE}
set MIXER uuv_x
@@ -16,4 +16,7 @@
# disable circuit breaker for airspeed sensor
param set-default CBRK_AIRSPD_CHK 162128
set MAV_TYPE 12
param set MAV_TYPE ${MAV_TYPE}
set MIXER uuv_x
@@ -23,9 +23,6 @@
. ${R}etc/init.d/rc.mc_defaults
# MAV_TYPE_HEXAROTOR 13
param set-default MAV_TYPE 13
param set-default CA_ROTOR_COUNT 6
param set-default CA_ROTOR0_PX 0.0
param set-default CA_ROTOR0_PY 0.5
@@ -27,8 +27,9 @@
. ${R}etc/init.d/rc.mc_defaults
# MAV_TYPE_HEXAROTOR 13
param set-default MAV_TYPE 13
set MIXER hexa_x
set PWM_OUT 12345678
###############################################
# Attitude & rate gains
@@ -119,7 +120,3 @@ param set-default MAV_1_MODE 2
param set-default MAV_1_FORWARD 1
param set-default MAV_1_RATE 800000
param set-default SER_TEL2_BAUD 921600
set MIXER hexa_x
set PWM_OUT 12345678
@@ -23,9 +23,6 @@
. ${R}etc/init.d/rc.mc_defaults
# MAV_TYPE_HEXAROTOR 13
param set-default MAV_TYPE 13
param set-default CA_ROTOR_COUNT 6
param set-default CA_ROTOR0_PX 0.5
param set-default CA_ROTOR0_PY 0.0
@@ -25,9 +25,6 @@
. ${R}etc/init.d/rc.mc_defaults
# MAV_TYPE_OCTOROTOR 14
param set-default MAV_TYPE 14
param set-default CA_ROTOR_COUNT 8
param set-default CA_ROTOR0_KM -0.05
param set-default CA_ROTOR0_PX 0.46
@@ -25,9 +25,6 @@
. ${R}etc/init.d/rc.mc_defaults
# MAV_TYPE_OCTOROTOR 14
param set-default MAV_TYPE 14
set MIXER octo_+
set PWM_OUT 12345678
@@ -7,9 +7,6 @@
set VEHICLE_TYPE airship
# MAV_TYPE_AIRSHIP 7
param set-default MAV_TYPE 7
#
# This is the gimbal pass mixer.
#
@@ -7,9 +7,6 @@
set VEHICLE_TYPE fw
# MAV_TYPE_FREE_BALLOON 8
param set-default MAV_TYPE 8
#
# Default parameters for balloon UAVs.
#
@@ -7,9 +7,6 @@
set VEHICLE_TYPE rover
# MAV_TYPE_SURFACE_BOAT 11
param set-default MAV_TYPE 11
#
# Default parameters for UGVs.
#
+2 -3
View File
@@ -7,15 +7,14 @@
set VEHICLE_TYPE fw
# MAV_TYPE_FIXED_WING 1
param set-default MAV_TYPE 1
#
# Default parameters for fixed wing UAVs.
#
param set-default COM_POS_FS_DELAY 5
param set-default COM_POS_FS_EPH 15
param set-default COM_POS_FS_EPV 30
param set-default COM_POS_FS_GAIN 0
param set-default COM_POS_FS_PROB 1
param set-default COM_VEL_FS_EVH 5
# Disable preflight disarm to not interfere with external launching
param set-default COM_DISARM_PRFLT -1
@@ -7,9 +7,6 @@
set VEHICLE_TYPE mc
# MAV_TYPE_QUADROTOR 2
param set-default MAV_TYPE 2
if param compare IMU_GYRO_RATEMAX 400
then
param set-default IMU_GYRO_RATEMAX 800
@@ -7,9 +7,6 @@
set VEHICLE_TYPE rover
# MAV_TYPE_GROUND_ROVER 10
param set-default MAV_TYPE 10
#
# Default parameters for UGVs.
#
-7
View File
@@ -155,13 +155,6 @@ then
irlock start -X
fi
# SPL06 sensor external I2C
if param compare -s SENS_EN_SPL06 1
then
spl06 -X start
spl06 -X -a 0x77 start
fi
# PCF8583 counter (RPM sensor)
if param compare -s SENS_EN_PCF8583 1
then
@@ -7,9 +7,6 @@
set VEHICLE_TYPE uuv
# MAV_TYPE_SUBMARINE 12
param set-default MAV_TYPE 12
param set-default PWM_MAIN_MAX 1950
param set-default PWM_MAIN_MIN 1050
param set-default PWM_MAIN_DISARM 1500
+93 -2
View File
@@ -12,9 +12,19 @@ if [ $VEHICLE_TYPE = fw ]
then
if [ $MIXER = none ]
then
echo "FW mixer undefined"
# Set default mixer for fixed wing if not defined.
set MIXER AERT
fi
if [ $MAV_TYPE = none ]
then
# Set a default MAV_TYPE = 1 if not defined.
set MAV_TYPE 1
fi
# Set the mav type parameter.
param set MAV_TYPE ${MAV_TYPE}
# Load mixer and configure outputs.
. ${R}etc/init.d/rc.interface
@@ -32,6 +42,41 @@ then
echo "MC mixer undefined"
fi
if [ $MAV_TYPE = none ]
then
# Set a default MAV_TYPE = 2 if not defined.
set MAV_TYPE 2
# Use mixer to detect vehicle type
if [ $MIXER = coax ]
then
set MAV_TYPE 3
fi
if [ $MIXER = hexa_x -o $MIXER = hexa_+ ]
then
set MAV_TYPE 13
fi
if [ $MIXER = hexa_cox ]
then
set MAV_TYPE 13
fi
if [ $MIXER = octo_x -o $MIXER = octo_+ ]
then
set MAV_TYPE 14
fi
if [ $MIXER = octo_cox -o $MIXER = octo_cox_w ]
then
set MAV_TYPE 14
fi
if [ $MIXER = tri_y_yaw- -o $MIXER = tri_y_yaw+ ]
then
set MAV_TYPE 15
fi
fi
# Set the mav type parameter.
param set MAV_TYPE ${MAV_TYPE}
# Load mixer and configure outputs.
. ${R}etc/init.d/rc.interface
@@ -46,9 +91,19 @@ if [ $VEHICLE_TYPE = rover ]
then
if [ $MIXER = none ]
then
echo "rover mixer undefined"
# Set default mixer for UGV if not defined.
set MIXER rover_generic
fi
if [ $MAV_TYPE = none ]
then
# Set a default MAV_TYPE = 10 if not defined.
set MAV_TYPE 10
fi
# Set the mav type parameter.
param set MAV_TYPE ${MAV_TYPE}
# Load mixer and configure outputs.
. ${R}etc/init.d/rc.interface
@@ -66,6 +121,25 @@ then
echo "VTOL mixer undefined"
fi
if [ $MAV_TYPE = none ]
then
# Set a default MAV_TYPE = 19 if not defined.
set MAV_TYPE 19
# Use mixer to detect vehicle type.
if [ $MIXER = firefly6 ]
then
set MAV_TYPE 21
fi
if [ $MIXER = quad_x_pusher_vtol ]
then
set MAV_TYPE 22
fi
fi
# Set the mav type parameter.
param set MAV_TYPE ${MAV_TYPE}
# Load mixer and configure outputs.
. ${R}etc/init.d/rc.interface
@@ -83,6 +157,15 @@ then
echo "Airship mixer undefined"
fi
if [ $MAV_TYPE = none ]
then
# Set a default MAV_TYPE = 7 if not defined.
set MAV_TYPE 7
fi
# Set the mav type parameter.
param set MAV_TYPE ${MAV_TYPE}
# Load mixer and configure outputs.
. ${R}etc/init.d/rc.interface
@@ -100,11 +183,19 @@ then
echo "UUV mixer undefined"
fi
if [ $MAV_TYPE = none ]
then
# Set default MAV_TYPE to submarine if not defined
set MAV_TYPE 12
fi
param set MAV_TYPE ${MAV_TYPE}
# Load mixer and configure outputs.
. ${R}etc/init.d/rc.interface
# Start standard vtol apps.
. ${R}etc/init.d/rc.uuv_apps
fi
@@ -7,9 +7,6 @@
set VEHICLE_TYPE vtol
# MAV_TYPE_VTOL_FIXEDROTOR 22
param set-default MAV_TYPE 22
param set-default MIS_TAKEOFF_ALT 20
param set-default MIS_YAW_TMT 10
+9 -7
View File
@@ -29,6 +29,7 @@ set IOFW "/etc/extras/px4_io-v2_default.bin"
set IO_PRESENT no
set LOGGER_ARGS ""
set LOGGER_BUF 8
set MAV_TYPE none
set MIXER none
set MIXER_AUX none
set MIXER_FILE none
@@ -408,13 +409,6 @@ else
commander start
fi
#
# Configure vehicle type specific parameters.
# Note: rc.vehicle_setup is the entry point for rc.interface,
# rc.fw_apps, rc.mc_apps, rc.rover_apps, and rc.vtol_apps.
#
. ${R}etc/init.d/rc.vehicle_setup
# Pre-takeoff continuous magnetometer calibration
if param compare -s MBE_ENABLE 1
then
@@ -465,6 +459,13 @@ else
fi
fi
#
# Configure vehicle type specific parameters.
# Note: rc.vehicle_setup is the entry point for rc.interface,
# rc.fw_apps, rc.mc_apps, rc.rover_apps, and rc.vtol_apps.
#
. ${R}etc/init.d/rc.vehicle_setup
#
# Play the startup tune (if not disabled or there is an error)
#
@@ -572,6 +573,7 @@ unset IO_PRESENT
unset IOFW
unset LOGGER_ARGS
unset LOGGER_BUF
unset MAV_TYPE
unset MIXER
unset MIXER_AUX
unset MIXER_FILE
@@ -1,7 +1,5 @@
Mixer for Tailsitter with x motor configuration and elevons
===========================================================
# @board px4_fmu-v2 exclude
# @board omnibus_f4sd exclude
This file defines a single mixer for tailsitter with motors in X configuration. All controls
are mixed 100%.
@@ -27,5 +27,4 @@ exec find boards msg src platforms test \
-path src/lib/crypto/monocypher -prune -o \
-path src/lib/crypto/libtomcrypt -prune -o \
-path src/lib/crypto/libtommath -prune -o \
-path src/modules/microdds_client/Micro-XRCE-DDS-Client -prune -o \
-type f \( -name "*.c" -o -name "*.h" -o -name "*.cpp" -o -name "*.hpp" \) | grep $PATTERN
-1
View File
@@ -139,7 +139,6 @@ mc_hover_thrust_estimator,CONFIG_MODULES_MC_HOVER_THRUST_ESTIMATOR=y
mc_pos_control,CONFIG_MODULES_MC_POS_CONTROL=y
mc_rate_control,CONFIG_MODULES_MC_RATE_CONTROL=y
micrortps_bridge,CONFIG_MODULES_MICRORTPS_BRIDGE=y
microdds_client,CONFIG_MODULES_MICRODDS_CLIENT=y
navigator,CONFIG_MODULES_NAVIGATOR=y
px4iofirmware,CONFIG_MODULES_PX4IOFIRMWARE=y
rc_update,CONFIG_MODULES_RC_UPDATE=y
@@ -525,9 +525,16 @@ Syslink::handle_raw(syslink_message_t *sys)
crtp_commander *cmd = (crtp_commander *) &c->data[0];
input_rc_s rc{};
rc.timestamp_sample = hrt_absolute_time();
input_rc_s rc = {};
rc.timestamp = hrt_absolute_time();
rc.timestamp_last_signal = rc.timestamp;
rc.channel_count = 5;
rc.rc_failsafe = false;
rc.rc_lost = false;
rc.rc_lost_frame_count = 0;
rc.rc_total_frame_count = 1;
rc.rc_ppm_frame_length = 0;
rc.input_source = input_rc_s::RC_INPUT_SOURCE_MAVLINK;
rc.rssi = _rssi;
@@ -541,7 +548,6 @@ Syslink::handle_raw(syslink_message_t *sys)
rc.values[3] = cmd->thrust * 1000 / USHRT_MAX + 1000;
rc.values[4] = 1000; // Dummy channel as px4 needs at least 5
rc.timestamp = hrt_absolute_time();
_rc_pub.publish(rc);
} else if (c->port == CRTP_PORT_MAVLINK) {
@@ -0,0 +1,245 @@
#
# 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_NET_CAN_CANFD is not set
# CONFIG_NET_ETHERNET is not set
# CONFIG_NET_IPv4 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_MKFATFS is not set
# CONFIG_NSH_DISABLE_REBOOT is not set
# CONFIG_NSH_DISABLE_SEMICOLON is not set
# CONFIG_NSH_DISABLE_SHUTDOWN is not set
# CONFIG_NSH_DISABLE_TIME is not set
CONFIG_ARCH="arm"
CONFIG_ARCH_BOARD_CUSTOM=y
CONFIG_ARCH_BOARD_CUSTOM_DIR="../../../../boards/cubepilot/cubeorange/nuttx-config"
CONFIG_ARCH_BOARD_CUSTOM_DIR_RELPATH=y
CONFIG_ARCH_BOARD_CUSTOM_NAME="px4"
CONFIG_ARCH_CHIP="stm32h7"
CONFIG_ARCH_CHIP_STM32H743ZI=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_ARM_MPU_EARLY_RESET=y
CONFIG_BOARDCTL_RESET=y
CONFIG_BOARD_CRASHDUMP=y
CONFIG_BOARD_LOOPSPERMSEC=79954
CONFIG_BOARD_RESET_ON_ASSERT=2
CONFIG_BUILTIN=y
CONFIG_C99_BOOL8=y
CONFIG_CANUTILS_CANDUMP=y
CONFIG_CANUTILS_CANSEND=y
CONFIG_CDCACM=y
CONFIG_CDCACM_IFLOWCONTROL=y
CONFIG_CDCACM_PRODUCTID=0x1016
CONFIG_CDCACM_PRODUCTSTR="CubeOrange"
CONFIG_CDCACM_RXBUFSIZE=600
CONFIG_CDCACM_TXBUFSIZE=12000
CONFIG_CDCACM_VENDORID=0x2DAE
CONFIG_CDCACM_VENDORSTR="CubePilot"
CONFIG_DEBUG_FULLOPT=y
CONFIG_DEBUG_HARDFAULT_ALERT=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_EXAMPLES_CALIB_UDELAY=y
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_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_MTD=y
CONFIG_MTD_BYTE_WRITE=y
CONFIG_MTD_PARTITION=y
CONFIG_MTD_PROGMEM=y
CONFIG_MTD_RAMTRON=y
CONFIG_NAME_MAX=40
CONFIG_NET=y
CONFIG_NETDEV_CAN_BITRATE_IOCTL=y
CONFIG_NETDEV_IFINDEX=y
CONFIG_NETDEV_PHY_IOCTL=y
CONFIG_NET_CAN=y
CONFIG_NET_CAN_RAW_TX_DEADLINE=y
CONFIG_NET_CAN_SOCK_OPTS=y
CONFIG_NET_TIMESTAMP=y
CONFIG_NSH_ARCHINIT=y
CONFIG_NSH_ARGCAT=y
CONFIG_NSH_BUILTIN_APPS=y
CONFIG_NSH_CMDPARMS=y
CONFIG_NSH_CROMFSETC=y
CONFIG_NSH_DISABLE_TELNETD=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_RAMTRON_SETSPEED=y
CONFIG_RAM_SIZE=245760
CONFIG_RAM_START=0x20010000
CONFIG_RAW_BINARY=y
CONFIG_READLINE_CMD_HISTORY=y
CONFIG_READLINE_TABCOMPLETION=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_BKPSRAM=y
CONFIG_STM32H7_DMA1=y
CONFIG_STM32H7_DMA2=y
CONFIG_STM32H7_DMACAPABLE=y
CONFIG_STM32H7_FDCAN1=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=1024
CONFIG_STM32H7_SPI2=y
CONFIG_STM32H7_SPI4=y
CONFIG_STM32H7_SPI4_DMA=y
CONFIG_STM32H7_SPI4_DMA_BUFFER=1024
CONFIG_STM32H7_SPI_DMA=y
CONFIG_STM32H7_TIM1=y
CONFIG_STM32H7_TIM3=y
CONFIG_STM32H7_TIM4=y
CONFIG_STM32H7_UART4=y
CONFIG_STM32H7_UART7=y
CONFIG_STM32H7_UART8=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_TTY_SIGINT=y
CONFIG_TTY_SIGTSTP=y
CONFIG_UART4_BAUD=57600
CONFIG_UART4_RXBUFSIZE=600
CONFIG_UART4_TXBUFSIZE=1500
CONFIG_UART7_BAUD=57600
CONFIG_UART7_RXBUFSIZE=600
CONFIG_UART7_SERIAL_CONSOLE=y
CONFIG_UART7_TXBUFSIZE=1500
CONFIG_UART8_BAUD=57600
CONFIG_UART8_RXBUFSIZE=600
CONFIG_UART8_TXBUFSIZE=1500
CONFIG_USART2_BAUD=57600
CONFIG_USART2_IFLOWCONTROL=y
CONFIG_USART2_OFLOWCONTROL=y
CONFIG_USART2_RXBUFSIZE=600
CONFIG_USART2_TXBUFSIZE=1500
CONFIG_USART3_BAUD=57600
CONFIG_USART3_IFLOWCONTROL=y
CONFIG_USART3_OFLOWCONTROL=y
CONFIG_USART3_RXBUFSIZE=600
CONFIG_USART3_TXBUFSIZE=3000
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
@@ -0,0 +1,22 @@
CONFIG_DRIVERS_ADC_ADS1115=n
CONFIG_DRIVERS_IMU_ANALOG_DEVICES_ADIS16448=n
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
CONFIG_MODULES_TEMPERATURE_COMPENSATION=n
CONFIG_DRIVERS_UAVCAN_V1=y
CONFIG_UAVCAN_V1_BMS_SUBSCRIBER=y
CONFIG_UAVCAN_V1_ESC_CONTROLLER=y
CONFIG_UAVCAN_V1_ESC_SUBSCRIBER=y
CONFIG_UAVCAN_V1_GNSS_PUBLISHER=y
CONFIG_UAVCAN_V1_GNSS_SUBSCRIBER_0=y
CONFIG_UAVCAN_V1_GNSS_SUBSCRIBER_1=y
CONFIG_UAVCAN_V1_READINESS_PUBLISHER=y
CONFIG_UAVCAN_V1_UORB_ACTUATOR_OUTPUTS_PUBLISHER=y
CONFIG_UAVCAN_V1_UORB_SENSOR_GPS_PUBLISHER=y
CONFIG_UAVCAN_V1_UORB_SENSOR_GPS_SUBSCRIBER=y
@@ -119,6 +119,8 @@ void NavioSysRCInput::Run()
connected_buf[sizeof(connected_buf) - 1] = '\0';
_connected = (atoi(connected_buf) == 1);
data.rc_lost = !_connected;
uint64_t timestamp_sample = hrt_absolute_time();
for (int i = 0; i < CHANNELS; ++i) {
@@ -143,11 +145,11 @@ void NavioSysRCInput::Run()
}
}
if (all_zero || !_connected) {
if (all_zero) {
return;
}
data.timestamp_sample = timestamp_sample;
data.timestamp_last_signal = timestamp_sample;
data.channel_count = CHANNELS;
data.input_source = input_rc_s::RC_INPUT_SOURCE_PX4FMU_PPM;
data.timestamp = hrt_absolute_time();
+1 -2
View File
@@ -71,8 +71,7 @@
#define BOOT_DELAY_ADDRESS 0x000001a0
#define BOARD_TYPE 1048
#define BOARD_FLASH_SECTORS (14)
#define BOARD_FLASH_SIZE (16 * 128 * 1024)
#define APP_RESERVATION_SIZE (1 * 128 * 1024)
#define BOARD_FLASH_SIZE ((16-2) * 128 * 1024)
#define OSC_FREQ 8
Binary file not shown.
@@ -7,11 +7,13 @@
#
# CONFIG_DISABLE_ENVIRON is not set
# CONFIG_DISABLE_PSEUDOFS_OPERATIONS is not set
# CONFIG_FS_PROCFS_EXCLUDE_ENVIRON 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_NET_CAN_CANFD is not set
# CONFIG_NET_ETHERNET is not set
# CONFIG_NET_IPv4 is not set
# CONFIG_NSH_DISABLEBG is not set
# CONFIG_NSH_DISABLESCRIPT is not set
# CONFIG_NSH_DISABLE_DF is not set
@@ -25,12 +27,12 @@
# CONFIG_NSH_DISABLE_TIME is not set
CONFIG_ARCH="arm"
CONFIG_ARCH_BOARD_CUSTOM=y
CONFIG_ARCH_BOARD_CUSTOM_DIR="../../../../boards/px4/fmu-v5/nuttx-config"
CONFIG_ARCH_BOARD_CUSTOM_DIR="../../../../boards/mro/ctrl-zero-h7-oem/nuttx-config"
CONFIG_ARCH_BOARD_CUSTOM_DIR_RELPATH=y
CONFIG_ARCH_BOARD_CUSTOM_NAME="px4"
CONFIG_ARCH_CHIP="stm32f7"
CONFIG_ARCH_CHIP_STM32F765II=y
CONFIG_ARCH_CHIP_STM32F7=y
CONFIG_ARCH_CHIP="stm32h7"
CONFIG_ARCH_CHIP_STM32H743II=y
CONFIG_ARCH_CHIP_STM32H7=y
CONFIG_ARCH_INTERRUPTSTACK=512
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARMV7M_BASEPRI_WAR=y
@@ -39,34 +41,32 @@ CONFIG_ARMV7M_DTCM=y
CONFIG_ARMV7M_ICACHE=y
CONFIG_ARMV7M_MEMCPY=y
CONFIG_ARMV7M_USEBASEPRI=y
CONFIG_ARM_MPU=y
CONFIG_ARM_MPU_EARLY_RESET=y
CONFIG_ARM_MPU_NREGIONS=8
CONFIG_BOARDCTL_IOCTL=y
CONFIG_BOARDCTL_RESET=y
CONFIG_BOARD_CRASHDUMP=y
CONFIG_BOARD_LOOPSPERMSEC=22114
CONFIG_BOARD_LOOPSPERMSEC=95150
CONFIG_BOARD_RESET_ON_ASSERT=2
CONFIG_BUILD_PROTECTED=y
CONFIG_BUILTIN=y
CONFIG_C99_BOOL8=y
CONFIG_CDCACM=y
CONFIG_CDCACM_IFLOWCONTROL=y
CONFIG_CDCACM_PRODUCTID=0x0032
CONFIG_CDCACM_PRODUCTSTR="PX4 FMU v5.x"
CONFIG_CDCACM_PRODUCTID=0x1024
CONFIG_CDCACM_PRODUCTSTR="mRoControlZeroH7 OEM"
CONFIG_CDCACM_RXBUFSIZE=600
CONFIG_CDCACM_TXBUFSIZE=12000
CONFIG_CDCACM_VENDORID=0x26ac
CONFIG_CDCACM_VENDORSTR="3D Robotics"
CONFIG_CDCACM_VENDORSTR="mRo"
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_DISABLE_MQUEUE=y
CONFIG_EXPERIMENTAL=y
CONFIG_FAT_DMAMEMORY=y
CONFIG_FAT_LCNAMES=y
CONFIG_FAT_LFN=y
@@ -91,19 +91,27 @@ CONFIG_IDLETHREAD_STACKSIZE=750
CONFIG_LIBC_FLOATINGPOINT=y
CONFIG_LIBC_LONG_LONG=y
CONFIG_LIBC_STRERROR=y
CONFIG_LIB_USRWORK=y
CONFIG_MEMSET_64BIT=y
CONFIG_MEMSET_OPTSPEED=y
CONFIG_MMCSD=y
CONFIG_MMCSD_SDIO=y
CONFIG_MMCSD_SDIOWAIT_WRCOMPLETE=y
CONFIG_MM_KERNEL_HEAPSIZE=131072
CONFIG_MM_REGIONS=3
CONFIG_MM_REGIONS=4
CONFIG_MTD=y
CONFIG_MTD_BYTE_WRITE=y
CONFIG_MTD_PARTITION=y
CONFIG_MTD_PROGMEM=y
CONFIG_MTD_RAMTRON=y
CONFIG_NAME_MAX=40
CONFIG_NET=y
CONFIG_NETDEV_CAN_BITRATE_IOCTL=y
CONFIG_NETDEV_IFINDEX=y
CONFIG_NETDEV_PHY_IOCTL=y
CONFIG_NET_CAN=y
CONFIG_NET_CAN_RAW_TX_DEADLINE=y
CONFIG_NET_CAN_SOCK_OPTS=y
CONFIG_NET_TIMESTAMP=y
CONFIG_NSH_ARCHINIT=y
CONFIG_NSH_ARGCAT=y
CONFIG_NSH_BUILTIN_APPS=y
CONFIG_NSH_CMDPARMS=y
@@ -119,7 +127,6 @@ CONFIG_NSH_ROMFSETC=y
CONFIG_NSH_ROMFSSECTSIZE=128
CONFIG_NSH_STRERROR=y
CONFIG_NSH_VARS=y
CONFIG_NUTTX_USERSPACE=0x08100000
CONFIG_OTG_ID_GPIO_DISABLE=y
CONFIG_PIPES=y
CONFIG_PREALLOC_TIMERS=50
@@ -144,7 +151,6 @@ CONFIG_SCHED_LPWORKPRIORITY=50
CONFIG_SCHED_LPWORKSTACKSIZE=1632
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
@@ -159,93 +165,85 @@ CONFIG_STACK_COLORATION=y
CONFIG_START_DAY=30
CONFIG_START_MONTH=11
CONFIG_STDIO_BUFFER_SIZE=256
CONFIG_STM32F7_ADC1=y
CONFIG_STM32F7_BBSRAM=y
CONFIG_STM32F7_BBSRAM_FILES=5
CONFIG_STM32F7_BKPSRAM=y
CONFIG_STM32F7_DMA1=y
CONFIG_STM32F7_DMA2=y
CONFIG_STM32F7_DMACAPABLE=y
CONFIG_STM32F7_FLOWCONTROL_BROKEN=y
CONFIG_STM32F7_I2C1=y
CONFIG_STM32F7_I2C2=y
CONFIG_STM32F7_I2C3=y
CONFIG_STM32F7_I2C4=y
CONFIG_STM32F7_I2C_DYNTIMEO=y
CONFIG_STM32F7_I2C_DYNTIMEO_STARTSTOP=10
CONFIG_STM32F7_OTGFS=y
CONFIG_STM32F7_PROGMEM=y
CONFIG_STM32F7_PWR=y
CONFIG_STM32F7_RTC=y
CONFIG_STM32F7_RTC_AUTO_LSECLOCK_START_DRV_CAPABILITY=y
CONFIG_STM32F7_RTC_MAGIC_REG=1
CONFIG_STM32F7_SAVE_CRASHDUMP=y
CONFIG_STM32F7_SDMMC1=y
CONFIG_STM32F7_SDMMC_DMA=y
CONFIG_STM32F7_SERIALBRK_BSDCOMPAT=y
CONFIG_STM32F7_SERIAL_DISABLE_REORDERING=y
CONFIG_STM32F7_SPI1=y
CONFIG_STM32F7_SPI1_DMA=y
CONFIG_STM32F7_SPI1_DMA_BUFFER=1024
CONFIG_STM32F7_SPI2=y
CONFIG_STM32F7_SPI4=y
CONFIG_STM32F7_SPI5=y
CONFIG_STM32F7_SPI6=y
CONFIG_STM32F7_SPI_DMA=y
CONFIG_STM32F7_SPI_DMATHRESHOLD=8
CONFIG_STM32F7_TIM10=y
CONFIG_STM32F7_TIM11=y
CONFIG_STM32F7_UART4=y
CONFIG_STM32F7_UART7=y
CONFIG_STM32F7_UART8=y
CONFIG_STM32F7_USART1=y
CONFIG_STM32F7_USART2=y
CONFIG_STM32F7_USART3=y
CONFIG_STM32F7_USART6=y
CONFIG_STM32F7_USART_BREAKS=y
CONFIG_STM32F7_USART_INVERT=y
CONFIG_STM32F7_USART_SINGLEWIRE=y
CONFIG_STM32F7_USART_SWAP=y
CONFIG_STM32F7_WWDG=y
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_FDCAN1=y
CONFIG_STM32H7_FLOWCONTROL_BROKEN=y
CONFIG_STM32H7_I2C1=y
CONFIG_STM32H7_I2C3=y
CONFIG_STM32H7_I2C4=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=1024
CONFIG_STM32H7_SPI2=y
CONFIG_STM32H7_SPI5=y
CONFIG_STM32H7_SPI5_DMA=y
CONFIG_STM32H7_SPI5_DMA_BUFFER=1024
CONFIG_STM32H7_SPI_DMA=y
CONFIG_STM32H7_TIM1=y
CONFIG_STM32H7_TIM2=y
CONFIG_STM32H7_TIM3=y
CONFIG_STM32H7_TIM4=y
CONFIG_STM32H7_TIM8=y
CONFIG_STM32H7_UART4=y
CONFIG_STM32H7_UART7=y
CONFIG_STM32H7_UART8=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_SYS_RESERVED=9
CONFIG_TASK_NAME_SIZE=24
CONFIG_TTY_SIGINT=y
CONFIG_TTY_SIGTSTP=y
CONFIG_UART4_BAUD=57600
CONFIG_UART4_RXBUFSIZE=600
CONFIG_UART4_RXDMA=y
CONFIG_UART4_TXBUFSIZE=1500
CONFIG_UART7_BAUD=57600
CONFIG_UART7_RXBUFSIZE=600
CONFIG_UART7_SERIAL_CONSOLE=y
CONFIG_UART7_TXBUFSIZE=1500
CONFIG_UART8_BAUD=57600
CONFIG_UART8_RXBUFSIZE=600
CONFIG_UART8_RXDMA=y
CONFIG_UART8_SERIAL_CONSOLE=y
CONFIG_UART8_TXBUFSIZE=1500
CONFIG_USART1_BAUD=57600
CONFIG_USART1_RXBUFSIZE=600
CONFIG_USART1_TXBUFSIZE=1500
CONFIG_USART2_BAUD=57600
CONFIG_USART2_IFLOWCONTROL=y
CONFIG_USART2_OFLOWCONTROL=y
CONFIG_USART2_RXBUFSIZE=600
CONFIG_USART2_RXDMA=y
CONFIG_USART2_TXBUFSIZE=1500
CONFIG_USART3_BAUD=57600
CONFIG_USART3_IFLOWCONTROL=y
CONFIG_USART3_OFLOWCONTROL=y
CONFIG_USART3_RXBUFSIZE=600
CONFIG_USART3_RXDMA=y
CONFIG_USART3_TXBUFSIZE=3000
CONFIG_USART3_TXDMA=y
CONFIG_USART6_BAUD=57600
CONFIG_USART6_RXBUFSIZE=600
CONFIG_USART6_RXDMA=y
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="px4_entry"
CONFIG_USER_ENTRYPOINT="nsh_main"
@@ -0,0 +1,13 @@
CONFIG_DRIVERS_UAVCAN=n
CONFIG_DRIVERS_UAVCAN_V1=y
CONFIG_UAVCAN_V1_BMS_SUBSCRIBER=y
CONFIG_UAVCAN_V1_CLIENT=y
CONFIG_UAVCAN_V1_ESC_CONTROLLER=y
CONFIG_UAVCAN_V1_ESC_SUBSCRIBER=y
CONFIG_UAVCAN_V1_GNSS_PUBLISHER=y
CONFIG_UAVCAN_V1_GNSS_SUBSCRIBER_0=y
CONFIG_UAVCAN_V1_GNSS_SUBSCRIBER_1=y
CONFIG_UAVCAN_V1_READINESS_PUBLISHER=y
CONFIG_UAVCAN_V1_UORB_ACTUATOR_OUTPUTS_PUBLISHER=y
CONFIG_UAVCAN_V1_UORB_SENSOR_GPS_PUBLISHER=y
CONFIG_UAVCAN_V1_UORB_SENSOR_GPS_SUBSCRIBER=y
Binary file not shown.
+1 -2
View File
@@ -41,13 +41,11 @@ CONFIG_DRIVERS_SMART_BATTERY_BATMON=y
CONFIG_COMMON_TELEMETRY=y
CONFIG_DRIVERS_TONE_ALARM=y
CONFIG_DRIVERS_UAVCAN=y
CONFIG_DRIVERS_UWB_UWB_SR150=y
CONFIG_MODULES_AIRSPEED_SELECTOR=y
CONFIG_MODULES_ATTITUDE_ESTIMATOR_Q=y
CONFIG_MODULES_BATTERY_STATUS=y
CONFIG_MODULES_CAMERA_FEEDBACK=y
CONFIG_MODULES_COMMANDER=y
CONFIG_MODULES_CONTROL_ALLOCATOR=y
CONFIG_MODULES_DATAMAN=y
CONFIG_MODULES_EKF2=y
CONFIG_MODULES_ESC_BATTERY=y
@@ -71,6 +69,7 @@ CONFIG_MODULES_MC_AUTOTUNE_ATTITUDE_CONTROL=y
CONFIG_MODULES_MC_HOVER_THRUST_ESTIMATOR=y
CONFIG_MODULES_MC_POS_CONTROL=y
CONFIG_MODULES_MC_RATE_CONTROL=y
CONFIG_MODULES_CONTROL_ALLOCATOR=y
CONFIG_MODULES_NAVIGATOR=y
CONFIG_MODULES_RC_UPDATE=y
CONFIG_MODULES_ROVER_POS_CONTROL=y
-1
View File
@@ -23,7 +23,6 @@ CONFIG_DRIVERS_PWM_OUT_SIM=y
CONFIG_DRIVERS_RC_INPUT=y
CONFIG_DRIVERS_SAFETY_BUTTON=y
CONFIG_DRIVERS_TONE_ALARM=y
CONFIG_COMMON_UWB=y
CONFIG_MODULES_BATTERY_STATUS=y
CONFIG_MODULES_CAMERA_FEEDBACK=y
CONFIG_MODULES_COMMANDER=y
+2
View File
@@ -21,6 +21,7 @@ CONFIG_MODULES_BATTERY_STATUS=y
CONFIG_MODULES_COMMANDER=y
CONFIG_MODULES_CONTROL_ALLOCATOR=y
CONFIG_MODULES_DATAMAN=y
CONFIG_MODULES_EKF2=y
CONFIG_MODULES_FLIGHT_MODE_MANAGER=y
CONFIG_MODULES_LAND_DETECTOR=y
CONFIG_MODULES_LOGGER=y
@@ -32,6 +33,7 @@ CONFIG_MODULES_MC_RATE_CONTROL=y
CONFIG_MODULES_NAVIGATOR=y
CONFIG_MODULES_RC_UPDATE=y
CONFIG_MODULES_SENSORS=y
CONFIG_SYSTEMCMDS_DMESG=n
CONFIG_SYSTEMCMDS_HARDFAULT_LOG=y
CONFIG_SYSTEMCMDS_MIXER=y
CONFIG_SYSTEMCMDS_PARAM=y
-3
View File
@@ -1,3 +0,0 @@
CONFIG_DRIVERS_TELEMETRY_FRSKY_TELEMETRY=n
CONFIG_MODULES_ATTITUDE_ESTIMATOR_Q=n
CONFIG_MODULES_EKF2=y
Binary file not shown.
+10 -6
View File
@@ -1,16 +1,20 @@
CONFIG_DRIVERS_DIFFERENTIAL_PRESSURE_MS4525=n
CONFIG_MODULES_FLIGHT_MODE_MANAGER=n
CONFIG_MODULES_MC_ATT_CONTROL=n
CONFIG_MODULES_MC_HOVER_THRUST_ESTIMATOR=n
CONFIG_MODULES_MC_POS_CONTROL=n
CONFIG_MODULES_MC_RATE_CONTROL=n
CONFIG_SYSTEMCMDS_BL_UPDATE=n
CONFIG_DRIVERS_DIFFERENTIAL_PRESSURE_MS4525=y
CONFIG_DRIVERS_DISTANCE_SENSOR_LIGHTWARE_LASER_I2C=y
CONFIG_DRIVERS_CAMERA_CAPTURE=y
CONFIG_DRIVERS_CAMERA_TRIGGER=y
CONFIG_DRIVERS_DIFFERENTIAL_PRESSURE_ETS=y
CONFIG_DRIVERS_DIFFERENTIAL_PRESSURE_MS5525=y
CONFIG_DRIVERS_DIFFERENTIAL_PRESSURE_SDP3X=y
CONFIG_DRIVERS_DISTANCE_SENSOR_LIGHTWARE_LASER_SERIAL=y
CONFIG_DRIVERS_DISTANCE_SENSOR_LL40LS=y
CONFIG_MODULES_AIRSPEED_SELECTOR=y
CONFIG_MODULES_FW_ATT_CONTROL=y
CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=y
CONFIG_MODULES_FW_POS_CONTROL_L1=y
CONFIG_MODULES_CAMERA_FEEDBACK=y
CONFIG_MODULES_GYRO_CALIBRATION=y
CONFIG_MODULES_LOAD_MON=y
CONFIG_MODULES_TEMPERATURE_COMPENSATION=y
CONFIG_SYSTEMCMDS_PERF=y
CONFIG_SYSTEMCMDS_VER=y
+10
View File
@@ -1,6 +1,16 @@
CONFIG_DRIVERS_DIFFERENTIAL_PRESSURE_MS4525=n
CONFIG_MODULES_AIRSPEED_SELECTOR=n
CONFIG_MODULES_FW_ATT_CONTROL=n
CONFIG_MODULES_FW_POS_CONTROL_L1=n
CONFIG_SYSTEMCMDS_BL_UPDATE=n
CONFIG_DRIVERS_CAMERA_CAPTURE=n
CONFIG_DRIVERS_CAMERA_TRIGGER=n
CONFIG_DRIVERS_DISTANCE_SENSOR_CM8JL65=y
CONFIG_DRIVERS_DISTANCE_SENSOR_LEDDAR_ONE=y
CONFIG_DRIVERS_DISTANCE_SENSOR_LIGHTWARE_LASER_I2C=y
CONFIG_DRIVERS_DISTANCE_SENSOR_LIGHTWARE_LASER_SERIAL=y
CONFIG_DRIVERS_DISTANCE_SENSOR_LL40LS=y
CONFIG_DRIVERS_DISTANCE_SENSOR_TFMINI=y
CONFIG_MODULES_LANDING_TARGET_ESTIMATOR=n
CONFIG_MODULES_LOAD_MON=y
CONFIG_MODULES_MC_AUTOTUNE_ATTITUDE_CONTROL=y
+2
View File
@@ -3,6 +3,8 @@ CONFIG_MODULES_MC_ATT_CONTROL=n
CONFIG_MODULES_MC_HOVER_THRUST_ESTIMATOR=n
CONFIG_MODULES_MC_POS_CONTROL=n
CONFIG_MODULES_MC_RATE_CONTROL=n
CONFIG_COMMON_DISTANCE_SENSOR=y
CONFIG_DRIVERS_BATT_SMBUS=y
CONFIG_DRIVERS_CAMERA_CAPTURE=y
CONFIG_DRIVERS_CAMERA_TRIGGER=y
CONFIG_DRIVERS_OPTICAL_FLOW_PX4FLOW=y
+15
View File
@@ -0,0 +1,15 @@
CONFIG_DRIVERS_DIFFERENTIAL_PRESSURE_MS4525=n
CONFIG_DRIVERS_GPS=n
CONFIG_DRIVERS_IMU_L3GD20=n
CONFIG_DRIVERS_IMU_LSM303D=n
CONFIG_MODULES_AIRSPEED_SELECTOR=n
CONFIG_MODULES_EKF2=n
CONFIG_MODULES_FW_ATT_CONTROL=n
CONFIG_MODULES_FW_POS_CONTROL_L1=n
CONFIG_MODULES_MC_HOVER_THRUST_ESTIMATOR=n
CONFIG_SYSTEMCMDS_BL_UPDATE=n
CONFIG_BOARD_ROMFSROOT="px4fmu_test"
CONFIG_BOARD_TESTING=y
CONFIG_SYSTEMCMDS_MICROBENCH=y
CONFIG_SYSTEMCMDS_PERF=y
CONFIG_SYSTEMCMDS_VER=y
Binary file not shown.
Binary file not shown.
-1
View File
@@ -21,7 +21,6 @@ CONFIG_DRIVERS_IMU_BOSCH_BMI055=y
CONFIG_DRIVERS_IMU_INVENSENSE_ICM20602=y
CONFIG_DRIVERS_IMU_INVENSENSE_ICM20689=y
CONFIG_DRIVERS_IMU_INVENSENSE_ICM20948=y
CONFIG_DRIVERS_IMU_INVENSENSE_ICM42688P=y
CONFIG_DRIVERS_IRLOCK=y
CONFIG_COMMON_LIGHT=y
CONFIG_DRIVERS_LIGHTS_RGBLED_PWM=y

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