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

[TimeCache] Improve performance for insertData() and pruneList() #680

Merged
merged 6 commits into from
May 22, 2024

Conversation

EricCousineau-TRI
Copy link
Contributor

@EricCousineau-TRI EricCousineau-TRI commented May 14, 2024

Resolves #676

Per #676 (comment), this should yield a ~1000x speedup for insertData (for inserting new data only)

@EricCousineau-TRI
Copy link
Contributor Author

EricCousineau-TRI commented May 14, 2024

Hm. This is breaking test_tf2/buffer_core_test

EDIT: Locally, seems fixed by 898b4b3

Specifically:
test_tf2/buffer_core_test/BufferCore_lookupTransform/ring_45_configuration
@EricCousineau-TRI
Copy link
Contributor Author

@clalancette @ahcorde If y'all have time, would y'all also be able to review + run full CI for this PR?

@ahcorde
Copy link
Contributor

ahcorde commented May 15, 2024

  • Linux Build Status
  • Linux-aarch64 Build Status
  • Windows Build Status

tf2/src/cache.cpp Outdated Show resolved Hide resolved
tf2/src/cache.cpp Show resolved Hide resolved
EricCousineau-TRI and others added 3 commits May 15, 2024 16:39
Co-authored-by: Chris Lalancette <clalancette@gmail.com>
Signed-off-by: Eric Cousineau <eric.cousineau@tri.global>
@ahcorde
Copy link
Contributor

ahcorde commented May 16, 2024

  • Linux Build Status
  • Linux-aarch64 Build Status
  • Windows Build Status

Copy link
Contributor

@clalancette clalancette left a comment

Choose a reason for hiding this comment

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

This looks great; I just added a request for one more comment. Otherwise, this will be ready to get CI run on it.

@@ -250,23 +250,38 @@ bool TimeCache::insertData(const TransformStorage & new_data)
{
const TimePoint latest_time = getLatestTimestamp();

// Always prune data. This (a) ensures we trim data we should not access, and
// (b) ensures we don't waste time iterating over items to be removed.
pruneList();
Copy link
Contributor

Choose a reason for hiding this comment

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

I like doing this first. It both improves performance for below, and also means that the list is always pruned, even if we are not going to insert the data.

tf2/src/cache.cpp Show resolved Hide resolved
@clalancette
Copy link
Contributor

CI:

  • Linux Build Status
  • Linux-aarch64 Build Status
  • Windows Build Status

@ahcorde ahcorde merged commit d700d78 into ros2:rolling May 22, 2024
2 checks passed
@ahcorde
Copy link
Contributor

ahcorde commented May 22, 2024

https://github.com/Mergifyio backport jazzy

Copy link
Contributor

mergify bot commented May 22, 2024

backport jazzy

✅ Backports have been created

mergify bot pushed a commit that referenced this pull request May 22, 2024
Signed-off-by: Eric Cousineau <eric.cousineau@tri.global>
Co-authored-by: Chris Lalancette <clalancette@gmail.com>
(cherry picked from commit d700d78)
@EricCousineau-TRI
Copy link
Contributor Author

is it possible to backport this for humble (and maybe iron) as well?

ahcorde pushed a commit that referenced this pull request May 28, 2024
… (#686)

Signed-off-by: Eric Cousineau <eric.cousineau@tri.global>
Co-authored-by: Chris Lalancette <clalancette@gmail.com>
(cherry picked from commit d700d78)

Co-authored-by: Eric Cousineau <eric.cousineau@tri.global>
@EricCousineau-TRI
Copy link
Contributor Author

(We are very interested in having this improvement in humble, so please let me know if there is anything I can do to help in this respect!)

@ahcorde
Copy link
Contributor

ahcorde commented May 28, 2024

Ey @EricCousineau-TRI,

I'm backporting some of your last PRs, if CI is green should be done today, then I will create a release

@EricCousineau-TRI
Copy link
Contributor Author

thanks! Just looking though, and I'm not sure if I saw this one (perf improvement) backported for humble.
Did I miss that one?

@EricCousineau-TRI
Copy link
Contributor Author

@ahcorde
Copy link
Contributor

ahcorde commented May 28, 2024

https://github.com/Mergifyio backport humble iron

Copy link
Contributor

mergify bot commented May 28, 2024

backport humble iron

✅ Backports have been created

mergify bot pushed a commit that referenced this pull request May 28, 2024
Signed-off-by: Eric Cousineau <eric.cousineau@tri.global>
Co-authored-by: Chris Lalancette <clalancette@gmail.com>
(cherry picked from commit d700d78)

# Conflicts:
#	tf2/src/cache.cpp
mergify bot pushed a commit that referenced this pull request May 28, 2024
Signed-off-by: Eric Cousineau <eric.cousineau@tri.global>
Co-authored-by: Chris Lalancette <clalancette@gmail.com>
(cherry picked from commit d700d78)

# Conflicts:
#	tf2/src/cache.cpp
ahcorde pushed a commit that referenced this pull request May 29, 2024
Signed-off-by: Eric Cousineau <eric.cousineau@tri.global>
Co-authored-by: Chris Lalancette <clalancette@gmail.com>
ahcorde pushed a commit that referenced this pull request May 29, 2024
Signed-off-by: Eric Cousineau <eric.cousineau@tri.global>
Co-authored-by: Chris Lalancette <clalancette@gmail.com>
ahcorde added a commit that referenced this pull request May 29, 2024
…kport #680) (#694)

* Nacho/minor fixes tf2 cache (#658)

* Remove unused parameter

* Make use of API function to improve redability

```cpp
TimePoint TimeCache::getLatestTimestamp()
{
  return storage_.front().stamp_;
}
```

And std::list<T>::front() is(gcclib):
```cpp
reference
front() _GLIBCXX_NOEXCEPT
{ return *begin(); }
```

* Same argument as 321bd22

```cpp

TimePoint TimeCache::getLatestTimestamp()
{
  // empty list case
  // ...
  return storage_.front().stamp_;
}
```

and std::list<T>::front():
```cpp
reference
front() _GLIBCXX_NOEXCEPT
{ return *begin(); }
```

* Improve readbility by relying on STL functions

By now reading to this block I can tell that we are preventing to
inserting a new element in the list, that has a timestamp that is
actually older than the max_storage_time_ we allow for

* Remove hardcoded algorithmg for STL one

The intent of the code is now more clear, instead of relying on raw
loops, we "find if" there is any element in the list that has a stamp
older than the incoming one. With this we find the position in the list
where we should insert the current timestamp: `storage_it`

* Remove to better express what this pointer is represetngin

* Replace raw loop for STL algorithm

Remove if any element is older thant the max_storage_time_ allowed,
relative to the latest(sooner) time seems clear npw

* [TimeCache] Improve performance for insertData() and pruneList() (#680)

Signed-off-by: Eric Cousineau <eric.cousineau@tri.global>
Co-authored-by: Chris Lalancette <clalancette@gmail.com>

* Don't break ABI

Signed-off-by: Alejandro Hernández Cordero <ahcorde@gmail.com>

---------

Signed-off-by: Eric Cousineau <eric.cousineau@tri.global>
Signed-off-by: Alejandro Hernández Cordero <ahcorde@gmail.com>
Co-authored-by: Ignacio Vizzo <ignacio@dexory.com>
Co-authored-by: Eric Cousineau <eric.cousineau@tri.global>
Co-authored-by: Chris Lalancette <clalancette@gmail.com>
Co-authored-by: Alejandro Hernández Cordero <ahcorde@gmail.com>
ahcorde added a commit that referenced this pull request May 29, 2024
…kport #680) (#693)

* Nacho/minor fixes tf2 cache (#658)

* Remove unused parameter

* Make use of API function to improve redability

```cpp
TimePoint TimeCache::getLatestTimestamp()
{
  return storage_.front().stamp_;
}
```

And std::list<T>::front() is(gcclib):
```cpp
reference
front() _GLIBCXX_NOEXCEPT
{ return *begin(); }
```

* Same argument as 321bd22

```cpp

TimePoint TimeCache::getLatestTimestamp()
{
  // empty list case
  // ...
  return storage_.front().stamp_;
}
```

and std::list<T>::front():
```cpp
reference
front() _GLIBCXX_NOEXCEPT
{ return *begin(); }
```

* Improve readbility by relying on STL functions

By now reading to this block I can tell that we are preventing to
inserting a new element in the list, that has a timestamp that is
actually older than the max_storage_time_ we allow for

* Remove hardcoded algorithmg for STL one

The intent of the code is now more clear, instead of relying on raw
loops, we "find if" there is any element in the list that has a stamp
older than the incoming one. With this we find the position in the list
where we should insert the current timestamp: `storage_it`

* Remove to better express what this pointer is represetngin

* Replace raw loop for STL algorithm

Remove if any element is older thant the max_storage_time_ allowed,
relative to the latest(sooner) time seems clear npw

* [TimeCache] Improve performance for insertData() and pruneList() (#680)

Signed-off-by: Eric Cousineau <eric.cousineau@tri.global>
Co-authored-by: Chris Lalancette <clalancette@gmail.com>

* Don't break ABI

Signed-off-by: Alejandro Hernández Cordero <ahcorde@gmail.com>

---------

Signed-off-by: Eric Cousineau <eric.cousineau@tri.global>
Signed-off-by: Alejandro Hernández Cordero <ahcorde@gmail.com>
Co-authored-by: Ignacio Vizzo <ignacio@dexory.com>
Co-authored-by: Eric Cousineau <eric.cousineau@tri.global>
Co-authored-by: Chris Lalancette <clalancette@gmail.com>
Co-authored-by: Alejandro Hernández Cordero <ahcorde@gmail.com>
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.

Performance regression due to #636
4 participants