mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 00:28:30 -04:00
Plane: remove trig calls from constexpr
This commit is contained in:
parent
494a3f86ad
commit
b3f093b877
@ -269,12 +269,18 @@ void QuadPlane::tailsitter_speed_scaling(void)
|
|||||||
} else {
|
} else {
|
||||||
// if no airspeed sensor reduce control surface throws at large tilt
|
// if no airspeed sensor reduce control surface throws at large tilt
|
||||||
// angles (assuming high airspeed)
|
// angles (assuming high airspeed)
|
||||||
|
|
||||||
// ramp down from 1 to max_atten at tilt angles over trans_angle
|
// ramp down from 1 to max_atten at tilt angles over trans_angle
|
||||||
// (angles here are represented by their cosines)
|
// (angles here are represented by their cosines)
|
||||||
constexpr float c_trans_angle = cosf(.125f * M_PI);
|
|
||||||
constexpr float alpha = (1 - max_atten) / (c_trans_angle - cosf(radians(90)));
|
// Note that the cosf call will be necessary if trans_angle becomes a parameter
|
||||||
|
// but the C language spec does not guarantee that trig functions can be used
|
||||||
|
// in constant expressions, even though gcc currently allows it.
|
||||||
|
constexpr float c_trans_angle = 0.9238795; // cosf(.125f * M_PI)
|
||||||
|
|
||||||
|
// alpha = (1 - max_atten) / (c_trans_angle - cosf(radians(90)));
|
||||||
|
constexpr float alpha = (1 - max_atten) / c_trans_angle;
|
||||||
constexpr float beta = 1 - alpha * c_trans_angle;
|
constexpr float beta = 1 - alpha * c_trans_angle;
|
||||||
|
|
||||||
const float c_tilt = ahrs_view->get_rotation_body_to_ned().c.z;
|
const float c_tilt = ahrs_view->get_rotation_body_to_ned().c.z;
|
||||||
if (c_tilt < c_trans_angle) {
|
if (c_tilt < c_trans_angle) {
|
||||||
spd_scaler = constrain_float(beta + alpha * c_tilt, max_atten, 1.0f);
|
spd_scaler = constrain_float(beta + alpha * c_tilt, max_atten, 1.0f);
|
||||||
|
Loading…
Reference in New Issue
Block a user