Skip to content

Commit 26cbdd9

Browse files
abaghiyantridge
authored andcommitted
Plane: Fixed formula for load factor
In general when there the pitch and roll exist the formula for the aerodynamic load factor should be as follows: aerodynamic_load_factor = cosf(radians(_ahrs.pitch))/cosf(radians(demanded_roll)); which in case of turns (in the horizontal plane) becomes aerodynamic_load_factor = 1.0f/cosf(radians(demanded_roll)); formulas can be obtained from equations of balanced spiral: liftForce * cos(roll) = gravityForce * cos(pitch); liftForce * sin(roll) = gravityForce * lateralAcceleration / gravityAcceleration; // as mass = gravityForce/gravityAcceleration see issue #24320 [#24320]. To connect loadFactor to airspeed we can use formula of balancing between lift force and gravity force: liftForce = loadFactor * gravityForce; on the other hand lift force can be expressed as liftForce = 0.5 * lifCoefficient * airDensity * sq(airspeed) * referenceArea; minimum airseepd is at loadFactor = 1 and lift force only balances the gravit force, so gravity force (which is same as lift force at minimum airspeed) with minimum airspeed can be expressed as gravityForce = 0.5 * lifCoefficient * airDensity * sq(airspeed_min) * referenceArea; substituting gravit force in previous formula gives us 0.5 * lifCoefficient * airDensity * sq(airspeed) * referenceArea = loadFactor * 0.5 * lifCoefficient * airDensity * sq(airspeed_min) * referenceArea; from where we get: loadFactor = sq(airspeed / airspeed_min); These changes also require changes in ardupilot/libraries/AP_TECS/AP_TECS.cpp Line 418 (according to the comments by Peter Hall): _TASmin *= _load_factor; should be changed to _TASmin *= safe_sqrt(_load_factor); See details here: #24320
1 parent 1f3279c commit 26cbdd9

File tree

2 files changed

+8
-5
lines changed

2 files changed

+8
-5
lines changed

ArduPlane/Attitude.cpp

+7-4
Original file line numberDiff line numberDiff line change
@@ -633,7 +633,9 @@ void Plane::update_load_factor(void)
633633
// limit to 85 degrees to prevent numerical errors
634634
demanded_roll = 85;
635635
}
636-
aerodynamic_load_factor = 1.0f / safe_sqrt(cosf(radians(demanded_roll)));
636+
637+
// loadFactor = liftForce / gravityForce, where gravityForce = liftForce * cos(roll) on balanced horizontal turn
638+
aerodynamic_load_factor = 1.0f / cosf(radians(demanded_roll));
637639

638640
#if HAL_QUADPLANE_ENABLED
639641
if (quadplane.available() && quadplane.transition->set_FW_roll_limit(roll_limit_cd)) {
@@ -657,7 +659,8 @@ void Plane::update_load_factor(void)
657659
}
658660
#endif
659661

660-
float max_load_factor = smoothed_airspeed / MAX(aparm.airspeed_min, 1);
662+
float max_load_factor = sq(smoothed_airspeed / MAX(aparm.airspeed_min, 1));
663+
661664
if (max_load_factor <= 1) {
662665
// our airspeed is below the minimum airspeed. Limit roll to
663666
// 25 degrees
@@ -670,11 +673,11 @@ void Plane::update_load_factor(void)
670673
// allow at least 25 degrees of roll however, to ensure the
671674
// aircraft can be manoeuvred with a bad airspeed estimate. At
672675
// 25 degrees the load factor is 1.1 (10%)
673-
int32_t roll_limit = degrees(acosf(sq(1.0f / max_load_factor)))*100;
676+
int32_t roll_limit = degrees(acosf(1.0f / max_load_factor))*100;
674677
if (roll_limit < 2500) {
675678
roll_limit = 2500;
676679
}
677680
nav_roll_cd = constrain_int32(nav_roll_cd, -roll_limit, roll_limit);
678681
roll_limit_cd = MIN(roll_limit_cd, roll_limit);
679-
}
682+
}
680683
}

ArduPlane/Plane.h

+1-1
Original file line numberDiff line numberDiff line change
@@ -668,7 +668,7 @@ class Plane : public AP_Vehicle {
668668
int32_t nav_pitch_cd;
669669

670670
// the aerodynamic load factor. This is calculated from the demanded
671-
// roll before the roll is clipped, using 1/sqrt(cos(nav_roll))
671+
// roll before the roll is clipped, using 1/cos(nav_roll)
672672
float aerodynamic_load_factor = 1.0f;
673673

674674
// a smoothed airspeed estimate, used for limiting roll angle

0 commit comments

Comments
 (0)