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

AP_HAL: Improve speed param download in network links (sitl/linux) #25357

Merged
merged 2 commits into from
Oct 31, 2023

Conversation

Williangalvani
Copy link
Contributor

@Williangalvani Williangalvani commented Oct 24, 2023

This improves parameter loading speed with SITL and Linux. After the linked patch, parameter loading speed (not using mavftp) got ~10x slower.

There is no reason for assuming that these are limited to 57600 baud.

In my tests:
param fetch in master with QGC takes ~30 seconds
with this patch (thanks @magicrub), it takes ~2s

Linux shows similar results

Apparently it was a typo in here:
866db28#diff-da049e0cf2dd85cd33145ab82688554b96b56444b22e5475a1d961e259aa69d9L136

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.

Wowzers! Nice catch. This effects non-ChibiOS and non-MAVFTP param downloads. That's a big deal. This is probably a good one for 4.4.3!

@WickedShell
Copy link
Contributor

WickedShell commented Oct 24, 2023

The change implies a 576000 baud link. Now to be fair SITL should probably sim something faster, but as a generic fall back that's probably faster then we want to keep here. But the linked commit wasn't actually a typo, it was correct.

EDIT: To be clear, I do want SITL to be faster on this, it's been killing me recently!

@magicrub
Copy link
Contributor

oh, right! It's bandwidth in bytes so 57.6Kbit BYTE equivalent, minus start bit and a gap, is 57.6k/10 = 5760 BYTES per second.

@Williangalvani
Copy link
Contributor Author

Williangalvani commented Oct 24, 2023

But the linked commit wasn't actually a typo, it was correct.

Were things incorrect before, then? I see it now. yes. things were wrong.
I've seen a ~10x slowdown after that patch.
I also assumed changing from bytes to kilobytes would be a 1000x factor, which is what led me to believe it was a typo.

But yes, I do see that 57600 baud means 5.7kbps

So the linked pr should mean we use 30% of the bw at most for params?

@WickedShell
Copy link
Contributor

So the linked pr should mean we use 30% of the bw at most for params?

I'm not as sure about that. I do know our math for param bandwidth usage is low. Everytime I download params I see a large reduction in radio throughput. The same isn't true for the FTP interface, but if you are using the old param interface it's very bad. I'd pretty happily take anything that allocates a larger percentage of bandwidth to params during the download.

@Williangalvani Williangalvani marked this pull request as draft October 24, 2023 22:36
@Williangalvani
Copy link
Contributor Author

The current patch worked well here on SITL and Linux.

test in SITL
param fetch with the previous patch (extra 0) took ~3 seconds
param fetch in master takes ~30 seconds
with this patch (thanks @magicrub), it takes ~2s

@Williangalvani Williangalvani changed the title AP_HAL: fix bw_in_kilobytes_per_second AP_HAL: Improve speed param download in network links (sitl/linux) Oct 25, 2023
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.

LGTM! The code is better in the C file like this but it breaks the pattern from the other AP_HAL implementations. I'm neutral about it. Change it if you want, I'm happy to merge as-is

@magicrub magicrub marked this pull request as ready for review October 25, 2023 16:53
@magicrub
Copy link
Contributor

This has the potential to speed up CI but I don't notice any significant difference.

@magicrub
Copy link
Contributor

This PR inspired me to make PR #25365

@magicrub
Copy link
Contributor

The reason for this PR makes me think we should change bw_in_bytes_per_second() to be a pure virtual (aka must be implemented by the driver)

// if connected, assume at least a 10/100Mbps connection
const uint32_t bitrate = (_connected && _ip != nullptr) ? 10E6 : _baudrate;
return bitrate/10; // convert bits to bytes minus overhead
};
Copy link
Collaborator

Choose a reason for hiding this comment

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

Add a missing newline, otherwise the pre-commit stuff will start to fail again.

@tridge tridge merged commit 60a38a0 into ArduPilot:master Oct 31, 2023
@Williangalvani Williangalvani deleted the fix_params_speed branch January 23, 2024 02:52
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Projects
None yet
Development

Successfully merging this pull request may close these issues.

8 participants