From f58e831b406745d044429a7b2f58a8a1d3e4144a Mon Sep 17 00:00:00 2001 From: Matthias Grob Date: Tue, 21 Mar 2017 14:19:11 +0100 Subject: [PATCH] startup scripts/mc_pos_control: renamed parameters after refactor --- ROMFS/px4fmu_common/init.d/12002_steadidrone_mavrik | 2 +- ROMFS/px4fmu_common/init.d/13008_QuadRanger | 2 +- ROMFS/px4fmu_common/init.d/13009_vtol_spt_ranger | 1 - ROMFS/px4fmu_common/init.d/4030_solo | 2 +- ROMFS/px4fmu_common/init.d/rc.vtol_defaults | 2 +- ROMFS/tap_common/init.d/rc.vtol_defaults | 2 +- posix-configs/SITL/init/ekf2/iris | 1 - posix-configs/SITL/init/ekf2/iris_opt_flow | 1 - posix-configs/SITL/init/ekf2/multiple_iris | 1 - posix-configs/SITL/init/ekf2/solo | 1 - posix-configs/SITL/init/ekf2/standard_vtol | 2 +- posix-configs/SITL/init/ekf2/tailsitter | 1 - posix-configs/SITL/init/ekf2/typhoon_h480 | 1 - posix-configs/SITL/init/inav/iris_opt_flow | 1 - posix-configs/SITL/init/lpe/iris | 1 - posix-configs/SITL/init/lpe/iris_opt_flow | 3 +-- posix-configs/SITL/init/lpe/solo | 1 - posix-configs/SITL/init/lpe/standard_vtol | 2 +- posix-configs/SITL/init/lpe/typhoon_h480 | 1 - 19 files changed, 8 insertions(+), 20 deletions(-) diff --git a/ROMFS/px4fmu_common/init.d/12002_steadidrone_mavrik b/ROMFS/px4fmu_common/init.d/12002_steadidrone_mavrik index 2d9a6dbd3bbd..3ddc4d937f07 100644 --- a/ROMFS/px4fmu_common/init.d/12002_steadidrone_mavrik +++ b/ROMFS/px4fmu_common/init.d/12002_steadidrone_mavrik @@ -31,7 +31,7 @@ then param set MPC_HOLD_MAX_XY 0.25 param set MPC_THR_MIN 0.15 - param set MPC_Z_VEL_MAX 2.0 + param set MPC_Z_VEL_MAX_DN 2.0 param set BAT_N_CELLS 4 fi diff --git a/ROMFS/px4fmu_common/init.d/13008_QuadRanger b/ROMFS/px4fmu_common/init.d/13008_QuadRanger index b2100c21d1af..89533d63f9c8 100644 --- a/ROMFS/px4fmu_common/init.d/13008_QuadRanger +++ b/ROMFS/px4fmu_common/init.d/13008_QuadRanger @@ -38,7 +38,7 @@ then param set MC_YAWRAUTO_MAX 40.0 param set MPC_ACC_HOR_MAX 2.0 - param set MPC_Z_VEL_MAX 1.5 + param set MPC_Z_VEL_MAX_DN 1.5 param set MPC_TKO_SPEED 1.5 param set MPC_LAND_SPEED 0.8 diff --git a/ROMFS/px4fmu_common/init.d/13009_vtol_spt_ranger b/ROMFS/px4fmu_common/init.d/13009_vtol_spt_ranger index 16546cf3634c..841692dddde8 100644 --- a/ROMFS/px4fmu_common/init.d/13009_vtol_spt_ranger +++ b/ROMFS/px4fmu_common/init.d/13009_vtol_spt_ranger @@ -67,7 +67,6 @@ then param set MPC_XY_VEL_P 0.05 param set MPC_Z_FF 0.3 param set MPC_Z_P 0.5 - param set MPC_Z_VEL_MAX 1.0 param set MPC_Z_VEL_P 0.1 param set NAV_ACC_RAD 3.0 diff --git a/ROMFS/px4fmu_common/init.d/4030_solo b/ROMFS/px4fmu_common/init.d/4030_solo index e9616a7ad8f0..c86891fbfdd0 100644 --- a/ROMFS/px4fmu_common/init.d/4030_solo +++ b/ROMFS/px4fmu_common/init.d/4030_solo @@ -23,7 +23,7 @@ then 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 2.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 diff --git a/ROMFS/px4fmu_common/init.d/rc.vtol_defaults b/ROMFS/px4fmu_common/init.d/rc.vtol_defaults index aa0b476b4449..f4580b252285 100644 --- a/ROMFS/px4fmu_common/init.d/rc.vtol_defaults +++ b/ROMFS/px4fmu_common/init.d/rc.vtol_defaults @@ -14,7 +14,7 @@ then param set NAV_ACC_RAD 3 param set MPC_TKO_SPEED 1.0 param set MPC_LAND_SPEED 0.7 - param set MPC_Z_VEL_MAX 1.5 + param set MPC_Z_VEL_MAX_DN 1.5 param set MPC_XY_VEL_MAX 4.0 param set MIS_YAW_TMT 10 param set MPC_ACC_HOR_MAX 2.0 diff --git a/ROMFS/tap_common/init.d/rc.vtol_defaults b/ROMFS/tap_common/init.d/rc.vtol_defaults index ec0e262a4c24..58e24d1dbe91 100644 --- a/ROMFS/tap_common/init.d/rc.vtol_defaults +++ b/ROMFS/tap_common/init.d/rc.vtol_defaults @@ -14,7 +14,7 @@ then param set NAV_ACC_RAD 3 param set MPC_TKO_SPEED 1.0 param set MPC_LAND_SPEED 0.7 - param set MPC_Z_VEL_MAX 1.5 + param set MPC_Z_VEL_MAX_DN 1.5 param set MPC_XY_VEL_MAX 4.0 param set MIS_YAW_TMT 10 param set MPC_ACC_HOR_MAX 2.0 diff --git a/posix-configs/SITL/init/ekf2/iris b/posix-configs/SITL/init/ekf2/iris index dd2c41878a7d..888edce7fdf2 100644 --- a/posix-configs/SITL/init/ekf2/iris +++ b/posix-configs/SITL/init/ekf2/iris @@ -32,7 +32,6 @@ param set MC_ROLL_P 6 param set MC_ROLLRATE_P 0.2 param set MIS_TAKEOFF_ALT 2.5 param set MPC_HOLD_MAX_Z 2.0 -param set MPC_HOLD_XY_DZ 0.1 param set MPC_Z_VEL_I 0.15 param set MPC_Z_VEL_P 0.6 param set NAV_ACC_RAD 2.0 diff --git a/posix-configs/SITL/init/ekf2/iris_opt_flow b/posix-configs/SITL/init/ekf2/iris_opt_flow index 3d3f123ddab6..0cf072fbc118 100644 --- a/posix-configs/SITL/init/ekf2/iris_opt_flow +++ b/posix-configs/SITL/init/ekf2/iris_opt_flow @@ -37,7 +37,6 @@ param set MC_PITCHRATE_P 0.2 param set MC_PITCH_P 6 param set MC_ROLL_P 6 param set MPC_HOLD_MAX_Z 2.0 -param set MPC_HOLD_XY_DZ 0.1 param set MPC_Z_VEL_P 0.6 param set MPC_Z_VEL_I 0.15 param set EKF2_GBIAS_INIT 0.01 diff --git a/posix-configs/SITL/init/ekf2/multiple_iris b/posix-configs/SITL/init/ekf2/multiple_iris index d50dacb5ac53..f9ca63c4b26d 100644 --- a/posix-configs/SITL/init/ekf2/multiple_iris +++ b/posix-configs/SITL/init/ekf2/multiple_iris @@ -32,7 +32,6 @@ param set MC_ROLL_P 6 param set MC_ROLLRATE_P 0.2 param set MIS_TAKEOFF_ALT 2.5 param set MPC_HOLD_MAX_Z 2.0 -param set MPC_HOLD_XY_DZ 0.1 param set MPC_Z_VEL_I 0.15 param set MPC_Z_VEL_P 0.6 param set NAV_ACC_RAD 2.0 diff --git a/posix-configs/SITL/init/ekf2/solo b/posix-configs/SITL/init/ekf2/solo index 0961b786079e..a459ce233c27 100644 --- a/posix-configs/SITL/init/ekf2/solo +++ b/posix-configs/SITL/init/ekf2/solo @@ -29,7 +29,6 @@ param set MC_ROLL_P 6 param set MC_ROLLRATE_P 0.15 param set MIS_TAKEOFF_ALT 2.5 param set MPC_HOLD_MAX_Z 2.0 -param set MPC_HOLD_XY_DZ 0.1 param set MPC_Z_VEL_I 0.15 param set MPC_Z_VEL_P 0.6 param set NAV_ACC_RAD 2.0 diff --git a/posix-configs/SITL/init/ekf2/standard_vtol b/posix-configs/SITL/init/ekf2/standard_vtol index bacb88d817bd..534574360a3b 100644 --- a/posix-configs/SITL/init/ekf2/standard_vtol +++ b/posix-configs/SITL/init/ekf2/standard_vtol @@ -42,7 +42,7 @@ param set MPC_XY_VEL_D 0.005 param set MPC_XY_VEL_I 0.2 param set MPC_XY_VEL_P 0.15 param set MPC_Z_VEL_I 0.15 -param set MPC_Z_VEL_MAX 1.5 +param set MPC_Z_VEL_MAX_DN 1.5 param set MPC_Z_VEL_P 0.6 param set NAV_ACC_RAD 5.0 param set NAV_DLL_ACT 2 diff --git a/posix-configs/SITL/init/ekf2/tailsitter b/posix-configs/SITL/init/ekf2/tailsitter index b90f640595ad..cff93d3cf788 100644 --- a/posix-configs/SITL/init/ekf2/tailsitter +++ b/posix-configs/SITL/init/ekf2/tailsitter @@ -31,7 +31,6 @@ param set MPC_XY_P 0.15 param set MPC_XY_VEL_D 0.005 param set MPC_XY_VEL_P 0.05 param set MPC_Z_VEL_I 0.15 -param set MPC_Z_VEL_MAX 1.0 param set MPC_Z_VEL_P 0.8 param set NAV_DLL_ACT 2 param set SENS_BOARD_ROT 0 diff --git a/posix-configs/SITL/init/ekf2/typhoon_h480 b/posix-configs/SITL/init/ekf2/typhoon_h480 index 8e939b414d8a..8d92c998b23e 100644 --- a/posix-configs/SITL/init/ekf2/typhoon_h480 +++ b/posix-configs/SITL/init/ekf2/typhoon_h480 @@ -29,7 +29,6 @@ param set MC_ROLL_P 6 param set MC_ROLLRATE_P 0.1 param set MIS_TAKEOFF_ALT 2.5 param set MPC_HOLD_MAX_Z 2.0 -param set MPC_HOLD_XY_DZ 0.1 param set MPC_XY_VEL_I 0.2 param set MPC_XY_VEL_P 0.15 param set MPC_Z_VEL_I 0.15 diff --git a/posix-configs/SITL/init/inav/iris_opt_flow b/posix-configs/SITL/init/inav/iris_opt_flow index c0c9c2989075..af9008085658 100644 --- a/posix-configs/SITL/init/inav/iris_opt_flow +++ b/posix-configs/SITL/init/inav/iris_opt_flow @@ -36,7 +36,6 @@ param set MC_ROLL_P 5.5 param set MC_ROLLRATE_I 0.1 param set MC_PITCHRATE_I 0.1 param set MPC_HOLD_MAX_Z 2.0 -param set MPC_HOLD_XY_DZ 0.1 param set MPC_Z_VEL_P 0.8 param set MPC_Z_VEL_I 0.15 param set MPC_XY_VEL_P 0.15 diff --git a/posix-configs/SITL/init/lpe/iris b/posix-configs/SITL/init/lpe/iris index 095b2ad19683..5521d6febc86 100644 --- a/posix-configs/SITL/init/lpe/iris +++ b/posix-configs/SITL/init/lpe/iris @@ -37,7 +37,6 @@ param set MC_PITCHRATE_P 0.2 param set MC_PITCH_P 6 param set MC_ROLL_P 6 param set MPC_HOLD_MAX_Z 2.0 -param set MPC_HOLD_XY_DZ 0.1 param set MPC_Z_VEL_P 0.6 param set MPC_Z_VEL_I 0.15 param set EKF2_GBIAS_INIT 0.01 diff --git a/posix-configs/SITL/init/lpe/iris_opt_flow b/posix-configs/SITL/init/lpe/iris_opt_flow index 4869f246bbd9..3a41ba1bb83e 100644 --- a/posix-configs/SITL/init/lpe/iris_opt_flow +++ b/posix-configs/SITL/init/lpe/iris_opt_flow @@ -36,7 +36,6 @@ param set MC_ROLL_P 5.5 param set MC_ROLLRATE_I 0.1 param set MC_PITCHRATE_I 0.1 param set MPC_HOLD_MAX_Z 2.0 -param set MPC_HOLD_XY_DZ 0.1 param set MPC_Z_VEL_P 0.8 param set MPC_Z_VEL_I 0.15 param set MPC_XY_VEL_P 0.15 @@ -53,7 +52,7 @@ param set LPE_GPS_ON 0 param set MPC_ALT_MODE 1 param set LPE_T_MAX_GRADE 0 param set MPC_XY_VEL_MAX 2 -param set MPC_Z_VEL_MAX 2 +param set MPC_Z_VEL_MAX_DN 2 param set MPC_TILTMAX_AIR 10 param set MPC_TILTMAX_LND 10 param set MPC_XY_P 0.5 diff --git a/posix-configs/SITL/init/lpe/solo b/posix-configs/SITL/init/lpe/solo index 6bcfe544b3c7..8128c008077c 100644 --- a/posix-configs/SITL/init/lpe/solo +++ b/posix-configs/SITL/init/lpe/solo @@ -37,7 +37,6 @@ param set MC_PITCHRATE_P 0.2 param set MC_PITCH_P 6 param set MC_ROLL_P 6 param set MPC_HOLD_MAX_Z 2.0 -param set MPC_HOLD_XY_DZ 0.1 param set MPC_Z_VEL_P 0.6 param set MPC_Z_VEL_I 0.15 param set EKF2_GBIAS_INIT 0.01 diff --git a/posix-configs/SITL/init/lpe/standard_vtol b/posix-configs/SITL/init/lpe/standard_vtol index 01f42f8793c0..d84f37af4a4d 100644 --- a/posix-configs/SITL/init/lpe/standard_vtol +++ b/posix-configs/SITL/init/lpe/standard_vtol @@ -32,7 +32,7 @@ param set MPC_XY_VEL_P 0.1 param set MPC_XY_VEL_I 0.1 param set MPC_XY_VEL_D 0.005 param set MPC_XY_FF 0.1 -param set MPC_Z_VEL_MAX 1.5 +param set MPC_Z_VEL_MAX_DN 1.5 param set MPC_Z_VEL_P 0.6 param set MPC_Z_VEL_I 0.15 param set FW_AIRSPD_MIN 14 diff --git a/posix-configs/SITL/init/lpe/typhoon_h480 b/posix-configs/SITL/init/lpe/typhoon_h480 index d63d0b2b3d40..245b27dc2c9c 100644 --- a/posix-configs/SITL/init/lpe/typhoon_h480 +++ b/posix-configs/SITL/init/lpe/typhoon_h480 @@ -34,7 +34,6 @@ param set MC_PITCHRATE_P 0.2 param set MC_PITCH_P 6 param set MC_ROLL_P 6 param set MPC_HOLD_MAX_Z 2.0 -param set MPC_HOLD_XY_DZ 0.1 param set MPC_Z_VEL_P 0.6 param set MPC_Z_VEL_I 0.15 param set MPC_XY_VEL_P 0.15