diff --git a/ROMFS/px4fmu_common/init.d/airframes/17002_TF-AutoG2 b/ROMFS/px4fmu_common/init.d/airframes/17002_TF-AutoG2 deleted file mode 100644 index 0ed3b201c8a5..000000000000 --- a/ROMFS/px4fmu_common/init.d/airframes/17002_TF-AutoG2 +++ /dev/null @@ -1,62 +0,0 @@ -#!/bin/sh -# -# @name ThunderFly Auto-G2 -# -# @type Autogyro -# @class Autogyro -# -# @output Motor1 throttle -# @output Servo1 rotor_head_L -# @output Servo2 rotor_head_R -# @output Servo3 elevator -# @output Servo4 rudder -# @output Servo5 rudder (second, optional) -# @output Servo6 wheel -# -# @url https://github.com/ThunderFly-aerospace/Auto-G2/ -# @maintainer ThunderFly s.r.o., Roman Dvorak -# -# @board px4_fmu-v2 exclude -# @board bitcraze_crazyflie exclude -# - -. ${R}etc/init.d/rc.fw_defaults - - -param set-default BAT1_CAPACITY 2500 -param set-default BAT1_N_CELLS 3 - -param set-default SENS_BOARD_ROT 8 - -param set-default FW_AIRSPD_MAX 20 -param set-default FW_AIRSPD_MIN 7 -param set-default FW_AIRSPD_TRIM 13 -param set-default FW_THR_TRIM 0.8 - -param set-default FW_MAN_P_MAX 25 -param set-default FW_MAN_R_MAX 25 -param set-default FW_PR_I 0.02 -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 - - -param set-default CA_AIRFRAME 1 - -param set-default CA_ROTOR_COUNT 1 -param set-default CA_ROTOR0_PX 0.3 - -param set-default CA_SV_CS_COUNT 3 -param set-default CA_SV_CS0_TRQ_R 0 -param set-default CA_SV_CS0_TRQ_Y 1 -param set-default CA_SV_CS0_TYPE 4 -param set-default CA_SV_CS1_TRQ_P 0 -param set-default CA_SV_CS1_TRQ_R -0.5 -param set-default CA_SV_CS1_TYPE 1 -param set-default CA_SV_CS2_TRQ_P 1 -param set-default CA_SV_CS2_TYPE 3 - -param set-default PWM_MAIN_TIM0 50 -param set-default PWM_MAIN_TIM1 50 -param set-default PWM_MAIN_TIM2 50 diff --git a/ROMFS/px4fmu_common/init.d/airframes/17003_TF-G2 b/ROMFS/px4fmu_common/init.d/airframes/17003_TF-G2 deleted file mode 100644 index 4596edf8d703..000000000000 --- a/ROMFS/px4fmu_common/init.d/airframes/17003_TF-G2 +++ /dev/null @@ -1,59 +0,0 @@ -#!/bin/sh -# -# @name ThunderFly TF-G2 -# -# @type Autogyro -# @class Autogyro -# -# @output Motor1 throttle -# @output Servo1 rotor_head_L -# @output Servo2 rotor_head_R -# @output Servo3 rudder -# -# -# @url https://github.com/ThunderFly-aerospace/TF-G2/ -# @maintainer ThunderFly s.r.o., Roman Dvorak -# -# @board px4_fmu-v2 exclude -# @board bitcraze_crazyflie exclude -# - -. ${R}etc/init.d/rc.fw_defaults - - -param set-default BAT1_CAPACITY 3300 -param set-default BAT1_N_CELLS 3 - -param set-default SENS_BOARD_ROT 4 - -param set-default FW_AIRSPD_MAX 20 -param set-default FW_AIRSPD_MIN 7 -param set-default FW_AIRSPD_TRIM 13 -param set-default FW_THR_TRIM 0.8 - -param set-default FW_MAN_P_MAX 25 -param set-default FW_MAN_R_MAX 25 -param set-default FW_PR_I 0.02 -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 - -param set-default CA_AIRFRAME 1 - -param set-default CA_ROTOR_COUNT 1 -param set-default CA_ROTOR0_PX 0.3 - -param set-default CA_SV_CS_COUNT 3 -param set-default CA_SV_CS0_TRQ_R 0 -param set-default CA_SV_CS0_TRQ_Y 1 -param set-default CA_SV_CS0_TYPE 4 -param set-default CA_SV_CS1_TRQ_P 0 -param set-default CA_SV_CS1_TRQ_R -0.5 -param set-default CA_SV_CS1_TYPE 1 -param set-default CA_SV_CS2_TRQ_P 1 -param set-default CA_SV_CS2_TYPE 3 - -param set-default PWM_MAIN_TIM0 50 -param set-default PWM_MAIN_TIM1 50 -param set-default PWM_MAIN_TIM2 50 diff --git a/ROMFS/px4fmu_common/init.d/airframes/18001_TF-B1 b/ROMFS/px4fmu_common/init.d/airframes/18001_TF-B1 deleted file mode 100644 index 90965eeb32db..000000000000 --- a/ROMFS/px4fmu_common/init.d/airframes/18001_TF-B1 +++ /dev/null @@ -1,26 +0,0 @@ -#!/bin/sh -# -# @name ThunderFly balloon TF-B1 -# -# @type Balloon -# @class Balloon -# -# -# @url https://github.com/ThunderFly-aerospace/TF-B1/ -# @maintainer ThunderFly s.r.o. -# -# @board px4_fmu-v2 exclude -# @board bitcraze_crazyflie exclude -# - -. ${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 -param set-default SDLOG_MODE 2 -param set-default MAV_0_MODE 1 -param set-default MAV_0_CONFIG 102 -param set-default GPS_UBX_DYNMODEL 8 -param set-default SER_TEL2_BAUD 9600 - diff --git a/ROMFS/px4fmu_common/init.d/airframes/2507_cloudship b/ROMFS/px4fmu_common/init.d/airframes/2507_cloudship deleted file mode 100644 index a458d830ea65..000000000000 --- a/ROMFS/px4fmu_common/init.d/airframes/2507_cloudship +++ /dev/null @@ -1,41 +0,0 @@ -#!/bin/sh -# -# @name Cloudship -# @type Airship -# @class Airship -# -# @output Motor1 starboard thruster -# @output Motor2 port thruster -# @output Motor3 tail thruster -# @output Servo1 thrust tilt -# -# @board px4_fmu-v2 exclude -# @board bitcraze_crazyflie exclude -# - -. ${R}etc/init.d/rc.airship_defaults - -param set-default COM_PREARM_MODE 2 -param set-default CBRK_IO_SAFETY 22027 - -param set-default CA_AIRFRAME 9 - -param set-default CA_ROTOR_COUNT 3 -param set-default CA_ROTOR0_AX 1.0000 -param set-default CA_ROTOR0_AZ 0.0000 -param set-default CA_ROTOR0_KM 0.0000 -param set-default CA_ROTOR0_PY 2.0000 -param set-default CA_ROTOR1_AX 1.0000 -param set-default CA_ROTOR1_AZ 0.0000 -param set-default CA_ROTOR1_KM 0.0000 -param set-default CA_ROTOR1_PY -2.0000 -param set-default CA_ROTOR2_AY -1.0000 -param set-default CA_ROTOR2_AZ 0.0000 -param set-default CA_ROTOR2_KM 0.0000 -param set-default CA_ROTOR2_PX -10.0000 - -param set-default CA_SV_CS_COUNT 1 -param set-default CA_SV_CS0_TRQ_P 1.0000 - -param set-default CA_R_REV 7 - diff --git a/ROMFS/px4fmu_common/init.d/airframes/4071_ifo b/ROMFS/px4fmu_common/init.d/airframes/4071_ifo deleted file mode 100644 index 1f83f951fd59..000000000000 --- a/ROMFS/px4fmu_common/init.d/airframes/4071_ifo +++ /dev/null @@ -1,103 +0,0 @@ -#!/bin/sh -# -# @name UVify IFO -# -# @type Quadrotor x -# @class Copter -# -# @maintainer Hyon Lim -# -# @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 -# @board cuav_x7pro exclude -# - -. ${R}etc/init.d/rc.mc_defaults - -# 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 -param set-default MPC_MANTHR_MIN 0.08 - -# Filter settings -param set-default IMU_DGYRO_CUTOFF 90 -param set-default IMU_GYRO_CUTOFF 100 - -# System - -param set-default SENS_BOARD_ROT 10 - -# EKF2 -param set-default EKF2_GND_EFF_DZ 6 -param set-default EKF2_HGT_REF 1 - -# Position control -param set-default MPC_Z_P 1 -param set-default MPC_Z_VEL_P_ACC 4 -param set-default MPC_Z_VEL_I_ACC 0.4 - -param set-default MPC_THR_MIN 0.06 -param set-default MPC_THR_HOVER 0.3 - -param set-default MIS_TAKEOFF_ALT 1.1 -param set-default MPC_XY_P 1.7 -param set-default MPC_XY_VEL_P_ACC 2.6 -param set-default MPC_XY_VEL_I_ACC 1.2 -param set-default MPC_XY_VEL_D_ACC 0.2 -param set-default MPC_TKO_RAMP_T 1 -param set-default MPC_VEL_MANUAL 3 - -param set-default BAT1_SOURCE 0 -param set-default BAT1_N_CELLS 4 -param set-default BAT1_V_DIV 10.14 -param set-default BAT1_A_PER_V 18.18 -param set-default COM_DISARM_LAND 2 - -# Filter settings -param set-default IMU_GYRO_CUTOFF 90 -param set-default IMU_DGYRO_CUTOFF 70 - -# Don't try to be intelligent on RC loss: just cut the motors -param set-default NAV_RCL_ACT 6 - -# TELEM1 ttyS1 - Wifi module -param set-default MAV_0_CONFIG 101 -param set-default MAV_0_RATE 0 -# onboard -param set-default MAV_0_MODE 2 -param set-default SER_TEL1_BAUD 921600 - -# TELEM2 ttyS2 - Sub 1-Ghz -param set-default MAV_1_CONFIG 102 -# normal -param set-default MAV_1_MODE 0 -param set-default SER_TEL2_BAUD 57600 - - -param set-default CA_ROTOR_COUNT 4 -param set-default CA_ROTOR0_PX 0.15 -param set-default CA_ROTOR0_PY 0.15 -param set-default CA_ROTOR1_PX -0.15 -param set-default CA_ROTOR1_PY -0.15 -param set-default CA_ROTOR2_PX 0.15 -param set-default CA_ROTOR2_PY -0.15 -param set-default CA_ROTOR2_KM -0.05 -param set-default CA_ROTOR3_PX -0.15 -param set-default CA_ROTOR3_PY 0.15 -param set-default CA_ROTOR3_KM -0.05 - -param set-default PWM_MAIN_TIM0 0 - -param set-default PWM_MAIN_FUNC1 101 -param set-default PWM_MAIN_FUNC2 102 -param set-default PWM_MAIN_FUNC3 103 -param set-default PWM_MAIN_FUNC4 104 - diff --git a/ROMFS/px4fmu_common/init.d/airframes/4073_ifo-s b/ROMFS/px4fmu_common/init.d/airframes/4073_ifo-s deleted file mode 100644 index 945f5ef71551..000000000000 --- a/ROMFS/px4fmu_common/init.d/airframes/4073_ifo-s +++ /dev/null @@ -1,118 +0,0 @@ -#!/bin/sh -# -# @name UVify IFO -# -# @type Quadrotor x -# @class Copter -# -# @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 -# @board cuav_x7pro exclude -# -# @maintainer Hyon Lim -# - -. ${R}etc/init.d/rc.mc_defaults - -# Attitude & rate gains -param set-default MC_ROLLRATE_D 0.0013 - -param set-default MC_PITCHRATE_D 0.0016 - - -param set-default MPC_MANTHR_MIN 0.08 - -# Filter settings -param set-default IMU_GYRO_CUTOFF 100 - -# Sensors -param set-default SENS_BOARD_ROT 10 -# Yaw 180 -param set-default SENS_FLOW_ROT 4 -# TFMini on TELEM3 -param set-default SENS_TFMINI_CFG 103 - -# Smart Battery -param set-default SENS_EN_BATT 1 - -# EKF2 -param set-default EKF2_AID_MASK 3 -param set-default EKF2_GND_EFF_DZ 6 -param set-default EKF2_HGT_REF 1 -param set-default EKF2_MIN_RNG 0.3 - -# Flow -param set-default EKF2_OF_QMIN 70 - -# Position control -param set-default MPC_Z_P 1.1 -param set-default MPC_Z_VEL_P_ACC 6 -param set-default MPC_Z_VEL_I_ACC 1 - -param set-default MPC_THR_MIN 0.06 -param set-default MPC_THR_HOVER 0.44 - -param set-default MIS_TAKEOFF_ALT 1.1 -param set-default MPC_XY_P 1.7 -param set-default MPC_XY_VEL_P_ACC 2.6 -param set-default MPC_XY_VEL_I_ACC 1.2 -param set-default MPC_XY_VEL_D_ACC 0.2 -param set-default MPC_TKO_RAMP_T 1 -param set-default MPC_VEL_MANUAL 3 - -param set-default BAT1_SOURCE 0 -param set-default BAT1_N_CELLS 4 -param set-default BAT1_V_DIV 10.14 -param set-default BAT1_A_PER_V 18.18 -param set-default COM_DISARM_LAND 2 - -# Filter settings -param set-default IMU_GYRO_CUTOFF 90 - -# Don't try to be intelligent on RC loss: just cut the motors -param set-default NAV_RCL_ACT 6 - -# TELEM1 ttyS1 - Wifi module -param set-default MAV_0_CONFIG 101 -param set-default MAV_0_RATE 0 -# onboard -param set-default MAV_0_MODE 2 -param set-default SER_TEL1_BAUD 921600 - -# TELEM2 ttyS2 - Sub 1-Ghz -param set-default MAV_1_CONFIG 102 -# normal -param set-default MAV_1_MODE 0 -param set-default SER_TEL2_BAUD 57600 - -# EKF OF POSITION -param set-default EKF2_OF_POS_X 0.06 -param set-default EKF2_OF_POS_Y 0.03 -param set-default EKF2_OF_POS_Z -0.07 - -# Failsafe -param set-default COM_LOW_BAT_ACT 3 - -param set-default CA_ROTOR_COUNT 4 -param set-default CA_ROTOR0_PX 0.15 -param set-default CA_ROTOR0_PY 0.15 -param set-default CA_ROTOR1_PX -0.15 -param set-default CA_ROTOR1_PY -0.15 -param set-default CA_ROTOR2_PX 0.15 -param set-default CA_ROTOR2_PY -0.15 -param set-default CA_ROTOR2_KM -0.05 -param set-default CA_ROTOR3_PX -0.15 -param set-default CA_ROTOR3_PY 0.15 -param set-default CA_ROTOR3_KM -0.05 - -param set-default PWM_MAIN_TIM0 -3 - -param set-default PWM_MAIN_FUNC1 101 -param set-default PWM_MAIN_FUNC2 102 -param set-default PWM_MAIN_FUNC3 103 -param set-default PWM_MAIN_FUNC4 104 - diff --git a/ROMFS/px4fmu_common/init.d/airframes/4420_ssrc_arwing b/ROMFS/px4fmu_common/init.d/airframes/4420_ssrc_arwing new file mode 100644 index 000000000000..7158e334e675 --- /dev/null +++ b/ROMFS/px4fmu_common/init.d/airframes/4420_ssrc_arwing @@ -0,0 +1,65 @@ +#!/bin/sh +# +# @name SSRC ARWing +# +# @type Flying Wing +# @class Plane +# +# @board px4_fmu-v2 exclude +# @board bitcraze_crazyflie exclude +# + +. /etc/init.d/rc.fw_defaults + +# Control allocator parameters +param set-default CA_AIRFRAME 1 +param set-default CA_ROTOR_COUNT 1 +param set-default CA_SV_CS_COUNT 2 +param set-default CA_SV_CS0_TYPE 5 +param set-default CA_SV_CS0_TRQ_P 0.5 +param set-default CA_SV_CS0_TRQ_R -0.5 +param set-default CA_SV_CS1_TYPE 6 +param set-default CA_SV_CS1_TRQ_P 0.5 +param set-default CA_SV_CS1_TRQ_R 0.5 + +# PWM +param set-default PWM_MAIN_FUNC1 201 +param set-default PWM_MAIN_FUNC2 202 +param set-default PWM_MAIN_FUNC4 101 +param set-default PWM_AUX_FUNC1 201 +param set-default PWM_AUX_FUNC2 202 +param set-default PWM_AUX_FUNC4 101 + +# Airspeed parameters +sdp3x start -X -f 400 +param set-default ASPD_DO_CHECKS 15 +param set-default FW_AIRSPD_MAX 22.0 +param set-default FW_AIRSPD_MIN 14.0 +param set-default FW_AIRSPD_STALL 12.0 +param set-default FW_AIRSPD_TRIM 18.0 + +# Battery parameters +param set-default BAT1_N_CELLS 4 +param set-default BAT1_R_INTERNAL 0.0050 +param set-default BAT1_V_EMPTY 3.6000 +param set-default BAT1_V_LOAD_DROP 0.1000 + +param set-default BAT2_R_INTERNAL 0.0050 +param set-default BAT2_V_EMPTY 3.6000 +param set-default BAT2_V_LOAD_DROP 0.1000 + +# Disable internal magnetometer +param set CAL_MAG0_PRIO 0 + +# Launch detection +param set-default FW_LAUN_DETCN_ON 1 + +# Maximum manual roll angle +param set-default FW_MAN_R_MAX 60.0 + +# Rate control +param set-default FW_RR_IMAX 0.4000 +param set-default FW_YR_IMAX 0.4000 + +# Misc +param set-default RTL_RETURN_ALT 30.0 diff --git a/ROMFS/px4fmu_common/init.d/airframes/4430_ssrc_strivermini b/ROMFS/px4fmu_common/init.d/airframes/4430_ssrc_strivermini new file mode 100644 index 000000000000..01877128d7b1 --- /dev/null +++ b/ROMFS/px4fmu_common/init.d/airframes/4430_ssrc_strivermini @@ -0,0 +1,126 @@ +#!/bin/sh +# +# @name SSRC Striver Mini +# +# @type Standard VTOL +# @class VTOL +# +# @maintainer +# +# @output MAIN1 motor 1 +# @output MAIN2 motor 2 +# @output MAIN3 motor 3 +# @output MAIN4 motor 4 +# @output AUX1 Aileron 1 +# @output AUX2 Aileron 2 +# @output AUX3 Elevator 1 +# @output AUX4 Elevator 2 +# @output AUX5 Rudder +# @output AUX6 Throttle +# +# @board px4_fmu-v2 exclude +# @board bitcraze_crazyflie exclude +# @board holybro_kakutef7 exclude +# + +. ${R}etc/init.d/rc.vtol_defaults + +# Control allocator parameters +param set-default CA_AIRFRAME 2 +param set-default CA_ROTOR_COUNT 5 +param set-default CA_ROTOR0_PX 0.37 +param set-default CA_ROTOR0_PY 0.42 +param set-default CA_ROTOR1_PX -0.41 +param set-default CA_ROTOR1_PY -0.42 +param set-default CA_ROTOR2_PX 0.37 +param set-default CA_ROTOR2_PY -0.42 +param set-default CA_ROTOR2_KM -0.05 +param set-default CA_ROTOR3_PX -0.41 +param set-default CA_ROTOR3_PY 0.42 +param set-default CA_ROTOR3_KM -0.05 +param set-default CA_ROTOR4_AX 1.0 +param set-default CA_ROTOR4_AZ 0.0 +param set-default CA_SV_CS_COUNT 5 +param set-default CA_SV_CS0_TYPE 1 +param set-default CA_SV_CS0_TRQ_R -0.5 +param set-default CA_SV_CS1_TYPE 2 +param set-default CA_SV_CS1_TRQ_R -0.5 +param set-default CA_SV_CS2_TYPE 3 +param set-default CA_SV_CS2_TRQ_P 1.0 +param set-default CA_SV_CS3_TYPE 3 +param set-default CA_SV_CS3_TRQ_P -1.0 +param set-default CA_SV_CS4_TYPE 4 +param set-default CA_SV_CS4_TRQ_Y 1.0 + +# PWM functions +param set-default PWM_MAIN_FUNC1 101 +param set-default PWM_MAIN_FUNC2 102 +param set-default PWM_MAIN_FUNC3 103 +param set-default PWM_MAIN_FUNC4 104 +param set-default PWM_MAIN_FUNC5 201 +param set-default PWM_MAIN_FUNC6 202 +param set-default PWM_MAIN_FUNC7 203 +param set-default PWM_MAIN_FUNC8 204 +param set-default PWM_MAIN_FUNC9 205 +param set-default PWM_MAIN_FUNC10 105 +param set-default PWM_AUX_FUNC1 201 +param set-default PWM_AUX_FUNC2 202 +param set-default PWM_AUX_FUNC3 203 +param set-default PWM_AUX_FUNC4 204 +param set-default PWM_AUX_FUNC5 205 +param set-default PWM_AUX_FUNC6 105 + +# Start airspeed sensor driver +ms4525do start -X -f 500 + +# Airspeed parameters +param set-default ASPD_DO_CHECKS 15 +param set-default FW_AIRSPD_MAX 22.0 +param set-default FW_AIRSPD_MIN 15.0 +param set-default FW_AIRSPD_STALL 12.0 +param set-default FW_AIRSPD_TRIM 18.0 + +# Battery parameters +param set-default BAT1_N_CELLS 4 +param set-default BAT1_V_CHARGED 4.2 +param set-default BAT1_V_EMPTY 3.6 +param set-default BAT1_V_DIV 18.1 + +# Disable internal magnetometer +param set CAL_MAG0_PRIO 0 + +# Return mode return altitude +param set-default RTL_RETURN_ALT 30.0 + +# Fixed wing specific +param set-default FW_MAN_R_MAX 60.0 +param set-default FW_RR_IMAX 0.4000 +param set-default FW_YR_IMAX 0.4000 + +# VTOL specific +# VTOL type +param set-default VT_TYPE 2 + +# Airspeed at which we can start blending both fw and mc controls. +param set-default VT_ARSP_BLEND 10 + +# Airspeed at which we can switch to fw mode +param set-default VT_ARSP_TRANS 12 + +# Back-transition duration +param set-default VT_B_TRANS_DUR 4 +param set-default VT_B_TRANS_RAMP 3 + +# Transition duration +param set-default VT_F_TRANS_DUR 6 +param set-default VT_F_TRANS_THR 1 + +# VTOL takeoff +param set-default VTO_LOITER_ALT 20 + +# QuadChute altitude (transition to quad mode as a failsafe) +param set-default VT_FW_MIN_ALT 5 + +# QuadChute angle limits +param set-default VT_FW_QC_P 35 +param set-default VT_FW_QC_R 60 diff --git a/ROMFS/px4fmu_common/init.d/airframes/60001_uuv_hippocampus b/ROMFS/px4fmu_common/init.d/airframes/60001_uuv_hippocampus deleted file mode 100644 index 611701fc6779..000000000000 --- a/ROMFS/px4fmu_common/init.d/airframes/60001_uuv_hippocampus +++ /dev/null @@ -1,54 +0,0 @@ -#!/bin/sh -# -# @name HippoCampus UUV (Unmanned Underwater Vehicle) -# -# @type Underwater Robot -# @class Underwater Robot -# -# @maintainer Daniel Duecker -# -# @board px4_fmu-v2 exclude -# @board bitcraze_crazyflie exclude -# - -. ${R}etc/init.d/rc.uuv_defaults - -# disable circuit breaker for airspeed sensor -param set-default CBRK_AIRSPD_CHK 162128 - -param set-default CA_AIRFRAME 7 -param set-default CA_ROTOR_COUNT 4 -param set-default CA_R_REV 255 -param set-default CA_ROTOR0_AX 1 -param set-default CA_ROTOR0_AY 0 -param set-default CA_ROTOR0_AZ 0 -param set-default CA_ROTOR0_KM 0 -param set-default CA_ROTOR0_PX 0 -param set-default CA_ROTOR0_PY -0.3 -param set-default CA_ROTOR0_PZ -0.3 -param set-default CA_ROTOR1_AX 1 -param set-default CA_ROTOR1_AY 0 -param set-default CA_ROTOR1_AZ 0 -param set-default CA_ROTOR1_KM 0 -param set-default CA_ROTOR1_PX 0 -param set-default CA_ROTOR1_PY 0.3 -param set-default CA_ROTOR1_PZ -0.3 -param set-default CA_ROTOR2_AX 1 -param set-default CA_ROTOR2_AY 0 -param set-default CA_ROTOR2_AZ 0 -param set-default CA_ROTOR2_KM 0 -param set-default CA_ROTOR2_PX 0 -param set-default CA_ROTOR2_PY 0.3 -param set-default CA_ROTOR2_PZ 0.3 -param set-default CA_ROTOR3_AX 1 -param set-default CA_ROTOR3_AY 0 -param set-default CA_ROTOR3_AZ 0 -param set-default CA_ROTOR3_KM 0 -param set-default CA_ROTOR3_PX 0 -param set-default CA_ROTOR3_PY -0.3 -param set-default CA_ROTOR3_PZ 0.3 - -param set-default PWM_MAIN_FUNC1 101 -param set-default PWM_MAIN_FUNC2 102 -param set-default PWM_MAIN_FUNC3 103 -param set-default PWM_MAIN_FUNC4 104 diff --git a/ROMFS/px4fmu_common/init.d/airframes/60002_uuv_bluerov2_heavy b/ROMFS/px4fmu_common/init.d/airframes/60002_uuv_bluerov2_heavy deleted file mode 100644 index 6124d105d5f1..000000000000 --- a/ROMFS/px4fmu_common/init.d/airframes/60002_uuv_bluerov2_heavy +++ /dev/null @@ -1,97 +0,0 @@ -#!/bin/sh -# -# @name BlueROV2 (Heavy Configuration) -# -# @type Vectored 6 DOF UUV -# @class Underwater Robot -# -# @output Motor1 motor 1 CCW, bow starboard horizontal, , propeller CCW -# @output Motor2 motor 2 CCW, bow port horizontal, propeller CCW -# @output Motor3 motor 3 CCW, stern starboard horizontal, propeller CW -# @output Motor4 motor 4 CCW, stern port horizontal, propeller CW -# @output Motor5 motor 5 CCW, bow starboard vertical, propeller CCW -# @output Motor6 motor 6 CCW, bow port vertical, propeller CW -# @output Motor7 motor 7 CCW, stern starboard vertical, propeller CW -# @output Motor8 motor 8 CCW, stern port vertical, propeller CCW -# -# @maintainer Thies Lennart Alff -# -# @board px4_fmu-v2 exclude -# @board bitcraze_crazyflie exclude -# - -. ${R}etc/init.d/rc.uuv_defaults - - -# disable circuit breaker for airspeed sensor -param set-default CBRK_AIRSPD_CHK 162128 -# companion computer is connected via USB permanently -param set-default CBRK_USB_CHK 197848 -param set-default CBRK_IO_SAFETY 22027 - -param set-default COM_PREARM_MODE 0 - -param set-default MAV_1_CONFIG 102 - -param set-default BAT1_A_PER_V 37.8798 -param set-default BAT1_CAPACITY 18000 -param set-default BAT1_V_DIV 11.0 -param set-default BAT1_N_CELLS 4 -param set-default BAT_V_OFFS_CURR 0.33 - -param set-default CA_AIRFRAME 7 - -param set-default CA_ROTOR_COUNT 8 -param set-default CA_R_REV 255 -param set-default CA_ROTOR0_AX 1.0000 -param set-default CA_ROTOR0_AY -1.0000 -param set-default CA_ROTOR0_AZ 0.0000 -param set-default CA_ROTOR0_KM 0.0000 -param set-default CA_ROTOR0_PX 0.5000 -param set-default CA_ROTOR0_PY 0.3000 -param set-default CA_ROTOR0_PZ 0.2000 -param set-default CA_ROTOR1_AX 1.0000 -param set-default CA_ROTOR1_AY 1.0000 -param set-default CA_ROTOR1_AZ 0.0000 -param set-default CA_ROTOR1_KM 0.0000 -param set-default CA_ROTOR1_PX 0.5000 -param set-default CA_ROTOR1_PY -0.3000 -param set-default CA_ROTOR1_PZ 0.2000 -param set-default CA_ROTOR2_AX 1.0000 -param set-default CA_ROTOR2_AY 1.0000 -param set-default CA_ROTOR2_AZ 0.0000 -param set-default CA_ROTOR2_KM 0.0000 -param set-default CA_ROTOR2_PX -0.5000 -param set-default CA_ROTOR2_PY 0.3000 -param set-default CA_ROTOR2_PZ 0.2000 -param set-default CA_ROTOR3_AX 1.0000 -param set-default CA_ROTOR3_AY -1.0000 -param set-default CA_ROTOR3_AZ 0.0000 -param set-default CA_ROTOR3_KM 0.0000 -param set-default CA_ROTOR3_PX -0.5000 -param set-default CA_ROTOR3_PY -0.3000 -param set-default CA_ROTOR3_PZ 0.2000 -param set-default CA_ROTOR4_AZ -1.0000 -param set-default CA_ROTOR4_KM 0.0000 -param set-default CA_ROTOR4_PX 0.5000 -param set-default CA_ROTOR4_PY 0.5000 -param set-default CA_ROTOR5_AZ 1.0000 -param set-default CA_ROTOR5_KM 0.0000 -param set-default CA_ROTOR5_PX 0.5000 -param set-default CA_ROTOR5_PY -0.5000 -param set-default CA_ROTOR6_AZ 1.0000 -param set-default CA_ROTOR6_KM 0.0000 -param set-default CA_ROTOR6_PX -0.5000 -param set-default CA_ROTOR6_PY 0.5000 -param set-default CA_ROTOR7_KM 0.0000 -param set-default CA_ROTOR7_PX -0.5000 -param set-default CA_ROTOR7_PY -0.5000 - -param set-default PWM_MAIN_FUNC1 101 -param set-default PWM_MAIN_FUNC2 102 -param set-default PWM_MAIN_FUNC3 103 -param set-default PWM_MAIN_FUNC4 104 -param set-default PWM_MAIN_FUNC5 105 -param set-default PWM_MAIN_FUNC6 106 -param set-default PWM_MAIN_FUNC7 107 -param set-default PWM_MAIN_FUNC8 108 diff --git a/ROMFS/px4fmu_common/init.d/airframes/CMakeLists.txt b/ROMFS/px4fmu_common/init.d/airframes/CMakeLists.txt index dcdb5c6e566b..cbdc381d6b2e 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/CMakeLists.txt +++ b/ROMFS/px4fmu_common/init.d/airframes/CMakeLists.txt @@ -45,8 +45,6 @@ px4_add_romfs_files( 2100_standard_plane 2106_albatross - 2507_cloudship - # [3000, 3999] Flying wing" 3000_generic_wing @@ -64,10 +62,10 @@ px4_add_romfs_files( 4052_holybro_qav250 4053_holybro_kopis2 4061_atl_mantis_edu - 4071_ifo - 4073_ifo-s 4400_ssrc_fog_x 4401_ssrc_fog_x_tmotor + 4420_ssrc_arwing + 4430_ssrc_strivermini 4500_clover4 4900_crazyflie 4901_crazyflie21 @@ -107,13 +105,6 @@ px4_add_romfs_files( 16001_helicopter - # [17000, 17999] Autogyro - 17002_TF-AutoG2 - 17003_TF-G2 - - # [18000, 18999] High-altitude balloons - 18001_TF-B1 - # [22000, 22999] Reserve for custom models 24001_dodeca_cox @@ -126,6 +117,5 @@ px4_add_romfs_files( # [60000, 61000] (Unmanned) Underwater Robots 60000_uuv_generic - 60001_uuv_hippocampus - 60002_uuv_bluerov2_heavy ) +