Skip to content

Commit 1621942

Browse files
authored
Fix constantly increasing memory in std::list (#636)
* Fix constantly increasing memory in std::list When someone is constantly publishing with the same tf2 timestamp (application error, I know), the storage_ of the tf2::TimeCache grows unbounded causing system-wide memory leaks. In a ROS system, each tf2 Listener will spawn one of these TimeCache objects and thus, all ROS nodes that have any sort of tf2 listener will slowly start allocating more and more memory And also fixed the situation where two different tf2 needs to be introduced at the same timestamp. Since the tests were failing I realized that I had to dive a bit deeper into the simple solution. And extend a bit the TransformStorage clase to be comparable, now instead of just looking to the timestamps, the implementation avoids inserting duplicates in the buffer. If for some reason, someone is publishing a different Transfrom (xyz,rpy) at the same timestamp. Well, that case is not being captured now, but I'd say that's another problem Signed-off-by: Ignacio Vizzo <[email protected]>
1 parent ce72ad5 commit 1621942

File tree

5 files changed

+177
-1
lines changed

5 files changed

+177
-1
lines changed

Diff for: tf2/CMakeLists.txt

+5
Original file line numberDiff line numberDiff line change
@@ -105,6 +105,11 @@ if(BUILD_TESTING)
105105
if(TARGET test_time)
106106
target_link_libraries(test_time tf2)
107107
endif()
108+
109+
ament_add_gtest(test_storage test/test_storage.cpp)
110+
if(TARGET test_storage)
111+
target_link_libraries(test_storage tf2)
112+
endif()
108113
endif()
109114

110115
ament_export_dependencies(console_bridge geometry_msgs rcutils rosidl_runtime_cpp)

Diff for: tf2/include/tf2/transform_storage.h

+16
Original file line numberDiff line numberDiff line change
@@ -67,6 +67,22 @@ class TransformStorage
6767
return *this;
6868
}
6969

70+
TF2_PUBLIC
71+
bool operator==(const TransformStorage & rhs) const
72+
{
73+
return (this->rotation_ == rhs.rotation_) &&
74+
(this->translation_ == rhs.translation_) &&
75+
(this->stamp_ == rhs.stamp_) &&
76+
(this->frame_id_ == rhs.frame_id_) &&
77+
(this->child_frame_id_ == rhs.child_frame_id_);
78+
}
79+
80+
TF2_PUBLIC
81+
bool operator!=(const TransformStorage & rhs) const
82+
{
83+
return !(*this == rhs);
84+
}
85+
7086
tf2::Quaternion rotation_;
7187
tf2::Vector3 translation_;
7288
TimePoint stamp_;

Diff for: tf2/src/cache.cpp

+5-1
Original file line numberDiff line numberDiff line change
@@ -28,6 +28,7 @@
2828

2929
/** \author Tully Foote */
3030

31+
#include <algorithm>
3132
#include <cassert>
3233
#include <sstream>
3334
#include <string>
@@ -260,7 +261,10 @@ bool TimeCache::insertData(const TransformStorage & new_data)
260261
}
261262
storage_it++;
262263
}
263-
storage_.insert(storage_it, new_data);
264+
// Insert elements only if not already present
265+
if (std::find(storage_.begin(), storage_.end(), new_data) == storage_.end()) {
266+
storage_.insert(storage_it, new_data);
267+
}
264268

265269
pruneList();
266270
return true;

Diff for: tf2/test/cache_unittest.cpp

+21
Original file line numberDiff line numberDiff line change
@@ -112,6 +112,27 @@ TEST(TimeCache, RepeatabilityReverseInsertOrder)
112112
}
113113
}
114114

115+
TEST(TimeCache, RepeatedElements)
116+
{
117+
constexpr uint64_t runs = 100;
118+
119+
tf2::TimeCache cache;
120+
EXPECT_EQ(cache.getListLength(), 0);
121+
122+
tf2::TransformStorage stor;
123+
setIdentity(stor);
124+
stor.frame_id_ = tf2::CompactFrameID(0);
125+
stor.stamp_ = tf2::TimePoint(std::chrono::nanoseconds(0));
126+
127+
// Attempt to insert the same element 100 times
128+
for (uint64_t i = 1; i < runs; ++i) {
129+
cache.insertData(stor);
130+
}
131+
132+
// Even after 100 insertions, there should be one unique element in the internal list
133+
EXPECT_EQ(cache.getListLength(), 1);
134+
}
135+
115136
TEST(TimeCache, ZeroAtFront)
116137
{
117138
uint64_t runs = 100;

Diff for: tf2/test/test_storage.cpp

+130
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,130 @@
1+
// Copyright (c) 2024 Dexory. All rights reserved.
2+
//
3+
// Redistribution and use in source and binary forms, with or without
4+
// modification, are permitted provided that the following conditions are met:
5+
//
6+
// * Redistributions of source code must retain the above copyright
7+
// notice, this list of conditions and the following disclaimer.
8+
//
9+
// * Redistributions in binary form must reproduce the above copyright
10+
// notice, this list of conditions and the following disclaimer in the
11+
// documentation and/or other materials provided with the distribution.
12+
//
13+
// * Neither the name of the Willow Garage nor the names of its
14+
// contributors may be used to endorse or promote products derived from
15+
// this software without specific prior written permission.
16+
//
17+
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18+
// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19+
// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20+
// ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
21+
// LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22+
// CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23+
// SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24+
// INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25+
// CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26+
// ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27+
// POSSIBILITY OF SUCH DAMAGE.
28+
29+
#include <gtest/gtest.h>
30+
31+
#include "tf2/LinearMath/Quaternion.h"
32+
#include "tf2/LinearMath/Vector3.h"
33+
#include "tf2/time.h"
34+
#include "tf2/transform_storage.h"
35+
36+
class TransformStorageTest : public ::testing::Test
37+
{
38+
protected:
39+
tf2::TransformStorage createTransformStorage()
40+
{
41+
const tf2::CompactFrameID frame_id(0);
42+
const tf2::CompactFrameID child_frame_id(1);
43+
const tf2::TimePoint stamp(tf2::TimePointZero);
44+
const tf2::Quaternion rotation(0.0, 0.0, 0.0, 1.0);
45+
const tf2::Vector3 translation(0.0, 0.0, 0.0);
46+
return tf2::TransformStorage(stamp, rotation, translation, frame_id, child_frame_id);
47+
}
48+
};
49+
50+
TEST_F(TransformStorageTest, EqualityOperator) {
51+
// Create a dummy storage, set to identity
52+
tf2::TransformStorage transformStorage1 = createTransformStorage();
53+
54+
// tf2::Quaternion rotation_;
55+
{
56+
tf2::TransformStorage transformStorage2 = createTransformStorage();
57+
ASSERT_TRUE(transformStorage1 == transformStorage2);
58+
transformStorage2.rotation_.setValue(1.0, 0.0, 0.0, 0.0);
59+
ASSERT_FALSE(transformStorage1 == transformStorage2);
60+
}
61+
// tf2::Vector3 translation_;
62+
{
63+
tf2::TransformStorage transformStorage2 = createTransformStorage();
64+
ASSERT_TRUE(transformStorage1 == transformStorage2);
65+
transformStorage2.translation_.setValue(1.0, 0.0, 0.0);
66+
ASSERT_FALSE(transformStorage1 == transformStorage2);
67+
}
68+
// TimePoint stamp_;
69+
{
70+
tf2::TransformStorage transformStorage2 = createTransformStorage();
71+
ASSERT_TRUE(transformStorage1 == transformStorage2);
72+
transformStorage2.stamp_ = tf2::TimePoint(tf2::durationFromSec(1.0));
73+
ASSERT_FALSE(transformStorage1 == transformStorage2);
74+
}
75+
// CompactFrameID frame_id_;
76+
{
77+
tf2::TransformStorage transformStorage2 = createTransformStorage();
78+
ASSERT_TRUE(transformStorage1 == transformStorage2);
79+
transformStorage2.frame_id_ = 55;
80+
ASSERT_FALSE(transformStorage1 == transformStorage2);
81+
}
82+
// CompactFrameID child_frame_id_;
83+
{
84+
tf2::TransformStorage transformStorage2 = createTransformStorage();
85+
ASSERT_TRUE(transformStorage1 == transformStorage2);
86+
transformStorage2.translation_.setValue(1.0, 0.0, 0.0);
87+
ASSERT_FALSE(transformStorage1 == transformStorage2);
88+
}
89+
}
90+
91+
TEST_F(TransformStorageTest, InequalityOperator) {
92+
// Create a dummy storage, set to identity
93+
tf2::TransformStorage transformStorage1 = createTransformStorage();
94+
95+
// tf2::Quaternion rotation_;
96+
{
97+
tf2::TransformStorage transformStorage2 = createTransformStorage();
98+
ASSERT_TRUE(transformStorage1 == transformStorage2);
99+
transformStorage2.rotation_.setValue(1.0, 0.0, 0.0, 0.0);
100+
ASSERT_TRUE(transformStorage1 != transformStorage2);
101+
}
102+
// tf2::Vector3 translation_;
103+
{
104+
tf2::TransformStorage transformStorage2 = createTransformStorage();
105+
ASSERT_TRUE(transformStorage1 == transformStorage2);
106+
transformStorage2.translation_.setValue(1.0, 0.0, 0.0);
107+
ASSERT_TRUE(transformStorage1 != transformStorage2);
108+
}
109+
// TimePoint stamp_;
110+
{
111+
tf2::TransformStorage transformStorage2 = createTransformStorage();
112+
ASSERT_TRUE(transformStorage1 == transformStorage2);
113+
transformStorage2.stamp_ = tf2::TimePoint(tf2::durationFromSec(1.0));
114+
ASSERT_TRUE(transformStorage1 != transformStorage2);
115+
}
116+
// CompactFrameID frame_id_;
117+
{
118+
tf2::TransformStorage transformStorage2 = createTransformStorage();
119+
ASSERT_TRUE(transformStorage1 == transformStorage2);
120+
transformStorage2.frame_id_ = 55;
121+
ASSERT_TRUE(transformStorage1 != transformStorage2);
122+
}
123+
// CompactFrameID child_frame_id_;
124+
{
125+
tf2::TransformStorage transformStorage2 = createTransformStorage();
126+
ASSERT_TRUE(transformStorage1 == transformStorage2);
127+
transformStorage2.translation_.setValue(1.0, 0.0, 0.0);
128+
ASSERT_TRUE(transformStorage1 != transformStorage2);
129+
}
130+
}

0 commit comments

Comments
 (0)