mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-06-13 03:20:04 +08:00
Compare commits
61 Commits
| Author | SHA1 | Date | |
|---|---|---|---|
| 7f99cf5f49 | |||
| e8a064af02 | |||
| b88c8eb245 | |||
| d35cf78e4a | |||
| 4559230de6 | |||
| ef4d4c3093 | |||
| 4535b18a80 | |||
| 07d72f8604 | |||
| 443666199e | |||
| ae9e91f90c | |||
| c3e961a1ed | |||
| 0cf3ef87e3 | |||
| 581ec224be | |||
| f08f2a340d | |||
| fed234de81 | |||
| 07303af8f8 | |||
| ed394027b1 | |||
| a732ddaefb | |||
| c1b0d78077 | |||
| 8b37db7825 | |||
| f5e1da5b0f | |||
| 7de00469a6 | |||
| f91aa76645 | |||
| 426efb515f | |||
| 351f679c2f | |||
| e6658547cf | |||
| 5509235517 | |||
| 41a4045630 | |||
| 49a4283d0d | |||
| ffb47466df | |||
| 56b0c46444 | |||
| fab053d33b | |||
| 12670b70f4 | |||
| 801ef2d520 | |||
| 342e9900f8 | |||
| 5ebe41efbf | |||
| 8f8304f31e | |||
| ae5d3103f4 | |||
| e2f048f608 | |||
| 99b098f608 | |||
| c92cd65831 | |||
| 6576e1fda9 | |||
| b56bd7cb21 | |||
| 47a72a6b7b | |||
| 9fd19a2c83 | |||
| af34b21ba8 | |||
| 98f655815a | |||
| 4be45229bf | |||
| 089f96f800 | |||
| fd39d5b9a1 | |||
| 47dc2ae5a5 | |||
| 2ba369dd54 | |||
| d8e88aedc6 | |||
| ba66f8a1e2 | |||
| ba1b7f3a07 | |||
| d1a2d6e1aa | |||
| 984a698760 | |||
| 21b1f090e6 | |||
| b18b7e84d2 | |||
| 927c0c4296 | |||
| 212df95193 |
@@ -734,12 +734,26 @@ void checkoutSCM() {
|
||||
}
|
||||
|
||||
void quickCalibrate() {
|
||||
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "commander calibrate accel quick; sleep 1; param show CAL_ACC*"'
|
||||
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "commander calibrate gyro; sleep 1; param show CAL_GYRO*"'
|
||||
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "commander calibrate level; sleep 1; param show SENS_BOARD*"'
|
||||
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "commander calibrate mag quick; sleep 1; param show CAL_MAG*"'
|
||||
|
||||
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "gyro_calibration status; param show CAL_GYRO*"'
|
||||
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "param show CAL_*"' // parameters before
|
||||
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "sensors status"'
|
||||
|
||||
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"'
|
||||
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"'
|
||||
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"'
|
||||
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"'
|
||||
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 "param show CAL_*"' // parameters after
|
||||
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "sensors status"'
|
||||
}
|
||||
|
||||
void checkStatus() {
|
||||
@@ -831,6 +845,7 @@ void runTests() {
|
||||
|
||||
//sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "sd_stress"'
|
||||
|
||||
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "commander stop"'
|
||||
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "sensors stop"' // ignore irrelevant sensor timeouts during microbenchmarks
|
||||
sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-*` --cmd "microbench all"'
|
||||
|
||||
|
||||
@@ -82,6 +82,7 @@ Checks: '*,
|
||||
-modernize-use-equals-delete,
|
||||
-modernize-use-override,
|
||||
-modernize-use-using,
|
||||
-modernize-use-trailing-return-type,
|
||||
-performance-inefficient-string-concatenation,
|
||||
-readability-avoid-const-params-in-decls,
|
||||
-readability-container-size-empty,
|
||||
|
||||
@@ -81,7 +81,7 @@ jobs:
|
||||
echo "base_dir = ${GITHUB_WORKSPACE}" > ~/.ccache/ccache.conf
|
||||
echo "compression = true" >> ~/.ccache/ccache.conf
|
||||
echo "compression_level = 6" >> ~/.ccache/ccache.conf
|
||||
echo "max_size = 50M" >> ~/.ccache/ccache.conf
|
||||
echo "max_size = 75M" >> ~/.ccache/ccache.conf
|
||||
echo "hash_dir = false" >> ~/.ccache/ccache.conf
|
||||
ccache -s
|
||||
ccache -z
|
||||
|
||||
@@ -46,7 +46,7 @@ jobs:
|
||||
echo "base_dir = ${GITHUB_WORKSPACE}" > ~/.ccache/ccache.conf
|
||||
echo "compression = true" >> ~/.ccache/ccache.conf
|
||||
echo "compression_level = 6" >> ~/.ccache/ccache.conf
|
||||
echo "max_size = 20M" >> ~/.ccache/ccache.conf
|
||||
echo "max_size = 40M" >> ~/.ccache/ccache.conf
|
||||
echo "hash_dir = false" >> ~/.ccache/ccache.conf
|
||||
ccache -s
|
||||
ccache -z
|
||||
|
||||
@@ -0,0 +1,10 @@
|
||||
#!/bin/sh
|
||||
#
|
||||
# @name Plane SITL with catapult
|
||||
#
|
||||
|
||||
. ${R}etc/init.d-posix/airframes/1030_plane
|
||||
|
||||
param set-default FW_THR_CRUISE 0.0
|
||||
param set-default RWTO_TKOFF 0
|
||||
|
||||
+9
@@ -8,6 +8,15 @@
|
||||
. ${R}etc/init.d/rc.mc_defaults
|
||||
. ${R}etc/init.d/rc.ctrlalloc
|
||||
|
||||
param set-default MC_PITCHRATE_P 0.0800
|
||||
param set-default MC_PITCHRATE_I 0.0400
|
||||
param set-default MC_PITCHRATE_D 0.0010
|
||||
param set-default MC_PITCH_P 9.0
|
||||
param set-default MC_ROLLRATE_P 0.0800
|
||||
param set-default MC_ROLLRATE_I 0.0400
|
||||
param set-default MC_ROLLRATE_D 0.0010
|
||||
param set-default MC_ROLL_P 9.0
|
||||
|
||||
param set-default MPC_XY_VEL_I_ACC 4
|
||||
param set-default MPC_XY_VEL_P_ACC 3
|
||||
|
||||
@@ -61,6 +61,7 @@ px4_add_romfs_files(
|
||||
1035_techpod
|
||||
1036_malolo
|
||||
1037_believer
|
||||
1038_glider
|
||||
1040_standard_vtol
|
||||
1041_tailsitter
|
||||
1042_tiltrotor
|
||||
@@ -76,6 +77,6 @@ px4_add_romfs_files(
|
||||
2507_cloudship
|
||||
6011_typhoon_h480
|
||||
6011_typhoon_h480.post
|
||||
6012_typhoon_ctrlalloc
|
||||
6012_typhoon_ctrlalloc.post
|
||||
6012_typhoon_h480_ctrlalloc
|
||||
6012_typhoon_h480_ctrlalloc.post
|
||||
)
|
||||
|
||||
@@ -18,7 +18,6 @@
|
||||
|
||||
. ${R}etc/init.d/rc.fw_defaults
|
||||
|
||||
|
||||
param set-default BAT1_N_CELLS 3
|
||||
|
||||
param set-default FW_AIRSPD_MAX 20
|
||||
@@ -40,7 +39,6 @@ param set-default FW_RR_P 0.3
|
||||
|
||||
param set-default RWTO_TKOFF 1
|
||||
|
||||
|
||||
param set SYS_HITL 1
|
||||
|
||||
# disable some checks to allow to fly
|
||||
|
||||
@@ -34,5 +34,3 @@ param set-default MC_PITCHRATE_D 0.0025
|
||||
param set-default MC_YAWRATE_P 0.28
|
||||
|
||||
set MIXER quad_w
|
||||
|
||||
set PWM_OUT 1234
|
||||
|
||||
@@ -23,7 +23,6 @@
|
||||
|
||||
. ${R}etc/init.d/rc.mc_defaults
|
||||
|
||||
|
||||
# TODO tune roll/pitch separately
|
||||
param set-default MC_ROLL_P 7
|
||||
param set-default MC_ROLLRATE_I 0.05
|
||||
@@ -39,5 +38,3 @@ param set-default BAT1_V_DIV 12.27559
|
||||
param set-default BAT1_A_PER_V 15.39103
|
||||
|
||||
set MIXER quad_w
|
||||
|
||||
set PWM_OUT 1234
|
||||
|
||||
@@ -25,7 +25,6 @@
|
||||
|
||||
. ${R}etc/init.d/rc.mc_defaults
|
||||
|
||||
|
||||
param set-default BAT1_N_CELLS 4
|
||||
|
||||
param set-default MC_ROLL_P 7
|
||||
@@ -38,5 +37,3 @@ 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
|
||||
|
||||
set PWM_OUT 1234
|
||||
|
||||
@@ -25,7 +25,6 @@
|
||||
|
||||
. ${R}etc/init.d/rc.mc_defaults
|
||||
|
||||
|
||||
param set-default BAT1_N_CELLS 6
|
||||
param set-default BAT1_V_EMPTY 3.5
|
||||
|
||||
@@ -42,5 +41,3 @@ param set-default MPC_XY_VEL_MAX 2
|
||||
param set-default PWM_MAIN_MIN 1080
|
||||
|
||||
set MIXER quad_w
|
||||
|
||||
set PWM_OUT 1234
|
||||
|
||||
@@ -12,7 +12,6 @@
|
||||
. ${R}etc/init.d/rc.mc_defaults
|
||||
|
||||
set MIXER quad_x
|
||||
set PWM_OUT 1234
|
||||
|
||||
param set SYS_HITL 1
|
||||
|
||||
|
||||
@@ -22,11 +22,11 @@
|
||||
|
||||
. ${R}etc/init.d/rc.vtol_defaults
|
||||
|
||||
|
||||
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
|
||||
|
||||
@@ -23,10 +23,8 @@
|
||||
|
||||
. ${R}etc/init.d/rc.vtol_defaults
|
||||
|
||||
|
||||
param set-default PWM_AUX_DIS5 950
|
||||
|
||||
|
||||
param set-default MC_ROLL_P 6
|
||||
param set-default MC_ROLLRATE_P 0.17
|
||||
param set-default MC_ROLLRATE_I 0.002
|
||||
|
||||
@@ -26,7 +26,6 @@ param set-default MC_ROLLRATE_I 0.01
|
||||
param set-default MC_PITCHRATE_I 0.01
|
||||
param set-default MC_YAW_P 3.5
|
||||
|
||||
|
||||
param set-default MC_YAWRATE_MAX 50
|
||||
|
||||
param set-default MPC_XY_P 0.8
|
||||
|
||||
@@ -13,7 +13,6 @@
|
||||
|
||||
. ${R}etc/init.d/rc.vtol_defaults
|
||||
|
||||
|
||||
param set-default FW_AIRSPD_MAX 22
|
||||
param set-default FW_AIRSPD_MIN 14
|
||||
param set-default FW_AIRSPD_TRIM 16
|
||||
@@ -68,7 +67,6 @@ param set-default PWM_AUX_REV4 1
|
||||
|
||||
param set-default PWM_AUX_DIS5 950
|
||||
|
||||
|
||||
param set-default VT_ARSP_TRANS 15
|
||||
param set-default VT_F_TRANS_THR 0.6
|
||||
param set-default VT_IDLE_PWM_MC 1180
|
||||
|
||||
@@ -13,7 +13,6 @@
|
||||
|
||||
. ${R}etc/init.d/rc.vtol_defaults
|
||||
|
||||
|
||||
param set-default PWM_AUX_DISARM 1000
|
||||
param set-default PWM_AUX_MAX 2000
|
||||
param set-default PWM_AUX_MIN 1000
|
||||
|
||||
@@ -22,7 +22,6 @@
|
||||
|
||||
. ${R}etc/init.d/rc.vtol_defaults
|
||||
|
||||
|
||||
param set-default CBRK_AIRSPD_CHK 162128
|
||||
|
||||
param set-default FW_ARSP_MODE 1
|
||||
|
||||
@@ -22,7 +22,6 @@
|
||||
|
||||
. ${R}etc/init.d/rc.vtol_defaults
|
||||
|
||||
|
||||
param set-default BAT1_CAPACITY 23000
|
||||
param set-default BAT1_N_CELLS 4
|
||||
param set-default BAT1_R_INTERNAL 0.0025
|
||||
|
||||
@@ -22,7 +22,6 @@
|
||||
|
||||
. ${R}etc/init.d/rc.vtol_defaults
|
||||
|
||||
|
||||
param set-default BAT1_N_CELLS 6
|
||||
|
||||
param set-default FW_AIRSPD_MAX 30
|
||||
|
||||
@@ -26,8 +26,6 @@
|
||||
|
||||
. ${R}etc/init.d/rc.vtol_defaults
|
||||
|
||||
|
||||
|
||||
param set-default VT_IDLE_PWM_MC 1100
|
||||
param set-default VT_TYPE 1
|
||||
param set-default VT_MOT_ID 1234
|
||||
|
||||
@@ -25,7 +25,6 @@
|
||||
|
||||
. ${R}etc/init.d/rc.vtol_defaults
|
||||
|
||||
|
||||
param set-default PWM_AUX_DIS5 950
|
||||
|
||||
param set-default VT_TYPE 2
|
||||
|
||||
@@ -18,7 +18,6 @@
|
||||
|
||||
. ${R}etc/init.d/rc.vtol_defaults
|
||||
|
||||
|
||||
param set-default VT_ELEV_MC_LOCK 0
|
||||
param set-default VT_MOT_COUNT 2
|
||||
param set-default VT_TYPE 0
|
||||
|
||||
@@ -19,5 +19,3 @@
|
||||
. ${R}etc/init.d/rc.mc_defaults
|
||||
|
||||
set MIXER tri_y_yaw+
|
||||
|
||||
set PWM_OUT 1234
|
||||
|
||||
@@ -19,5 +19,3 @@
|
||||
. ${R}etc/init.d/rc.mc_defaults
|
||||
|
||||
set MIXER tri_y_yaw-
|
||||
|
||||
set PWM_OUT 1234
|
||||
|
||||
@@ -19,7 +19,6 @@
|
||||
. ${R}etc/init.d/rc.mc_defaults
|
||||
set MIXER coax
|
||||
|
||||
|
||||
param set-default MC_ROLLRATE_P 0.17
|
||||
param set-default MC_ROLLRATE_I 0.05
|
||||
param set-default MC_ROLLRATE_D 0.005
|
||||
@@ -41,5 +40,4 @@ param set-default RTL_DESCEND_ALT 10
|
||||
set MIXER_AUX pass
|
||||
|
||||
# use PWM parameters for throttle channel
|
||||
set PWM_AUX_OUT 1234
|
||||
set PWM_OUT 34
|
||||
|
||||
@@ -24,8 +24,7 @@ set MAV_TYPE 4
|
||||
|
||||
set MIXER blade130
|
||||
|
||||
#set PWM_OUT 1234
|
||||
|
||||
set PWM_OUT none
|
||||
|
||||
param set-default ATT_BIAS_MAX 0
|
||||
|
||||
|
||||
@@ -15,7 +15,6 @@
|
||||
|
||||
. ${R}etc/init.d/rc.balloon_defaults
|
||||
|
||||
|
||||
param set-default COM_PREARM_MODE 2 # always in prearm state
|
||||
param set-default CBRK_IO_SAFETY 22027
|
||||
param set-default SDLOG_PROFILE 17
|
||||
@@ -28,6 +27,5 @@ 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
|
||||
|
||||
@@ -28,7 +28,6 @@
|
||||
|
||||
set VEHICLE_TYPE mc
|
||||
|
||||
|
||||
param set-default NAV_ACC_RAD 2
|
||||
|
||||
param set-default PWM_AUX_RATE 400
|
||||
|
||||
@@ -18,6 +18,5 @@
|
||||
param set-default COM_PREARM_MODE 2
|
||||
param set-default CBRK_IO_SAFETY 22027
|
||||
|
||||
|
||||
set MIXER cloudship
|
||||
set PWM_OUT 1234
|
||||
|
||||
@@ -37,5 +37,4 @@ param set-default FW_PR_FF 0.35
|
||||
param set-default FW_RR_FF 0.6
|
||||
param set-default FW_RR_P 0.04
|
||||
|
||||
|
||||
set MIXER fw_generic_wing
|
||||
|
||||
@@ -41,7 +41,6 @@ param set-default FW_RR_P 0.04
|
||||
|
||||
param set-default PWM_MAIN_DISARM 1000
|
||||
|
||||
|
||||
# Configure this as plane.
|
||||
set MAV_TYPE 1
|
||||
|
||||
|
||||
@@ -21,7 +21,6 @@
|
||||
|
||||
. ${R}etc/init.d/rc.fw_defaults
|
||||
|
||||
|
||||
param set-default FW_AIRSPD_MAX 25
|
||||
param set-default FW_AIRSPD_MIN 12.5
|
||||
param set-default FW_AIRSPD_TRIM 16.5
|
||||
|
||||
@@ -21,7 +21,3 @@
|
||||
#
|
||||
|
||||
. ${R}etc/init.d/rc.mc_defaults
|
||||
|
||||
set MIXER quad_x
|
||||
|
||||
set PWM_OUT 1234
|
||||
|
||||
@@ -13,10 +13,6 @@
|
||||
|
||||
. ${R}etc/init.d/rc.mc_defaults
|
||||
|
||||
set MIXER quad_x
|
||||
set PWM_OUT 1234
|
||||
|
||||
|
||||
param set-default MC_ROLL_P 8
|
||||
param set-default MC_ROLLRATE_P 0.08
|
||||
param set-default MC_ROLLRATE_I 0.16
|
||||
|
||||
@@ -13,10 +13,6 @@
|
||||
|
||||
. ${R}etc/init.d/rc.mc_defaults
|
||||
|
||||
set MIXER quad_x
|
||||
set PWM_OUT 1234
|
||||
|
||||
|
||||
param set-default ATT_BIAS_MAX 0
|
||||
|
||||
param set-default CBRK_IO_SAFETY 22027
|
||||
|
||||
@@ -11,9 +11,6 @@
|
||||
|
||||
. ${R}etc/init.d/rc.mc_defaults
|
||||
|
||||
set MIXER quad_x
|
||||
set PWM_OUT 1234
|
||||
|
||||
param set-default MC_ROLL_P 7
|
||||
param set-default MC_ROLLRATE_I 0.05
|
||||
param set-default MC_PITCH_P 7
|
||||
|
||||
@@ -10,9 +10,6 @@
|
||||
|
||||
. ${R}etc/init.d/rc.mc_defaults
|
||||
|
||||
set MIXER quad_x
|
||||
set PWM_OUT 1234
|
||||
|
||||
param set-default MC_ROLL_P 7
|
||||
param set-default MC_ROLLRATE_I 0.05
|
||||
param set-default MC_PITCH_P 7
|
||||
|
||||
@@ -13,10 +13,6 @@
|
||||
|
||||
. ${R}etc/init.d/rc.mc_defaults
|
||||
|
||||
set MIXER quad_x
|
||||
set PWM_OUT 1234
|
||||
|
||||
|
||||
param set-default MC_ROLLRATE_P 0.18
|
||||
param set-default MC_PITCHRATE_P 0.18
|
||||
param set-default MC_ROLLRATE_I 0.15
|
||||
|
||||
@@ -13,10 +13,6 @@
|
||||
|
||||
. ${R}etc/init.d/rc.mc_defaults
|
||||
|
||||
set MIXER quad_x
|
||||
set PWM_OUT 1234
|
||||
|
||||
|
||||
param set-default IMU_GYRO_CUTOFF 30
|
||||
|
||||
param set-default MC_ROLLRATE_P 0.14
|
||||
|
||||
@@ -16,10 +16,6 @@
|
||||
|
||||
. ${R}etc/init.d/rc.mc_defaults
|
||||
|
||||
set MIXER quad_x
|
||||
set PWM_OUT 1234
|
||||
|
||||
|
||||
# System parameters
|
||||
# use FMU motor outputs for less delay in the rate control loop
|
||||
param set-default SYS_USE_IO 0
|
||||
|
||||
@@ -18,9 +18,6 @@
|
||||
|
||||
. ${R}etc/init.d/rc.mc_defaults
|
||||
|
||||
set MIXER quad_x
|
||||
set PWM_OUT 1234
|
||||
|
||||
param set-default IMU_DGYRO_CUTOFF 20
|
||||
|
||||
param set-default MC_ROLLRATE_P 0.18
|
||||
|
||||
@@ -13,6 +13,7 @@
|
||||
. ${R}etc/init.d/rc.mc_defaults
|
||||
. ${R}etc/init.d/rc.ctrlalloc
|
||||
|
||||
set MIXER none
|
||||
|
||||
param set-default MPC_USE_HTE 0
|
||||
|
||||
@@ -50,7 +51,5 @@ param set-default CA_MC_R3_CT 6.5
|
||||
param set-default CA_MC_R3_KM -0.05
|
||||
|
||||
set MIXER direct
|
||||
set PWM_OUT 1234
|
||||
|
||||
set MIXER_AUX direct_aux
|
||||
set PWM_AUX_OUT 1234
|
||||
|
||||
@@ -18,7 +18,6 @@
|
||||
|
||||
. ${R}etc/init.d/rc.mc_defaults
|
||||
|
||||
|
||||
# tuning
|
||||
param set-default MC_PITCHRATE_P 0.11
|
||||
param set-default MC_ROLLRATE_P 0.11
|
||||
@@ -83,7 +82,5 @@ param set-default RC5_TRIM 1500
|
||||
param set-default MAV_0_RATE 80000
|
||||
param set-default MAV_0_MODE 2
|
||||
param set-default SER_TEL1_BAUD 921600
|
||||
set MIXER quad_x
|
||||
|
||||
set PWM_OUT 1234
|
||||
set MIXER_AUX none
|
||||
|
||||
@@ -13,9 +13,6 @@
|
||||
|
||||
. ${R}etc/init.d/rc.mc_defaults
|
||||
|
||||
set MIXER quad_x
|
||||
set PWM_OUT 1234
|
||||
|
||||
param set-default MC_ROLLRATE_P 0.14
|
||||
param set-default MC_ROLLRATE_I 0.1
|
||||
param set-default MC_ROLLRATE_D 0.004
|
||||
|
||||
@@ -42,8 +42,4 @@ param set-default RTL_DESCEND_ALT 10
|
||||
|
||||
set MIXER quad_h
|
||||
|
||||
set PWM_OUT 1234
|
||||
|
||||
set MIXER_AUX pass
|
||||
|
||||
set PWM_AUX_OUT 1234
|
||||
|
||||
@@ -23,7 +23,6 @@
|
||||
|
||||
. ${R}etc/init.d/rc.mc_defaults
|
||||
|
||||
|
||||
param set-default CBRK_SUPPLY_CHK 894281
|
||||
param set-default CBRK_USB_CHK 197848
|
||||
|
||||
@@ -57,5 +56,3 @@ param set-default SYS_HAS_MAG 0
|
||||
param set-default BAT1_N_CELLS 2
|
||||
# The Whoop uses reversed props
|
||||
set MIXER quad_h
|
||||
set PWM_OUT 1234
|
||||
|
||||
|
||||
@@ -12,10 +12,6 @@
|
||||
|
||||
. ${R}etc/init.d/rc.mc_defaults
|
||||
|
||||
set MIXER quad_x
|
||||
set PWM_OUT 1234
|
||||
|
||||
|
||||
param set-default MC_ROLL_P 8
|
||||
param set-default MC_ROLLRATE_P 0.08
|
||||
param set-default MC_ROLLRATE_I 0.25
|
||||
|
||||
@@ -23,11 +23,9 @@
|
||||
. ${R}etc/init.d/rc.mc_defaults
|
||||
|
||||
set MIXER quad_s250aq
|
||||
|
||||
set MAV_TYPE 2
|
||||
|
||||
set PWM_OUT 1234
|
||||
|
||||
|
||||
param set-default ATT_BIAS_MAX 0
|
||||
|
||||
param set-default CBRK_IO_SAFETY 22027
|
||||
|
||||
@@ -15,10 +15,6 @@
|
||||
|
||||
. ${R}etc/init.d/rc.mc_defaults
|
||||
|
||||
set MIXER quad_x
|
||||
set PWM_OUT 1234
|
||||
|
||||
|
||||
# The set does not include a battery, but most people will probably use 4S
|
||||
param set-default BAT1_N_CELLS 4
|
||||
|
||||
|
||||
@@ -13,10 +13,6 @@
|
||||
|
||||
. ${R}etc/init.d/rc.mc_defaults
|
||||
|
||||
set MIXER quad_x
|
||||
set PWM_OUT 1234
|
||||
|
||||
|
||||
param set-default BAT1_N_CELLS 4
|
||||
|
||||
param set-default GPS_1_CONFIG 0
|
||||
|
||||
@@ -13,10 +13,6 @@
|
||||
|
||||
. ${R}etc/init.d/rc.mc_defaults
|
||||
|
||||
set MIXER quad_x
|
||||
set PWM_OUT 1234
|
||||
|
||||
|
||||
param set-default BAT1_N_CELLS 6
|
||||
|
||||
param set-default MC_ROLLRATE_P 0.05
|
||||
|
||||
@@ -19,7 +19,6 @@
|
||||
set MIXER none
|
||||
set MIXER_AUX none
|
||||
|
||||
|
||||
# Battery settings
|
||||
param set-default BAT_CRIT_THR 0.20
|
||||
param set-default BAT_LOW_THR 0.25
|
||||
|
||||
@@ -28,10 +28,8 @@ set PWM_OUT 1234
|
||||
|
||||
# Attitude & rate gains
|
||||
param set-default MC_ROLLRATE_D 0.0013
|
||||
|
||||
param set-default MC_PITCHRATE_D 0.0016
|
||||
|
||||
|
||||
param set-default MC_YAW_FF 0.5
|
||||
|
||||
param set-default MPC_MANTHR_MAX 0.9
|
||||
|
||||
@@ -22,10 +22,6 @@
|
||||
|
||||
. ${R}etc/init.d/rc.mc_defaults
|
||||
|
||||
set MIXER quad_x
|
||||
set PWM_OUT 1234
|
||||
|
||||
|
||||
# use the Q attitude estimator, it works w/o mag or GPS.
|
||||
param set-default SYS_MC_EST_GROUP 3
|
||||
param set-default ATT_ACC_COMP 0
|
||||
|
||||
@@ -17,10 +17,6 @@
|
||||
|
||||
. ${R}etc/init.d/rc.mc_defaults
|
||||
|
||||
set MIXER quad_x
|
||||
set PWM_OUT 1234
|
||||
|
||||
|
||||
param set-default BAT1_N_CELLS 1
|
||||
|
||||
param set-default MC_ROLL_P 8
|
||||
|
||||
@@ -31,5 +31,3 @@
|
||||
# Set mixer
|
||||
set MIXER tilt_quad
|
||||
set MIXER_AUX tilt_quad
|
||||
|
||||
set PWM_OUT 1234
|
||||
|
||||
@@ -1,190 +0,0 @@
|
||||
#!/bin/sh
|
||||
#
|
||||
# @name Teal One
|
||||
#
|
||||
# @type Quadrotor x
|
||||
# @class Copter
|
||||
#
|
||||
# @output MAIN1 motor 1
|
||||
# @output MAIN2 motor 2
|
||||
# @output MAIN3 motor 3
|
||||
# @output MAIN4 motor 4
|
||||
#
|
||||
# @maintainer Matt McFadden <matt.mcfadden@tealdrones.com>
|
||||
#
|
||||
# @board px4_fmu-v2 exclude
|
||||
# @board px4_fmu-v3 exclude
|
||||
# @board px4_fmu-v4pro exclude
|
||||
# @board px4_fmu-v5 exclude
|
||||
# @board px4_fmu-v5x exclude
|
||||
# @board bitcraze_crazyflie exclude
|
||||
#
|
||||
|
||||
echo "Executing 4250_teal script."
|
||||
|
||||
. ${R}etc/init.d/rc.mc_defaults
|
||||
|
||||
set MIXER quad_x
|
||||
set PWM_OUT 1234
|
||||
|
||||
|
||||
# First thing, reset all params to default... EXCEPT THIS LIST
|
||||
param reset_all SYS_AUTOSTART SYS_AUTOCONFIG RC* COM_FLTMODE* LND_FLIGHT_T_* TC_* CAL_ACC* CAL_GYRO* CAL_MAG* SENS_BOARD* EKF2_MAGBIAS*
|
||||
|
||||
# battery
|
||||
param set-default BAT_CRIT_THR 0.15
|
||||
param set-default BAT_EMERGEN_THR 0.075
|
||||
param set-default BAT_LOW_THR 0.20
|
||||
|
||||
param set-default BAT1_CAPACITY 2750
|
||||
param set-default BAT1_N_CELLS 4
|
||||
param set-default BAT1_R_INTERNAL 0.06
|
||||
param set-default BAT1_SOURCE 1
|
||||
param set-default BAT1_V_CHARGED 4.15
|
||||
param set-default BAT1_V_DIV 11.1625
|
||||
param set-default BAT1_V_EMPTY 3.65
|
||||
param set-default BAT1_V_OFFS_CURR -0.0045
|
||||
|
||||
# sensor calibration
|
||||
param set-default CAL_MAG_SIDES 63
|
||||
|
||||
# circuit breakers
|
||||
param set-default CBRK_IO_SAFETY 22027
|
||||
param set-default CBRK_USB_CHK 197848
|
||||
|
||||
# commander
|
||||
param set-default COM_DISARM_LAND 0.1
|
||||
# Return mode at critically low level, Land mode at current position if reaching dangerously low levels.
|
||||
param set-default COM_LOW_BAT_ACT 3
|
||||
|
||||
# ekf2
|
||||
param set-default EKF2_MAG_TYPE 1
|
||||
param set-default EKF2_GPS_CHECK 511
|
||||
param set-default EKF2_GPS_POS_X -0.04
|
||||
param set-default EKF2_IMU_POS_X -0.06
|
||||
param set-default EKF2_PCOEF_XN 0.1
|
||||
param set-default EKF2_PCOEF_XP -0.5
|
||||
param set-default EKF2_RNG_A_VMAX 20
|
||||
param set-default EKF2_RNG_NOISE 0.2
|
||||
param set-default EKF2_MIN_RNG 0.07
|
||||
|
||||
# geofence
|
||||
# Geofence violation action -- Warning.
|
||||
param set-default GF_ACTION 1
|
||||
|
||||
# land detector
|
||||
param set-default LNDMC_XY_VEL_MAX 1
|
||||
# This is set high because we have lots of vibrations while in contact with ground.
|
||||
param set-default LNDMC_ROT_MAX 50
|
||||
|
||||
# serial comms
|
||||
param set-default SER_TEL1_BAUD 921600
|
||||
param set-default SER_TEL2_BAUD 921600
|
||||
|
||||
# mavlink stream configuration
|
||||
# TEL1 ttyS1 -- disabled. TX1 FTDI UART has issues.
|
||||
param set-default MAV_0_CONFIG 0
|
||||
param set-default MAV_0_RATE 800000
|
||||
|
||||
# TEL2 ttyS2 -- Primary MAVLINK stream to companion computer.
|
||||
param set-default MAV_1_CONFIG 102
|
||||
param set-default MAV_1_RATE 800000
|
||||
|
||||
# mc_att_control
|
||||
param set-default MC_ACRO_P_MAX 360
|
||||
param set-default MC_ACRO_R_MAX 360
|
||||
param set-default MC_ACRO_Y_MAX 360
|
||||
|
||||
param set-default MC_ROLL_P 6
|
||||
param set-default MC_ROLLRATE_P 0.055
|
||||
param set-default MC_ROLLRATE_D 0.0012
|
||||
param set-default MC_ROLLRATE_MAX 180
|
||||
|
||||
param set-default MC_PITCHRATE_P 0.06
|
||||
param set-default MC_PITCHRATE_D 0.0012
|
||||
param set-default MC_PITCHRATE_MAX 180
|
||||
|
||||
param set-default MC_YAW_P 1
|
||||
param set-default MC_YAWRATE_P 0.08
|
||||
param set-default MC_YAWRATE_I 0.08
|
||||
|
||||
param set-default MC_YAWRATE_MAX 180
|
||||
|
||||
# Set to reduce voltage transients as seen by battery management system.
|
||||
param set-default MOT_SLEW_MAX 0.15
|
||||
|
||||
#### CONTROLLER ###
|
||||
param set-default MPC_LAND_ALT1 8
|
||||
param set-default MPC_LAND_ALT2 5
|
||||
param set-default MPC_TKO_RAMP_T 0.75
|
||||
param set-default MPC_TKO_SPEED 0.75
|
||||
param set-default MPC_TILTMAX_LND 18
|
||||
param set-default MPC_TILTMAX_AIR 45
|
||||
param set-default MPC_MAN_TILT_MAX 45
|
||||
|
||||
param set-default MPC_MANTHR_MAX 0.85
|
||||
param set-default MPC_MANTHR_MIN 0.15
|
||||
# Full throttle can trip over current protection on BMS.
|
||||
param set-default MPC_THR_MAX 0.85
|
||||
param set-default MPC_THR_MIN 0.15
|
||||
|
||||
param set-default MPC_VEL_MANUAL 26.5
|
||||
# RTL speed, it was too fast and scaring people.
|
||||
param set-default MPC_XY_CRUISE 15
|
||||
|
||||
param set-default MPC_MAN_Y_MAX 200
|
||||
|
||||
param set-default MPC_JERK_MAX 5
|
||||
param set-default MPC_ACC_UP_MAX 10
|
||||
param set-default MPC_ACC_DOWN_MAX 10
|
||||
param set-default MPC_ACC_HOR 10
|
||||
param set-default MPC_ACC_HOR_MAX 15
|
||||
|
||||
param set-default MPC_XY_P 1.15
|
||||
param set-default MPC_XY_VEL_P_ACC 2.8
|
||||
param set-default MPC_XY_VEL_I_ACC 0.28
|
||||
param set-default MPC_XY_VEL_D_ACC 0.28
|
||||
param set-default MPC_XY_VEL_MAX 26.5
|
||||
|
||||
param set-default MPC_Z_P 0.85
|
||||
param set-default MPC_Z_VEL_P_ACC 5
|
||||
param set-default MPC_Z_VEL_I_ACC 1.7
|
||||
param set-default MPC_Z_VEL_D_ACC 0.4
|
||||
# Documentation says limit is 8.0, but does not seem to be enforced in code.
|
||||
param set-default MPC_Z_VEL_MAX_UP 20
|
||||
param set-default MPC_Z_VEL_MAX_DN 2.5
|
||||
#### CONTROLLER ###
|
||||
|
||||
# navigator
|
||||
param set-default NAV_ACC_RAD 2.5
|
||||
# RC loss failsafe behavior -- hold mode.
|
||||
param set-default NAV_RCL_ACT 1
|
||||
|
||||
# pwm control
|
||||
param set-default PWM_MAIN_DISARM 900
|
||||
param set-default PWM_MAIN_MAX 1850
|
||||
param set-default PWM_MAIN_MIN 1075
|
||||
# Oneshot125
|
||||
param set-default PWM_MAIN_RATE 0
|
||||
|
||||
# rtl
|
||||
param set-default RTL_DESCEND_ALT 5
|
||||
param set-default RTL_LAND_DELAY 5
|
||||
param set-default RTL_MIN_DIST 7.5
|
||||
param set-default RTL_RETURN_ALT 25
|
||||
|
||||
# calibration
|
||||
param set-default CAL_ACC0_PRIO 255
|
||||
param set-default CAL_ACC1_PRIO 0
|
||||
|
||||
param set-default CAL_GYRO0_PRIO 255
|
||||
param set-default CAL_GYRO1_PRIO 0
|
||||
# Logger mode. Default(1) + estimator replay(2) + thermal calibration(4)
|
||||
param set-default SDLOG_PROFILE 6
|
||||
|
||||
# Do not start frsky_telemetry on port ttyS6 by default, PGA460 lives there. 500 is in arbitrary unused number.
|
||||
param set TEL_FRSKY_CONFIG 500
|
||||
# We want to make sure these always start
|
||||
param set SENS_EN_PGA460 1
|
||||
param set SENS_EN_THERMAL 1
|
||||
param set SENS_EN_BATT 1
|
||||
@@ -13,10 +13,6 @@
|
||||
|
||||
. ${R}etc/init.d/rc.mc_defaults
|
||||
|
||||
set MIXER quad_x
|
||||
set PWM_OUT 1234
|
||||
|
||||
|
||||
param set-default MC_PITCHRATE_P 0.087
|
||||
param set-default MC_PITCHRATE_I 0.037
|
||||
param set-default MC_PITCHRATE_D 0.0044
|
||||
|
||||
@@ -17,7 +17,6 @@
|
||||
. ${R}etc/init.d/rc.mc_defaults
|
||||
|
||||
set MIXER quad_x_cw
|
||||
set PWM_OUT 1234
|
||||
|
||||
param set-default BAT1_N_CELLS 1
|
||||
param set-default BAT1_CAPACITY 240
|
||||
@@ -69,4 +68,3 @@ set PWM_MAIN_MIN none
|
||||
|
||||
syslink start
|
||||
mavlink start -d /dev/bridge0 -b 57600 -m osd -r 40000
|
||||
|
||||
|
||||
@@ -17,7 +17,6 @@
|
||||
. ${R}etc/init.d/rc.mc_defaults
|
||||
|
||||
set MIXER quad_x_cw
|
||||
set PWM_OUT 1234
|
||||
|
||||
param set-default SYS_MC_EST_GROUP 2
|
||||
param set-default SYS_HAS_MAG 0
|
||||
@@ -61,7 +60,6 @@ param set-default PWM_MAIN_RATE 3921
|
||||
|
||||
param set-default SENS_FLOW_MINRNG 0.05
|
||||
|
||||
|
||||
set PWM_MAIN_DISARM none
|
||||
set PWM_MAIN_MAX none
|
||||
set PWM_MAIN_MIN none
|
||||
|
||||
@@ -18,7 +18,6 @@
|
||||
|
||||
. ${R}etc/init.d/rc.rover_defaults
|
||||
|
||||
|
||||
param set-default BAT1_N_CELLS 4
|
||||
|
||||
param set-default EKF2_GBIAS_INIT 0.01
|
||||
|
||||
@@ -20,7 +20,6 @@
|
||||
|
||||
. ${R}etc/init.d/rc.rover_defaults
|
||||
|
||||
|
||||
param set-default BAT1_N_CELLS 2
|
||||
|
||||
param set-default EKF2_GBIAS_INIT 0.01
|
||||
|
||||
@@ -26,5 +26,3 @@
|
||||
. ${R}etc/init.d/rc.mc_defaults
|
||||
|
||||
set MIXER quad_+
|
||||
|
||||
set PWM_OUT 1234
|
||||
|
||||
@@ -22,7 +22,6 @@
|
||||
|
||||
. ${R}etc/init.d/rc.uuv_defaults
|
||||
|
||||
|
||||
#Set data link loss failsafe mode (0: disabled)
|
||||
|
||||
# disable circuit breaker for airspeed sensor
|
||||
@@ -43,4 +42,3 @@ param set-default BAT_V_OFFS_CURR 0.33
|
||||
set PWM_OUT 12345678
|
||||
# set MIXER IO_pass
|
||||
set MIXER vectored6dof
|
||||
|
||||
|
||||
@@ -26,6 +26,7 @@
|
||||
#
|
||||
|
||||
. ${R}etc/init.d/rc.mc_defaults
|
||||
|
||||
set MIXER hexa_x
|
||||
set PWM_OUT 12345678
|
||||
|
||||
|
||||
@@ -13,7 +13,6 @@
|
||||
. ${R}etc/init.d/rc.mc_defaults
|
||||
. ${R}etc/init.d/rc.ctrlalloc
|
||||
|
||||
|
||||
param set-default MPC_USE_HTE 0
|
||||
|
||||
param set-default VM_MASS 1.5
|
||||
|
||||
@@ -88,7 +88,6 @@ px4_add_romfs_files(
|
||||
4080_zmr250
|
||||
4090_nanomind
|
||||
4100_tiltquadrotor
|
||||
4250_teal
|
||||
4500_clover4
|
||||
4900_crazyflie
|
||||
4901_crazyflie21
|
||||
|
||||
@@ -8,8 +8,8 @@
|
||||
#
|
||||
# Start angular velocity controller
|
||||
#
|
||||
angular_velocity_controller start
|
||||
mc_rate_control stop
|
||||
# angular_velocity_controller start
|
||||
# mc_rate_control stop
|
||||
|
||||
#
|
||||
# Start Control Allocator
|
||||
|
||||
@@ -25,4 +25,8 @@ param set-default GPS_UBX_DYNMODEL 6
|
||||
#
|
||||
set MIXER_AUX pass
|
||||
|
||||
set MIXER quad_x
|
||||
|
||||
set PWM_OUT 1234
|
||||
|
||||
set PWM_AUX_OUT 1234
|
||||
|
||||
@@ -108,7 +108,13 @@ fi
|
||||
# Python3 dependencies
|
||||
echo
|
||||
echo "Installing PX4 Python3 dependencies"
|
||||
python3 -m pip install --user -r ${DIR}/requirements.txt
|
||||
if [ -n "$VIRTUAL_ENV" ]; then
|
||||
# virtual envrionments don't allow --user option
|
||||
python -m pip install -r ${DIR}/requirements.txt
|
||||
else
|
||||
# older versions of Ubuntu require --user option
|
||||
python3 -m pip install --user -r ${DIR}/requirements.txt
|
||||
fi
|
||||
|
||||
# NuttX toolchain (arm-none-eabi-gcc)
|
||||
if [[ $INSTALL_NUTTX == "true" ]]; then
|
||||
|
||||
@@ -78,6 +78,12 @@
|
||||
#define GPIO_I2C2_SCL_RESET /* PB10 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN10)
|
||||
#define GPIO_I2C2_SDA_RESET /* PB9 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN9)
|
||||
|
||||
#define GPIO_USART1_RX_GPIO (GPIO_INPUT|GPIO_PULLUP|GPIO_SPEED_50MHz|GPIO_PORTB|GPIO_PIN3)
|
||||
#define GPIO_USART1_TX_GPIO (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_PULLUP|GPIO_SPEED_50MHz|GPIO_PORTA|GPIO_PIN15)
|
||||
|
||||
#define GPIO_USART2_RX_GPIO (GPIO_INPUT|GPIO_PULLUP|GPIO_SPEED_50MHz|GPIO_PORTA|GPIO_PIN3)
|
||||
#define GPIO_USART2_TX_GPIO (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_PULLUP|GPIO_SPEED_50MHz|GPIO_PORTA|GPIO_PIN2)
|
||||
|
||||
#define FLASH_BASED_PARAMS
|
||||
|
||||
/* High-resolution timer */
|
||||
|
||||
@@ -55,6 +55,7 @@
|
||||
|
||||
#include <stm32.h>
|
||||
#include "board_config.h"
|
||||
#include "led.h"
|
||||
#include <stm32_uart.h>
|
||||
|
||||
#include <arch/board/board.h>
|
||||
@@ -92,6 +93,21 @@ __EXPORT void stm32_boardinitialize(void)
|
||||
|
||||
// Configure SPI all interfaces GPIO & enable power.
|
||||
stm32_spiinitialize();
|
||||
|
||||
// Check if button is held. If so go into gps passthrough mode
|
||||
if (stm32_gpioread(GPIO_BTN_SAFETY)) {
|
||||
rgb_led(128, 128, 128, 10);
|
||||
stm32_configgpio(GPIO_USART1_TX_GPIO);
|
||||
stm32_configgpio(GPIO_USART1_RX_GPIO);
|
||||
stm32_configgpio(GPIO_USART2_TX_GPIO);
|
||||
stm32_configgpio(GPIO_USART2_RX_GPIO);
|
||||
|
||||
while (1) {
|
||||
watchdog_pet();
|
||||
stm32_gpiowrite(GPIO_USART2_TX_GPIO, stm32_gpioread(GPIO_USART1_RX_GPIO));
|
||||
stm32_gpiowrite(GPIO_USART1_TX_GPIO, stm32_gpioread(GPIO_USART2_RX_GPIO));
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
|
||||
@@ -78,6 +78,15 @@
|
||||
#define GPIO_I2C2_SCL_RESET /* PB10 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN10)
|
||||
#define GPIO_I2C2_SDA_RESET /* PB9 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN9)
|
||||
|
||||
#define GPIO_I2C2_SCL_RESET /* PB10 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN10)
|
||||
#define GPIO_I2C2_SDA_RESET /* PB9 */ (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN9)
|
||||
|
||||
#define GPIO_USART1_RX_GPIO (GPIO_INPUT|GPIO_PULLUP|GPIO_SPEED_50MHz|GPIO_PORTB|GPIO_PIN3)
|
||||
#define GPIO_USART1_TX_GPIO (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_PULLUP|GPIO_SPEED_50MHz|GPIO_PORTA|GPIO_PIN15)
|
||||
|
||||
#define GPIO_USART2_RX_GPIO (GPIO_INPUT|GPIO_PULLUP|GPIO_SPEED_50MHz|GPIO_PORTA|GPIO_PIN3)
|
||||
#define GPIO_USART2_TX_GPIO (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_PULLUP|GPIO_SPEED_50MHz|GPIO_PORTA|GPIO_PIN2)
|
||||
|
||||
#define FLASH_BASED_PARAMS
|
||||
|
||||
/* High-resolution timer */
|
||||
|
||||
@@ -55,6 +55,7 @@
|
||||
|
||||
#include <stm32.h>
|
||||
#include "board_config.h"
|
||||
#include "led.h"
|
||||
#include <stm32_uart.h>
|
||||
|
||||
#include <arch/board/board.h>
|
||||
@@ -92,6 +93,21 @@ __EXPORT void stm32_boardinitialize(void)
|
||||
|
||||
// Configure SPI all interfaces GPIO & enable power.
|
||||
stm32_spiinitialize();
|
||||
|
||||
// Check if button is held. If so go into gps passthrough mode
|
||||
if (stm32_gpioread(GPIO_BTN_SAFETY)) {
|
||||
rgb_led(128, 128, 128, 10);
|
||||
stm32_configgpio(GPIO_USART1_TX_GPIO);
|
||||
stm32_configgpio(GPIO_USART1_RX_GPIO);
|
||||
stm32_configgpio(GPIO_USART2_TX_GPIO);
|
||||
stm32_configgpio(GPIO_USART2_RX_GPIO);
|
||||
|
||||
while (1) {
|
||||
watchdog_pet();
|
||||
stm32_gpiowrite(GPIO_USART2_TX_GPIO, stm32_gpioread(GPIO_USART1_RX_GPIO));
|
||||
stm32_gpiowrite(GPIO_USART1_TX_GPIO, stm32_gpioread(GPIO_USART2_RX_GPIO));
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
|
||||
@@ -254,11 +254,11 @@ __EXPORT int board_app_initialize(uintptr_t arg)
|
||||
syslog(LOG_ERR, "DMA alloc FAILED\n");
|
||||
}
|
||||
|
||||
#if defined(SERIAL_HAVE_RXDMA)
|
||||
#if defined(SERIAL_HAVE_DMA) || defined(LPSERIAL_HAVE_DMA)
|
||||
// set up the serial DMA polling at 1ms intervals for received bytes that have not triggered a DMA event.
|
||||
static struct hrt_call serial_dma_call;
|
||||
hrt_call_every(&serial_dma_call, 1000, 1000, (hrt_callout)kinetis_lpserial_dma_poll_all, NULL);
|
||||
#endif
|
||||
#endif /* SERIAL_HAVE_DMA || LPSERIAL_HAVE_DMA */
|
||||
|
||||
/* initial LED state */
|
||||
drv_led_start();
|
||||
|
||||
@@ -1,2 +1,9 @@
|
||||
CONFIG_DRIVERS_UAVCAN=n
|
||||
CONFIG_DRIVERS_UAVCAN_V1=y
|
||||
CONFIG_UAVCAN_V1_BMS_SUBSCRIBER=y
|
||||
CONFIG_UAVCAN_V1_ESC_SUBSCRIBER=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_SUBSCRIBER=y
|
||||
|
||||
@@ -254,11 +254,11 @@ __EXPORT int board_app_initialize(uintptr_t arg)
|
||||
syslog(LOG_ERR, "DMA alloc FAILED\n");
|
||||
}
|
||||
|
||||
#if defined(SERIAL_HAVE_RXDMA)
|
||||
#if defined(SERIAL_HAVE_DMA) || defined(LPSERIAL_HAVE_DMA)
|
||||
// set up the serial DMA polling at 1ms intervals for received bytes that have not triggered a DMA event.
|
||||
static struct hrt_call serial_dma_call;
|
||||
hrt_call_every(&serial_dma_call, 1000, 1000, (hrt_callout)kinetis_lpserial_dma_poll_all, NULL);
|
||||
#endif
|
||||
#endif /* SERIAL_HAVE_DMA || LPSERIAL_HAVE_DMA */
|
||||
|
||||
/* initial LED state */
|
||||
drv_led_start();
|
||||
|
||||
@@ -0,0 +1,10 @@
|
||||
#!/bin/sh
|
||||
#
|
||||
# board specific MAVLink startup script.
|
||||
#------------------------------------------------------------------------------
|
||||
|
||||
if ver hwtypecmp V5Xa0 V5X91 V5Xa1
|
||||
then
|
||||
# Start MAVLink on the UART connected to the mission computer
|
||||
mavlink start -d /dev/ttyS4 -b 3000000 -r 290000 -m onboard_low_bandwidth -x -z
|
||||
fi
|
||||
@@ -0,0 +1 @@
|
||||
CONFIG_MODULES_MICRORTPS_BRIDGE=y
|
||||
@@ -46,7 +46,7 @@ endif()
|
||||
add_custom_target(upload
|
||||
COMMAND rsync -arh --progress
|
||||
${CMAKE_RUNTIME_OUTPUT_DIRECTORY} ${PX4_SOURCE_DIR}/posix-configs/rpi/pilotpi*.config ${PX4_BINARY_DIR}/etc # source
|
||||
\$\{AUTOPILOT_USER\}@\$\{AUTOPILOT_HOST\}:/home/\$\{AUTOPILOT_USER\}/px4 # destination
|
||||
"${AUTOPILOT_USER}@${AUTOPILOT_HOST}:/home/${AUTOPILOT_USER}/px4" # destination
|
||||
DEPENDS px4
|
||||
COMMENT "uploading px4"
|
||||
USES_TERMINAL
|
||||
|
||||
@@ -85,8 +85,6 @@ function(px4_add_common_flags)
|
||||
-Wunknown-pragmas
|
||||
-Wunused-variable
|
||||
|
||||
-Wfloat-conversion
|
||||
|
||||
# disabled warnings
|
||||
-Wno-missing-field-initializers
|
||||
-Wno-missing-include-dirs # TODO: fix and enable
|
||||
|
||||
@@ -378,7 +378,7 @@ void uORB::DeviceMaster::showTop(char **topic_filter, int num_filters)
|
||||
|
||||
while (cur_node) {
|
||||
unsigned int num_msgs = cur_node->node->updates_available(cur_node->last_pub_msg_count);
|
||||
cur_node->pub_msg_delta = (int)roundf(num_msgs / dt);
|
||||
cur_node->pub_msg_delta = roundf(num_msgs / dt);
|
||||
cur_node->last_pub_msg_count += num_msgs;
|
||||
|
||||
total_size += cur_node->pub_msg_delta * cur_node->node->get_meta()->o_size;
|
||||
|
||||
@@ -150,7 +150,7 @@ static void mavlink_usb_check(void *arg)
|
||||
if (nread >= MAVLINK_HEARTBEAT_MIN_LENGTH) {
|
||||
// scan buffer for mavlink HEARTBEAT (v1 & v2)
|
||||
for (int i = 0; i < nread - MAVLINK_HEARTBEAT_MIN_LENGTH; i++) {
|
||||
if ((buffer[i] = 0xFE) && (buffer[i + 1] = 9) && (buffer[i + 5] == 0)) {
|
||||
if ((buffer[i] == 0xFE) && (buffer[i + 1] == 9) && (buffer[i + 5] == 0)) {
|
||||
// mavlink v1 HEARTBEAT
|
||||
// buffer[0]: start byte (0xFE for mavlink v1)
|
||||
// buffer[1]: length (9 for HEARTBEAT)
|
||||
@@ -162,7 +162,7 @@ static void mavlink_usb_check(void *arg)
|
||||
launch_mavlink = true;
|
||||
break;
|
||||
|
||||
} else if ((buffer[i] = 0xFD) && (buffer[i + 1] = 9)
|
||||
} else if ((buffer[i] == 0xFD) && (buffer[i + 1] == 9)
|
||||
&& (buffer[i + 7] == 0) && (buffer[i + 8] == 0) && (buffer[i + 9] == 0)) {
|
||||
// mavlink v2 HEARTBEAT
|
||||
// buffer[0]: start byte (0xFD for mavlink v2)
|
||||
|
||||
@@ -120,6 +120,7 @@ set(models
|
||||
believer
|
||||
boat
|
||||
cloudship
|
||||
glider
|
||||
if750a
|
||||
iris
|
||||
iris_ctrlalloc
|
||||
@@ -147,6 +148,7 @@ set(models
|
||||
techpod
|
||||
tiltrotor
|
||||
typhoon_h480
|
||||
typhoon_h480_ctrlalloc
|
||||
uuv_bluerov2_heavy
|
||||
uuv_hippocampus
|
||||
)
|
||||
|
||||
@@ -342,11 +342,10 @@ CameraTrigger::update_intervalometer()
|
||||
PX4_DEBUG("update intervalometer, trigger enabled: %d, trigger paused: %d", _trigger_enabled, _trigger_paused);
|
||||
|
||||
// schedule trigger on and off calls
|
||||
hrt_call_every(&_engagecall, 0, (int)(_interval * 1000), &CameraTrigger::engage, this);
|
||||
hrt_call_every(&_engagecall, 0, (_interval * 1000), &CameraTrigger::engage, this);
|
||||
|
||||
// schedule trigger on and off calls
|
||||
hrt_call_every(&_disengagecall, (int)(0 + (_activation_time * 1000)), (int)(_interval * 1000),
|
||||
&CameraTrigger::disengage, this);
|
||||
hrt_call_every(&_disengagecall, 0 + (_activation_time * 1000), (_interval * 1000), &CameraTrigger::disengage, this);
|
||||
|
||||
}
|
||||
}
|
||||
@@ -430,7 +429,7 @@ CameraTrigger::shoot_once()
|
||||
hrt_call_after(&_engagecall, 0,
|
||||
(hrt_callout)&CameraTrigger::engage, this);
|
||||
|
||||
hrt_call_after(&_disengagecall, (int)(0 + (_activation_time * 1000)), &CameraTrigger::disengage, this);
|
||||
hrt_call_after(&_disengagecall, 0 + (_activation_time * 1000), &CameraTrigger::disengage, this);
|
||||
}
|
||||
|
||||
bool
|
||||
@@ -673,8 +672,8 @@ CameraTrigger::Run()
|
||||
|
||||
if (cmd.param4 >= 2.0f) {
|
||||
_CAMPOS_num_poses = commandParamToInt(cmd.param4);
|
||||
_CAMPOS_roll_angle = static_cast<float>(cmd.param5);
|
||||
_CAMPOS_pitch_angle = static_cast<float>(cmd.param6);
|
||||
_CAMPOS_roll_angle = cmd.param5;
|
||||
_CAMPOS_pitch_angle = cmd.param6;
|
||||
_CAMPOS_angle_interval = _CAMPOS_roll_angle * 2 / (_CAMPOS_num_poses - 1);
|
||||
_CAMPOS_pose_counter = 0;
|
||||
_CAMPOS_updated_roll_angle = false;
|
||||
|
||||
@@ -31,4 +31,4 @@
|
||||
#
|
||||
############################################################################
|
||||
|
||||
#add_subdirectory(afbrs50) # not suitable for general inclusion
|
||||
add_subdirectory(afbrs50)
|
||||
|
||||
@@ -115,7 +115,7 @@ LightwareLaserSerial::init()
|
||||
/* SF30/B (50m 39Hz) */
|
||||
_px4_rangefinder.set_min_distance(0.2f);
|
||||
_px4_rangefinder.set_max_distance(50.0f);
|
||||
_interval = (int)round(1e6 / 39);
|
||||
_interval = 1e6 / 39;
|
||||
_simple_serial = true;
|
||||
break;
|
||||
|
||||
@@ -123,10 +123,17 @@ LightwareLaserSerial::init()
|
||||
/* SF30/C (100m 39Hz) */
|
||||
_px4_rangefinder.set_min_distance(0.2f);
|
||||
_px4_rangefinder.set_max_distance(100.0f);
|
||||
_interval = (int)round(1e6 / 39);
|
||||
_interval = 1e6 / 39;
|
||||
_simple_serial = true;
|
||||
break;
|
||||
|
||||
case 8:
|
||||
/* LW20/c (100M 20Hz) */
|
||||
_px4_rangefinder.set_min_distance(0.2f);
|
||||
_px4_rangefinder.set_max_distance(100.0f);
|
||||
_interval = 50000;
|
||||
break;
|
||||
|
||||
default:
|
||||
PX4_ERR("invalid HW model %" PRIi32 ".", hw_model);
|
||||
return -1;
|
||||
@@ -297,6 +304,12 @@ void LightwareLaserSerial::Run()
|
||||
if ((termios_state = tcsetattr(_fd, TCSANOW, &uart_config)) < 0) {
|
||||
PX4_ERR("baud %d ATTR", termios_state);
|
||||
}
|
||||
|
||||
// LW20: Enable serial mode by sending some characters
|
||||
if (hw_model == 8) {
|
||||
const char *data = "www\r\n";
|
||||
(void)!::write(_fd, &data, strlen(data));
|
||||
}
|
||||
}
|
||||
|
||||
/* collection phase? */
|
||||
|
||||
@@ -41,5 +41,8 @@
|
||||
* @value 3 SF10/b
|
||||
* @value 4 SF10/c
|
||||
* @value 5 SF11/c
|
||||
* @value 6 SF30/b
|
||||
* @value 7 SF30/c
|
||||
* @value 8 LW20/c
|
||||
*/
|
||||
PARAM_DEFINE_INT32(SENS_EN_SF0X, 1);
|
||||
|
||||
@@ -38,7 +38,6 @@ px4_add_module(
|
||||
MAIN gps
|
||||
COMPILE_FLAGS
|
||||
-Wno-stringop-overflow # due to https://gcc.gnu.org/bugzilla/show_bug.cgi?id=91707
|
||||
-Wno-float-conversion # TODO: fix and enable
|
||||
SRCS
|
||||
gps.cpp
|
||||
devices/src/gps_helper.cpp
|
||||
|
||||
@@ -894,7 +894,7 @@ GPS::run()
|
||||
float dt = (float)((hrt_absolute_time() - last_rate_measurement)) / 1000000.0f;
|
||||
_rate = last_rate_count / dt;
|
||||
_rate_rtcm_injection = _last_rate_rtcm_injection_count / dt;
|
||||
_rate_reading = (int)roundf((float)_num_bytes_read / dt);
|
||||
_rate_reading = _num_bytes_read / dt;
|
||||
last_rate_measurement = hrt_absolute_time();
|
||||
last_rate_count = 0;
|
||||
_last_rate_rtcm_injection_count = 0;
|
||||
|
||||
@@ -277,12 +277,19 @@ void ICM20602::RunImpl()
|
||||
timestamp_sample -= extra_samples * static_cast<int>(FIFO_SAMPLE_DT);
|
||||
samples = _fifo_gyro_samples;
|
||||
|
||||
ScheduleOnInterval(_fifo_empty_interval_us,
|
||||
_fifo_empty_interval_us - (extra_samples * FIFO_SAMPLE_DT));
|
||||
if (_fifo_gyro_samples > extra_samples) {
|
||||
// reschedule to run when a total of _fifo_gyro_samples should be available in the FIFO
|
||||
const uint32_t reschedule_delay_us = (_fifo_gyro_samples - extra_samples) * static_cast<int>(FIFO_SAMPLE_DT);
|
||||
ScheduleOnInterval(_fifo_empty_interval_us, reschedule_delay_us);
|
||||
|
||||
} else {
|
||||
// otherwise reschedule to run immediately
|
||||
ScheduleOnInterval(_fifo_empty_interval_us);
|
||||
}
|
||||
|
||||
} else if (samples < _fifo_gyro_samples) {
|
||||
// reschedule next cycle to catch the desired number of samples
|
||||
ScheduleOnInterval(_fifo_empty_interval_us, (_fifo_gyro_samples - samples) * FIFO_SAMPLE_DT);
|
||||
ScheduleOnInterval(_fifo_empty_interval_us, (_fifo_gyro_samples - samples) * static_cast<int>(FIFO_SAMPLE_DT));
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
@@ -232,12 +232,19 @@ void ICM20649::RunImpl()
|
||||
timestamp_sample -= extra_samples * static_cast<int>(FIFO_SAMPLE_DT);
|
||||
samples = _fifo_gyro_samples;
|
||||
|
||||
ScheduleOnInterval(_fifo_empty_interval_us,
|
||||
_fifo_empty_interval_us - (extra_samples * FIFO_SAMPLE_DT));
|
||||
if (_fifo_gyro_samples > extra_samples) {
|
||||
// reschedule to run when a total of _fifo_gyro_samples should be available in the FIFO
|
||||
const uint32_t reschedule_delay_us = (_fifo_gyro_samples - extra_samples) * static_cast<int>(FIFO_SAMPLE_DT);
|
||||
ScheduleOnInterval(_fifo_empty_interval_us, reschedule_delay_us);
|
||||
|
||||
} else {
|
||||
// otherwise reschedule to run immediately
|
||||
ScheduleOnInterval(_fifo_empty_interval_us);
|
||||
}
|
||||
|
||||
} else if (samples < _fifo_gyro_samples) {
|
||||
// reschedule next cycle to catch the desired number of samples
|
||||
ScheduleOnInterval(_fifo_empty_interval_us, (_fifo_gyro_samples - samples) * FIFO_SAMPLE_DT);
|
||||
ScheduleOnInterval(_fifo_empty_interval_us, (_fifo_gyro_samples - samples) * static_cast<int>(FIFO_SAMPLE_DT));
|
||||
}
|
||||
|
||||
if (samples == _fifo_gyro_samples) {
|
||||
|
||||
@@ -268,12 +268,19 @@ void ICM20948::RunImpl()
|
||||
timestamp_sample -= extra_samples * static_cast<int>(FIFO_SAMPLE_DT);
|
||||
samples = _fifo_gyro_samples;
|
||||
|
||||
ScheduleOnInterval(_fifo_empty_interval_us,
|
||||
_fifo_empty_interval_us - (extra_samples * FIFO_SAMPLE_DT));
|
||||
if (_fifo_gyro_samples > extra_samples) {
|
||||
// reschedule to run when a total of _fifo_gyro_samples should be available in the FIFO
|
||||
const uint32_t reschedule_delay_us = (_fifo_gyro_samples - extra_samples) * static_cast<int>(FIFO_SAMPLE_DT);
|
||||
ScheduleOnInterval(_fifo_empty_interval_us, reschedule_delay_us);
|
||||
|
||||
} else {
|
||||
// otherwise reschedule to run immediately
|
||||
ScheduleOnInterval(_fifo_empty_interval_us);
|
||||
}
|
||||
|
||||
} else if (samples < _fifo_gyro_samples) {
|
||||
// reschedule next cycle to catch the desired number of samples
|
||||
ScheduleOnInterval(_fifo_empty_interval_us, (_fifo_gyro_samples - samples) * FIFO_SAMPLE_DT);
|
||||
ScheduleOnInterval(_fifo_empty_interval_us, (_fifo_gyro_samples - samples) * static_cast<int>(FIFO_SAMPLE_DT));
|
||||
}
|
||||
|
||||
if (samples == _fifo_gyro_samples) {
|
||||
|
||||
@@ -568,8 +568,8 @@ void DevCommon::cleanup()
|
||||
|
||||
size_t garbage_end = 0;
|
||||
|
||||
if (!mavlink_available && !rtps_available && (_read_buffer->buf_size > 0)) {
|
||||
garbage_end = _read_buffer->buf_size - 1;
|
||||
if (!mavlink_available && !rtps_available) {
|
||||
garbage_end = math::max(_read_buffer->start_mavlink, _read_buffer->start_rtps);
|
||||
|
||||
} else {
|
||||
garbage_end = math::min(_read_buffer->start_mavlink, _read_buffer->start_rtps);
|
||||
|
||||
@@ -63,7 +63,7 @@ int rpm_simulator_main(int argc, char *argv[])
|
||||
|
||||
uORB::Publication<rpm_s> rpm_pub{ORB_ID(rpm)};
|
||||
uint64_t timestamp_us = hrt_absolute_time();
|
||||
float frequency = (float)atof(argv[1]);
|
||||
float frequency = atof(argv[1]);
|
||||
|
||||
// prpepare RPM data message
|
||||
rpm.timestamp = timestamp_us;
|
||||
|
||||
@@ -50,6 +50,8 @@ else()
|
||||
endif()
|
||||
|
||||
set(SRCS)
|
||||
set(DPNDS)
|
||||
|
||||
if(${PX4_PLATFORM} MATCHES "nuttx")
|
||||
if(CONFIG_NET_CAN)
|
||||
list(APPEND SRCS
|
||||
@@ -64,6 +66,40 @@ if(${PX4_PLATFORM} MATCHES "nuttx")
|
||||
endif()
|
||||
endif()
|
||||
|
||||
if(CONFIG_UAVCAN_V1_NODE_MANAGER)
|
||||
list(APPEND SRCS
|
||||
NodeManager.hpp
|
||||
NodeManager.cpp
|
||||
)
|
||||
endif()
|
||||
|
||||
if(CONFIG_UAVCAN_V1_NODE_CLIENT)
|
||||
list(APPEND SRCS
|
||||
NodeClient.hpp
|
||||
NodeClient.cpp
|
||||
)
|
||||
list(APPEND DPNDS
|
||||
drivers_bootloaders
|
||||
)
|
||||
endif()
|
||||
|
||||
# Temporary measure to get Kconfig option as defines into this application
|
||||
# Ideally we want nicely decouple and define this in kconfig.cmake
|
||||
# But then we need to overhaul the src modules naming convention
|
||||
set(DRIVERS_UAVCAN_V1_OPTIONS)
|
||||
get_cmake_property(_variableNames VARIABLES)
|
||||
foreach (_variableName ${_variableNames})
|
||||
string(REGEX MATCH "^CONFIG_UAVCAN_V1_" UAVCAN_V1_OPTION ${_variableName})
|
||||
|
||||
if(UAVCAN_V1_OPTION)
|
||||
if(${${_variableName}} STREQUAL "y")
|
||||
list(APPEND DRIVERS_UAVCAN_V1_OPTIONS "-D${_variableName}=1")
|
||||
else()
|
||||
list(APPEND DRIVERS_UAVCAN_V1_OPTIONS "-D${_variableName}=${${_variableName}}")
|
||||
endif()
|
||||
endif()
|
||||
endforeach()
|
||||
|
||||
px4_add_module(
|
||||
MODULE drivers__uavcan_v1
|
||||
MAIN uavcan_v1
|
||||
@@ -72,6 +108,7 @@ px4_add_module(
|
||||
#-DCANARD_ASSERT
|
||||
-DUINT32_C\(x\)=__UINT32_C\(x\)
|
||||
-O0
|
||||
${DRIVERS_UAVCAN_V1_OPTIONS}
|
||||
INCLUDES
|
||||
${LIBCANARD_DIR}/libcanard/
|
||||
${CMAKE_CURRENT_BINARY_DIR}/dsdlc_generated
|
||||
@@ -82,8 +119,6 @@ px4_add_module(
|
||||
SubscriptionManager.hpp
|
||||
ParamManager.hpp
|
||||
ParamManager.cpp
|
||||
NodeManager.hpp
|
||||
NodeManager.cpp
|
||||
Uavcan.cpp
|
||||
Uavcan.hpp
|
||||
Publishers/uORB/uorb_publisher.cpp
|
||||
@@ -97,4 +132,5 @@ px4_add_module(
|
||||
git_public_regulated_data_types
|
||||
git_legacy_data_types
|
||||
version
|
||||
${DPNDS}
|
||||
)
|
||||
|
||||
@@ -20,15 +20,91 @@ if DRIVERS_UAVCAN_V1
|
||||
|
||||
endchoice
|
||||
|
||||
config UAVCAN_V1_GETINFO_RESPONDER
|
||||
bool "GetInfo1.0 responder"
|
||||
default n
|
||||
config UAVCAN_V1_NODE_MANAGER
|
||||
bool "Node manager"
|
||||
default y
|
||||
depends on UAVCAN_V1_FMU
|
||||
help
|
||||
Implement UAVCAN v1 PNP server functionality and manages discovered nodes
|
||||
|
||||
config UAVCAN_V1_EXECUTECOMMAND_RESPONDER
|
||||
bool "ExecuteCommand1.0 responder"
|
||||
default n
|
||||
config UAVCAN_V1_NODE_CLIENT
|
||||
bool "Node client"
|
||||
default y
|
||||
depends on UAVCAN_V1_CLIENT
|
||||
help
|
||||
Implement UAVCAN v1 PNP client functionality
|
||||
|
||||
config UAVCAN_V1_GNSS_PUBLISHER
|
||||
bool "GNSS Publisher"
|
||||
config UAVCAN_V1_APP_DESCRIPTOR
|
||||
bool "UAVCAN v0 bootloader app descriptor"
|
||||
default n
|
||||
depends on UAVCAN_V1_CLIENT && DRIVERS_BOOTLOADERS
|
||||
help
|
||||
When the board uses the UAVCANv0 bootloader functionality you need a AppImageDescriptor defined
|
||||
|
||||
|
||||
menu "Publisher support"
|
||||
|
||||
config UAVCAN_V1_GNSS_PUBLISHER
|
||||
bool "GNSS Publisher"
|
||||
default n
|
||||
|
||||
config UAVCAN_V1_ESC_CONTROLLER
|
||||
bool "ESC Controller"
|
||||
default n
|
||||
|
||||
config UAVCAN_V1_READINESS_PUBLISHER
|
||||
bool "Readiness Publisher"
|
||||
default n
|
||||
|
||||
config UAVCAN_V1_UORB_ACTUATOR_OUTPUTS_PUBLISHER
|
||||
bool "uORB actuator_outputs publisher"
|
||||
default n
|
||||
|
||||
config UAVCAN_V1_UORB_SENSOR_GPS_PUBLISHER
|
||||
bool "uORB sensor_gps publisher"
|
||||
default n
|
||||
|
||||
endmenu
|
||||
|
||||
menu "Subscriber support"
|
||||
|
||||
config UAVCAN_V1_ESC_SUBSCRIBER
|
||||
bool "ESC Subscriber"
|
||||
default n
|
||||
|
||||
config UAVCAN_V1_GNSS_SUBSCRIBER_0
|
||||
bool "GNSS Subscriber 0 "
|
||||
default n
|
||||
|
||||
config UAVCAN_V1_GNSS_SUBSCRIBER_1
|
||||
bool "GNSS Subscriber 1"
|
||||
default n
|
||||
|
||||
config UAVCAN_V1_BMS_SUBSCRIBER
|
||||
bool "BMS Subscriber"
|
||||
default n
|
||||
|
||||
config UAVCAN_V1_UORB_SENSOR_GPS_SUBSCRIBER
|
||||
bool "uORB sensor_gps Subscriber"
|
||||
default n
|
||||
endmenu
|
||||
|
||||
menu "Advertised Services"
|
||||
config UAVCAN_V1_GETINFO_RESPONDER
|
||||
bool "GetInfo1.0 responder"
|
||||
default y
|
||||
help
|
||||
Responds to uavcan.node.GetInfo.1.0 request sending over node information
|
||||
See https://github.com/UAVCAN/public_regulated_data_types/blob/master/uavcan/node/430.GetInfo.1.0.uavcan for full response
|
||||
|
||||
config UAVCAN_V1_EXECUTECOMMAND_RESPONDER
|
||||
bool "ExecuteCommand1.0 responder"
|
||||
default n
|
||||
help
|
||||
To be implemented
|
||||
endmenu
|
||||
|
||||
menu "Service invokers"
|
||||
endmenu
|
||||
|
||||
endif #DRIVERS_UAVCAN_V1
|
||||
|
||||
Some files were not shown because too many files have changed in this diff Show More
Reference in New Issue
Block a user