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

Lua Script for copter CoM compensation #27402

Merged
merged 1 commit into from
Jul 3, 2024

Conversation

Georacer
Copy link
Contributor

@Georacer Georacer commented Jun 27, 2024

This PR is a script that corrects for the CoM discrepancy in a quad-X frame. It is applicable both in Copter and (quad)Plane.
I guess it's what #17461 was envisioned for.

It uses the dynamic mixer matrix to update the front-to-back thrust ratio on the fly.

I've been testing with RealFlight on this model, after "bringing it close to reality" by reverting the "cheat" I had made in the motor positions:
Screenshot from 2024-06-24 19-45-46

The issue with this model is that due to the CoM misplacement, a throttle-up causes a pitch-down. The script corrects the buildup of the pitch I-term and suppresses the pitch-down motion upon throttling up.

The results have been documented in this blog post.

If you think this script is too dangerous to exist in the applets directory, I'm happy with it being in the examples too.

@Georacer Georacer marked this pull request as draft June 27, 2024 17:15
@Georacer Georacer force-pushed the script-copter-cg-allocation branch 4 times, most recently from d75c672 to 8a010a3 Compare July 1, 2024 17:56
@Georacer Georacer marked this pull request as ready for review July 1, 2024 17:56
@Georacer Georacer changed the title WIP: Script copter cg allocation Lua Script for copter CoM compensation Jul 1, 2024
Copy link
Member

@IamPete1 IamPete1 left a comment

Choose a reason for hiding this comment

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

Dynamic mixer is great for finding the correct value, but it would be nice to transition people onto the normal mixer. Then you can just have a script that runs at boot with no callbacks. I think the load_factors call skips the normalization step that we do on a "normal" matrix. So there could be some change in tune.

end

-- Start running update loop
return protected_wrapper()
Copy link
Member

Choose a reason for hiding this comment

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

Suggested change
return protected_wrapper()
return protected_wrapper()

Main loop function
--]]
function update()
fsm_step()
Copy link
Member

Choose a reason for hiding this comment

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

You might as well call this directly

@Georacer
Copy link
Contributor Author

Georacer commented Jul 1, 2024

Dynamic mixer is great for finding the correct value, but it would be nice to transition people onto the normal mixer. Then you can just have a script that runs at boot with no callbacks. I think the load_factors call skips the normalization step that we do on a "normal" matrix. So there could be some change in tune.

@IamPete1 A static mixer would definitely bring better performance, agreed. But I really wanted to be able to tune on the fly.
How does the idea that I modify the present script so that it switches between dynamic and static based on a parameter sound?

@IamPete1
Copy link
Member

IamPete1 commented Jul 1, 2024

@IamPete1 A static mixer would definitely bring better performance, agreed. But I really wanted to be able to tune on the fly.
How does the idea that I modify the present script so that it switches between dynamic and static based on a parameter sound?

You could check if you can see the Motors_dynamic or AP_MotorsMatrix singletons so it would switch based on frame class.

@tridge
Copy link
Contributor

tridge commented Jul 2, 2024

this is so common that I wonder if a param in the C++ code is warranted?

@Georacer
Copy link
Contributor Author

Georacer commented Jul 2, 2024

this is so common that I wonder if a param in the C++ code is warranted?

You mean skip the .lua script entirely and implement this in C++? If so, I'd like to have this merged first and then dive into those deep waters 😅.

@Georacer
Copy link
Contributor Author

Georacer commented Jul 2, 2024

Dynamic mixer is great for finding the correct value, but it would be nice to transition people onto the normal mixer. Then you can just have a script that runs at boot with no callbacks. I think the load_factors call skips the normalization step that we do on a "normal" matrix. So there could be some change in tune.

How about I add the normalization step to the AP_MotorsMatrix_Scripting_Dynamic::init() as well?

@IamPete1
Copy link
Member

IamPete1 commented Jul 2, 2024

this is so common that I wonder if a param in the C++ code is warranted?

Using throttle factors does add some inaccuracy in the mixer. We do the full mix and then apply throttle factors afterwards, so there not taken into account for the saturation handling. Unless there is a quite significant issue its probably better not to set them and I would not recommend large values at all. As ever, a hardware fix is better if possible.

How about I add the normalization step to the AP_MotorsMatrix_Scripting_Dynamic::init() as well?

You would have to do it on every call to load_factors. I think its fine that the dynamic mix doesn't do it automatically. You could add it in the script. They thing is that if you do the normalization then you can use the same mix with both scripting mixers.

@Georacer
Copy link
Contributor Author

Georacer commented Jul 2, 2024

@IamPete1 A static mixer would definitely bring better performance, agreed. But I really wanted to be able to tune on the fly.
How does the idea that I modify the present script so that it switches between dynamic and static based on a parameter sound?

You could check if you can see the Motors_dynamic or AP_MotorsMatrix singletons so it would switch based on frame class.

@IamPete1 is this what you meant?

    if MotorsMatrix then
        is_mixer_matrix_static = true
        warn_user("Found static mixer", MAV_SEVERITY.INFO)
    end

This check follows the truthy path even if Q_FRAME_CLASS=1.
Did you have another check in mind?

@Georacer Georacer force-pushed the script-copter-cg-allocation branch from 8a010a3 to af3c4d3 Compare July 2, 2024 14:00
@Georacer
Copy link
Contributor Author

Georacer commented Jul 2, 2024

@IamPete1 I've pushed another another version.

I've managed to implement dual operation, both dynamic and static scriptable matrices.
The switch is done via the [Q_]FRAME_CLASS parameter. I wasn't sure how to achieve it via the singletons.

Both use the same factors, normalized to have max 1.

I've tested it in RealFlight. Some examples:

When Q_FRAME_CLASS=1:
Screenshot from 2024-07-02 15-15-32

Operation in Q_FRAME_CLASS=17:
Screenshot from 2024-07-02 15-46-10

Operation in Q_FRAME_CLASS=15
Screenshot from 2024-07-02 15-49-19

Do you require any more specific testing?

The script uses the scripting matrix to produce non-equal
front and back thrust, compensating for the lever arm between the center
of thrust and the center of mass.
@Georacer Georacer force-pushed the script-copter-cg-allocation branch from af3c4d3 to 02ea9d1 Compare July 2, 2024 14:30
@Georacer
Copy link
Contributor Author

Georacer commented Jul 2, 2024

Got another update in, to delete two unused variables.
For some reason run_lua_language_check.py didn't catch them.

❯ ./Tools/scripts/run_lua_language_check.py libraries/AP_Scripting/applets/x-quad-cg-allocation.lua
Initializing ...
>>>>>>>>>>========== 1/2
>>>>>>>>>>>>>>>>>>>> 2/2
Diagnosis completed, no problems found
2 Files checked

@IamPete1
Copy link
Member

IamPete1 commented Jul 2, 2024

I wasn't sure how to achieve it via the singletons.

I think you can just see if the singleton is nil. Something like:

if Motors_dynamic then

else if AP_MotorsMatrix then

end

For some reason run_lua_language_check.py didn't catch them.

Yeah, it doesn't get everything. The other one, run_luacheck might get them tho.

@Georacer
Copy link
Contributor Author

Georacer commented Jul 2, 2024

I think you can just see if the singleton is nil.

I had tried the following before, but I believe was getting exceptions.

-- Decide if the UA is using a static mixer matrix.
function inspect_mixer_matrix_static()
    if MotorsMatrix then
        is_mixer_matrix_static = true
        warn_user("Found static mixer", MAV_SEVERITY.INFO)
    end
end

-- Decide if the UA is using a dynamic mixer matrix.
function inspect_mixer_matrix_dynamic()
    if Motors_dynamic then
        is_mixer_matrix_dynamic = true
        warn_user("Found dynamic mixer", MAV_SEVERITY.INFO)
    end
end

@tridge tridge merged commit 61c910b into ArduPilot:master Jul 3, 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.

4 participants