From cbde9729e85bf6ddec15bb318eced79e21264ca7 Mon Sep 17 00:00:00 2001 From: Matthias Grob Date: Wed, 11 Dec 2024 19:44:31 +0100 Subject: [PATCH] Airframes: remove unnecessary double newlines --- ROMFS/px4fmu_common/init.d/airframes/1101_rc_plane_sih.hil | 1 - ROMFS/px4fmu_common/init.d/airframes/12001_octo_cox | 1 - ROMFS/px4fmu_common/init.d/airframes/16001_helicopter | 1 - ROMFS/px4fmu_common/init.d/airframes/17002_TF-AutoG2 | 2 -- ROMFS/px4fmu_common/init.d/airframes/17003_TF-G2 | 1 - ROMFS/px4fmu_common/init.d/airframes/24001_dodeca_cox | 1 - ROMFS/px4fmu_common/init.d/airframes/4050_generic_250 | 1 - ROMFS/px4fmu_common/init.d/airframes/4061_atl_mantis_edu | 5 ----- ROMFS/px4fmu_common/init.d/airframes/4071_ifo | 1 - ROMFS/px4fmu_common/init.d/airframes/4901_crazyflie21 | 2 -- .../init.d/airframes/50001_aion_robotics_r1_rover | 1 - .../init.d/airframes/59000_generic_ground_vehicle | 1 - .../px4fmu_common/init.d/airframes/60002_uuv_bluerov2_heavy | 1 - 13 files changed, 19 deletions(-) diff --git a/ROMFS/px4fmu_common/init.d/airframes/1101_rc_plane_sih.hil b/ROMFS/px4fmu_common/init.d/airframes/1101_rc_plane_sih.hil index e124e9981a..2bcfc14a2e 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/1101_rc_plane_sih.hil +++ b/ROMFS/px4fmu_common/init.d/airframes/1101_rc_plane_sih.hil @@ -12,7 +12,6 @@ . ${R}etc/init.d/rc.fw_defaults - param set UAVCAN_ENABLE 0 param set-default CA_AIRFRAME 1 diff --git a/ROMFS/px4fmu_common/init.d/airframes/12001_octo_cox b/ROMFS/px4fmu_common/init.d/airframes/12001_octo_cox index 1dba92b89d..d72eaa2132 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/12001_octo_cox +++ b/ROMFS/px4fmu_common/init.d/airframes/12001_octo_cox @@ -21,7 +21,6 @@ . ${R}etc/init.d/rc.mc_defaults - param set-default MAV_TYPE 14 param set-default CA_ROTOR_COUNT 8 diff --git a/ROMFS/px4fmu_common/init.d/airframes/16001_helicopter b/ROMFS/px4fmu_common/init.d/airframes/16001_helicopter index de21a88216..695604e0b1 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/16001_helicopter +++ b/ROMFS/px4fmu_common/init.d/airframes/16001_helicopter @@ -11,7 +11,6 @@ . ${R}etc/init.d/rc.heli_defaults - # Disable PID gains for initial setup. These should be enabled after setting the FF gain. # P is expected to be lower than FF. param set-default MC_ROLLRATE_P 0 diff --git a/ROMFS/px4fmu_common/init.d/airframes/17002_TF-AutoG2 b/ROMFS/px4fmu_common/init.d/airframes/17002_TF-AutoG2 index 0ed3b201c8..7f85a770e1 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/17002_TF-AutoG2 +++ b/ROMFS/px4fmu_common/init.d/airframes/17002_TF-AutoG2 @@ -22,7 +22,6 @@ . ${R}etc/init.d/rc.fw_defaults - param set-default BAT1_CAPACITY 2500 param set-default BAT1_N_CELLS 3 @@ -41,7 +40,6 @@ 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 diff --git a/ROMFS/px4fmu_common/init.d/airframes/17003_TF-G2 b/ROMFS/px4fmu_common/init.d/airframes/17003_TF-G2 index 0fced30c8e..1907b33a32 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/17003_TF-G2 +++ b/ROMFS/px4fmu_common/init.d/airframes/17003_TF-G2 @@ -20,7 +20,6 @@ . ${R}etc/init.d/rc.fw_defaults - param set-default BAT1_CAPACITY 3300 param set-default BAT1_N_CELLS 3 diff --git a/ROMFS/px4fmu_common/init.d/airframes/24001_dodeca_cox b/ROMFS/px4fmu_common/init.d/airframes/24001_dodeca_cox index f894d47d74..6f75f86198 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/24001_dodeca_cox +++ b/ROMFS/px4fmu_common/init.d/airframes/24001_dodeca_cox @@ -19,7 +19,6 @@ param set-default NAV_ACC_RAD 2 param set-default RTL_DESCEND_ALT 10 param set-default RTL_RETURN_ALT 30 - param set-default CA_ROTOR_COUNT 12 # Bottom motors param set-default CA_ROTOR0_PX 0 diff --git a/ROMFS/px4fmu_common/init.d/airframes/4050_generic_250 b/ROMFS/px4fmu_common/init.d/airframes/4050_generic_250 index d460138cc8..129eacbffd 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/4050_generic_250 +++ b/ROMFS/px4fmu_common/init.d/airframes/4050_generic_250 @@ -21,7 +21,6 @@ param set-default MC_PITCHRATE_P 0.08 param set-default MC_PITCHRATE_D 0.001 param set-default MC_YAW_P 4 - param set-default MC_ROLLRATE_MAX 1600 param set-default MC_PITCHRATE_MAX 1600 param set-default MC_YAWRATE_MAX 1000 diff --git a/ROMFS/px4fmu_common/init.d/airframes/4061_atl_mantis_edu b/ROMFS/px4fmu_common/init.d/airframes/4061_atl_mantis_edu index e5e5e08343..fe40b95aa0 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/4061_atl_mantis_edu +++ b/ROMFS/px4fmu_common/init.d/airframes/4061_atl_mantis_edu @@ -38,7 +38,6 @@ param set-default COM_FLTMODE5 -1 param set-default COM_FLTMODE6 1 param set-default COM_RC_LOSS_T 3 - # ekf2 param set-default EKF2_BARO_NOISE 2 @@ -79,19 +78,16 @@ param set-default EKF2_RNG_POS_Z 0.033 param set-default EKF2_TERR_NOISE 1 - # Maximum allowed angle velocity in the landed state param set-default LNDMC_ROT_MAX 40 # Maximum vertical velocity allowed in the landed state param set-default LNDMC_Z_VEL_MAX 0.7 - # filtering param set-default IMU_DGYRO_CUTOFF 50 param set-default IMU_GYRO_CUTOFF 65 - # Pitch angle & rate setting param set-default MC_PITCHRATE_P 0.075 param set-default MC_PITCHRATE_I 0.1 @@ -148,7 +144,6 @@ param set-default RC_MAP_RETURN_SW 7 param set-default RC1_TRIM 1000 - # optical flow param set-default SENS_FLOW_MAXR 7.4 param set-default SENS_FLOW_MINHGT 0.15 diff --git a/ROMFS/px4fmu_common/init.d/airframes/4071_ifo b/ROMFS/px4fmu_common/init.d/airframes/4071_ifo index 8cfc14ae1e..141ca861c4 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/4071_ifo +++ b/ROMFS/px4fmu_common/init.d/airframes/4071_ifo @@ -30,7 +30,6 @@ param set-default IMU_DGYRO_CUTOFF 90 param set-default IMU_GYRO_CUTOFF 100 # System - param set-default SENS_BOARD_ROT 10 # EKF2 diff --git a/ROMFS/px4fmu_common/init.d/airframes/4901_crazyflie21 b/ROMFS/px4fmu_common/init.d/airframes/4901_crazyflie21 index 4833d17af2..85b045e84a 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/4901_crazyflie21 +++ b/ROMFS/px4fmu_common/init.d/airframes/4901_crazyflie21 @@ -18,7 +18,6 @@ # . ${R}etc/init.d/rc.mc_defaults - param set-default SYS_HAS_MAG 0 param set-default EKF2_OF_CTRL 1 param set-default EKF2_GPS_CTRL 0 @@ -85,6 +84,5 @@ param set-default PWM_MAIN_MAX3 255 param set-default SENS_FLOW_MINRNG 0.05 - syslink start mavlink start -d /dev/bridge0 -b 57600 -m osd -r 40000 diff --git a/ROMFS/px4fmu_common/init.d/airframes/50001_aion_robotics_r1_rover b/ROMFS/px4fmu_common/init.d/airframes/50001_aion_robotics_r1_rover index 7cdf2d10a6..57a3644dae 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/50001_aion_robotics_r1_rover +++ b/ROMFS/px4fmu_common/init.d/airframes/50001_aion_robotics_r1_rover @@ -40,7 +40,6 @@ param set-default RD_YAW_I 0.1 param set-default RD_YAW_RATE_P 0.1 param set-default RD_YAW_RATE_I 0.01 - # Pure pursuit parameters param set-default PP_LOOKAHD_MAX 10 param set-default PP_LOOKAHD_MIN 1 diff --git a/ROMFS/px4fmu_common/init.d/airframes/59000_generic_ground_vehicle b/ROMFS/px4fmu_common/init.d/airframes/59000_generic_ground_vehicle index a773c1158d..078ea7859d 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/59000_generic_ground_vehicle +++ b/ROMFS/px4fmu_common/init.d/airframes/59000_generic_ground_vehicle @@ -15,7 +15,6 @@ . ${R}etc/init.d/rc.rover_defaults - param set-default BAT1_N_CELLS 2 param set-default EKF2_ANGERR_INIT 0.01 diff --git a/ROMFS/px4fmu_common/init.d/airframes/60002_uuv_bluerov2_heavy b/ROMFS/px4fmu_common/init.d/airframes/60002_uuv_bluerov2_heavy index 06a2d3fb2f..1449a6d3ad 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/60002_uuv_bluerov2_heavy +++ b/ROMFS/px4fmu_common/init.d/airframes/60002_uuv_bluerov2_heavy @@ -22,7 +22,6 @@ . ${R}etc/init.d/rc.uuv_defaults - param set-default MAV_1_CONFIG 102 param set-default BAT1_A_PER_V 37.8798