aboutsummaryrefslogtreecommitdiff
path: root/src
diff options
context:
space:
mode:
authorThomas Gubler <thomasgubler@gmail.com>2014-12-13 17:13:20 +0100
committerThomas Gubler <thomasgubler@gmail.com>2014-12-13 17:20:42 +0100
commitd0325f2b125a3573231443b7b4bac04b65081426 (patch)
tree3ed220b3eae23998a7cff80ae2397ab7dd8b825c /src
parenta78264507e510d75b8694e3a0ec7c2acd35ea1e3 (diff)
downloadpx4-firmware-d0325f2b125a3573231443b7b4bac04b65081426.tar.gz
px4-firmware-d0325f2b125a3573231443b7b4bac04b65081426.tar.bz2
px4-firmware-d0325f2b125a3573231443b7b4bac04b65081426.zip
fw pos ctrl: takeoff special case only in takeoff
Diffstat (limited to 'src')
-rw-r--r--src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp51
1 files changed, 27 insertions, 24 deletions
diff --git a/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp b/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp
index 1592e70d8..eec37f80c 100644
--- a/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp
+++ b/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp
@@ -1207,15 +1207,15 @@ FixedwingPositionControl::control_position(const math::Vector<2> &current_positi
tecs_update_pitch_throttle(_pos_sp_triplet.current.alt,
calculate_target_airspeed(_parameters.airspeed_trim),
eas2tas,
- math::radians(_parameters.pitch_limit_min),
- math::radians(_parameters.pitch_limit_max),
- _parameters.throttle_min,
- takeoff_throttle,
- _parameters.throttle_cruise,
- false,
- math::radians(_parameters.pitch_limit_min),
- _global_pos.alt,
- ground_speed);
+ math::radians(_parameters.pitch_limit_min),
+ math::radians(_parameters.pitch_limit_max),
+ _parameters.throttle_min,
+ takeoff_throttle,
+ _parameters.throttle_cruise,
+ false,
+ math::radians(_parameters.pitch_limit_min),
+ _global_pos.alt,
+ ground_speed);
}
} else {
/* Tell the attitude controller to stop integrating while we are waiting
@@ -1290,18 +1290,18 @@ FixedwingPositionControl::control_position(const math::Vector<2> &current_positi
was_in_deadband = true;
}
tecs_update_pitch_throttle(_hold_alt,
- altctrl_airspeed,
- eas2tas,
- math::radians(_parameters.pitch_limit_min),
- math::radians(_parameters.pitch_limit_max),
- _parameters.throttle_min,
- _parameters.throttle_max,
- _parameters.throttle_cruise,
- false,
- math::radians(_parameters.pitch_limit_min),
- _global_pos.alt,
- ground_speed,
- TECS_MODE_NORMAL);
+ altctrl_airspeed,
+ eas2tas,
+ math::radians(_parameters.pitch_limit_min),
+ math::radians(_parameters.pitch_limit_max),
+ _parameters.throttle_min,
+ _parameters.throttle_max,
+ _parameters.throttle_cruise,
+ false,
+ math::radians(_parameters.pitch_limit_min),
+ _global_pos.alt,
+ ground_speed,
+ TECS_MODE_NORMAL);
} else {
_control_mode_current = FW_POSCTRL_MODE_OTHER;
@@ -1320,10 +1320,12 @@ FixedwingPositionControl::control_position(const math::Vector<2> &current_positi
}
}
+ /* Copy thrust output for publication */
if (_vehicle_status.engine_failure || _vehicle_status.engine_failure_cmd) {
/* Set thrust to 0 to minimize damage */
_att_sp.thrust = 0.0f;
- } else if (pos_sp_triplet.current.type == SETPOINT_TYPE_TAKEOFF &&
+ } else if (_control_mode_current == FW_POSCTRL_MODE_AUTO && // launchdetector only available in auot
+ pos_sp_triplet.current.type == SETPOINT_TYPE_TAKEOFF &&
launch_detection_state != LAUNCHDETECTION_RES_DETECTED_ENABLEMOTORS) {
/* making sure again that the correct thrust is used,
* without depending on library calls for safety reasons */
@@ -1336,8 +1338,9 @@ FixedwingPositionControl::control_position(const math::Vector<2> &current_positi
/* During a takeoff waypoint while waiting for launch the pitch sp is set
* already (not by tecs) */
- if (!(pos_sp_triplet.current.type == SETPOINT_TYPE_TAKEOFF &&
- launch_detection_state == LAUNCHDETECTION_RES_NONE)) {
+ if (!(_control_mode_current == FW_POSCTRL_MODE_AUTO &&
+ pos_sp_triplet.current.type == SETPOINT_TYPE_TAKEOFF &&
+ launch_detection_state == LAUNCHDETECTION_RES_NONE)) {
_att_sp.pitch_body = _mTecs.getEnabled() ? _mTecs.getPitchSetpoint() : _tecs.get_pitch_demand();
}