Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Legibility changes #27124

Merged
merged 4 commits into from
Jun 19, 2024
Merged

Legibility changes #27124

merged 4 commits into from
Jun 19, 2024

Conversation

Georacer
Copy link
Contributor

This PR is two small legibility improvements in TECS.cpp

It also adds small typo fixes I did while reading TECS.cpp.

Copy link
Contributor

@magicrub magicrub left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

The K_thr2STE maths is not equivalent, just remove that bit now. The other changes look OK

@@ -749,7 +749,7 @@ void AP_TECS::_update_throttle_with_airspeed(void)
// drag increase during turns.
const float cosPhi = sqrtf((rotMat.a.y*rotMat.a.y) + (rotMat.b.y*rotMat.b.y));
STEdot_dem = STEdot_dem + _rollComp * (1.0f/constrain_float(cosPhi * cosPhi, 0.1f, 1.0f) - 1.0f);
const float ff_throttle = nomThr + STEdot_dem / (_STEdot_max - _STEdot_min) * (_THRmaxf - _THRminf);
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

this is not equivalent. The const var is doing / and this one is doing *.

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I did the math on my mind, with pencil and paper and here too:

nomThr + STEdot_dem / (_STEdot_max - _STEdot_min) * (_THRmaxf - _THRminf) =
nomThr + STEdot_dem * (_THRmaxf - _THRminf) / (_STEdot_max - _STEdot_min) =
nomThr + STEdot_dem * ( (_THRmaxf - _THRminf) / (_STEdot_max - _STEdot_min) ) =
nomThr + STEdot_dem / ( (_STEdot_max - _STEdot_min) / (_THRmaxf - _THRminf) ) =
nomThr + STEdot_dem / K_thr2STE

Perhaps you can give it another look?

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Not sure why it fails the CI, though.

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I think this is correct, should be checked again
@magicrub note the lack of () in the original, makes it on the numerator

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Ping @magicrub

@Georacer Georacer force-pushed the legibility_changes branch 2 times, most recently from 9752697 to b08a305 Compare May 29, 2024 21:40
@peterbarker
Copy link
Contributor

I tested this PR with this patch on top:

diff --git a/libraries/AP_TECS/AP_TECS.cpp b/libraries/AP_TECS/AP_TECS.cpp
index 9307502caaf..86a07566b7d 100644
--- a/libraries/AP_TECS/AP_TECS.cpp
+++ b/libraries/AP_TECS/AP_TECS.cpp
@@ -740,6 +740,10 @@ void AP_TECS::_update_throttle_with_airspeed(void)
         // Calculate gain scaler from specific energy error to throttle
         const float K_thr2STE = (_STEdot_max - _STEdot_min) / (_THRmaxf - _THRminf); // This is the derivative of STEdot wrt throttle measured across the max allowed throttle range.
         const float K_STE2Thr = 1 / (timeConstant() * K_thr2STE);
+        const float old_K_STE2Thr = 1 / (timeConstant() * (_STEdot_max - _STEdot_min) / (_THRmaxf - _THRminf));
+        if (!is_zero(K_STE2Thr-old_K_STE2Thr)) {
+            abort();
+        }
 
         // Calculate feed-forward throttle
         const float nomThr = aparm.throttle_cruise * 0.01f;
@@ -750,6 +754,10 @@ void AP_TECS::_update_throttle_with_airspeed(void)
         const float cosPhi = sqrtf((rotMat.a.y*rotMat.a.y) + (rotMat.b.y*rotMat.b.y));
         STEdot_dem = STEdot_dem + _rollComp * (1.0f/constrain_float(cosPhi * cosPhi, 0.1f, 1.0f) - 1.0f);
         const float ff_throttle = nomThr + STEdot_dem / K_thr2STE;
+        const float old_ff_throttle = nomThr + STEdot_dem / (_STEdot_max - _STEdot_min) * (_THRmaxf - _THRminf);
+        if (!is_zero(ff_throttle-old_ff_throttle)) {
+            abort();
+        }
 
         // Calculate PD + FF throttle
         float throttle_damp = _thrDamp;

... and there were not aborts.

Merging as agreed on DevCall last night.

@peterbarker peterbarker merged commit 5ca8c00 into ArduPilot:master Jun 19, 2024
93 checks passed
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

Successfully merging this pull request may close these issues.

6 participants