aboutsummaryrefslogtreecommitdiff
path: root/src/modules
diff options
context:
space:
mode:
authorsjwilks <sjwilks@gmail.com>2014-09-11 09:49:14 +0200
committersjwilks <sjwilks@gmail.com>2014-09-11 09:49:14 +0200
commit852b36661d5f03d76c8217444554122c3cadfba0 (patch)
tree3814de9a3f7bd92c68f38975184f86139accef29 /src/modules
parente4f3fd88f0623659e6759b9b076be15e4e2f5703 (diff)
parent26e6d7e12e5036b0e3008b0543d7771d3e527a39 (diff)
downloadpx4-firmware-852b36661d5f03d76c8217444554122c3cadfba0.tar.gz
px4-firmware-852b36661d5f03d76c8217444554122c3cadfba0.tar.bz2
px4-firmware-852b36661d5f03d76c8217444554122c3cadfba0.zip
Merge pull request #1356 from PX4/launchpitchlimit_master
FW: additional upper pitch limit during launch
Diffstat (limited to 'src/modules')
-rw-r--r--src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp28
1 files changed, 22 insertions, 6 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 d339b1c4d..23167eef4 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
@@ -383,7 +383,8 @@ private:
bool climbout_mode, float climbout_pitch_min_rad,
float altitude,
const math::Vector<3> &ground_speed,
- tecs_mode mode = TECS_MODE_NORMAL);
+ tecs_mode mode = TECS_MODE_NORMAL,
+ bool pitch_max_special = false);
};
@@ -1120,7 +1121,13 @@ FixedwingPositionControl::control_position(const math::Vector<2> &current_positi
LAUNCHDETECTION_RES_DETECTED_ENABLEMOTORS ?
launchDetector.getThrottlePreTakeoff() : _parameters.throttle_max;
- /* apply minimum pitch and limit roll if target altitude is not within 10 meters */
+ /* select maximum pitch: the launchdetector may impose another limit for the pitch
+ * depending on the state of the launch */
+ float takeoff_pitch_max_deg = launchDetector.getPitchMax(_parameters.pitch_limit_max);
+ float takeoff_pitch_max_rad = math::radians(takeoff_pitch_max_deg);
+
+ /* apply minimum pitch and limit roll if target altitude is not within climbout_diff
+ * meters */
if (_parameters.climbout_diff > 0.001f && altitude_error > _parameters.climbout_diff) {
/* enforce a minimum of 10 degrees pitch up on takeoff, or take parameter */
@@ -1128,7 +1135,7 @@ FixedwingPositionControl::control_position(const math::Vector<2> &current_positi
calculate_target_airspeed(1.3f * _parameters.airspeed_min),
eas2tas,
math::radians(_parameters.pitch_limit_min),
- math::radians(_parameters.pitch_limit_max),
+ takeoff_pitch_max_rad,
_parameters.throttle_min, takeoff_throttle,
_parameters.throttle_cruise,
true,
@@ -1136,7 +1143,8 @@ FixedwingPositionControl::control_position(const math::Vector<2> &current_positi
math::radians(10.0f)),
_global_pos.alt,
ground_speed,
- TECS_MODE_TAKEOFF);
+ TECS_MODE_TAKEOFF,
+ takeoff_pitch_max_deg != _parameters.pitch_limit_max);
/* limit roll motion to ensure enough lift */
_att_sp.roll_body = math::constrain(_att_sp.roll_body, math::radians(-15.0f),
@@ -1204,7 +1212,7 @@ FixedwingPositionControl::control_position(const math::Vector<2> &current_positi
/* Copy thrust and pitch values from tecs
* making sure again that the correct thrust is used,
- * without depending on library calls */
+ * without depending on library calls for safety reasons */
if (pos_sp_triplet.current.type == SETPOINT_TYPE_TAKEOFF &&
launch_detection_state != LAUNCHDETECTION_RES_DETECTED_ENABLEMOTORS) {
_att_sp.thrust = launchDetector.getThrottlePreTakeoff();
@@ -1390,7 +1398,7 @@ void FixedwingPositionControl::tecs_update_pitch_throttle(float alt_sp, float v_
bool climbout_mode, float climbout_pitch_min_rad,
float altitude,
const math::Vector<3> &ground_speed,
- tecs_mode mode)
+ tecs_mode mode, bool pitch_max_special)
{
if (_mTecs.getEnabled()) {
/* Using mtecs library: prepare arguments for mtecs call */
@@ -1405,6 +1413,14 @@ void FixedwingPositionControl::tecs_update_pitch_throttle(float alt_sp, float v_
} else {
limitOverride.disablePitchMinOverride();
}
+
+ if (pitch_max_special) {
+ /* Use the maximum pitch from the argument */
+ limitOverride.enablePitchMaxOverride(M_RAD_TO_DEG_F * pitch_max_rad);
+ } else {
+ /* use pitch max set by MT param */
+ limitOverride.disablePitchMaxOverride();
+ }
_mTecs.updateAltitudeSpeed(flightPathAngle, altitude, alt_sp, _airspeed.true_airspeed_m_s, v_sp, mode,
limitOverride);
} else {