Skip to content

Commit

Permalink
fix edge case when cache is empty, fix codestyle
Browse files Browse the repository at this point in the history
fixes segfault in Cache::getSurroundingInterval
  • Loading branch information
Cakem1x committed Jul 31, 2024
1 parent 86af191 commit dd5bb14
Show file tree
Hide file tree
Showing 2 changed files with 12 additions and 1 deletion.
6 changes: 6 additions & 0 deletions include/message_filters/cache.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -209,6 +209,12 @@ class Cache : public SimpleFilter<M>
namespace mt = message_filters::message_traits;

std::lock_guard<std::mutex> lock(cache_lock_);
if (cache_.size() == 0)
{
// early return for empty cache; Logic below is only valid for caches with at least one element.
return {};
}

// Find the starting index. (Find the first index after [or at] the start of the interval)
int start_index = static_cast<int>(cache_.size()) - 1;
while (start_index > 0 &&
Expand Down
7 changes: 6 additions & 1 deletion test/msg_cache_unittest.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -78,7 +78,12 @@ void fillCacheEasy(message_filters::Cache<Msg> & cache, unsigned int start, unsi
TEST(Cache, emptySurroundingInterval)
{
message_filters::Cache<Msg> cache(10);
const std::vector<std::shared_ptr<Msg const> > interval_data = cache.getSurroundingInterval(rclcpp::Time(5, 0), rclcpp::Time(9, 0));
const std::vector<std::shared_ptr<Msg const>> interval_data = cache.getSurroundingInterval(
rclcpp::Time(
5,
0), rclcpp::Time(
9, 0));

EXPECT_EQ(interval_data.size(), (unsigned int) 0); // empty cache shall return empty interval
}

Expand Down

0 comments on commit dd5bb14

Please sign in to comment.