From 89878fcc884bd73bb0cf64313b40239e4733e9dc Mon Sep 17 00:00:00 2001 From: xdwgood <1308455330@qq.com> Date: Wed, 3 Feb 2021 09:10:41 +0800 Subject: [PATCH] clean up --- ROMFS/px4fmu_common/init.d/airframes/13013_deltaquad | 1 - src/drivers/camera_trigger/camera_trigger.cpp | 4 ---- src/modules/mc_pos_control/mc_pos_control_params.c | 2 +- 3 files changed, 1 insertion(+), 6 deletions(-) diff --git a/ROMFS/px4fmu_common/init.d/airframes/13013_deltaquad b/ROMFS/px4fmu_common/init.d/airframes/13013_deltaquad index 7bb7a3252e9a..5e8306a4cdce 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/13013_deltaquad +++ b/ROMFS/px4fmu_common/init.d/airframes/13013_deltaquad @@ -101,7 +101,6 @@ then param set MPC_ACC_HOR_MAX 2 param set MPC_LAND_SPEED 1.2 param set MPC_TILTMAX_LND 35 - param set MPC_Z_VEL_MAX 1.5 param set MPC_Z_VEL_MAX_UP 1.5 param set MPC_Z_VEL_MAX_DN 1.5 param set MPC_HOLD_MAX_XY 0.5 diff --git a/src/drivers/camera_trigger/camera_trigger.cpp b/src/drivers/camera_trigger/camera_trigger.cpp index 745fed294b75..f7073c676632 100644 --- a/src/drivers/camera_trigger/camera_trigger.cpp +++ b/src/drivers/camera_trigger/camera_trigger.cpp @@ -54,17 +54,13 @@ #include #include #include -#include #include #include #include -#include -#include #include #include #include -#include #include diff --git a/src/modules/mc_pos_control/mc_pos_control_params.c b/src/modules/mc_pos_control/mc_pos_control_params.c index 59d42627f402..6a7912957c25 100644 --- a/src/modules/mc_pos_control/mc_pos_control_params.c +++ b/src/modules/mc_pos_control/mc_pos_control_params.c @@ -679,7 +679,7 @@ PARAM_DEFINE_FLOAT(MPC_YAWRAUTO_MAX, 45.0f); * * Below this altitude: * - descending velocity gets limited to a value - * between "MPC_Z_VEL_MAX" and "MPC_LAND_SPEED" + * between "MPC_Z_VEL_MAX_DN" and "MPC_LAND_SPEED" * - horizontal velocity gets limited to a value * between "MPC_VEL_MANUAL" and "MPC_LAND_VEL_XY" * for a smooth descent and landing experience.