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

orb_exists: change semantics from (is published or subscribed) to (is published) #8135

Merged
merged 10 commits into from
Oct 18, 2017

Conversation

bkueng
Copy link
Member

@bkueng bkueng commented Oct 16, 2017

Existing users of orb_exists:

  • logger (dynamic subscribe to multi-instances)
  • mavlink (orb subscription)
  • sdlog2
  • preflightcheck (check for home_position)
  • wait_for_topic shell command (it's not used)
  • orb_group_count() (used in sensors: dynamic sensor addition)

All use-cases benefit from the changed semantics: they are really only interested if there is a publisher, not another subscriber.

Additional changes:

  • logger: do not subscribe to the first instance if the topic is not advertised (but dynamically check if it's published later on)
  • logger: remove unused topics commander_state & rc_channels
  • avoid dynamic allocations in orb_exists on POSIX
  • mavlink_orb_subscription: reduce orb_exists() check from 10Hz to 3Hz

This has deeper impacts on the overall system, hopefully mostly positive!
The following provides some test results.

Testing

To get representative results, I tested on a fully assembled quad (pixracer) in armed state with RC and an open QGC connection.

Used file descriptors

Number of used file descriptors (mavlink instance is the one that is connected to QGC, without b50b0b7):

Before:  mavlink: 46, logger: 54
This PR: mavlink: 30, logger: 33

Memory (Fragmentation)

The additional file operations (open & close) in orb_exists do not lead to memory allocations/frees on Nuttx, but did so on POSIX. I changed this in 3b31a03.

My tests showed a considerable memory reduction of 4.2 KB. A bit more than half is because of mavlink, the rest is logger. Since pixracer runs more mavlink instances than other boards, it will be slightly less on other boards.

CPU usage

Tests showed this is pretty much unchanged (without 191622b). This is the execution time of orb_exists before (with locked scheduling):

orb_exists: 23174 events, 879696us elapsed, 37us avg, min 20us max 196us 24.192us rms

And this PR:

orb_exists: 22182 events, 1383130us elapsed, 62us avg, min 20us max 274us 47.743us rms

Obviously slower, but I think it's still ok, since it's not called with high frequency or at critical places.

I suggest reviewing each individual commit.

… published)

Existing users of orb_exists:
- logger (dynamic subscribe to multi-instances)
- mavlink (orb subscription)
- sdlog2
- preflightcheck (check for home_position)
- wait_for_topic shell command (it's not used)
- orb_group_count() (sensors: dynamic sensor addition)

All use-cases benefit from the changed semantics: they are really only
interested if there is a publisher, not another subscriber.
…instance

To keep track of the configured interval, we store it as negative file
descriptor, until we do the subscription.

This frees up a considerable amount of file descriptors in most use-cases.
If logger is started very early, orb_exists() will fail for a lot of
topics, they will be advertised within the next few seconds.
Logger already dynamically adds subscriptions during logging, but if we
do that before as well, we'll avoid any delays and having to subscribe
to a lot of topics all at once.
…ointers

to avoid dynamic memory allocations & frees (specifically in orb_exists)
flight review now uses vehicle_status & manual_control_setpoint
Checking with 3Hz for new topics should be fast enough.
// - we avoid subscribing to many topics at once, when logging starts
// - we'll get the data immediately once we start logging (no need to wait for the next subscribe timeout)
if (next_subscribe_topic_index != -1) {
for (uint8_t instance = 0; instance < ORB_MULTI_MAX_INSTANCES; instance++) {
Copy link
Contributor

Choose a reason for hiding this comment

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

using uint8_t as index is not an optimization, you should use a counter of processor word size

Copy link
Member Author

Choose a reason for hiding this comment

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

I know, I copy-pasted that :/
Fixed in 37902d9

@dagar
Copy link
Member

dagar commented Oct 16, 2017

This is great! Should we reduce the nuttx fds again?

@bkueng
Copy link
Member Author

bkueng commented Oct 16, 2017

This is great! Should we reduce the nuttx fds again?

Thanks! I deliberately did not do that (yet), because:

  • Some setups will need more than my numbers above (e.g. VTOL's with camera control, or optical flow setups), however, not as many as before.
  • We'll likely use more again in future

If we're short on RAM we can certainly reduce them. One FD needs 16 bytes, so reducing by one implies around 16*20 (tasks) = 320 Bytes more RAM.

@dagar
Copy link
Member

dagar commented Oct 16, 2017

Memory can be tight in some setups right now, but in most cases it's avoidable. For example it's easy for a user to unintentionally configure a pixracer where they'll run out of memory. Certain combinations of USB connected, SYS_COMPANION, vmount, camera trigger, etc can already leave you without enough memory to successfully calibrate. Not to mention UAVCAN.

It's too bad we can't (easily) configure the nuttx FDs per task. Alternatively we create another uORB interface that doesn't use FDs (for logger and mavlink), but that would need significantly more thought.

Other than mavlink and logger most tasks use < 20 FDs with the exception of commanader, but I already see quite a few ways to bring that down. At what point does it become worth it? Reducing by 20-30 FDs and save 5-10kBs of RAM?

@LorenzMeier
Copy link
Member

@bkueng Could you look into fixing the CI failures (or rebase) and please ping and tag @PX4TestFlights so they can start testing it? Thanks!

@bkueng
Copy link
Member Author

bkueng commented Oct 17, 2017

@dagar
i'd like to see full-blown configs working too on boards like pixracer. But at some point we just hit the limit and I'd suggest to use Pixhawk Pro (it's a really good board too), or fmu-v5 in such cases.

Specifically on Pixracer, we can do one more thing that does not require much effort: frsky_telemetry is continuously running (as task), and I think most people don't require it. We could detect if the bus is connected on startup, and if not, exit the task. This would free around 3KB.

How about we reduce the number of FD's by 5? That should definitely be safe.

As for dynamic FD's: I already talked to @davids5 and he told me that Greg had some NuttX testing branch for that, but there were some complications with sockets. So I think it's not going to happen soon. But it's also not that urgent anymore with this PR.
Also the NuttX upgrade requires more RAM, and I think David is looking into reducing that again.
Then together with this PR and @dagar 's navigator optimizations I'd say we're in a good shape again.

CI failed because of flash overflow. I removed the blacksheep telemetry driver from fmu-v2. Circle-CI failure is unrelated and succeeded before.

@PX4TestFlights this is ready for testing. Please test on all boards and look that:

  • all the plots for the logs show up correctly, and there are no new error messages
  • QGC connection works as expected via USB and telemetry.

@dagar dagar added this to the Release v1.7.0 milestone Oct 17, 2017
@santiago3dr
Copy link

santiago3dr commented Oct 17, 2017

@LorenzMeier LorenzMeier merged commit 8b797d9 into master Oct 18, 2017
@LorenzMeier LorenzMeier deleted the uorb_exists_update branch October 18, 2017 06:40
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