Skip to content

Commit bdc53cf

Browse files
authored
Queue library (#25)
* feat: separated queue into a shared library * fix: compile structure done feat: tests added * fix: queue tests finalised * fix: header-only library built * fix: linter errors fixed * fix: requested changes implemented fix: added header-only include location correctly
1 parent 672e6f3 commit bdc53cf

File tree

8 files changed

+197
-6
lines changed

8 files changed

+197
-6
lines changed

packages/camera/CMakeLists.txt

Lines changed: 14 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -15,24 +15,34 @@ find_package(yaml_cpp_vendor REQUIRED)
1515
find_package(geometry_msgs REQUIRED)
1616
find_package(Boost REQUIRED)
1717
find_package(camera_srvs REQUIRED)
18+
find_package(common REQUIRED)
1819

1920
add_library(mvsdk SHARED IMPORTED)
2021
set_target_properties(mvsdk PROPERTIES IMPORTED_LOCATION "/lib/libMVSDK.so")
2122

23+
add_library(queue_lib INTERFACE)
24+
2225
add_executable(camera src/camera_main.cpp src/camera.cpp src/params.cpp
2326
src/camera_status.cpp)
2427
add_executable(calibration src/calibration_main.cpp src/calibration.cpp
2528
src/params.cpp)
2629

2730
target_include_directories(
2831
camera PUBLIC "$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>"
29-
"/usr/include")
32+
"$<INSTALL_INTERFACE:include/${PROJECT_NAME}>" "/usr/include")
33+
3034
target_include_directories(
3135
calibration PUBLIC "$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>"
3236
"/usr/include")
3337

34-
ament_target_dependencies(camera rclcpp cv_bridge OpenCV sensor_msgs
35-
yaml_cpp_vendor)
38+
ament_target_dependencies(
39+
camera
40+
rclcpp
41+
cv_bridge
42+
OpenCV
43+
sensor_msgs
44+
yaml_cpp_vendor
45+
common)
3646

3747
ament_target_dependencies(
3848
calibration
@@ -49,7 +59,7 @@ ament_target_dependencies(
4959
Boost
5060
camera_srvs)
5161

52-
target_link_libraries(camera mvsdk)
62+
target_link_libraries(camera mvsdk common::common)
5363

5464
install(TARGETS camera calibration DESTINATION lib/${PROJECT_NAME})
5565

packages/camera/include/camera.h

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -6,7 +6,7 @@
66
#include <opencv2/core/core.hpp>
77

88
#include "CameraApi.h"
9-
#include "lock_free_queue.h"
9+
#include "common/lock_free_queue.h"
1010
#include "params.h"
1111

1212
#include <chrono>

packages/camera/package.xml

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -21,6 +21,7 @@
2121
<depend>yaml_cpp_vendor</depend>
2222
<depend>Boost</depend>
2323
<depend>camera_srvs</depend>
24+
<depend>common</depend>
2425

2526
<test_depend>ament_lint_auto</test_depend>
2627
<test_depend>ament_lint_common</test_depend>

packages/common/CMakeLists.txt

Lines changed: 29 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,29 @@
1+
cmake_minimum_required(VERSION 3.8)
2+
project(common)
3+
4+
find_package(ament_cmake REQUIRED)
5+
6+
add_library(${PROJECT_NAME} INTERFACE)
7+
target_include_directories(
8+
${PROJECT_NAME}
9+
INTERFACE "$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>"
10+
"$<INSTALL_INTERFACE:include>")
11+
12+
install(
13+
TARGETS ${PROJECT_NAME}
14+
EXPORT "export_${PROJECT_NAME}"
15+
ARCHIVE DESTINATION lib
16+
LIBRARY DESTINATION lib
17+
RUNTIME DESTINATION bin
18+
INCLUDES
19+
DESTINATION include)
20+
21+
install(DIRECTORY include/ DESTINATION include/${PROJECT_NAME})
22+
23+
if(BUILD_TESTING)
24+
find_package(ament_cmake_gtest REQUIRED)
25+
add_subdirectory("tests")
26+
endif()
27+
28+
ament_export_targets("export_${PROJECT_NAME}")
29+
ament_package()

packages/camera/include/lock_free_queue.h renamed to packages/common/include/lock_free_queue.h

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -34,7 +34,7 @@ class LockFreeQueue {
3434
// while could not proccess
3535
while (true) {
3636
int snap = tail_.load();
37-
if (snap - head_.load() == data_.size()) {
37+
if (snap - head_.load() == static_cast<int>(data_.size())) {
3838
// buffer is full and can't be updated
3939
// in fact, slot can be freed during verification, but we do not double-check
4040
return false;

packages/common/package.xml

Lines changed: 23 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,23 @@
1+
<?xml version="1.0"?>
2+
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
3+
<package format="3">
4+
<name>common</name>
5+
<version>0.0.0</version>
6+
<description>common</description>
7+
<license>MIT</license>
8+
<maintainer email="denis.bakin5@gmail.com">Denis Bakin</maintainer>
9+
10+
<buildtool_depend>ament_cmake</buildtool_depend>
11+
<buildtool_depend>rosidl_default_generators</buildtool_depend>
12+
<build_depend>builtin_interfaces</build_depend>
13+
14+
<test_depend>ament_lint_auto</test_depend>
15+
<test_depend>ament_lint_common</test_depend>
16+
<test_depend>ament_cmake_gtest</test_depend>
17+
18+
<member_of_group>rosidl_interface_packages</member_of_group>
19+
20+
<export>
21+
<build_type>ament_cmake</build_type>
22+
</export>
23+
</package>

packages/common/tests/CMakeLists.txt

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,4 @@
1+
ament_add_gtest(queue_test src/test.cpp)
2+
target_include_directories(
3+
queue_test PUBLIC "$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>")
4+
target_link_libraries(queue_test ${PROJECT_NAME})

packages/common/tests/src/test.cpp

Lines changed: 124 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,124 @@
1+
#include "lock_free_queue.h"
2+
3+
#include <gtest/gtest.h>
4+
5+
#include <thread>
6+
#include <vector>
7+
8+
TEST(Correctness, push) {
9+
handy::LockFreeQueue<int> queue(2);
10+
ASSERT_TRUE(queue.push(2));
11+
ASSERT_TRUE(queue.push(2));
12+
ASSERT_FALSE(queue.push(2));
13+
ASSERT_FALSE(queue.push(2));
14+
}
15+
16+
TEST(Correctness, pop) {
17+
int value;
18+
handy::LockFreeQueue<int> queue(2);
19+
ASSERT_FALSE(queue.pop(value));
20+
ASSERT_FALSE(queue.pop(value));
21+
}
22+
23+
TEST(Correctness, pushpop) {
24+
int value = 0;
25+
handy::LockFreeQueue<int> queue(2);
26+
ASSERT_TRUE(queue.push(1));
27+
ASSERT_TRUE(queue.pop(value));
28+
ASSERT_EQ(value, 1);
29+
ASSERT_FALSE(queue.pop(value));
30+
31+
ASSERT_TRUE(queue.push(2));
32+
ASSERT_TRUE(queue.push(3));
33+
ASSERT_FALSE(queue.push(4));
34+
35+
ASSERT_TRUE(queue.pop(value));
36+
ASSERT_EQ(value, 2);
37+
ASSERT_TRUE(queue.pop(value));
38+
ASSERT_EQ(value, 3);
39+
40+
ASSERT_FALSE(queue.pop(value));
41+
}
42+
43+
TEST(Performance, NoSpuriousFails) {
44+
const int n = 1024 * 1024;
45+
const int n_threads = 8;
46+
handy::LockFreeQueue<int> queue(n * n_threads);
47+
48+
std::vector<std::thread> writers;
49+
// check that all threads managed to push elements without fake fails
50+
for (int i = 0; i < n_threads; i++) {
51+
writers.emplace_back([&] { // NOLINT
52+
for (int j = 0; j < n; ++j) {
53+
ASSERT_TRUE(queue.push(0));
54+
}
55+
});
56+
}
57+
58+
for (auto& t : writers) {
59+
t.join();
60+
}
61+
62+
std::vector<std::thread> readers;
63+
// check that all threads managed to pop elements without fake fails
64+
// and no elements were lost
65+
for (int i = 0; i < n_threads; i++) {
66+
readers.emplace_back([&] { // NOLINT
67+
for (int j = 0; j < n; ++j) {
68+
int k;
69+
ASSERT_TRUE(queue.pop(k));
70+
}
71+
});
72+
}
73+
74+
for (auto& t : readers) {
75+
t.join();
76+
}
77+
}
78+
79+
TEST(Performance, NoQueueLock) {
80+
const int n = 1024 * 1024;
81+
const int n_threads = 8;
82+
handy::LockFreeQueue<int> queue(64);
83+
84+
std::vector<std::thread> threads;
85+
int id = 0;
86+
for (int i = 0; i < n_threads; i++) {
87+
const int current_id = id++;
88+
if (current_id % 2 == 0) {
89+
threads.emplace_back([&] { // NOLINT
90+
for (int cnt = 0; cnt < n; ++cnt) {
91+
queue.push(0);
92+
}
93+
});
94+
} else {
95+
threads.emplace_back([&] { // NOLINT
96+
for (int cnt = 0; cnt < n; ++cnt) {
97+
int _;
98+
queue.pop(_);
99+
}
100+
});
101+
}
102+
}
103+
104+
for (auto& t : threads) {
105+
t.join();
106+
}
107+
108+
int k;
109+
// empty queue
110+
while (queue.pop(k)) {
111+
queue.pop(k);
112+
}
113+
// check that it still works
114+
ASSERT_TRUE(queue.push(0));
115+
ASSERT_TRUE(queue.pop(k));
116+
ASSERT_EQ(k, 0);
117+
// must be empty
118+
ASSERT_FALSE(queue.pop(k));
119+
}
120+
121+
int main(int argc, char** argv) {
122+
testing::InitGoogleTest(&argc, argv);
123+
return RUN_ALL_TESTS();
124+
}

0 commit comments

Comments
 (0)