Skip to content

Commit

Permalink
mc_pos_control: prevent takeoff with thrust setpoint
Browse files Browse the repository at this point in the history
This was only necessary for stabilized mode before #10805.
The  unit length thrust setpoint will anyways not be available
anymore soon because it gets replaced with the acceleration
setpoint in m/s².
  • Loading branch information
MaEtUgR committed Mar 18, 2020
1 parent 1f98ebd commit 3049a3d
Showing 1 changed file with 3 additions and 3 deletions.
6 changes: 3 additions & 3 deletions src/modules/mc_pos_control/mc_pos_control_main.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -594,7 +594,7 @@ MulticopterPositionControl::Run()
}

// limit tilt during takeoff ramupup
if (_takeoff.getTakeoffState() < TakeoffState::flight && !PX4_ISFINITE(setpoint.thrust[2])) {
if (_takeoff.getTakeoffState() < TakeoffState::flight) {
constraints.tilt = math::radians(_param_mpc_tiltmax_lnd.get());
}

Expand All @@ -608,7 +608,7 @@ MulticopterPositionControl::Run()
constraints.speed_up, !_control_mode.flag_control_climb_rate_enabled, time_stamp_now);
constraints.speed_up = _takeoff.updateRamp(_dt, constraints.speed_up);

if (_takeoff.getTakeoffState() < TakeoffState::rampup && !PX4_ISFINITE(setpoint.thrust[2])) {
if (_takeoff.getTakeoffState() < TakeoffState::rampup) {
// we are not flying yet and need to avoid any corrections
reset_setpoint_to_nan(setpoint);
setpoint.thrust[0] = setpoint.thrust[1] = setpoint.thrust[2] = 0.0f;
Expand Down Expand Up @@ -664,7 +664,7 @@ MulticopterPositionControl::Run()
// Part of landing logic: if ground-contact/maybe landed was detected, turn off
// controller. This message does not have to be logged as part of the vehicle_local_position_setpoint topic.
// Note: only adust thrust output if there was not thrust-setpoint demand in D-direction.
if (_takeoff.getTakeoffState() > TakeoffState::rampup && !PX4_ISFINITE(setpoint.thrust[2])) {
if (_takeoff.getTakeoffState() > TakeoffState::rampup) {
limit_thrust_during_landing(attitude_setpoint);
}

Expand Down

0 comments on commit 3049a3d

Please sign in to comment.