This commit is contained in:
xdwgood
2021-02-03 09:10:41 +08:00
committed by Lorenz Meier
parent 4b4a9a925b
commit 89878fcc88
3 changed files with 1 additions and 6 deletions
@@ -101,7 +101,6 @@ then
param set MPC_ACC_HOR_MAX 2 param set MPC_ACC_HOR_MAX 2
param set MPC_LAND_SPEED 1.2 param set MPC_LAND_SPEED 1.2
param set MPC_TILTMAX_LND 35 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_UP 1.5
param set MPC_Z_VEL_MAX_DN 1.5 param set MPC_Z_VEL_MAX_DN 1.5
param set MPC_HOLD_MAX_XY 0.5 param set MPC_HOLD_MAX_XY 0.5
@@ -54,17 +54,13 @@
#include <px4_platform_common/px4_work_queue/ScheduledWorkItem.hpp> #include <px4_platform_common/px4_work_queue/ScheduledWorkItem.hpp>
#include <systemlib/err.h> #include <systemlib/err.h>
#include <parameters/param.h> #include <parameters/param.h>
#include <systemlib/mavlink_log.h>
#include <uORB/Publication.hpp> #include <uORB/Publication.hpp>
#include <uORB/Subscription.hpp> #include <uORB/Subscription.hpp>
#include <uORB/topics/camera_trigger.h> #include <uORB/topics/camera_trigger.h>
#include <uORB/topics/camera_capture.h>
#include <uORB/topics/sensor_combined.h>
#include <uORB/topics/vehicle_command.h> #include <uORB/topics/vehicle_command.h>
#include <uORB/topics/vehicle_command_ack.h> #include <uORB/topics/vehicle_command_ack.h>
#include <uORB/topics/vehicle_local_position.h> #include <uORB/topics/vehicle_local_position.h>
#include <uORB/topics/vehicle_global_position.h>
#include <drivers/drv_hrt.h> #include <drivers/drv_hrt.h>
@@ -679,7 +679,7 @@ PARAM_DEFINE_FLOAT(MPC_YAWRAUTO_MAX, 45.0f);
* *
* Below this altitude: * Below this altitude:
* - descending velocity gets limited to a value * - 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 * - horizontal velocity gets limited to a value
* between "MPC_VEL_MANUAL" and "MPC_LAND_VEL_XY" * between "MPC_VEL_MANUAL" and "MPC_LAND_VEL_XY"
* for a smooth descent and landing experience. * for a smooth descent and landing experience.