mirror of https://github.com/ArduPilot/ardupilot
Plane: tidy 2 comments
This commit is contained in:
parent
f51fa31aae
commit
a4302e5fb8
|
@ -1627,7 +1627,7 @@ void SLT_Transition::update()
|
|||
gcs().send_text(MAV_SEVERITY_CRITICAL, "Transition failed, exceeded time limit");
|
||||
quadplane.transition_failure.warned = true;
|
||||
}
|
||||
// if option is set and ground speed> 1/2 arspd_fbw_min for non-tiltrotors, then complete transition, otherwise QLAND.
|
||||
// if option is set and ground speed> 1/2 AIRSPEED_MIN for non-tiltrotors, then complete transition, otherwise QLAND.
|
||||
// tiltrotors will immediately transition
|
||||
const bool tiltrotor_with_ground_speed = quadplane.tiltrotor.enabled() && (plane.ahrs.groundspeed() > plane.aparm.airspeed_min * 0.5);
|
||||
if (quadplane.option_is_set(QuadPlane::OPTION::TRANS_FAIL_TO_FW) && tiltrotor_with_ground_speed) {
|
||||
|
|
|
@ -158,7 +158,7 @@ void Plane::takeoff_calc_roll(void)
|
|||
takeoff_roll_limit_cd = g.level_roll_limit * 100;
|
||||
} else {
|
||||
// lim1 - below altitude TKOFF_LVL_ALT, restrict roll to LEVEL_ROLL_LIMIT
|
||||
// lim2 - above altitude (TKOFF_LVL_ALT * 3) allow full flight envelope of LIM_ROLL_CD
|
||||
// lim2 - above altitude (TKOFF_LVL_ALT * 3) allow full flight envelope of ROLL_LIMIT_DEG
|
||||
// In between lim1 and lim2 use a scaled roll limit.
|
||||
// The *3 scheme should scale reasonably with both small and large aircraft
|
||||
const float lim1 = MAX(mode_takeoff.level_alt, 0);
|
||||
|
|
Loading…
Reference in New Issue