From 1d43974944d7f7fa92a4f9ff05c97043dbdcae94 Mon Sep 17 00:00:00 2001 From: bresch Date: Wed, 3 Jul 2019 16:52:27 +0200 Subject: [PATCH] MC pos control - Force cruise and manual speeds below max speed. Force hover thrust between min and max thrust --- .../mc_pos_control/mc_pos_control_main.cpp | 27 +++++++++++++++++++ 1 file changed, 27 insertions(+) diff --git a/src/modules/mc_pos_control/mc_pos_control_main.cpp b/src/modules/mc_pos_control/mc_pos_control_main.cpp index b96ef25e47c0..d2c7cfb30038 100644 --- a/src/modules/mc_pos_control/mc_pos_control_main.cpp +++ b/src/modules/mc_pos_control/mc_pos_control_main.cpp @@ -109,6 +109,7 @@ class MulticopterPositionControl : public ModuleBase orb_advert_t _att_sp_pub{nullptr}; /**< attitude setpoint publication */ orb_advert_t _pub_vehicle_command{nullptr}; /**< vehicle command publication */ + orb_advert_t _mavlink_log_pub{nullptr}; orb_id_t _attitude_setpoint_id{nullptr}; @@ -147,6 +148,9 @@ class MulticopterPositionControl : public ModuleBase DEFINE_PARAMETERS( (ParamFloat) _param_mpc_tko_ramp_t, /**< time constant for smooth takeoff ramp */ + (ParamFloat) _param_mpc_xy_vel_max, + (ParamFloat) _param_mpc_vel_manual, + (ParamFloat) _param_mpc_xy_cruise, (ParamFloat) _param_mpc_z_vel_max_up, (ParamFloat) _param_mpc_z_vel_max_dn, (ParamFloat) _param_mpc_land_speed, @@ -157,7 +161,9 @@ class MulticopterPositionControl : public ModuleBase (ParamInt) _param_mpc_alt_mode, (ParamFloat) _param_mpc_spoolup_time, /**< time to let motors spool up after arming */ (ParamFloat) _param_mpc_tiltmax_lnd, /**< maximum tilt for landing and smooth takeoff */ + (ParamFloat)_param_mpc_thr_min, (ParamFloat)_param_mpc_thr_hover, + (ParamFloat)_param_mpc_thr_max, (ParamFloat)_param_mpc_z_vel_p ); @@ -312,6 +318,27 @@ MulticopterPositionControl::parameters_update(bool force) ModuleParams::updateParams(); SuperBlock::updateParams(); + // Check that the design parameters are inside the absolute maximum constraints + if (_param_mpc_xy_cruise.get() > _param_mpc_xy_vel_max.get()) { + _param_mpc_xy_cruise.set(_param_mpc_xy_vel_max.get()); + _param_mpc_xy_cruise.commit(); + mavlink_log_critical(&_mavlink_log_pub, "Cruise speed has been constrained by max speed") + } + + if (_param_mpc_vel_manual.get() > _param_mpc_xy_vel_max.get()) { + _param_mpc_vel_manual.set(_param_mpc_xy_vel_max.get()); + _param_mpc_vel_manual.commit(); + mavlink_log_critical(&_mavlink_log_pub, "Manual speed has been constrained by max speed") + } + + if (_param_mpc_thr_hover.get() > _param_mpc_thr_max.get() || + _param_mpc_thr_hover.get() < _param_mpc_thr_min.get()) { + _param_mpc_thr_hover.set(math::constrain(_param_mpc_thr_hover.get(), _param_mpc_thr_min.get(), + _param_mpc_thr_max.get())); + _param_mpc_thr_hover.commit(); + mavlink_log_critical(&_mavlink_log_pub, "Hover thrust has been constrained by min/max") + } + _flight_tasks.handleParameterUpdate(); // initialize vectors from params and enforce constraints