Skip to content

Conversation

@Filipe-Cavalheiro
Copy link

Two new tools were implemented and one was updated

Summary

This pull request introduces two new tools and an update to Avl_automation, aiming to improve simulation accuracy and enhance aerodynamic modeling.

New Tool: QGC2ROMFS_parameters

  • Ensures that parameters set in QGroundControl (QGC) are correctly transferred to Gazebo.
  • Addresses a critical issue where discrepancies between QGC and Gazebo parameters caused severe crashes during real-world tests.
  • Can be executed manually or with a single-line command, as described in the README.

New Tool: ROMFS2QGC_parameters (In Development)

  • Enables the export of simulation-tuned parameters back to QGC for real-world use.
  • Provides an automated solution to ensure consistency between simulation and physical flight behavior.

Updated Tool: Avl_automation

  • Now supports multiple control surfaces per wing surface.
  • A new example has been added to demonstrate this feature.

Feedback & Next Steps

Any feedback is appreciated to ensure a smooth integration of these improvements. Let me know if anything needs adjustment!

Filipe-Cavalheiro and others added 8 commits February 18, 2025 16:11
…piler' since the more robust

surface definition is not compatible with the old yaml version

This new tool helps make the simulation more accurate by importing from QGC the parameters
and adding them to the gazebo sim

This tool is not complete and turns Gazebo parameters back to a .param file for QGC
Copied an actual error from the gazebo output to better show and explain why do errors appear on the first simulation run
README was updated to reflect this change
Copy link
Member

@Jaeyoung-Lim Jaeyoung-Lim left a comment

Choose a reason for hiding this comment

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

Thank you for the contribution!

  • Could you separate the two features to two different PRs?

  • I am not sure if I understand correctly the QGC2ROMFS feature. Wouldnt this be agnostic to the simulator used, and simply a separate tool for px4? Why is this useful for gazebo?

@Filipe-Cavalheiro
Copy link
Author

Hi @Jaeyoung-Lim,

Thank you for your reply.

I’ve only used Gazebo Classic, so I hadn’t considered the versatility of QGC2ROMFS across different simulators. As long as the parameter definition format remains consistent across all simulators, then yes! Both QGC2ROMFS and ROMFS2QGC will have a PR submitted to PX4, with only the updated AVL_automation remaining specific to Gazebo.

}
],
"version": 4
} No newline at end of file
Copy link
Member

Choose a reason for hiding this comment

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

Please remove vscode artifacts from the PR

@Jaeyoung-Lim
Copy link
Member

@Filipe-Cavalheiro There seems to be vscode artifacts and pycache submitted as part of the PR. After these are removed, I can review the PR

@Filipe-Cavalheiro
Copy link
Author

Hi @Jaeyoung-Lim,
The artifacts have been removed, apologies for the newbie mistake, and both QGC2ROMFS and ROMFS2QGC have been transferred to new PRs in the PX4 repository:

To be completely honest, I do believe that the AVL automation with multiple control surfaces per wing is functional. However, I haven’t been able to create a YAML file for AVL that I’m fully satisfied with. This is mainly because aerodynamics are outside my area of expertise so I believe that my definition of the wings (easy_glider4) is not totally correct.

@hamishwillee
Copy link

Assuming this changes the way the AVL tool is run, would be great if we could have a docs update after this merges: https://docs.px4.io/main/en/sim_gazebo_gz/tools_avl_automation.html#advanced-lift-drag-avl-automation-tool

Previously, the parser incorrectly assumed that the second aileron in AVL output should be inverted for differential control. However, AVL only outputs values for one of the symmetric control surfaces, requiring manual inversion if needed (e.g., for ailerons). The parser has been updated to invert the *first* aileron instead.

This fix corrects control behavior in Gazebo/QGroundControl simulations, particularly for the Easy Glider 4 model, which now responds as expected under autonomous control.

Note: This fix is based on simulation results only; no real-world flight tests have been conducted to validate the parser/model accuracy.
@Filipe-Cavalheiro Filipe-Cavalheiro changed the title Implemented QGC-Gazebo Parameter Sync Tools & Avl_automation Enhancements Implemented Avl_automation Enhancements Apr 14, 2025
@Filipe-Cavalheiro
Copy link
Author

Hi @hamishwillee,
I've updated the README to reflect the new usage of the AVL automation. No changes were made directly to AVL—only to the parsers: from YAML to AVL (input_parser) and from AVL output to Gazebo (avl_output).

I have finally also discovered what was wrong with the parser and fixed it, the easy glider 4 now works as expected, further details located in the commit Fix aileron inversion logic in AVL output parser.

As always, any changes needed to get this push through are more than welcome.

@hamishwillee
Copy link

Thanks. I'm on holiday. If no one else gets to this, I will check it out in 2 weeks.

@@ -0,0 +1,335 @@
#!/usr/bin/env

Copy link
Member

Choose a reason for hiding this comment

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

What is the difference with this and the original avl_out_parse_0_0.py? Shouldn't they be one file?

Copy link
Author

Choose a reason for hiding this comment

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

The main difference between this and the original avl_out_parse_0_0.py is that the new version includes some variable name changes and updates to how the received data is parsed for Gazebo. Specifically, this commit corrects the inversion order of the ailerons in the simulation, which was necessary for proper behavior in Gazebo.

If it's deemed better for clarity and maintenance, we can remove avl_out_parse_0_0.py entirely and just use the updated version going forward.

Copy link
Member

Choose a reason for hiding this comment

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

The problem is that it is not even clear what have changed between the two PRs making it hard to review. If you think it is an improvement please change the file.


# Call main function of avl parse script to parse the generated AVL files.
avl_out_parse.main(plane_name,frame_type,AR,mac,ref_pt_x,ref_pt_y,ref_pt_z,num_ctrl_surfaces,area,ctrl_surface_order,inputs.avl_path)
avl_out_parse_0_0.main(plane_name,frame_type,AR,mac,ref_pt_x,ref_pt_y,ref_pt_z,num_ctrl_surfaces,area,ctrl_surface_order,inputs.avl_path)
Copy link
Member

Choose a reason for hiding this comment

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

why was this file renamed?

Copy link
Author

Choose a reason for hiding this comment

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

Since there are two versions of the parser, the original input parser currently relies on the original output parser. However, this setup no longer makes sense—the updated output parser should always be used instead. Therefore, the deprecated avl_out_parse_0_0.py and input_avl_parse_0_0.py will be removed to avoid redundancy and ensure consistency.

This two files were removed since they have been update
to a new version avl_out_parser_1_0.py and avl_input_parser_1_0.py

There were also a avl_input_parser_1_0.py missplaced in the
/gz/ folder, the plane_example_0 was also updated to work
corretly with the new parser
@Filipe-Cavalheiro
Copy link
Author

Hi all,

For simplicity's sake, the 0_0 versions of both the input and output parsers have been removed. Both examples—plane_example_0 and easy_glider4—work as intended with the updated parsers.

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.

3 participants