From 9386ab6afedc811bdb30b0d5790688b1a1e8082f Mon Sep 17 00:00:00 2001 From: mcsauder Date: Wed, 4 Jul 2018 18:46:13 -0600 Subject: [PATCH] Breakout rc.thermal_cal from rcS and group set/unset parameters at the beginning and end of the rcS script. Revert commit 2a3d66cf457e9b7879276bd01be7936876b56147 to reduce px4fmu-v2_default flash size. Standardize tabs/whitespaces across all files in the init.d directory. --- .../init.d/13003_quad_tailsitter | 8 +- .../init.d/13004_quad+_tailsitter | 8 +- .../init.d/13009_vtol_spt_ranger | 112 ++++----- ROMFS/px4fmu_common/init.d/13012_convergence | 96 ++++---- ROMFS/px4fmu_common/init.d/14001_tri_y_yaw+ | 1 - ROMFS/px4fmu_common/init.d/2105_maja | 26 +-- ROMFS/px4fmu_common/init.d/2106_albatross | 26 +-- ROMFS/px4fmu_common/init.d/3035_viper | 1 - .../init.d/3037_parrot_disco_mod | 16 +- ROMFS/px4fmu_common/init.d/4002_quad_x_mount | 1 - ROMFS/px4fmu_common/init.d/4013_bebop | 28 +-- ROMFS/px4fmu_common/init.d/4030_3dr_solo | 122 +++++----- ROMFS/px4fmu_common/init.d/4040_reaper | 30 +-- ROMFS/px4fmu_common/init.d/4900_crazyflie | 80 +++---- ROMFS/px4fmu_common/init.d/CMakeLists.txt | 1 + ROMFS/px4fmu_common/init.d/rc.thermal_cal | 40 ++++ ROMFS/px4fmu_common/init.d/rcS | 213 +++++++++--------- cmake/configs/nuttx_px4fmu-v2_default.cmake | 2 +- 18 files changed, 426 insertions(+), 385 deletions(-) create mode 100644 ROMFS/px4fmu_common/init.d/rc.thermal_cal diff --git a/ROMFS/px4fmu_common/init.d/13003_quad_tailsitter b/ROMFS/px4fmu_common/init.d/13003_quad_tailsitter index ae820f6224..a96cb3ff73 100644 --- a/ROMFS/px4fmu_common/init.d/13003_quad_tailsitter +++ b/ROMFS/px4fmu_common/init.d/13003_quad_tailsitter @@ -12,10 +12,10 @@ sh /etc/init.d/rc.vtol_defaults if [ $AUTOCNF == yes ] then - param set VT_MOT_COUNT 4 - param set VT_IDLE_PWM_MC 1080 - param set VT_TYPE 0 - param set VT_ELEV_MC_LOCK 1 + param set VT_MOT_COUNT 4 + param set VT_IDLE_PWM_MC 1080 + param set VT_TYPE 0 + param set VT_ELEV_MC_LOCK 1 fi set MIXER quad_x_vtol diff --git a/ROMFS/px4fmu_common/init.d/13004_quad+_tailsitter b/ROMFS/px4fmu_common/init.d/13004_quad+_tailsitter index fa78638b52..26f2a42a07 100644 --- a/ROMFS/px4fmu_common/init.d/13004_quad+_tailsitter +++ b/ROMFS/px4fmu_common/init.d/13004_quad+_tailsitter @@ -23,10 +23,10 @@ sh /etc/init.d/rc.vtol_defaults if [ $AUTOCNF == yes ] then - param set VT_MOT_COUNT 4 - param set VT_IDLE_PWM_MC 1080 - param set VT_TYPE 0 - param set VT_ELEV_MC_LOCK 1 + param set VT_MOT_COUNT 4 + param set VT_IDLE_PWM_MC 1080 + param set VT_TYPE 0 + param set VT_ELEV_MC_LOCK 1 fi set MIXER quad_+_vtol diff --git a/ROMFS/px4fmu_common/init.d/13009_vtol_spt_ranger b/ROMFS/px4fmu_common/init.d/13009_vtol_spt_ranger index ee8e73b917..7dc69193eb 100644 --- a/ROMFS/px4fmu_common/init.d/13009_vtol_spt_ranger +++ b/ROMFS/px4fmu_common/init.d/13009_vtol_spt_ranger @@ -12,68 +12,68 @@ sh /etc/init.d/rc.vtol_defaults if [ $AUTOCNF == yes ] then - param set VT_TYPE 2 - param set VT_MOT_COUNT 4 - param set VT_IDLE_PWM_MC 1180 - param set MAV_TYPE 22 - param set VT_ARSP_TRANS 15.0 - param set VT_B_TRANS_DUR 4.0 - param set VT_TRANS_MIN_TM 5.0 - param set VT_F_TRANS_THR 0.6 - param set VT_TRANS_TIMEOUT 30.0 + param set VT_TYPE 2 + param set VT_MOT_COUNT 4 + param set VT_IDLE_PWM_MC 1180 + param set MAV_TYPE 22 + param set VT_ARSP_TRANS 15.0 + param set VT_B_TRANS_DUR 4.0 + param set VT_TRANS_MIN_TM 5.0 + param set VT_F_TRANS_THR 0.6 + param set VT_TRANS_TIMEOUT 30.0 - param set FW_AIRSPD_MAX 22.0 - param set FW_AIRSPD_MIN 14.0 - param set FW_AIRSPD_TRIM 16.0 - param set FW_L1_PERIOD 25.0 - param set FW_PR_P 0.060 - param set FW_P_RMAX_NEG 40.0 - param set FW_P_RMAX_POS 40.0 - param set FW_RR_FF 0.4 - param set FW_RR_P 0.04 - param set FW_R_RMAX 40.0 + param set FW_AIRSPD_MAX 22.0 + param set FW_AIRSPD_MIN 14.0 + param set FW_AIRSPD_TRIM 16.0 + param set FW_L1_PERIOD 25.0 + param set FW_PR_P 0.060 + param set FW_P_RMAX_NEG 40.0 + param set FW_P_RMAX_POS 40.0 + param set FW_RR_FF 0.4 + param set FW_RR_P 0.04 + param set FW_R_RMAX 40.0 - param set MC_PITCHRATE_D 0.004 - param set MC_PITCHRATE_I 0.0 - param set MC_PITCHRATE_MAX 60.0 - param set MC_PITCHRATE_P 0.21 - param set MC_PITCH_P 4.0 - param set MC_ROLLRATE_D 0.004 - param set MC_ROLLRATE_I 0.002 - param set MC_ROLLRATE_MAX 60.0 - param set MC_ROLLRATE_P 0.24 - param set MC_ROLL_P 4.0 - param set MC_YAWRATE_I 0.02 - param set MC_YAWRATE_MAX 40.0 - param set MC_YAWRATE_P 0.18 - param set MC_YAWRATE_MAX 40.0 - param set MC_YAWRAUTO_MAX 40.0 + param set MC_PITCHRATE_D 0.004 + param set MC_PITCHRATE_I 0.0 + param set MC_PITCHRATE_MAX 60.0 + param set MC_PITCHRATE_P 0.21 + param set MC_PITCH_P 4.0 + param set MC_ROLLRATE_D 0.004 + param set MC_ROLLRATE_I 0.002 + param set MC_ROLLRATE_MAX 60.0 + param set MC_ROLLRATE_P 0.24 + param set MC_ROLL_P 4.0 + param set MC_YAWRATE_I 0.02 + param set MC_YAWRATE_MAX 40.0 + param set MC_YAWRATE_P 0.18 + param set MC_YAWRATE_MAX 40.0 + param set MC_YAWRAUTO_MAX 40.0 - param set MIS_TAKEOFF_ALT 2.5 - param set MIS_YAW_TMT 20.0 + param set MIS_TAKEOFF_ALT 2.5 + param set MIS_YAW_TMT 20.0 - param set MPC_ACC_HOR_MAX 1.0 - param set MPC_HOLD_MAX_XY 0.5 - param set MPC_HOLD_MAX_Z 0.5 - param set MPC_LAND_SPEED 1.0 - param set MPC_MANTHR_MIN 0.05 - param set MPC_MAN_Y_MAX 120.0 - param set MPC_THR_MIN 0.07 - param set MPC_TILTMAX_AIR 35.0 - param set MPC_TILTMAX_LND 20.0 - param set MPC_TKO_SPEED 1.0 - param set MPC_XY_P 0.3 - param set MPC_XY_VEL_MAX 3.0 - param set MPC_XY_VEL_P 0.05 - param set MPC_Z_P 0.5 - param set MPC_Z_VEL_P 0.1 + param set MPC_ACC_HOR_MAX 1.0 + param set MPC_HOLD_MAX_XY 0.5 + param set MPC_HOLD_MAX_Z 0.5 + param set MPC_LAND_SPEED 1.0 + param set MPC_MANTHR_MIN 0.05 + param set MPC_MAN_Y_MAX 120.0 + param set MPC_THR_MIN 0.07 + param set MPC_TILTMAX_AIR 35.0 + param set MPC_TILTMAX_LND 20.0 + param set MPC_TKO_SPEED 1.0 + param set MPC_XY_P 0.3 + param set MPC_XY_VEL_MAX 3.0 + param set MPC_XY_VEL_P 0.05 + param set MPC_Z_P 0.5 + param set MPC_Z_VEL_P 0.1 - param set NAV_ACC_RAD 3.0 + param set NAV_ACC_RAD 3.0 - param set PWM_AUX_REV1 1 - param set PWM_AUX_REV2 1 - param set PWM_AUX_REV3 1 - param set PWM_AUX_REV4 1 + param set PWM_AUX_REV1 1 + param set PWM_AUX_REV2 1 + param set PWM_AUX_REV3 1 + param set PWM_AUX_REV4 1 fi set MIXER quad_x diff --git a/ROMFS/px4fmu_common/init.d/13012_convergence b/ROMFS/px4fmu_common/init.d/13012_convergence index d70f09ac7e..416ea45074 100644 --- a/ROMFS/px4fmu_common/init.d/13012_convergence +++ b/ROMFS/px4fmu_common/init.d/13012_convergence @@ -21,59 +21,59 @@ sh /etc/init.d/rc.vtol_defaults if [ $AUTOCNF == yes ] then - param set VT_MOT_COUNT 3 - param set VT_FW_MOT_OFFID 3 - param set VT_IDLE_PWM_MC 1200 - param set VT_TYPE 1 + param set VT_MOT_COUNT 3 + param set VT_FW_MOT_OFFID 3 + param set VT_IDLE_PWM_MC 1200 + param set VT_TYPE 1 - param set VT_B_TRANS_DUR 1.0 - param set VT_FW_DIFTHR_EN 1 - param set VT_FW_DIFTHR_SC 0.17 - param set VT_FW_PERM_STAB 0 - param set VT_F_TRANS_DUR 1.2 - param set VT_F_TR_OL_TM 4.0 - param set VT_TILT_FW 1.0 - param set VT_TILT_MC 0.0 - param set VT_TILT_TRANS 0.45 - param set VT_TRANS_MIN_TM 1.2 - param set VT_TRANS_P2_DUR 1.3 + param set VT_B_TRANS_DUR 1.0 + param set VT_FW_DIFTHR_EN 1 + param set VT_FW_DIFTHR_SC 0.17 + param set VT_FW_PERM_STAB 0 + param set VT_F_TRANS_DUR 1.2 + param set VT_F_TR_OL_TM 4.0 + param set VT_TILT_FW 1.0 + param set VT_TILT_MC 0.0 + param set VT_TILT_TRANS 0.45 + param set VT_TRANS_MIN_TM 1.2 + param set VT_TRANS_P2_DUR 1.3 - param set FW_L1_PERIOD 17 - param set FW_MAN_R_MAX 50.0 - param set FW_ACRO_X_MAX 270 - param set FW_ACRO_Y_MAX 270 - param set FW_ACRO_Z_MAX 180 - param set FW_PR_FF 0.5 - param set FW_PR_P 0.08 - param set FW_PSP_OFF 5.0 - param set FW_P_LIM_MAX 30 - param set FW_P_LIM_MIN -30 - param set FW_P_RMAX_NEG 60 - param set FW_P_RMAX_POS 60 - param set FW_RR_FF 0.33 - param set FW_RR_P 0.11 - param set FW_YR_FF 0.3 - param set FW_YR_P 0.05 - param set MC_PITCHRATE_D 0.003 - param set MC_PITCHRATE_P 0.15 - param set MC_PITCH_P 6.0 - param set MC_ROLLRATE_D 0.003 - param set MC_ROLLRATE_P 0.15 - param set MC_ROLL_P 6.0 - param set MC_YAWRATE_MAX 120 - param set MC_YAWRATE_P 0.27 - param set MC_YAW_FF 0.35 - param set MC_YAW_P 2.5 + param set FW_L1_PERIOD 17 + param set FW_MAN_R_MAX 50.0 + param set FW_ACRO_X_MAX 270 + param set FW_ACRO_Y_MAX 270 + param set FW_ACRO_Z_MAX 180 + param set FW_PR_FF 0.5 + param set FW_PR_P 0.08 + param set FW_PSP_OFF 5.0 + param set FW_P_LIM_MAX 30 + param set FW_P_LIM_MIN -30 + param set FW_P_RMAX_NEG 60 + param set FW_P_RMAX_POS 60 + param set FW_RR_FF 0.33 + param set FW_RR_P 0.11 + param set FW_YR_FF 0.3 + param set FW_YR_P 0.05 + param set MC_PITCHRATE_D 0.003 + param set MC_PITCHRATE_P 0.15 + param set MC_PITCH_P 6.0 + param set MC_ROLLRATE_D 0.003 + param set MC_ROLLRATE_P 0.15 + param set MC_ROLL_P 6.0 + param set MC_YAWRATE_MAX 120 + param set MC_YAWRATE_P 0.27 + param set MC_YAW_FF 0.35 + param set MC_YAW_P 2.5 - param set MC_YAWRATE_P 0.3 - param set MPC_LAND_SPEED 1.2 - param set MPC_TKO_SPEED 2.5 - param set MPC_Z_VEL_MAX_UP 3.0 + param set MC_YAWRATE_P 0.3 + param set MPC_LAND_SPEED 1.2 + param set MPC_TKO_SPEED 2.5 + param set MPC_Z_VEL_MAX_UP 3.0 - param set CBRK_AIRSPD_CHK 162128 - param set FW_ARSP_MODE 2 + param set CBRK_AIRSPD_CHK 162128 + param set FW_ARSP_MODE 2 - param set SENS_BOARD_ROT 8 + param set SENS_BOARD_ROT 8 fi set MIXER vtol_convergence diff --git a/ROMFS/px4fmu_common/init.d/14001_tri_y_yaw+ b/ROMFS/px4fmu_common/init.d/14001_tri_y_yaw+ index d9e6ecc270..04ad1f8c15 100644 --- a/ROMFS/px4fmu_common/init.d/14001_tri_y_yaw+ +++ b/ROMFS/px4fmu_common/init.d/14001_tri_y_yaw+ @@ -18,4 +18,3 @@ sh /etc/init.d/rc.mc_defaults set MIXER tri_y_yaw+ set PWM_OUT 1234 - diff --git a/ROMFS/px4fmu_common/init.d/2105_maja b/ROMFS/px4fmu_common/init.d/2105_maja index 7a8fd88c4a..e713b37919 100644 --- a/ROMFS/px4fmu_common/init.d/2105_maja +++ b/ROMFS/px4fmu_common/init.d/2105_maja @@ -24,22 +24,22 @@ sh /etc/init.d/rc.fw_defaults if [ $AUTOCNF == yes ] then - param set FW_AIRSPD_MIN 10 - param set FW_AIRSPD_TRIM 15 - param set FW_AIRSPD_MAX 20 + param set FW_AIRSPD_MIN 10 + param set FW_AIRSPD_TRIM 15 + param set FW_AIRSPD_MAX 20 - param set FW_MAN_P_MAX 55 - param set FW_MAN_R_MAX 55 - param set FW_R_LIM 55 + param set FW_MAN_P_MAX 55 + param set FW_MAN_R_MAX 55 + param set FW_R_LIM 55 - param set FW_WR_FF 0.2 - param set FW_WR_I 0.2 - param set FW_WR_IMAX 0.8 - param set FW_WR_P 1 - param set FW_W_RMAX 0 + param set FW_WR_FF 0.2 + param set FW_WR_I 0.2 + param set FW_WR_IMAX 0.8 + param set FW_WR_P 1 + param set FW_W_RMAX 0 - # set disarmed value for the ESC - param set PWM_DISARMED 1000 + # set disarmed value for the ESC + param set PWM_DISARMED 1000 fi set MIXER AAERTWF diff --git a/ROMFS/px4fmu_common/init.d/2106_albatross b/ROMFS/px4fmu_common/init.d/2106_albatross index edd5f9ef05..c0fe27aa23 100644 --- a/ROMFS/px4fmu_common/init.d/2106_albatross +++ b/ROMFS/px4fmu_common/init.d/2106_albatross @@ -25,22 +25,22 @@ sh /etc/init.d/rc.fw_defaults if [ $AUTOCNF == yes ] then - param set FW_AIRSPD_MIN 10 - param set FW_AIRSPD_TRIM 15 - param set FW_AIRSPD_MAX 20 + param set FW_AIRSPD_MIN 10 + param set FW_AIRSPD_TRIM 15 + param set FW_AIRSPD_MAX 20 - param set FW_MAN_P_MAX 55 - param set FW_MAN_R_MAX 55 - param set FW_R_LIM 55 + param set FW_MAN_P_MAX 55 + param set FW_MAN_R_MAX 55 + param set FW_R_LIM 55 - param set FW_WR_FF 0.2 - param set FW_WR_I 0.2 - param set FW_WR_IMAX 0.8 - param set FW_WR_P 1 - param set FW_W_RMAX 0 + param set FW_WR_FF 0.2 + param set FW_WR_I 0.2 + param set FW_WR_IMAX 0.8 + param set FW_WR_P 1 + param set FW_W_RMAX 0 - # set disarmed value for the ESC - param set PWM_DISARMED 1000 + # set disarmed value for the ESC + param set PWM_DISARMED 1000 fi set MIXER AAVVTWFF diff --git a/ROMFS/px4fmu_common/init.d/3035_viper b/ROMFS/px4fmu_common/init.d/3035_viper index 1e79b9d19f..9c542af178 100644 --- a/ROMFS/px4fmu_common/init.d/3035_viper +++ b/ROMFS/px4fmu_common/init.d/3035_viper @@ -12,4 +12,3 @@ sh /etc/init.d/rc.fw_defaults set MIXER Viper - diff --git a/ROMFS/px4fmu_common/init.d/3037_parrot_disco_mod b/ROMFS/px4fmu_common/init.d/3037_parrot_disco_mod index c383c2e589..ba80e5b240 100644 --- a/ROMFS/px4fmu_common/init.d/3037_parrot_disco_mod +++ b/ROMFS/px4fmu_common/init.d/3037_parrot_disco_mod @@ -48,32 +48,32 @@ then param set FW_P_LIM_MAX 45 param set FW_P_LIM_MIN -45 - # Time Constant (def = 0.4s) + # Time Constant (def = 0.4s) param set FW_P_TC 0.4 # Pitch rate feed forward (def = 0.5 %/rad/sec) param set FW_PR_FF 0.35 - + # Pitch rate integrator limit (def = 0.4) param set FW_PR_IMAX 0.4 - + # Pitch rate proportional gain (def = 0.08 %/rad/sec) param set FW_PR_P 0.08 - + #################################### # Roll #################################### - # Basic limits (def = 50 deg) + # Basic limits (def = 50 deg) param set FW_R_LIM 40 - + # Roll rate upper limit (def = 70 deg/s) param set FW_R_RMAX 50 # Roll Time Constant (def = 0.4 s) - param set FW_R_TC 0.4 + param set FW_R_TC 0.4 - # Roll rate feed forward (def = 0.5 %/rad/sec) + # Roll rate feed forward (def = 0.5 %/rad/sec) param set FW_RR_FF 0.5 # Roll rate proportional Gain (def = 0.05 %/rad/sec) diff --git a/ROMFS/px4fmu_common/init.d/4002_quad_x_mount b/ROMFS/px4fmu_common/init.d/4002_quad_x_mount index d4f7b8b501..c2ddaeb878 100644 --- a/ROMFS/px4fmu_common/init.d/4002_quad_x_mount +++ b/ROMFS/px4fmu_common/init.d/4002_quad_x_mount @@ -28,4 +28,3 @@ set PWM_OUT 1234 set MIXER_AUX mount set PWM_AUX_OUT 123456 set PWM_AUX_RATE 50 - diff --git a/ROMFS/px4fmu_common/init.d/4013_bebop b/ROMFS/px4fmu_common/init.d/4013_bebop index b68bf84085..8b23184307 100644 --- a/ROMFS/px4fmu_common/init.d/4013_bebop +++ b/ROMFS/px4fmu_common/init.d/4013_bebop @@ -22,20 +22,20 @@ sh /etc/init.d/rc.mc_defaults # if [ $AUTOCNF == yes ] then - # Set all params here, then disable autoconfig - param set MC_ROLL_P 6.5 - param set MC_ROLLRATE_P 0.109999999403953552 - param set MC_ROLLRATE_I 0.0 - param set MC_ROLLRATE_D 0.0006 - param set MC_PITCH_P 6.5 - param set MC_PITCHRATE_P 0.1 - param set MC_PITCHRATE_I 0.0 - param set MC_PITCHRATE_D 0.000799999 - param set MC_YAW_P 1.049999 - param set MC_YAWRATE_P 0.05 - param set MC_YAWRATE_I 0.001 - param set MC_YAWRATE_D 0.0 - param set MC_YAW_FF 0.7 + # Set all params here, then disable autoconfig + param set MC_ROLL_P 6.5 + param set MC_ROLLRATE_P 0.109999999403953552 + param set MC_ROLLRATE_I 0.0 + param set MC_ROLLRATE_D 0.0006 + param set MC_PITCH_P 6.5 + param set MC_PITCHRATE_P 0.1 + param set MC_PITCHRATE_I 0.0 + param set MC_PITCHRATE_D 0.000799999 + param set MC_YAW_P 1.049999 + param set MC_YAWRATE_P 0.05 + param set MC_YAWRATE_I 0.001 + param set MC_YAWRATE_D 0.0 + param set MC_YAW_FF 0.7 fi set OUTPUT_MODE bebop diff --git a/ROMFS/px4fmu_common/init.d/4030_3dr_solo b/ROMFS/px4fmu_common/init.d/4030_3dr_solo index ce02c41e14..aa1ff52820 100644 --- a/ROMFS/px4fmu_common/init.d/4030_3dr_solo +++ b/ROMFS/px4fmu_common/init.d/4030_3dr_solo @@ -18,72 +18,72 @@ sh /etc/init.d/rc.mc_defaults if [ $AUTOCNF == yes ] then - # tuning - param set MC_PITCHRATE_P 0.11 - param set MC_ROLLRATE_P 0.11 - param set MPC_MANTHR_MIN 0.08 - param set MPC_XY_VEL_MAX 3.0 - param set MPC_Z_VEL_MAX_DN 2.0 + # tuning + param set MC_PITCHRATE_P 0.11 + param set MC_ROLLRATE_P 0.11 + param set MPC_MANTHR_MIN 0.08 + param set MPC_XY_VEL_MAX 3.0 + param set MPC_Z_VEL_MAX_DN 2.0 - # INAV: higher GPS weights for better altitude control - param set INAV_W_Z_BARO 0.3 - param set INAV_W_Z_GPS_P 0.8 - param set INAV_W_Z_GPS_V 0.8 + # INAV: higher GPS weights for better altitude control + param set INAV_W_Z_BARO 0.3 + param set INAV_W_Z_GPS_P 0.8 + param set INAV_W_Z_GPS_V 0.8 - # takeoff, land and RTL settings - param set MIS_TAKEOFF_ALT 4.0 - param set COM_DISARM_LAND 1 - param set RTL_LAND_DELAY 1 - param set RTL_DESCEND_ALT 5.0 - param set RTL_RETURN_ALT 15.0 - param set MPC_TILTMAX_LND 8.0 - param set MPC_LAND_SPEED 0.4 - param set MPC_HOLD_MAX_Z 1.5 - param set MPC_TKO_JMPSPD 2.0 - param set MPC_TKO_SPEED 1.5 + # takeoff, land and RTL settings + param set MIS_TAKEOFF_ALT 4.0 + param set COM_DISARM_LAND 1 + param set RTL_LAND_DELAY 1 + param set RTL_DESCEND_ALT 5.0 + param set RTL_RETURN_ALT 15.0 + param set MPC_TILTMAX_LND 8.0 + param set MPC_LAND_SPEED 0.4 + param set MPC_HOLD_MAX_Z 1.5 + param set MPC_TKO_JMPSPD 2.0 + param set MPC_TKO_SPEED 1.5 - # setup - # main board rotation: pitch 180 - param set SENS_BOARD_ROT 12 - # solo external mag rotation - param set CAL_MAG0_ROT 30 - # no safety switch - param set CBRK_IO_SAFETY 22027 - # battery voltage not available yet - param set CBRK_SUPPLY_CHK 894281 + # setup + # main board rotation: pitch 180 + param set SENS_BOARD_ROT 12 + # solo external mag rotation + param set CAL_MAG0_ROT 30 + # no safety switch + param set CBRK_IO_SAFETY 22027 + # battery voltage not available yet + param set CBRK_SUPPLY_CHK 894281 - # RC configuration - param set RC_MAP_MODE_SW 5 - param set RC_MAP_PITCH 2 - param set RC_MAP_ROLL 1 - param set RC_MAP_THROTTLE 3 - param set RC_MAP_YAW 4 + # RC configuration + param set RC_MAP_MODE_SW 5 + param set RC_MAP_PITCH 2 + param set RC_MAP_ROLL 1 + param set RC_MAP_THROTTLE 3 + param set RC_MAP_YAW 4 - param set RC1_DZ 10 - param set RC1_MAX 1988 - param set RC1_MIN 1003 - param set RC1_REV 1 - param set RC1_TRIM 1499 - param set RC2_DZ 10 - param set RC2_MAX 1987 - param set RC2_MIN 1023 - param set RC2_REV -1 - param set RC2_TRIM 1499 - param set RC3_DZ 10 - param set RC3_MAX 1877 - param set RC3_MIN 1023 - param set RC3_REV 1 - param set RC3_TRIM 1023 - param set RC4_DZ 10 - param set RC4_MAX 1998 - param set RC4_MIN 1012 - param set RC4_REV 1 - param set RC4_TRIM 1500 - param set RC5_DZ 10 - param set RC5_MAX 2000 - param set RC5_MIN 1000 - param set RC5_REV 1 - param set RC5_TRIM 1500 + param set RC1_DZ 10 + param set RC1_MAX 1988 + param set RC1_MIN 1003 + param set RC1_REV 1 + param set RC1_TRIM 1499 + param set RC2_DZ 10 + param set RC2_MAX 1987 + param set RC2_MIN 1023 + param set RC2_REV -1 + param set RC2_TRIM 1499 + param set RC3_DZ 10 + param set RC3_MAX 1877 + param set RC3_MIN 1023 + param set RC3_REV 1 + param set RC3_TRIM 1023 + param set RC4_DZ 10 + param set RC4_MAX 1998 + param set RC4_MIN 1012 + param set RC4_REV 1 + param set RC4_TRIM 1500 + param set RC5_DZ 10 + param set RC5_MAX 2000 + param set RC5_MIN 1000 + param set RC5_REV 1 + param set RC5_TRIM 1500 fi set MIXER quad_x diff --git a/ROMFS/px4fmu_common/init.d/4040_reaper b/ROMFS/px4fmu_common/init.d/4040_reaper index b048604ef0..f825a179d4 100644 --- a/ROMFS/px4fmu_common/init.d/4040_reaper +++ b/ROMFS/px4fmu_common/init.d/4040_reaper @@ -19,23 +19,23 @@ sh /etc/init.d/rc.mc_defaults if [ $AUTOCNF == yes ] then - param set MC_ROLL_P 6.5 - param set MC_ROLLRATE_P 0.14 - param set MC_ROLLRATE_I 0.1 - param set MC_ROLLRATE_D 0.004 - param set MC_PITCH_P 6.0 - param set MC_PITCHRATE_P 0.14 - param set MC_PITCHRATE_I 0.09 - param set MC_PITCHRATE_D 0.004 - param set MC_YAW_P 4 + param set MC_ROLL_P 6.5 + param set MC_ROLLRATE_P 0.14 + param set MC_ROLLRATE_I 0.1 + param set MC_ROLLRATE_D 0.004 + param set MC_PITCH_P 6.0 + param set MC_PITCHRATE_P 0.14 + param set MC_PITCHRATE_I 0.09 + param set MC_PITCHRATE_D 0.004 + param set MC_YAW_P 4 - param set NAV_ACC_RAD 2.0 - param set RTL_RETURN_ALT 30.0 - param set RTL_DESCEND_ALT 10.0 + param set NAV_ACC_RAD 2.0 + param set RTL_RETURN_ALT 30.0 + param set RTL_DESCEND_ALT 10.0 - param set PWM_MIN 1100 - param set PWM_MAX 1900 - param set PWM_AUX_DISARMED 950 + param set PWM_MIN 1100 + param set PWM_MAX 1900 + param set PWM_AUX_DISARMED 950 fi set MIXER quad_h diff --git a/ROMFS/px4fmu_common/init.d/4900_crazyflie b/ROMFS/px4fmu_common/init.d/4900_crazyflie index 08bccdf2f0..8bc6d76b6d 100644 --- a/ROMFS/px4fmu_common/init.d/4900_crazyflie +++ b/ROMFS/px4fmu_common/init.d/4900_crazyflie @@ -17,46 +17,46 @@ sh /etc/init.d/4001_quad_x if [ $AUTOCNF == yes ] then - param set COM_RC_IN_MODE 1 - param set BAT_N_CELLS 1 - param set BAT_CAPACITY 240 - param set BAT_SOURCE 1 - param set PWM_DISARMED 0 - param set PWM_MIN 0 - param set PWM_MAX 255 - param set SYS_COMPANION 20 - param set MC_PITCHRATE_D 0.002 - param set MC_PITCHRATE_I 0.2 - param set MC_PITCHRATE_P 0.07 - param set MC_PITCH_P 6.5 - param set MC_ROLLRATE_D 0.002 - param set MC_ROLLRATE_I 0.2 - param set MC_ROLLRATE_P 0.07 - param set MC_ROLL_P 6.5 - param set MC_YAW_P 3.0 - param set EKF2_HGT_MODE 2 - param set EKF2_AID_MASK 3 - param set EKF2_OF_DELAY 10 - param set MPC_THR_HOVER 0.7 - param set MPC_MANTHR_MAX 1.0 - param set MPC_THR_MAX 1.0 - param set MPC_Z_P 1.5 - param set MPC_Z_VEL_I 0.3 - param set MPC_Z_VEL_P 0.4 - param set MPC_HOLD_MAX_XY 0.1 - param set MPC_MAX_FLOW_HGT 3 - param set IMU_GYRO_CUTOFF 100 - param set IMU_ACCEL_CUTOFF 30 - param set MC_DTERM_CUTOFF 70 - param set SYS_FMU_TASK 1 - param set CBRK_SUPPLY_CHK 894281 - param set CBRK_USB_CHK 197848 - param set SDLOG_PROFILE 1 - param set EKF2_MAG_TYPE 1 - param set EKF2_ABL_LIM 2.0 - param set MC_AIRMODE 1 - param set NAV_RCL_ACT 3 - param set SENS_FLOW_MINRNG 0.05 + param set COM_RC_IN_MODE 1 + param set BAT_N_CELLS 1 + param set BAT_CAPACITY 240 + param set BAT_SOURCE 1 + param set PWM_DISARMED 0 + param set PWM_MIN 0 + param set PWM_MAX 255 + param set SYS_COMPANION 20 + param set MC_PITCHRATE_D 0.002 + param set MC_PITCHRATE_I 0.2 + param set MC_PITCHRATE_P 0.07 + param set MC_PITCH_P 6.5 + param set MC_ROLLRATE_D 0.002 + param set MC_ROLLRATE_I 0.2 + param set MC_ROLLRATE_P 0.07 + param set MC_ROLL_P 6.5 + param set MC_YAW_P 3.0 + param set EKF2_HGT_MODE 2 + param set EKF2_AID_MASK 3 + param set EKF2_OF_DELAY 10 + param set MPC_THR_HOVER 0.7 + param set MPC_MANTHR_MAX 1.0 + param set MPC_THR_MAX 1.0 + param set MPC_Z_P 1.5 + param set MPC_Z_VEL_I 0.3 + param set MPC_Z_VEL_P 0.4 + param set MPC_HOLD_MAX_XY 0.1 + param set MPC_MAX_FLOW_HGT 3 + param set IMU_GYRO_CUTOFF 100 + param set IMU_ACCEL_CUTOFF 30 + param set MC_DTERM_CUTOFF 70 + param set SYS_FMU_TASK 1 + param set CBRK_SUPPLY_CHK 894281 + param set CBRK_USB_CHK 197848 + param set SDLOG_PROFILE 1 + param set EKF2_MAG_TYPE 1 + param set EKF2_ABL_LIM 2.0 + param set MC_AIRMODE 1 + param set NAV_RCL_ACT 3 + param set SENS_FLOW_MINRNG 0.05 fi set PWM_MIN none set PWM_MAX none diff --git a/ROMFS/px4fmu_common/init.d/CMakeLists.txt b/ROMFS/px4fmu_common/init.d/CMakeLists.txt index faaeb11f21..0f2029c4eb 100644 --- a/ROMFS/px4fmu_common/init.d/CMakeLists.txt +++ b/ROMFS/px4fmu_common/init.d/CMakeLists.txt @@ -111,6 +111,7 @@ px4_add_romfs_files( rc.mc_defaults rcS rc.sensors + rc.thermal_cal rc.ugv_apps rc.ugv_defaults rc.vtol_apps diff --git a/ROMFS/px4fmu_common/init.d/rc.thermal_cal b/ROMFS/px4fmu_common/init.d/rc.thermal_cal new file mode 100644 index 0000000000..88bf8f0b8e --- /dev/null +++ b/ROMFS/px4fmu_common/init.d/rc.thermal_cal @@ -0,0 +1,40 @@ +#!nsh +# +# Thermal Calibration startup script. +# +# NOTE: Script variables are declared/initialized/unset in the rcS script. +# + +set TEMP_CALIB_ARGS "" + +# +# Determine if a thermal calibration should be started. +# + +if param compare SYS_CAL_ACCEL 1 +then + set TEMP_CALIB_ARGS "${TEMP_CALIB_ARGS} -a" + param set SYS_CAL_ACCEL 0 +fi + +if param compare SYS_CAL_GYRO 1 +then + set TEMP_CALIB_ARGS "${TEMP_CALIB_ARGS} -g" + param set SYS_CAL_GYRO 0 +fi + +if param compare SYS_CAL_BARO 1 +then + set TEMP_CALIB_ARGS "${TEMP_CALIB_ARGS} -b" + param set SYS_CAL_BARO 0 +fi + +# +# Start the thermal calibration cycle. +# +if [ "x$TEMP_CALIB_ARGS" != "x" ] +then + send_event temperature_calibration ${TEMP_CALIB_ARGS} +fi + +unset TEMP_CALIB_ARGS \ No newline at end of file diff --git a/ROMFS/px4fmu_common/init.d/rcS b/ROMFS/px4fmu_common/init.d/rcS index c5f5dc1c45..8a50da0240 100644 --- a/ROMFS/px4fmu_common/init.d/rcS +++ b/ROMFS/px4fmu_common/init.d/rcS @@ -15,29 +15,70 @@ set +e # # UART mapping on OMNIBUSF4SD: # -# USART1 /dev/ttyS0 SerialRX -# USART4 /dev/ttyS1 TELEM1 -# USART6 /dev/ttyS2 GPS +# USART1 /dev/ttyS0 SerialRX +# USART4 /dev/ttyS1 TELEM1 +# USART6 /dev/ttyS2 GPS # # UART mapping on FMUv2/3/4: # -# UART1 /dev/ttyS0 IO debug (except v4, there ttyS0 is the wifi) -# USART2 /dev/ttyS1 TELEM1 (flow control) -# USART3 /dev/ttyS2 TELEM2 (flow control) +# UART1 /dev/ttyS0 IO debug (except v4, there ttyS0 is the wifi) +# USART2 /dev/ttyS1 TELEM1 (flow control) +# USART3 /dev/ttyS2 TELEM2 (flow control) # UART4 -# UART7 CONSOLE -# UART8 SERIAL4 +# UART7 CONSOLE +# UART8 SERIAL4 # # # UART mapping on FMUv5: # -# UART1 /dev/ttyS0 GPS -# USART2 /dev/ttyS1 TELEM1 (flow control) -# USART3 /dev/ttyS2 TELEM2 (flow control) -# UART4 /dev/ttyS3 TELEM4 -# USART6 /dev/ttyS4 TELEM3 (flow control) -# UART7 /dev/ttyS5 ? -# UART8 /dev/ttyS6 CONSOLE +# UART1 /dev/ttyS0 GPS +# USART2 /dev/ttyS1 TELEM1 (flow control) +# USART3 /dev/ttyS2 TELEM2 (flow control) +# UART4 /dev/ttyS3 TELEM4 +# USART6 /dev/ttyS4 TELEM3 (flow control) +# UART7 /dev/ttyS5 ? +# UART8 /dev/ttyS6 CONSOLE + +# +# Set default paramter values +# +set AUX_MODE pwm +set DATAMAN_OPT "" +set FAILSAFE none +set FAILSAFE_AUX none +set FCONFIG /fs/microsd/etc/config.txt +set FEXTRAS /fs/microsd/etc/extras.txt +set FRC /fs/microsd/etc/rc.txt +set FMU_ARGS "" +set FMU_MODE pwm +set IO_FILE "" +set IO_PRESENT no +set LOG_FILE /fs/microsd/bootlog.txt +set LOGGER_BUF 14 +set MAVLINK_F default +set MAVLINK_COMPANION_DEVICE /dev/ttyS2 +set MAV_TYPE none +set MIXER none +set MIXER_AUX none +set MK_MODE none +set MKBLCTRL_ARG "" +set MODE autostart +set OUTPUT_MODE none +set PARAM_FILE /fs/microsd/params +set PWM_OUT none +set PWM_RATE p:PWM_RATE +set PWM_DISARMED p:PWM_DISARMED +set PWM_MIN p:PWM_MIN +set PWM_MAX p:PWM_MAX +set PWM_AUX_OUT none +set PWM_AUX_RATE none +set PWM_ACHDIS none +set PWM_AUX_DISARMED p:PWM_AUX_DISARMED +set PWM_AUX_MIN p:PWM_AUX_MIN +set PWM_AUX_MAX p:PWM_AUX_MAX +set TUNE_ERR "ML<